|
| 1 | +#include <ctime> |
| 2 | +#include <iostream> |
| 3 | +#include <fstream> |
| 4 | +#include <string> |
| 5 | +#include <boost/array.hpp> |
| 6 | +#include <boost/asio.hpp> |
| 7 | +#include <boost/format.hpp> |
| 8 | +#include <boost/bind.hpp> |
| 9 | +#include <sys/types.h> /* See NOTES */ |
| 10 | +#include <sys/socket.h> |
| 11 | +#include <sysexits.h> |
| 12 | + |
| 13 | +#include "msgdef.h" |
| 14 | +#include "djicam.h" |
| 15 | + |
| 16 | +const size_t FRAME_SIZE = 1280*720*3; |
| 17 | + |
| 18 | +using boost::asio::ip::udp; |
| 19 | +using boost::asio::ip::tcp; |
| 20 | + |
| 21 | +typedef boost::asio::detail::socket_option::integer<SOL_SOCKET, SO_SNDBUF> send_buf_opt_t; |
| 22 | + |
| 23 | +uint8_t imgbuf[FRAME_SIZE]; |
| 24 | +uint8_t sockbuf[TOTAL_LEN]; |
| 25 | +bool accepted; |
| 26 | + |
| 27 | +std::string make_daytime_string() { |
| 28 | + using namespace std; // For time_t, time and ctime; |
| 29 | + time_t now = time(0); |
| 30 | + return ctime(&now); |
| 31 | +} |
| 32 | + |
| 33 | +std::ofstream * pOS; |
| 34 | + |
| 35 | +void accept_handle(const boost::system::error_code& error) { |
| 36 | + if (!error) |
| 37 | + accepted = true; |
| 38 | + else |
| 39 | + (*pOS) << "accept handle error=" << error.message() << std::endl; |
| 40 | +} |
| 41 | + |
| 42 | +void handle_wait(const boost::system::error_code& error, |
| 43 | + boost::asio::io_service& io) { |
| 44 | + if (!error) |
| 45 | + io.stop(); |
| 46 | + else |
| 47 | + std::cout << "handle_wait error="<< error.message() << std::endl; |
| 48 | +} |
| 49 | + |
| 50 | +int main() { |
| 51 | + std::ofstream logstream("/tmp/x3server.log"); |
| 52 | + if (!logstream.is_open()) { |
| 53 | + return EX_CANTCREAT; |
| 54 | + } |
| 55 | + |
| 56 | + pOS = &logstream; |
| 57 | + logstream << "x3server starts at " << make_daytime_string() << std::endl; |
| 58 | + |
| 59 | + int cam_func_ret; |
| 60 | + size_t cam_nframe = 0; |
| 61 | + bool cam_is_on; |
| 62 | + accepted = false; |
| 63 | + logstream << "X3 initializing..." << std::endl; |
| 64 | + cam_func_ret = manifold_cam_init(GETBUFFER_MODE | TRANSFER_MODE); |
| 65 | + if (cam_func_ret == -1) { |
| 66 | + logstream << "X3 init error" << std::endl; |
| 67 | + return -1; |
| 68 | + } |
| 69 | + else { |
| 70 | + logstream << "X3 inited" << std::endl; |
| 71 | + } |
| 72 | + |
| 73 | + logstream << "X3 reading first frame..." << std::endl; |
| 74 | + cam_func_ret = manifold_cam_read(imgbuf, &cam_nframe, CAM_BLOCK); |
| 75 | + if (cam_func_ret == -1) { |
| 76 | + logstream << "X3 first frame error" << std::endl; |
| 77 | + return -1; |
| 78 | + } |
| 79 | + else { |
| 80 | + logstream << "X3 first frame read" << std::endl; |
| 81 | + cam_is_on = true; |
| 82 | + } |
| 83 | + |
| 84 | + try { |
| 85 | + boost::asio::io_service io_service; |
| 86 | + tcp::acceptor acceptor(io_service, tcp::endpoint(boost::asio::ip::address_v4::loopback(), PORT_NUMBER)); |
| 87 | + while (cam_is_on) { |
| 88 | + tcp::socket socket(io_service); |
| 89 | + |
| 90 | + logstream << "start accept..." << std::endl; |
| 91 | + accepted = false; |
| 92 | + while(!accepted && cam_is_on) { |
| 93 | + io_service.reset(); |
| 94 | + acceptor.async_accept(socket, accept_handle); |
| 95 | + boost::asio::deadline_timer timer(io_service, boost::posix_time::seconds(3)); |
| 96 | + timer.async_wait(boost::bind(handle_wait, |
| 97 | + boost::asio::placeholders::error, |
| 98 | + boost::ref(io_service))); |
| 99 | + io_service.run(); |
| 100 | + // usleep(1000000/2); |
| 101 | + cam_func_ret = manifold_cam_read(imgbuf, &cam_nframe, CAM_NON_BLOCK); |
| 102 | + if (cam_func_ret==-1) { |
| 103 | + cam_is_on = false; |
| 104 | + break; |
| 105 | + } |
| 106 | + } |
| 107 | + |
| 108 | + if (!cam_is_on) { |
| 109 | + break; |
| 110 | + } |
| 111 | + |
| 112 | + if (accepted) { |
| 113 | + logstream << "accepted from " << socket.remote_endpoint() << " @ " << make_daytime_string() << std::endl; |
| 114 | + } |
| 115 | + |
| 116 | + |
| 117 | + // send_buf_opt_t opt1(212992); |
| 118 | + // socket.set_option(opt1); |
| 119 | + |
| 120 | + int frame_cnt = 0; |
| 121 | + struct timeval tm; |
| 122 | + ImageMsgHeader h; |
| 123 | + h.header = 0xFEDCBA98; |
| 124 | + h.image_w = IMAGE_W; |
| 125 | + h.image_h = IMAGE_H; |
| 126 | + h.image_ch = IMAGE_CH; |
| 127 | + while (cam_is_on) { |
| 128 | + cam_func_ret = manifold_cam_read(imgbuf, &cam_nframe, CAM_NON_BLOCK); |
| 129 | + if (cam_func_ret==-1) { |
| 130 | + cam_is_on = false; |
| 131 | + break; |
| 132 | + } |
| 133 | + else if (cam_func_ret == 0) { |
| 134 | + usleep(1000); |
| 135 | + continue; |
| 136 | + } |
| 137 | + memcpy(sockbuf+HEADER_LEN, imgbuf, FRAME_SIZE / 3); |
| 138 | + try { |
| 139 | + frame_cnt++; |
| 140 | + boost::asio::mutable_buffers_1 message = boost::asio::buffer(sockbuf, TOTAL_LEN); |
| 141 | + |
| 142 | + gettimeofday(&tm, NULL); |
| 143 | + h.secs = tm.tv_sec; |
| 144 | + h.usecs = tm.tv_usec; |
| 145 | + |
| 146 | + h.pack((uint8_t *)sockbuf); |
| 147 | + // std::string message = make_daytime_string(); |
| 148 | + |
| 149 | + boost::system::error_code ignored_error; |
| 150 | + int cnt = boost::asio::write(socket, boost::asio::buffer(message), |
| 151 | + boost::asio::transfer_all(), ignored_error); |
| 152 | + |
| 153 | + // logout every frame for first 1 sec, every sec for first 1 minutes, and every minute |
| 154 | + if (frame_cnt<30 || (frame_cnt<1800 && frame_cnt%30==0) || frame_cnt%1800==0) { |
| 155 | + logstream << boost::format("#%d frame sent %d bytes") % frame_cnt % cnt << std::endl; |
| 156 | + } |
| 157 | + |
| 158 | + if (!cnt) { |
| 159 | + logstream << "remote closed" << std::endl; |
| 160 | + socket.close(); |
| 161 | + break; |
| 162 | + } |
| 163 | + } catch (std::exception& e) { |
| 164 | + logstream << "ERROR in while(1):" << std::endl; |
| 165 | + logstream << e.what() << std::endl; |
| 166 | + break; |
| 167 | + } |
| 168 | + } |
| 169 | + logstream << "exit write loop..." << std::endl; |
| 170 | + } |
| 171 | + logstream << "exit accept loop..." << std::endl; |
| 172 | + } catch (std::exception& e) { |
| 173 | + logstream << "ERROR outside while(1):" << std::endl; |
| 174 | + logstream << e.what() << std::endl; |
| 175 | + } |
| 176 | + |
| 177 | + logstream << "exit x3..." << std::endl; |
| 178 | + while (!manifold_cam_exit()) { |
| 179 | + logstream << "X3 failed to exit, retrying..." << std::endl; |
| 180 | + sleep(1); |
| 181 | + } |
| 182 | + logstream << "X3 exit" << std::endl; |
| 183 | + |
| 184 | + return 0; |
| 185 | +} |
0 commit comments