RCInput.cpp 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224
  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. * Code by Andrew Tridgell and Siddharth Bharat Purohit
  16. */
  17. #include "RCInput.h"
  18. #include "hal.h"
  19. #include "hwdef/common/ppm.h"
  20. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  21. #if HAL_WITH_IO_MCU
  22. #include <AP_BoardConfig/AP_BoardConfig.h>
  23. #include <AP_IOMCU/AP_IOMCU.h>
  24. extern AP_IOMCU iomcu;
  25. #endif
  26. #include <AP_Math/AP_Math.h>
  27. #ifndef HAL_NO_UARTDRIVER
  28. #include <GCS_MAVLink/GCS.h>
  29. #endif
  30. #define SIG_DETECT_TIMEOUT_US 500000
  31. using namespace ChibiOS;
  32. extern const AP_HAL::HAL& hal;
  33. void RCInput::init()
  34. {
  35. #ifndef HAL_BUILD_AP_PERIPH
  36. AP::RC().init();
  37. #endif
  38. #if HAL_USE_ICU == TRUE
  39. //attach timer channel on which the signal will be received
  40. sig_reader.attach_capture_timer(&RCIN_ICU_TIMER, RCIN_ICU_CHANNEL, STM32_RCIN_DMA_STREAM, STM32_RCIN_DMA_CHANNEL);
  41. #endif
  42. #if HAL_USE_EICU == TRUE
  43. sig_reader.init(&RCININT_EICU_TIMER, RCININT_EICU_CHANNEL);
  44. #endif
  45. _init = true;
  46. }
  47. bool RCInput::new_input()
  48. {
  49. if (!_init) {
  50. return false;
  51. }
  52. if (!rcin_mutex.take_nonblocking()) {
  53. return false;
  54. }
  55. bool valid = _rcin_timestamp_last_signal != _last_read;
  56. _last_read = _rcin_timestamp_last_signal;
  57. rcin_mutex.give();
  58. #if HAL_RCINPUT_WITH_AP_RADIO
  59. if (!_radio_init) {
  60. _radio_init = true;
  61. radio = AP_Radio::get_singleton();
  62. if (radio) {
  63. radio->init();
  64. }
  65. }
  66. #endif
  67. return valid;
  68. }
  69. uint8_t RCInput::num_channels()
  70. {
  71. if (!_init) {
  72. return 0;
  73. }
  74. return _num_channels;
  75. }
  76. uint16_t RCInput::read(uint8_t channel)
  77. {
  78. if (!_init || (channel >= MIN(RC_INPUT_MAX_CHANNELS, _num_channels))) {
  79. return 0;
  80. }
  81. rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
  82. uint16_t v = _rc_values[channel];
  83. rcin_mutex.give();
  84. #if HAL_RCINPUT_WITH_AP_RADIO
  85. if (radio && channel == 0) {
  86. // hook to allow for update of radio on main thread, for mavlink sends
  87. radio->update();
  88. }
  89. #endif
  90. return v;
  91. }
  92. uint8_t RCInput::read(uint16_t* periods, uint8_t len)
  93. {
  94. if (!_init) {
  95. return false;
  96. }
  97. if (len > RC_INPUT_MAX_CHANNELS) {
  98. len = RC_INPUT_MAX_CHANNELS;
  99. }
  100. for (uint8_t i = 0; i < len; i++){
  101. periods[i] = read(i);
  102. }
  103. return len;
  104. }
  105. void RCInput::_timer_tick(void)
  106. {
  107. if (!_init) {
  108. return;
  109. }
  110. #ifndef HAL_NO_UARTDRIVER
  111. const char *rc_protocol = nullptr;
  112. #endif
  113. #ifndef HAL_BUILD_AP_PERIPH
  114. #if HAL_USE_ICU == TRUE
  115. const uint32_t *p;
  116. uint32_t n;
  117. while ((p = (const uint32_t *)sig_reader.sigbuf.readptr(n)) != nullptr) {
  118. AP::RC().process_pulse_list(p, n*2, sig_reader.need_swap);
  119. sig_reader.sigbuf.advance(n);
  120. }
  121. #endif
  122. #if HAL_USE_EICU == TRUE
  123. uint32_t width_s0, width_s1;
  124. while(sig_reader.read(width_s0, width_s1)) {
  125. AP::RC().process_pulse(width_s0, width_s1);
  126. }
  127. #endif
  128. if (AP::RC().new_input()) {
  129. rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
  130. _rcin_timestamp_last_signal = AP_HAL::micros();
  131. _num_channels = AP::RC().num_channels();
  132. _num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS);
  133. for (uint8_t i=0; i<_num_channels; i++) {
  134. _rc_values[i] = AP::RC().read(i);
  135. }
  136. rcin_mutex.give();
  137. #ifndef HAL_NO_UARTDRIVER
  138. rc_protocol = AP::RC().protocol_name();
  139. #endif
  140. }
  141. #endif // HAL_BUILD_AP_PERIPH
  142. #if HAL_RCINPUT_WITH_AP_RADIO
  143. if (radio && radio->last_recv_us() != last_radio_us) {
  144. last_radio_us = radio->last_recv_us();
  145. rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
  146. _rcin_timestamp_last_signal = last_radio_us;
  147. _num_channels = radio->num_channels();
  148. _num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS);
  149. for (uint8_t i=0; i<_num_channels; i++) {
  150. _rc_values[i] = radio->read(i);
  151. }
  152. rcin_mutex.give();
  153. }
  154. #endif
  155. #if HAL_WITH_IO_MCU
  156. rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
  157. if (AP_BoardConfig::io_enabled() &&
  158. iomcu.check_rcinput(last_iomcu_us, _num_channels, _rc_values, RC_INPUT_MAX_CHANNELS)) {
  159. _rcin_timestamp_last_signal = last_iomcu_us;
  160. #ifndef HAL_NO_UARTDRIVER
  161. rc_protocol = iomcu.get_rc_protocol();
  162. #endif
  163. }
  164. rcin_mutex.give();
  165. #endif
  166. #ifndef HAL_NO_UARTDRIVER
  167. if (rc_protocol && rc_protocol != last_protocol) {
  168. last_protocol = rc_protocol;
  169. gcs().send_text(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", last_protocol);
  170. }
  171. #endif
  172. // note, we rely on the vehicle code checking new_input()
  173. // and a timeout for the last valid input to handle failsafe
  174. }
  175. /*
  176. start a bind operation, if supported
  177. */
  178. bool RCInput::rc_bind(int dsmMode)
  179. {
  180. #if HAL_WITH_IO_MCU
  181. rcin_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
  182. if (AP_BoardConfig::io_enabled()) {
  183. iomcu.bind_dsm(dsmMode);
  184. }
  185. rcin_mutex.give();
  186. #endif
  187. #ifndef HAL_BUILD_AP_PERIPH
  188. // ask AP_RCProtocol to start a bind
  189. AP::RC().start_bind();
  190. #endif
  191. #if HAL_RCINPUT_WITH_AP_RADIO
  192. if (radio) {
  193. radio->start_recv_bind();
  194. }
  195. #endif
  196. return true;
  197. }
  198. #endif //#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS