AP_RCProtocol.h 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  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. #pragma once
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Common/AP_Common.h>
  20. #define MAX_RCIN_CHANNELS 18
  21. #define MIN_RCIN_CHANNELS 5
  22. class AP_RCProtocol_Backend;
  23. class AP_RCProtocol {
  24. public:
  25. AP_RCProtocol() {}
  26. ~AP_RCProtocol();
  27. enum rcprotocol_t {
  28. PPM = 0,
  29. IBUS,
  30. SBUS,
  31. SBUS_NI,
  32. DSM,
  33. SUMD,
  34. SRXL,
  35. ST24,
  36. NONE //last enum always is None
  37. };
  38. void init();
  39. bool valid_serial_prot()
  40. {
  41. return _valid_serial_prot;
  42. }
  43. void process_pulse(uint32_t width_s0, uint32_t width_s1);
  44. void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
  45. void process_byte(uint8_t byte, uint32_t baudrate);
  46. void update(void);
  47. void disable_for_pulses(enum rcprotocol_t protocol) {
  48. _disabled_for_pulses |= (1U<<(uint8_t)protocol);
  49. }
  50. // for protocols without strong CRCs we require 3 good frames to lock on
  51. bool requires_3_frames(enum rcprotocol_t p) {
  52. return (p == DSM || p == SBUS || p == SBUS_NI || p == PPM);
  53. }
  54. enum rcprotocol_t protocol_detected()
  55. {
  56. return _detected_protocol;
  57. }
  58. uint8_t num_channels();
  59. uint16_t read(uint8_t chan);
  60. bool new_input();
  61. void start_bind(void);
  62. // return protocol name as a string
  63. static const char *protocol_name_from_protocol(rcprotocol_t protocol);
  64. // return protocol name as a string
  65. const char *protocol_name(void) const;
  66. // return protocol name as a string
  67. enum rcprotocol_t protocol_detected(void) const {
  68. return _detected_protocol;
  69. }
  70. // add a UART for RCIN
  71. void add_uart(AP_HAL::UARTDriver* uart);
  72. private:
  73. void check_added_uart(void);
  74. enum rcprotocol_t _detected_protocol = NONE;
  75. uint16_t _disabled_for_pulses;
  76. bool _detected_with_bytes;
  77. AP_RCProtocol_Backend *backend[NONE];
  78. bool _new_input = false;
  79. uint32_t _last_input_ms;
  80. bool _valid_serial_prot = false;
  81. uint8_t _good_frames[NONE];
  82. // optional additional uart
  83. struct {
  84. AP_HAL::UARTDriver *uart;
  85. uint32_t baudrate;
  86. bool opened;
  87. uint32_t last_baud_change_ms;
  88. } added;
  89. };
  90. namespace AP {
  91. AP_RCProtocol &RC();
  92. };
  93. #include "AP_RCProtocol_Backend.h"