UARTDriver.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486
  1. #include "UARTDriver.h"
  2. #include <arpa/inet.h>
  3. #include <assert.h>
  4. #include <errno.h>
  5. #include <fcntl.h>
  6. #include <netinet/in.h>
  7. #include <netinet/tcp.h>
  8. #include <poll.h>
  9. #include <stdio.h>
  10. #include <stdlib.h>
  11. #include <string.h>
  12. #include <sys/ioctl.h>
  13. #include <sys/socket.h>
  14. #include <sys/stat.h>
  15. #include <sys/types.h>
  16. #include <termios.h>
  17. #include <unistd.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include "ConsoleDevice.h"
  20. #include "TCPServerDevice.h"
  21. #include "UARTDevice.h"
  22. #include "UDPDevice.h"
  23. #include <GCS_MAVLink/GCS.h>
  24. #include <AP_HAL/utility/packetise.h>
  25. extern const AP_HAL::HAL& hal;
  26. using namespace Linux;
  27. UARTDriver::UARTDriver(bool default_console) :
  28. device_path(nullptr),
  29. _packetise(false),
  30. _device{new ConsoleDevice()}
  31. {
  32. if (default_console) {
  33. _console = true;
  34. }
  35. }
  36. /*
  37. set the tty device to use for this UART
  38. */
  39. void UARTDriver::set_device_path(const char *path)
  40. {
  41. device_path = path;
  42. }
  43. /*
  44. open the tty
  45. */
  46. void UARTDriver::begin(uint32_t b)
  47. {
  48. begin(b, 0, 0);
  49. }
  50. void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
  51. {
  52. if (!_initialised) {
  53. if (device_path == nullptr && _console) {
  54. _device = new ConsoleDevice();
  55. } else {
  56. if (device_path == nullptr) {
  57. return;
  58. }
  59. _device = _parseDevicePath(device_path);
  60. if (!_device.get()) {
  61. ::fprintf(stderr, "Argument is not valid. Fallback to console.\n"
  62. "Launch with --help to see an example.\n");
  63. _device = new ConsoleDevice();
  64. }
  65. }
  66. }
  67. if (!_connected) {
  68. _connected = _device->open();
  69. _device->set_blocking(false);
  70. }
  71. _initialised = false;
  72. while (_in_timer) hal.scheduler->delay(1);
  73. _device->set_speed(b);
  74. bool clear_buffers = false;
  75. if (b != 0) {
  76. if (_baudrate != b && hal.console != this) {
  77. clear_buffers = true;
  78. }
  79. _baudrate = b;
  80. }
  81. _allocate_buffers(rxS, txS);
  82. if (clear_buffers) {
  83. _readbuf.clear();
  84. _writebuf.clear();
  85. }
  86. }
  87. void UARTDriver::_allocate_buffers(uint16_t rxS, uint16_t txS)
  88. {
  89. /* we have enough memory to have a larger transmit buffer for
  90. * all ports. This means we don't get delays while waiting to
  91. * write GPS config packets
  92. */
  93. if (rxS < 8192) {
  94. rxS = 8192;
  95. }
  96. if (txS < 32000) {
  97. txS = 32000;
  98. }
  99. if (_writebuf.set_size(txS) && _readbuf.set_size(rxS)) {
  100. _initialised = true;
  101. }
  102. }
  103. void UARTDriver::_deallocate_buffers()
  104. {
  105. _readbuf.set_size(0);
  106. _writebuf.set_size(0);
  107. }
  108. /*
  109. Device path accepts the following syntaxes:
  110. - /dev/ttyO1
  111. - tcp:*:1243:wait
  112. - udp:192.168.2.15:1243
  113. */
  114. AP_HAL::OwnPtr<SerialDevice> UARTDriver::_parseDevicePath(const char *arg)
  115. {
  116. struct stat st;
  117. if (stat(arg, &st) == 0 && S_ISCHR(st.st_mode)) {
  118. return AP_HAL::OwnPtr<SerialDevice>(new UARTDevice(arg));
  119. } else if (strncmp(arg, "tcp:", 4) != 0 &&
  120. strncmp(arg, "udp:", 4) != 0 &&
  121. strncmp(arg, "udpin:", 6)) {
  122. return nullptr;
  123. }
  124. char *devstr = strdup(arg);
  125. if (devstr == nullptr) {
  126. return nullptr;
  127. }
  128. char *saveptr = nullptr;
  129. char *protocol, *ip, *port, *flag;
  130. protocol = strtok_r(devstr, ":", &saveptr);
  131. ip = strtok_r(nullptr, ":", &saveptr);
  132. port = strtok_r(nullptr, ":", &saveptr);
  133. flag = strtok_r(nullptr, ":", &saveptr);
  134. if (ip == nullptr || port == nullptr) {
  135. free(devstr);
  136. return nullptr;
  137. }
  138. if (_ip) {
  139. free(_ip);
  140. _ip = nullptr;
  141. }
  142. if (_flag) {
  143. free(_flag);
  144. _flag = nullptr;
  145. }
  146. _base_port = (uint16_t) atoi(port);
  147. _ip = strdup(ip);
  148. /* Optional flag for TCP */
  149. if (flag != nullptr) {
  150. _flag = strdup(flag);
  151. }
  152. AP_HAL::OwnPtr<SerialDevice> device = nullptr;
  153. if (strcmp(protocol, "udp") == 0 || strcmp(protocol, "udpin") == 0) {
  154. bool bcast = (_flag && strcmp(_flag, "bcast") == 0);
  155. _packetise = true;
  156. if (strcmp(protocol, "udp") == 0) {
  157. device = new UDPDevice(_ip, _base_port, bcast, false);
  158. } else {
  159. if (bcast) {
  160. AP_HAL::panic("Can't combine udpin with bcast");
  161. }
  162. device = new UDPDevice(_ip, _base_port, false, true);
  163. }
  164. } else {
  165. bool wait = (_flag && strcmp(_flag, "wait") == 0);
  166. device = new TCPServerDevice(_ip, _base_port, wait);
  167. }
  168. free(devstr);
  169. return device;
  170. }
  171. /*
  172. shutdown a UART
  173. */
  174. void UARTDriver::end()
  175. {
  176. _initialised = false;
  177. _connected = false;
  178. while (_in_timer) {
  179. hal.scheduler->delay(1);
  180. }
  181. _device->close();
  182. _deallocate_buffers();
  183. }
  184. void UARTDriver::flush()
  185. {
  186. // we are not doing any buffering, so flush is a no-op
  187. }
  188. /*
  189. return true if the UART is initialised
  190. */
  191. bool UARTDriver::is_initialized()
  192. {
  193. return _initialised;
  194. }
  195. /*
  196. enable or disable blocking writes
  197. */
  198. void UARTDriver::set_blocking_writes(bool blocking)
  199. {
  200. _nonblocking_writes = !blocking;
  201. }
  202. /*
  203. do we have any bytes pending transmission?
  204. */
  205. bool UARTDriver::tx_pending()
  206. {
  207. return (_writebuf.available() > 0);
  208. }
  209. /*
  210. return the number of bytes available to be read
  211. */
  212. uint32_t UARTDriver::available()
  213. {
  214. if (!_initialised) {
  215. return 0;
  216. }
  217. return _readbuf.available();
  218. }
  219. /*
  220. how many bytes are available in the output buffer?
  221. */
  222. uint32_t UARTDriver::txspace()
  223. {
  224. if (!_initialised) {
  225. return 0;
  226. }
  227. return _writebuf.space();
  228. }
  229. int16_t UARTDriver::read()
  230. {
  231. if (!_initialised) {
  232. return -1;
  233. }
  234. uint8_t byte;
  235. if (!_readbuf.read_byte(&byte)) {
  236. return -1;
  237. }
  238. return byte;
  239. }
  240. /* Linux implementations of Print virtual methods */
  241. size_t UARTDriver::write(uint8_t c)
  242. {
  243. if (!_initialised) {
  244. return 0;
  245. }
  246. if (!_write_mutex.take_nonblocking()) {
  247. return 0;
  248. }
  249. while (_writebuf.space() == 0) {
  250. if (_nonblocking_writes) {
  251. _write_mutex.give();
  252. return 0;
  253. }
  254. hal.scheduler->delay(1);
  255. }
  256. size_t ret = _writebuf.write(&c, 1);
  257. _write_mutex.give();
  258. return ret;
  259. }
  260. /*
  261. write size bytes to the write buffer
  262. */
  263. size_t UARTDriver::write(const uint8_t *buffer, size_t size)
  264. {
  265. if (!_initialised) {
  266. return 0;
  267. }
  268. if (!_write_mutex.take_nonblocking()) {
  269. return 0;
  270. }
  271. if (!_nonblocking_writes) {
  272. /*
  273. use the per-byte delay loop in write() above for blocking writes
  274. */
  275. size_t ret = 0;
  276. while (size--) {
  277. if (write(*buffer++) != 1) break;
  278. ret++;
  279. }
  280. _write_mutex.give();
  281. return ret;
  282. }
  283. size_t ret = _writebuf.write(buffer, size);
  284. _write_mutex.give();
  285. return ret;
  286. }
  287. /*
  288. try writing n bytes, handling an unresponsive port
  289. */
  290. int UARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
  291. {
  292. /*
  293. allow for delayed connection. This allows ArduPilot to start
  294. before a network interface is available.
  295. */
  296. if (!_connected) {
  297. _connected = _device->open();
  298. }
  299. if (!_connected) {
  300. return 0;
  301. }
  302. return _device->write(buf, n);
  303. }
  304. /*
  305. try reading n bytes, handling an unresponsive port
  306. */
  307. int UARTDriver::_read_fd(uint8_t *buf, uint16_t n)
  308. {
  309. return _device->read(buf, n);
  310. }
  311. /*
  312. try to push out one lump of pending bytes
  313. return true if progress is made
  314. */
  315. bool UARTDriver::_write_pending_bytes(void)
  316. {
  317. // write any pending bytes
  318. uint32_t available_bytes = _writebuf.available();
  319. uint16_t n = available_bytes;
  320. if (_packetise && n > 0) {
  321. // send on MAVLink packet boundaries if possible
  322. n = mavlink_packetise(_writebuf, n);
  323. }
  324. if (n > 0) {
  325. int ret;
  326. if (_packetise) {
  327. // keep as a single UDP packet
  328. uint8_t tmpbuf[n];
  329. _writebuf.peekbytes(tmpbuf, n);
  330. ret = _write_fd(tmpbuf, n);
  331. if (ret > 0)
  332. _writebuf.advance(ret);
  333. } else {
  334. ByteBuffer::IoVec vec[2];
  335. const auto n_vec = _writebuf.peekiovec(vec, n);
  336. for (int i = 0; i < n_vec; i++) {
  337. ret = _write_fd(vec[i].data, (uint16_t)vec[i].len);
  338. if (ret < 0) {
  339. break;
  340. }
  341. _writebuf.advance(ret);
  342. /* We wrote less than we asked for, stop */
  343. if ((unsigned)ret != vec[i].len) {
  344. break;
  345. }
  346. }
  347. }
  348. }
  349. return _writebuf.available() != available_bytes;
  350. }
  351. /*
  352. push any pending bytes to/from the serial port. This is called at
  353. 1kHz in the timer thread. Doing it this way reduces the system call
  354. overhead in the main task enormously.
  355. */
  356. void UARTDriver::_timer_tick(void)
  357. {
  358. if (!_initialised) return;
  359. _in_timer = true;
  360. uint8_t num_send = 10;
  361. while (num_send != 0 && _write_pending_bytes()) {
  362. num_send--;
  363. }
  364. // try to fill the read buffer
  365. int ret;
  366. ByteBuffer::IoVec vec[2];
  367. const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
  368. for (int i = 0; i < n_vec; i++) {
  369. ret = _read_fd(vec[i].data, vec[i].len);
  370. if (ret < 0) {
  371. break;
  372. }
  373. _readbuf.commit((unsigned)ret);
  374. // update receive timestamp
  375. _receive_timestamp[_receive_timestamp_idx^1] = AP_HAL::micros64();
  376. _receive_timestamp_idx ^= 1;
  377. /* stop reading as we read less than we asked for */
  378. if ((unsigned)ret < vec[i].len) {
  379. break;
  380. }
  381. }
  382. _in_timer = false;
  383. }
  384. void UARTDriver::configure_parity(uint8_t v) {
  385. _device->set_parity(v);
  386. }
  387. /*
  388. return timestamp estimate in microseconds for when the start of
  389. a nbytes packet arrived on the uart. This should be treated as a
  390. time constraint, not an exact time. It is guaranteed that the
  391. packet did not start being received after this time, but it
  392. could have been in a system buffer before the returned time.
  393. This takes account of the baudrate of the link. For transports
  394. that have no baudrate (such as USB) the time estimate may be
  395. less accurate.
  396. A return value of zero means the HAL does not support this API
  397. */
  398. uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
  399. {
  400. uint64_t last_receive_us = _receive_timestamp[_receive_timestamp_idx];
  401. if (_baudrate > 0) {
  402. // assume 10 bits per byte.
  403. uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes+available());
  404. last_receive_us -= transport_time_us;
  405. }
  406. return last_receive_us;
  407. }