RC_UART.cpp 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123
  1. /*
  2. take RC channels in from UART and put out as PWM
  3. */
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
  6. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  7. #define NUM_CHANNELS 4
  8. #define ESC_MAGIC 0xF7
  9. #define RC_SPEED 490
  10. #define UART uartE
  11. class RC_UART : public AP_HAL::HAL::Callbacks {
  12. public:
  13. // HAL::Callbacks implementation.
  14. void setup() override;
  15. void loop() override;
  16. private:
  17. uint8_t read_wait(void);
  18. uint8_t enable_mask;
  19. const uint32_t baudrate = 115200;
  20. uint32_t counter;
  21. };
  22. void RC_UART::setup()
  23. {
  24. hal.scheduler->delay(1000);
  25. hal.console->printf("RC_UART starting\n");
  26. hal.UART->begin(baudrate, 512, 512);
  27. hal.rcout->set_freq(0xFF, RC_SPEED);
  28. }
  29. uint8_t RC_UART::read_wait(void)
  30. {
  31. while (true) {
  32. int16_t c = hal.UART->read();
  33. if (c != -1) {
  34. // hal.console->printf("c=0x%02x\n", (unsigned)c);
  35. return c;
  36. }
  37. hal.scheduler->delay_microseconds(100);
  38. }
  39. }
  40. void RC_UART::loop()
  41. {
  42. union {
  43. uint16_t period[NUM_CHANNELS];
  44. uint8_t bytes[NUM_CHANNELS*2];
  45. } u;
  46. // wait for magic
  47. while (true) {
  48. uint8_t c = read_wait();
  49. if (c == ESC_MAGIC) break;
  50. // hal.console->printf("c=0x%02x\n", (unsigned)c);
  51. }
  52. uint8_t nbytes=0;
  53. // wait for periods
  54. while (nbytes < NUM_CHANNELS*2) {
  55. u.bytes[nbytes++] = read_wait();
  56. }
  57. // and CRC
  58. union {
  59. uint8_t crc[2];
  60. uint16_t crc16;
  61. } u2;
  62. u2.crc[0] = read_wait();
  63. u2.crc[1] = read_wait();
  64. uint16_t crc2 = crc_calculate(u.bytes, NUM_CHANNELS*2);
  65. if (crc2 != u2.crc16) {
  66. hal.console->printf("bad CRC 0x%04x should be 0x%04x\n", (unsigned)crc2, (unsigned)u2.crc16);
  67. return;
  68. }
  69. // and output
  70. for (uint8_t i=0; i<NUM_CHANNELS; i++) {
  71. if (u.period[i] == 0) {
  72. continue;
  73. }
  74. if (!(enable_mask & 1U<<i)) {
  75. if (enable_mask == 0) {
  76. hal.rcout->force_safety_off();
  77. }
  78. hal.rcout->enable_ch(i);
  79. enable_mask |= 1U<<i;
  80. }
  81. hal.rcout->write(i, u.period[i]);
  82. }
  83. // report periods to console for debug
  84. counter++;
  85. if (counter % 100 == 0) {
  86. hal.console->printf("%4u %4u %4u %4u\n",
  87. (unsigned)u.period[0],
  88. (unsigned)u.period[1],
  89. (unsigned)u.period[2],
  90. (unsigned)u.period[3]);
  91. }
  92. // every 10th frame give an RCInput frame if possible
  93. if (counter % 10 == 0) {
  94. struct PACKED {
  95. uint8_t magic = 0xf6;
  96. uint16_t rcin[8];
  97. uint16_t crc;
  98. } rcin;
  99. if (hal.rcin->new_input() && hal.rcin->read(rcin.rcin, 8) == 8) {
  100. rcin.crc = crc_calculate((uint8_t*)&rcin.rcin[0], 16);
  101. hal.UART->write((uint8_t*)&rcin, sizeof(rcin));
  102. }
  103. }
  104. }
  105. RC_UART rc_uart;
  106. AP_HAL_MAIN_CALLBACKS(&rc_uart);