RCInput_RCProtocol.cpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157
  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. this is a driver for multiple RCInput methods on one board
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <stdio.h>
  18. #include <fcntl.h>
  19. #include <unistd.h>
  20. #include <errno.h>
  21. #include <sys/ioctl.h>
  22. #include <asm/termbits.h>
  23. #include "RCInput_RCProtocol.h"
  24. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
  25. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
  26. extern const AP_HAL::HAL& hal;
  27. using namespace Linux;
  28. /*
  29. open a SBUS UART
  30. */
  31. int RCInput_RCProtocol::open_sbus(const char *path)
  32. {
  33. int fd = open(path, O_RDWR | O_NONBLOCK | O_CLOEXEC);
  34. if (fd == -1) {
  35. return -1;
  36. }
  37. struct termios2 tio {};
  38. if (ioctl(fd, TCGETS2, &tio) != 0) {
  39. close(fd);
  40. fd = -1;
  41. return -1;
  42. }
  43. tio.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR
  44. | IGNCR | ICRNL | IXON);
  45. tio.c_iflag |= (INPCK | IGNPAR);
  46. tio.c_oflag &= ~OPOST;
  47. tio.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
  48. tio.c_cflag &= ~(CSIZE | CRTSCTS | PARODD | CBAUD);
  49. // use BOTHER to specify speed directly in c_[io]speed member
  50. tio.c_cflag |= (CS8 | CSTOPB | CLOCAL | PARENB | BOTHER | CREAD);
  51. tio.c_ispeed = 100000;
  52. tio.c_ospeed = 100000;
  53. if (ioctl(fd, TCSETS2, &tio) != 0) {
  54. close(fd);
  55. fd = -1;
  56. return -1;
  57. }
  58. return fd;
  59. }
  60. /*
  61. open a 115200 UART
  62. */
  63. int RCInput_RCProtocol::open_115200(const char *path)
  64. {
  65. int fd = open(path, O_RDWR | O_NONBLOCK | O_CLOEXEC);
  66. if (fd == -1) {
  67. return -1;
  68. }
  69. struct termios2 tio {};
  70. if (ioctl(fd, TCGETS2, &tio) != 0) {
  71. close(fd);
  72. fd = -1;
  73. return -1;
  74. }
  75. tio.c_cflag &= ~(PARENB|CSTOPB|CSIZE);
  76. tio.c_cflag |= CS8 | B115200;
  77. tio.c_lflag &= ~(ICANON|ECHO|ECHOE|ISIG);
  78. tio.c_iflag &= ~(IXON|IXOFF|IXANY);
  79. tio.c_oflag &= ~OPOST;
  80. if (ioctl(fd, TCSETS2, &tio) != 0) {
  81. close(fd);
  82. fd = -1;
  83. return -1;
  84. }
  85. return fd;
  86. }
  87. // constructor
  88. RCInput_RCProtocol::RCInput_RCProtocol(const char *_dev_sbus, const char *_dev_115200) :
  89. dev_sbus(_dev_sbus),
  90. dev_115200(_dev_115200)
  91. {
  92. }
  93. void RCInput_RCProtocol::init()
  94. {
  95. if (dev_sbus) {
  96. fd_sbus = open_sbus(dev_sbus);
  97. } else {
  98. fd_sbus = -1;
  99. }
  100. if (dev_115200) {
  101. fd_115200 = open_115200(dev_115200);
  102. } else {
  103. fd_115200 = -1;
  104. }
  105. AP::RC().init();
  106. printf("SBUS FD %d 115200 FD %d\n", fd_sbus, fd_115200);
  107. }
  108. void RCInput_RCProtocol::_timer_tick(void)
  109. {
  110. uint8_t b[40];
  111. if (fd_sbus != -1) {
  112. ssize_t n = ::read(fd_sbus, &b[0], sizeof(b));
  113. if (n > 0) {
  114. for (uint8_t i=0; i<n; i++) {
  115. AP::RC().process_byte(b[i], 100000);
  116. }
  117. }
  118. }
  119. if (fd_115200 != -1) {
  120. ssize_t n = ::read(fd_115200, &b[0], sizeof(b));
  121. if (n > 0) {
  122. for (uint8_t i=0; i<n; i++) {
  123. AP::RC().process_byte(b[i], 115200);
  124. }
  125. }
  126. }
  127. if (AP::RC().new_input()) {
  128. uint8_t n = AP::RC().num_channels();
  129. for (uint8_t i=0; i<n; i++) {
  130. _pwm_values[i] = AP::RC().read(i);
  131. }
  132. _num_channels = n;
  133. rc_input_count++;
  134. }
  135. }
  136. #endif // HAL