rc.cpp 4.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184
  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. SBUS output support
  15. */
  16. #include "ch.h"
  17. #include "hal.h"
  18. #include "iofirmware.h"
  19. #include "rc.h"
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <AP_Math/AP_Math.h>
  22. #include <AP_SBusOut/AP_SBusOut.h>
  23. extern const AP_HAL::HAL& hal;
  24. // usart3 is for SBUS input and output
  25. static const SerialConfig uart3_cfg = {
  26. 100000, // speed
  27. USART_CR1_PCE | USART_CR1_M, // cr1, enable even parity
  28. USART_CR2_STOP_1, // cr2, two stop bits
  29. 0, // cr3
  30. nullptr, // irq_cb
  31. nullptr, // ctx
  32. };
  33. // listen for parity errors on sd3 input
  34. static event_listener_t sd3_listener;
  35. void sbus_out_write(uint16_t *channels, uint8_t nchannels)
  36. {
  37. uint8_t buffer[25];
  38. AP_SBusOut::sbus_format_frame(channels, nchannels, buffer);
  39. chnWrite(&SD3, buffer, sizeof(buffer));
  40. }
  41. // usart1 is for DSM input and (optionally) debug to FMU
  42. static const SerialConfig uart1_cfg = {
  43. 115200, // speed
  44. 0, // cr1
  45. 0, // cr2
  46. 0, // cr3
  47. nullptr, // irq_cb
  48. nullptr, // ctx
  49. };
  50. /*
  51. init rcin on DSM USART1
  52. */
  53. void AP_IOMCU_FW::rcin_serial_init(void)
  54. {
  55. sdStart(&SD1, &uart1_cfg);
  56. sdStart(&SD3, &uart3_cfg);
  57. chEvtRegisterMaskWithFlags(chnGetEventSource(&SD3),
  58. &sd3_listener,
  59. EVENT_MASK(1),
  60. SD_PARITY_ERROR);
  61. // disable input for SBUS with pulses, we will use the UART for
  62. // SBUS.
  63. AP::RC().disable_for_pulses(AP_RCProtocol::SBUS);
  64. AP::RC().disable_for_pulses(AP_RCProtocol::SBUS_NI);
  65. }
  66. static struct {
  67. uint32_t num_dsm_bytes;
  68. uint32_t num_sbus_bytes;
  69. uint32_t num_sbus_errors;
  70. eventflags_t sbus_error;
  71. } rc_stats;
  72. /*
  73. check for data on DSM RX uart
  74. */
  75. void AP_IOMCU_FW::rcin_serial_update(void)
  76. {
  77. uint8_t b[16];
  78. uint32_t n;
  79. // read from DSM port
  80. if ((n = chnReadTimeout(&SD1, b, sizeof(b), TIME_IMMEDIATE)) > 0) {
  81. n = MIN(n, sizeof(b));
  82. rc_stats.num_dsm_bytes += n;
  83. for (uint8_t i=0; i<n; i++) {
  84. AP::RC().process_byte(b[i], 115200);
  85. }
  86. //BLUE_TOGGLE();
  87. }
  88. // read from SBUS port
  89. if ((n = chnReadTimeout(&SD3, b, sizeof(b), TIME_IMMEDIATE)) > 0) {
  90. eventflags_t flags;
  91. if ((flags = chEvtGetAndClearFlags(&sd3_listener)) & SD_PARITY_ERROR) {
  92. rc_stats.sbus_error = flags;
  93. rc_stats.num_sbus_errors++;
  94. } else {
  95. n = MIN(n, sizeof(b));
  96. rc_stats.num_sbus_bytes += n;
  97. for (uint8_t i=0; i<n; i++) {
  98. AP::RC().process_byte(b[i], 100000);
  99. }
  100. }
  101. }
  102. }
  103. /*
  104. sleep for 1ms using a busy loop
  105. */
  106. static void delay_one_ms(uint32_t &now)
  107. {
  108. while (now == AP_HAL::millis()) ;
  109. now = AP_HAL::millis();
  110. }
  111. /*
  112. perform a DSM bind operation
  113. */
  114. void AP_IOMCU_FW::dsm_bind_step(void)
  115. {
  116. uint32_t now = last_ms;
  117. switch (dsm_bind_state) {
  118. case 1:
  119. palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, PAL_MODE_OUTPUT_PUSHPULL);
  120. SPEKTRUM_POWER(0);
  121. palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_OUT, PAL_MODE_OUTPUT_PUSHPULL);
  122. SPEKTRUM_SET(1);
  123. dsm_bind_state = 2;
  124. last_dsm_bind_ms = now;
  125. break;
  126. case 2:
  127. if (now - last_dsm_bind_ms >= 500) {
  128. SPEKTRUM_POWER(1);
  129. dsm_bind_state = 3;
  130. last_dsm_bind_ms = now;
  131. }
  132. break;
  133. case 3: {
  134. if (now - last_dsm_bind_ms >= 72) {
  135. // 9 pulses works with all satellite receivers, and supports the highest
  136. // available protocol
  137. delay_one_ms(now);
  138. const uint8_t num_pulses = 9;
  139. for (uint8_t i=0; i<num_pulses; i++) {
  140. // the delay should be 120us, but we are running our
  141. // clock at 1kHz, and 1ms works fine
  142. delay_one_ms(now);
  143. SPEKTRUM_SET(0);
  144. delay_one_ms(now);
  145. SPEKTRUM_SET(1);
  146. }
  147. last_dsm_bind_ms = now;
  148. dsm_bind_state = 4;
  149. }
  150. break;
  151. }
  152. case 4:
  153. if (now - last_dsm_bind_ms >= 50) {
  154. // set back as input pin
  155. palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_OUT, PAL_MODE_INPUT);
  156. dsm_bind_state = 0;
  157. }
  158. break;
  159. default:
  160. dsm_bind_state = 0;
  161. break;
  162. }
  163. }