AP_RCProtocol.cpp 8.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306
  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 "AP_RCProtocol.h"
  18. #include "AP_RCProtocol_PPMSum.h"
  19. #include "AP_RCProtocol_DSM.h"
  20. #include "AP_RCProtocol_IBUS.h"
  21. #include "AP_RCProtocol_SBUS.h"
  22. #include "AP_RCProtocol_SUMD.h"
  23. #include "AP_RCProtocol_SRXL.h"
  24. #include "AP_RCProtocol_ST24.h"
  25. #include <AP_Math/AP_Math.h>
  26. void AP_RCProtocol::init()
  27. {
  28. backend[AP_RCProtocol::PPM] = new AP_RCProtocol_PPMSum(*this);
  29. backend[AP_RCProtocol::IBUS] = new AP_RCProtocol_IBUS(*this);
  30. backend[AP_RCProtocol::SBUS] = new AP_RCProtocol_SBUS(*this, true);
  31. backend[AP_RCProtocol::SBUS_NI] = new AP_RCProtocol_SBUS(*this, false);
  32. backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this);
  33. backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this);
  34. backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this);
  35. backend[AP_RCProtocol::ST24] = new AP_RCProtocol_ST24(*this);
  36. }
  37. AP_RCProtocol::~AP_RCProtocol()
  38. {
  39. for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
  40. if (backend[i] != nullptr) {
  41. delete backend[i];
  42. backend[i] = nullptr;
  43. }
  44. }
  45. }
  46. void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
  47. {
  48. uint32_t now = AP_HAL::millis();
  49. bool searching = (now - _last_input_ms >= 200);
  50. if (_detected_protocol != AP_RCProtocol::NONE && _detected_with_bytes && !searching) {
  51. // we're using byte inputs, discard pulses
  52. return;
  53. }
  54. // first try current protocol
  55. if (_detected_protocol != AP_RCProtocol::NONE && !searching) {
  56. backend[_detected_protocol]->process_pulse(width_s0, width_s1);
  57. if (backend[_detected_protocol]->new_input()) {
  58. _new_input = true;
  59. _last_input_ms = now;
  60. }
  61. return;
  62. }
  63. // otherwise scan all protocols
  64. for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
  65. if (_disabled_for_pulses & (1U << i)) {
  66. // this protocol is disabled for pulse input
  67. continue;
  68. }
  69. if (backend[i] != nullptr) {
  70. uint32_t frame_count = backend[i]->get_rc_frame_count();
  71. uint32_t input_count = backend[i]->get_rc_input_count();
  72. backend[i]->process_pulse(width_s0, width_s1);
  73. if (frame_count != backend[i]->get_rc_frame_count()) {
  74. _good_frames[i]++;
  75. if (requires_3_frames((rcprotocol_t)i) && _good_frames[i] < 3) {
  76. continue;
  77. }
  78. _new_input = (input_count != backend[i]->get_rc_input_count());
  79. _detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i;
  80. memset(_good_frames, 0, sizeof(_good_frames));
  81. _last_input_ms = now;
  82. _detected_with_bytes = false;
  83. break;
  84. }
  85. }
  86. }
  87. }
  88. /*
  89. process an array of pulses. n must be even
  90. */
  91. void AP_RCProtocol::process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap)
  92. {
  93. if (n & 1) {
  94. return;
  95. }
  96. while (n) {
  97. uint32_t widths0 = widths[0];
  98. uint32_t widths1 = widths[1];
  99. if (need_swap) {
  100. uint32_t tmp = widths1;
  101. widths1 = widths0;
  102. widths0 = tmp;
  103. }
  104. widths1 -= widths0;
  105. process_pulse(widths0, widths1);
  106. widths += 2;
  107. n -= 2;
  108. }
  109. }
  110. void AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
  111. {
  112. uint32_t now = AP_HAL::millis();
  113. bool searching = (now - _last_input_ms >= 200);
  114. if (_detected_protocol != AP_RCProtocol::NONE && !_detected_with_bytes && !searching) {
  115. // we're using pulse inputs, discard bytes
  116. return;
  117. }
  118. // first try current protocol
  119. if (_detected_protocol != AP_RCProtocol::NONE && !searching) {
  120. backend[_detected_protocol]->process_byte(byte, baudrate);
  121. if (backend[_detected_protocol]->new_input()) {
  122. _new_input = true;
  123. _last_input_ms = now;
  124. }
  125. return;
  126. }
  127. // otherwise scan all protocols
  128. for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
  129. if (backend[i] != nullptr) {
  130. uint32_t frame_count = backend[i]->get_rc_frame_count();
  131. uint32_t input_count = backend[i]->get_rc_input_count();
  132. backend[i]->process_byte(byte, baudrate);
  133. if (frame_count != backend[i]->get_rc_frame_count()) {
  134. _good_frames[i]++;
  135. if (requires_3_frames((rcprotocol_t)i) && _good_frames[i] < 3) {
  136. continue;
  137. }
  138. _new_input = (input_count != backend[i]->get_rc_input_count());
  139. _detected_protocol = (enum AP_RCProtocol::rcprotocol_t)i;
  140. memset(_good_frames, 0, sizeof(_good_frames));
  141. _last_input_ms = now;
  142. _detected_with_bytes = true;
  143. break;
  144. }
  145. }
  146. }
  147. }
  148. /*
  149. check for bytes from an additional uart. This is used to support RC
  150. protocols from SERIALn_PROTOCOL
  151. */
  152. void AP_RCProtocol::check_added_uart(void)
  153. {
  154. if (!added.uart) {
  155. return;
  156. }
  157. uint32_t now = AP_HAL::millis();
  158. bool searching = (now - _last_input_ms >= 200);
  159. if (!searching && !_detected_with_bytes) {
  160. // not using this uart
  161. return;
  162. }
  163. if (!added.opened) {
  164. added.uart->begin(added.baudrate, 128, 128);
  165. added.opened = true;
  166. if (added.baudrate == 100000) {
  167. // assume SBUS settings, even parity, 2 stop bits
  168. added.uart->configure_parity(2);
  169. added.uart->set_stop_bits(2);
  170. added.uart->set_options(added.uart->get_options() | AP_HAL::UARTDriver::OPTION_RXINV);
  171. } else {
  172. // setup for 115200 protocols
  173. added.uart->configure_parity(0);
  174. added.uart->set_stop_bits(1);
  175. added.uart->set_options(added.uart->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV);
  176. }
  177. added.last_baud_change_ms = AP_HAL::millis();
  178. }
  179. uint32_t n = added.uart->available();
  180. n = MIN(n, 255U);
  181. for (uint8_t i=0; i<n; i++) {
  182. int16_t b = added.uart->read();
  183. if (b >= 0) {
  184. process_byte(uint8_t(b), added.baudrate);
  185. }
  186. }
  187. if (!_detected_with_bytes) {
  188. if (now - added.last_baud_change_ms > 1000) {
  189. // flip baudrates if not detected once a second
  190. added.baudrate = (added.baudrate==100000)?115200:100000;
  191. added.opened = false;
  192. }
  193. }
  194. }
  195. void AP_RCProtocol::update()
  196. {
  197. check_added_uart();
  198. }
  199. bool AP_RCProtocol::new_input()
  200. {
  201. bool ret = _new_input;
  202. _new_input = false;
  203. // if we have an extra UART from a SERIALn_PROTOCOL then check it for data
  204. check_added_uart();
  205. // run update function on backends
  206. for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
  207. if (backend[i] != nullptr) {
  208. backend[i]->update();
  209. }
  210. }
  211. return ret;
  212. }
  213. uint8_t AP_RCProtocol::num_channels()
  214. {
  215. if (_detected_protocol != AP_RCProtocol::NONE) {
  216. return backend[_detected_protocol]->num_channels();
  217. }
  218. return 0;
  219. }
  220. uint16_t AP_RCProtocol::read(uint8_t chan)
  221. {
  222. if (_detected_protocol != AP_RCProtocol::NONE) {
  223. return backend[_detected_protocol]->read(chan);
  224. }
  225. return 0;
  226. }
  227. /*
  228. ask for bind start on supported receivers (eg spektrum satellite)
  229. */
  230. void AP_RCProtocol::start_bind(void)
  231. {
  232. for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
  233. if (backend[i] != nullptr) {
  234. backend[i]->start_bind();
  235. }
  236. }
  237. }
  238. /*
  239. return protocol name
  240. */
  241. const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
  242. {
  243. switch (protocol) {
  244. case PPM:
  245. return "PPM";
  246. case IBUS:
  247. return "IBUS";
  248. case SBUS:
  249. case SBUS_NI:
  250. return "SBUS";
  251. case DSM:
  252. return "DSM";
  253. case SUMD:
  254. return "SUMD";
  255. case SRXL:
  256. return "SRXL";
  257. case ST24:
  258. return "ST24";
  259. case NONE:
  260. break;
  261. }
  262. return nullptr;
  263. }
  264. /*
  265. return protocol name
  266. */
  267. const char *AP_RCProtocol::protocol_name(void) const
  268. {
  269. return protocol_name_from_protocol(_detected_protocol);
  270. }
  271. /*
  272. add a uart to decode
  273. */
  274. void AP_RCProtocol::add_uart(AP_HAL::UARTDriver* uart)
  275. {
  276. added.uart = uart;
  277. // start with DSM
  278. added.baudrate = 115200U;
  279. }
  280. namespace AP {
  281. AP_RCProtocol &RC()
  282. {
  283. static AP_RCProtocol rcprot;
  284. return rcprot;
  285. }
  286. };