RCProtocolDecoder.cpp 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. /*
  16. decode RC input using SITL on command line
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  20. void setup();
  21. void loop();
  22. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL
  23. #include <AP_RCProtocol/AP_RCProtocol.h>
  24. #include <stdio.h>
  25. #include <sys/types.h>
  26. #include <sys/stat.h>
  27. #include <fcntl.h>
  28. #include <time.h>
  29. #include <unistd.h>
  30. #include <stdlib.h>
  31. #include <termios.h>
  32. #include <string.h>
  33. #include <errno.h>
  34. static AP_RCProtocol *rcprot;
  35. // change this to the device being tested.
  36. const char *devname = "/dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A10596TP-if00-port0";
  37. const uint32_t baudrate = 115200;
  38. static int fd;
  39. // setup routine
  40. void setup()
  41. {
  42. // introduction
  43. hal.console->printf("ArduPilot RC protocol decoder\n");
  44. hal.scheduler->delay(100);
  45. fd = open(devname, O_RDONLY|O_CLOEXEC);
  46. if (fd == -1) {
  47. perror(devname);
  48. exit(1);
  49. }
  50. struct termios options;
  51. tcgetattr(fd, &options);
  52. cfsetspeed(&options, baudrate);
  53. tcgetattr(fd, &options);
  54. if (baudrate == 100000) {
  55. // SBUS: 100000bps, even parity, two stop bits
  56. options.c_cflag |= (CSTOPB | PARENB);
  57. } else {
  58. // DSM: 115200, one stop, no parity
  59. options.c_cflag &= ~(PARENB|CSTOPB|CSIZE);
  60. options.c_cflag |= CS8;
  61. }
  62. options.c_lflag &= ~(ICANON|ECHO|ECHOE|ISIG);
  63. options.c_iflag &= ~(IXON|IXOFF|IXANY);
  64. options.c_oflag &= ~OPOST;
  65. if (tcsetattr(fd, TCSANOW, &options) != 0) {
  66. perror("tcsetattr");
  67. exit(1);
  68. }
  69. tcflush(fd, TCIOFLUSH);
  70. rcprot = new AP_RCProtocol();
  71. rcprot->init();
  72. }
  73. //Main loop where the action takes place
  74. void loop()
  75. {
  76. uint8_t buf[32];
  77. ssize_t ret = read(fd, buf, sizeof(buf));
  78. if (ret <= 0) {
  79. return;
  80. }
  81. for (uint8_t i=0; i<ret; i++) {
  82. rcprot->process_byte(buf[i], 115200);
  83. if (rcprot->new_input()) {
  84. uint8_t nchan = rcprot->num_channels();
  85. printf("%u: ", nchan);
  86. for (uint8_t j=0; j<nchan; j++) {
  87. uint16_t v = rcprot->read(j);
  88. printf("%04u ", v);
  89. }
  90. printf("\n");
  91. }
  92. }
  93. }
  94. #else
  95. // dummy implementation
  96. void setup() {}
  97. void loop() {}
  98. #endif // CONFIG_HAL_BOARD
  99. AP_HAL_MAIN();