UARTDriver.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. //
  14. // Copyright (c) 2010 Michael Smith. All rights reserved.
  15. //
  16. #include <AP_HAL/AP_HAL.h>
  17. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  18. #include <limits.h>
  19. #include <stdlib.h>
  20. #include <stdio.h>
  21. #include <unistd.h>
  22. #include <fcntl.h>
  23. #include <stdarg.h>
  24. #include <AP_Math/AP_Math.h>
  25. #include <errno.h>
  26. #include <sys/ioctl.h>
  27. #include <sys/types.h>
  28. #include <sys/socket.h>
  29. #include <netinet/in.h>
  30. #include <netinet/tcp.h>
  31. #include <sys/select.h>
  32. #include <termios.h>
  33. #include <sys/time.h>
  34. #include "UARTDriver.h"
  35. #include "SITL_State.h"
  36. #include <AP_HAL/utility/packetise.h>
  37. extern const AP_HAL::HAL& hal;
  38. using namespace HALSITL;
  39. bool UARTDriver::_console;
  40. /* UARTDriver method implementations */
  41. void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
  42. {
  43. if (_portNumber >= ARRAY_SIZE(_sitlState->_uart_path)) {
  44. AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path");
  45. }
  46. const char *path = _sitlState->_uart_path[_portNumber];
  47. if (baud != 0) {
  48. _uart_baudrate = baud;
  49. }
  50. if (strcmp(path, "GPS1") == 0) {
  51. /* gps */
  52. _connected = true;
  53. _fd = _sitlState->gps_pipe();
  54. } else if (strcmp(path, "GPS2") == 0) {
  55. /* 2nd gps */
  56. _connected = true;
  57. _fd = _sitlState->gps2_pipe();
  58. } else {
  59. /* parse type:args:flags string for path.
  60. For example:
  61. tcp:5760:wait // tcp listen on port 5760
  62. tcp:0:wait // tcp listen on use base_port + 0
  63. tcpclient:192.168.2.15:5762
  64. udpclient:127.0.0.1
  65. udpclient:127.0.0.1:14550
  66. mcast:
  67. mcast:239.255.145.50:14550
  68. uart:/dev/ttyUSB0:57600
  69. sim:ParticleSensor_SDS021:
  70. */
  71. char *saveptr = nullptr;
  72. char *s = strdup(path);
  73. char *devtype = strtok_r(s, ":", &saveptr);
  74. char *args1 = strtok_r(nullptr, ":", &saveptr);
  75. char *args2 = strtok_r(nullptr, ":", &saveptr);
  76. if (strcmp(devtype, "tcp") == 0) {
  77. uint16_t port = atoi(args1);
  78. bool wait = (args2 && strcmp(args2, "wait") == 0);
  79. _tcp_start_connection(port, wait);
  80. } else if (strcmp(devtype, "tcpclient") == 0) {
  81. if (args2 == nullptr) {
  82. AP_HAL::panic("Invalid tcp client path: %s", path);
  83. }
  84. uint16_t port = atoi(args2);
  85. _tcp_start_client(args1, port);
  86. } else if (strcmp(devtype, "uart") == 0) {
  87. uint32_t baudrate = args2? atoi(args2) : baud;
  88. ::printf("UART connection %s:%u\n", args1, baudrate);
  89. _uart_path = strdup(args1);
  90. _uart_baudrate = baudrate;
  91. _uart_start_connection();
  92. } else if (strcmp(devtype, "sim") == 0) {
  93. ::printf("SIM connection %s:%s on port %u\n", args1, args2, _portNumber);
  94. if (!_connected) {
  95. _connected = true;
  96. _fd = _sitlState->sim_fd(args1, args2);
  97. }
  98. } else if (strcmp(devtype, "udpclient") == 0) {
  99. // udp client connection
  100. const char *ip = args1;
  101. uint16_t port = args2?atoi(args2):14550;
  102. if (!_connected) {
  103. ::printf("UDP connection %s:%u\n", ip, port);
  104. _udp_start_client(ip, port);
  105. }
  106. } else if (strcmp(devtype, "mcast") == 0) {
  107. // udp multicast connection
  108. const char *ip = args1 && *args1?args1:mcast_ip_default;
  109. uint16_t port = args2?atoi(args2):mcast_port_default;
  110. if (!_connected) {
  111. ::printf("UDP multicast connection %s:%u\n", ip, port);
  112. _udp_start_multicast(ip, port);
  113. }
  114. } else {
  115. AP_HAL::panic("Invalid device path: %s", path);
  116. }
  117. free(s);
  118. }
  119. if (hal.console != this) { // don't clear USB buffers (allows early startup messages to escape)
  120. _readbuffer.clear();
  121. _writebuffer.clear();
  122. }
  123. _set_nonblocking(_fd);
  124. }
  125. void UARTDriver::end()
  126. {
  127. }
  128. uint32_t UARTDriver::available(void)
  129. {
  130. _check_connection();
  131. if (!_connected) {
  132. return 0;
  133. }
  134. return _readbuffer.available();
  135. }
  136. uint32_t UARTDriver::txspace(void)
  137. {
  138. _check_connection();
  139. if (!_connected) {
  140. return 0;
  141. }
  142. return _writebuffer.space();
  143. }
  144. int16_t UARTDriver::read(void)
  145. {
  146. if (available() <= 0) {
  147. return -1;
  148. }
  149. uint8_t c;
  150. _readbuffer.read(&c, 1);
  151. return c;
  152. }
  153. void UARTDriver::flush(void)
  154. {
  155. }
  156. size_t UARTDriver::write(uint8_t c)
  157. {
  158. if (txspace() <= 0) {
  159. return 0;
  160. }
  161. _writebuffer.write(&c, 1);
  162. return 1;
  163. }
  164. size_t UARTDriver::write(const uint8_t *buffer, size_t size)
  165. {
  166. if (txspace() <= size) {
  167. size = txspace();
  168. }
  169. if (size <= 0) {
  170. return 0;
  171. }
  172. if (_unbuffered_writes) {
  173. // write buffer straight to the file descriptor
  174. const ssize_t nwritten = ::write(_fd, buffer, size);
  175. if (nwritten == -1 && errno != EAGAIN && _uart_path) {
  176. close(_fd);
  177. _fd = -1;
  178. _connected = false;
  179. }
  180. // these have no effect
  181. tcdrain(_fd);
  182. } else {
  183. _writebuffer.write(buffer, size);
  184. }
  185. return size;
  186. }
  187. /*
  188. start a TCP connection for the serial port. If wait_for_connection
  189. is true then block until a client connects
  190. */
  191. void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
  192. {
  193. int one=1;
  194. struct sockaddr_in sockaddr;
  195. int ret;
  196. if (_connected) {
  197. return;
  198. }
  199. _use_send_recv = true;
  200. if (_console) {
  201. // hack for console access
  202. _connected = true;
  203. _use_send_recv = false;
  204. _listen_fd = -1;
  205. _fd = 1;
  206. return;
  207. }
  208. if (_fd != -1) {
  209. close(_fd);
  210. }
  211. if (_listen_fd == -1) {
  212. memset(&sockaddr,0,sizeof(sockaddr));
  213. #ifdef HAVE_SOCK_SIN_LEN
  214. sockaddr.sin_len = sizeof(sockaddr);
  215. #endif
  216. if (port > 1000) {
  217. sockaddr.sin_port = htons(port);
  218. } else {
  219. sockaddr.sin_port = htons(_sitlState->base_port() + port);
  220. }
  221. sockaddr.sin_family = AF_INET;
  222. _listen_fd = socket(AF_INET, SOCK_STREAM, 0);
  223. if (_listen_fd == -1) {
  224. fprintf(stderr, "socket failed - %s\n", strerror(errno));
  225. exit(1);
  226. }
  227. ret = fcntl(_listen_fd, F_SETFD, FD_CLOEXEC);
  228. if (ret == -1) {
  229. fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno));
  230. exit(1);
  231. }
  232. /* we want to be able to re-use ports quickly */
  233. if (setsockopt(_listen_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) {
  234. fprintf(stderr, "setsockopt failed: %s\n", strerror(errno));
  235. exit(1);
  236. }
  237. fprintf(stderr, "bind port %u for %u\n",
  238. (unsigned)ntohs(sockaddr.sin_port),
  239. (unsigned)_portNumber);
  240. ret = bind(_listen_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
  241. if (ret == -1) {
  242. fprintf(stderr, "bind failed on port %u - %s\n",
  243. (unsigned)ntohs(sockaddr.sin_port),
  244. strerror(errno));
  245. exit(1);
  246. }
  247. ret = listen(_listen_fd, 5);
  248. if (ret == -1) {
  249. fprintf(stderr, "listen failed - %s\n", strerror(errno));
  250. exit(1);
  251. }
  252. fprintf(stderr, "Serial port %u on TCP port %u\n", _portNumber,
  253. _sitlState->base_port() + _portNumber);
  254. fflush(stdout);
  255. }
  256. if (wait_for_connection) {
  257. fprintf(stdout, "Waiting for connection ....\n");
  258. fflush(stdout);
  259. _fd = accept(_listen_fd, nullptr, nullptr);
  260. if (_fd == -1) {
  261. fprintf(stderr, "accept() error - %s", strerror(errno));
  262. exit(1);
  263. }
  264. setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
  265. setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
  266. fcntl(_fd, F_SETFD, FD_CLOEXEC);
  267. _connected = true;
  268. fprintf(stdout, "Connection on serial port %u\n", _portNumber);
  269. }
  270. }
  271. /*
  272. start a TCP client connection for the serial port.
  273. */
  274. void UARTDriver::_tcp_start_client(const char *address, uint16_t port)
  275. {
  276. int one=1;
  277. struct sockaddr_in sockaddr;
  278. int ret;
  279. if (_connected) {
  280. return;
  281. }
  282. _use_send_recv = true;
  283. if (_fd != -1) {
  284. close(_fd);
  285. }
  286. memset(&sockaddr,0,sizeof(sockaddr));
  287. #ifdef HAVE_SOCK_SIN_LEN
  288. sockaddr.sin_len = sizeof(sockaddr);
  289. #endif
  290. sockaddr.sin_port = htons(port);
  291. sockaddr.sin_family = AF_INET;
  292. sockaddr.sin_addr.s_addr = inet_addr(address);
  293. _fd = socket(AF_INET, SOCK_STREAM, 0);
  294. if (_fd == -1) {
  295. fprintf(stderr, "socket failed - %s\n", strerror(errno));
  296. exit(1);
  297. }
  298. ret = fcntl(_fd, F_SETFD, FD_CLOEXEC);
  299. if (ret == -1) {
  300. fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno));
  301. exit(1);
  302. }
  303. /* we want to be able to re-use ports quickly */
  304. setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
  305. ret = connect(_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
  306. if (ret == -1) {
  307. fprintf(stderr, "connect failed on port %u - %s\n",
  308. (unsigned)ntohs(sockaddr.sin_port),
  309. strerror(errno));
  310. exit(1);
  311. }
  312. setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
  313. setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
  314. fcntl(_fd, F_SETFD, FD_CLOEXEC);
  315. _connected = true;
  316. }
  317. /*
  318. start a UDP client connection for the serial port.
  319. */
  320. void UARTDriver::_udp_start_client(const char *address, uint16_t port)
  321. {
  322. struct sockaddr_in sockaddr;
  323. int ret;
  324. if (_connected) {
  325. return;
  326. }
  327. _use_send_recv = true;
  328. if (_fd != -1) {
  329. close(_fd);
  330. }
  331. memset(&sockaddr,0,sizeof(sockaddr));
  332. #ifdef HAVE_SOCK_SIN_LEN
  333. sockaddr.sin_len = sizeof(sockaddr);
  334. #endif
  335. sockaddr.sin_port = htons(port);
  336. sockaddr.sin_family = AF_INET;
  337. sockaddr.sin_addr.s_addr = inet_addr(address);
  338. _fd = socket(AF_INET, SOCK_DGRAM, 0);
  339. if (_fd == -1) {
  340. fprintf(stderr, "socket failed - %s\n", strerror(errno));
  341. exit(1);
  342. }
  343. ret = fcntl(_fd, F_SETFD, FD_CLOEXEC);
  344. if (ret == -1) {
  345. fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno));
  346. exit(1);
  347. }
  348. // try to setup for broadcast, this may fail if insufficient privileges
  349. int one = 1;
  350. setsockopt(_fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one));
  351. ret = connect(_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
  352. if (ret == -1) {
  353. fprintf(stderr, "udp connect failed on port %u - %s\n",
  354. (unsigned)ntohs(sockaddr.sin_port),
  355. strerror(errno));
  356. exit(1);
  357. }
  358. _is_udp = true;
  359. _packetise = true;
  360. _connected = true;
  361. }
  362. /*
  363. start a UDP multicast connection
  364. */
  365. void UARTDriver::_udp_start_multicast(const char *address, uint16_t port)
  366. {
  367. if (_connected) {
  368. return;
  369. }
  370. // establish the listening port
  371. struct sockaddr_in sockaddr;
  372. int ret;
  373. memset(&sockaddr,0,sizeof(sockaddr));
  374. #ifdef HAVE_SOCK_SIN_LEN
  375. sockaddr.sin_len = sizeof(sockaddr);
  376. #endif
  377. sockaddr.sin_port = htons(port);
  378. sockaddr.sin_family = AF_INET;
  379. sockaddr.sin_addr.s_addr = inet_addr(address);
  380. _mc_fd = socket(AF_INET, SOCK_DGRAM, 0);
  381. if (_mc_fd == -1) {
  382. fprintf(stderr, "socket failed - %s\n", strerror(errno));
  383. exit(1);
  384. }
  385. ret = fcntl(_mc_fd, F_SETFD, FD_CLOEXEC);
  386. if (ret == -1) {
  387. fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno));
  388. exit(1);
  389. }
  390. int one = 1;
  391. if (setsockopt(_mc_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) {
  392. fprintf(stderr, "setsockopt failed: %s\n", strerror(errno));
  393. exit(1);
  394. }
  395. // close on exec, to allow reboot
  396. fcntl(_mc_fd, F_SETFD, FD_CLOEXEC);
  397. ret = bind(_mc_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
  398. if (ret == -1) {
  399. fprintf(stderr, "multicast bind failed on port %u - %s\n",
  400. (unsigned)ntohs(sockaddr.sin_port),
  401. strerror(errno));
  402. exit(1);
  403. }
  404. struct ip_mreq mreq {};
  405. mreq.imr_multiaddr.s_addr = inet_addr(address);
  406. mreq.imr_interface.s_addr = htonl(INADDR_ANY);
  407. ret = setsockopt(_mc_fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mreq, sizeof(mreq));
  408. if (ret == -1) {
  409. fprintf(stderr, "multicast membership add failed on port %u - %s\n",
  410. (unsigned)ntohs(sockaddr.sin_port),
  411. strerror(errno));
  412. exit(1);
  413. }
  414. // now start the outgoing connection as an ordinary UDP connection
  415. _udp_start_client(address, port);
  416. }
  417. /*
  418. start a UART connection for the serial port
  419. */
  420. void UARTDriver::_uart_start_connection(void)
  421. {
  422. struct termios t {};
  423. if (!_connected) {
  424. _fd = ::open(_uart_path, O_RDWR | O_CLOEXEC);
  425. if (_fd == -1) {
  426. return;
  427. }
  428. // use much smaller buffer sizes on real UARTs
  429. _writebuffer.set_size(1024);
  430. _readbuffer.set_size(512);
  431. ::printf("Opened %s\n", _uart_path);
  432. }
  433. if (_fd == -1) {
  434. AP_HAL::panic("Unable to open UART %s", _uart_path);
  435. }
  436. // set non-blocking
  437. int flags = fcntl(_fd, F_GETFL, 0);
  438. flags = flags | O_NONBLOCK;
  439. fcntl(_fd, F_SETFL, flags);
  440. // disable LF -> CR/LF
  441. tcgetattr(_fd, &t);
  442. t.c_iflag &= ~(BRKINT | ICRNL | IMAXBEL | IXON | IXOFF);
  443. t.c_oflag &= ~(OPOST | ONLCR);
  444. t.c_lflag &= ~(ISIG | ICANON | IEXTEN | ECHO | ECHOE | ECHOK | ECHOCTL | ECHOKE);
  445. t.c_cc[VMIN] = 0;
  446. if (_sitlState->use_rtscts()) {
  447. t.c_cflag |= CRTSCTS;
  448. }
  449. tcsetattr(_fd, TCSANOW, &t);
  450. // set baudrate
  451. set_speed(_uart_baudrate);
  452. _connected = true;
  453. _use_send_recv = false;
  454. }
  455. /*
  456. see if a new connection is coming in
  457. */
  458. void UARTDriver::_check_connection(void)
  459. {
  460. if (_connected) {
  461. // we only want 1 connection at a time
  462. return;
  463. }
  464. if (_select_check(_listen_fd)) {
  465. _fd = accept(_listen_fd, nullptr, nullptr);
  466. if (_fd != -1) {
  467. int one = 1;
  468. _connected = true;
  469. setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
  470. setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
  471. fcntl(_fd, F_SETFD, FD_CLOEXEC);
  472. fprintf(stdout, "New connection on serial port %u\n", _portNumber);
  473. }
  474. }
  475. }
  476. /*
  477. use select() to see if something is pending
  478. */
  479. bool UARTDriver::_select_check(int fd)
  480. {
  481. if (fd == -1) {
  482. return false;
  483. }
  484. fd_set fds;
  485. struct timeval tv;
  486. FD_ZERO(&fds);
  487. FD_SET(fd, &fds);
  488. // zero time means immediate return from select()
  489. tv.tv_sec = 0;
  490. tv.tv_usec = 0;
  491. if (select(fd+1, &fds, nullptr, nullptr, &tv) == 1) {
  492. return true;
  493. }
  494. return false;
  495. }
  496. void UARTDriver::_set_nonblocking(int fd)
  497. {
  498. unsigned v = fcntl(fd, F_GETFL, 0);
  499. fcntl(fd, F_SETFL, v | O_NONBLOCK);
  500. }
  501. bool UARTDriver::set_unbuffered_writes(bool on) {
  502. if (_fd == -1) {
  503. return false;
  504. }
  505. _unbuffered_writes = on;
  506. // this has no effect
  507. unsigned v = fcntl(_fd, F_GETFL, 0);
  508. v &= ~O_NONBLOCK;
  509. #if defined(__APPLE__) && defined(__MACH__)
  510. fcntl(_fd, F_SETFL | F_NOCACHE, v | O_SYNC);
  511. #else
  512. fcntl(_fd, F_SETFL, v | O_DIRECT | O_SYNC);
  513. #endif
  514. return _unbuffered_writes;
  515. }
  516. void UARTDriver::_check_reconnect(void)
  517. {
  518. if (!_uart_path) {
  519. return;
  520. }
  521. _uart_start_connection();
  522. }
  523. void UARTDriver::_timer_tick(void)
  524. {
  525. if (!_connected) {
  526. _check_reconnect();
  527. return;
  528. }
  529. ssize_t nwritten;
  530. uint32_t max_bytes = 10000;
  531. SITL::SITL *_sitl = AP::sitl();
  532. if (_sitl && _sitl->telem_baudlimit_enable) {
  533. // limit byte rate to configured baudrate
  534. uint32_t now = AP_HAL::micros();
  535. float dt = 1.0e-6 * (now - last_tick_us);
  536. max_bytes = _uart_baudrate * dt / 10;
  537. if (max_bytes == 0) {
  538. return;
  539. }
  540. last_tick_us = now;
  541. }
  542. if (_packetise) {
  543. uint16_t n = _writebuffer.available();
  544. n = MIN(n, max_bytes);
  545. if (n > 0) {
  546. n = mavlink_packetise(_writebuffer, n);
  547. }
  548. if (n > 0) {
  549. // keep as a single UDP packet
  550. uint8_t tmpbuf[n];
  551. _writebuffer.peekbytes(tmpbuf, n);
  552. ssize_t ret = send(_fd, tmpbuf, n, MSG_DONTWAIT);
  553. if (ret > 0) {
  554. _writebuffer.advance(ret);
  555. }
  556. }
  557. } else {
  558. uint32_t navail;
  559. const uint8_t *readptr = _writebuffer.readptr(navail);
  560. if (readptr && navail > 0) {
  561. navail = MIN(navail, max_bytes);
  562. if (!_use_send_recv) {
  563. nwritten = ::write(_fd, readptr, navail);
  564. if (nwritten == -1 && errno != EAGAIN && _uart_path) {
  565. close(_fd);
  566. _fd = -1;
  567. _connected = false;
  568. }
  569. } else {
  570. nwritten = send(_fd, readptr, navail, MSG_DONTWAIT);
  571. }
  572. if (nwritten > 0) {
  573. _writebuffer.advance(nwritten);
  574. }
  575. }
  576. }
  577. uint32_t space = _readbuffer.space();
  578. if (space == 0) {
  579. return;
  580. }
  581. space = MIN(space, max_bytes);
  582. char buf[space];
  583. ssize_t nread = 0;
  584. if (_mc_fd >= 0) {
  585. if (_select_check(_mc_fd)) {
  586. struct sockaddr_in from;
  587. socklen_t fromlen = sizeof(from);
  588. nread = recvfrom(_mc_fd, buf, space, MSG_DONTWAIT, (struct sockaddr *)&from, &fromlen);
  589. uint16_t port = ntohs(from.sin_port);
  590. if (_mc_myport == 0) {
  591. // get our own address, so we can recognise packets from ourself
  592. struct sockaddr_in myaddr;
  593. socklen_t myaddrlen;
  594. if (getsockname(_fd, (struct sockaddr *)&myaddr, &myaddrlen) == 0) {
  595. _mc_myport = ntohs(myaddr.sin_port);
  596. }
  597. }
  598. if (_mc_myport == port) {
  599. // assume this is a packet from ourselves. This is not
  600. // entirely accurate, as it could be a packet from
  601. // another machine that has assigned the same port,
  602. // unfortunately we don't have a better way to detect
  603. // packets from ourselves
  604. nread = 0;
  605. }
  606. }
  607. } else if (!_use_send_recv) {
  608. if (!_select_check(_fd)) {
  609. return;
  610. }
  611. int fd = _console?0:_fd;
  612. nread = ::read(fd, buf, space);
  613. if (nread == -1 && errno != EAGAIN && _uart_path) {
  614. close(_fd);
  615. _fd = -1;
  616. _connected = false;
  617. }
  618. } else if (_select_check(_fd)) {
  619. nread = recv(_fd, buf, space, MSG_DONTWAIT);
  620. if (nread <= 0 && !_is_udp) {
  621. // the socket has reached EOF
  622. close(_fd);
  623. _fd = -1;
  624. _connected = false;
  625. fprintf(stdout, "Closed connection on serial port %u\n", _portNumber);
  626. fflush(stdout);
  627. return;
  628. }
  629. }
  630. if (nread > 0) {
  631. _readbuffer.write((uint8_t *)buf, nread);
  632. _receive_timestamp = AP_HAL::micros64();
  633. }
  634. }
  635. /*
  636. return timestamp estimate in microseconds for when the start of
  637. a nbytes packet arrived on the uart. This should be treated as a
  638. time constraint, not an exact time. It is guaranteed that the
  639. packet did not start being received after this time, but it
  640. could have been in a system buffer before the returned time.
  641. This takes account of the baudrate of the link. For transports
  642. that have no baudrate (such as USB) the time estimate may be
  643. less accurate.
  644. A return value of zero means the HAL does not support this API
  645. */
  646. uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
  647. {
  648. uint64_t last_receive_us = _receive_timestamp;
  649. if (_uart_baudrate > 0) {
  650. // assume 10 bits per byte.
  651. uint32_t transport_time_us = (1000000UL * 10UL / _uart_baudrate) * (nbytes+available());
  652. last_receive_us -= transport_time_us;
  653. }
  654. return last_receive_us;
  655. }
  656. #endif // CONFIG_HAL_BOARD