RCInput.h 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101
  1. #pragma once
  2. #include <atomic>
  3. #include "AP_HAL_Linux.h"
  4. #define LINUX_RC_INPUT_NUM_CHANNELS 16
  5. namespace Linux {
  6. class RCInput : public AP_HAL::RCInput {
  7. public:
  8. RCInput();
  9. static RCInput *from(AP_HAL::RCInput *rcinput) {
  10. return static_cast<RCInput*>(rcinput);
  11. }
  12. virtual void init() override;
  13. bool new_input() override;
  14. uint8_t num_channels() override;
  15. void set_num_channels(uint8_t num);
  16. uint16_t read(uint8_t ch) override;
  17. uint8_t read(uint16_t* periods, uint8_t len) override;
  18. int16_t get_rssi(void) override {
  19. return _rssi;
  20. }
  21. const char *protocol() const override { return "Unknown"; }
  22. // default empty _timer_tick, this is overridden by board
  23. // specific implementations
  24. virtual void _timer_tick() {}
  25. // add some DSM input bytes, for RCInput over a serial port
  26. bool add_dsm_input(const uint8_t *bytes, size_t nbytes);
  27. // add some SBUS input bytes, for RCInput over a serial port
  28. void add_sbus_input(const uint8_t *bytes, size_t nbytes);
  29. // add some SUMD input bytes, for RCInput over a serial port
  30. bool add_sumd_input(const uint8_t *bytes, size_t nbytes);
  31. // add some st24 input bytes, for RCInput over a serial port
  32. bool add_st24_input(const uint8_t *bytes, size_t nbytes);
  33. // add some srxl input bytes, for RCInput over a serial port
  34. bool add_srxl_input(const uint8_t *bytes, size_t nbytes);
  35. protected:
  36. void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1);
  37. void _update_periods(uint16_t *periods, uint8_t len);
  38. std::atomic<unsigned int> rc_input_count;
  39. std::atomic<unsigned int> last_rc_input_count;
  40. uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS];
  41. uint8_t _num_channels;
  42. void _process_ppmsum_pulse(uint16_t width);
  43. void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1);
  44. void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1);
  45. void _process_pwm_pulse(uint16_t channel, uint16_t width_s0, uint16_t width_s1);
  46. // state of ppm decoder
  47. struct {
  48. int8_t _channel_counter;
  49. uint16_t _pulse_capt[LINUX_RC_INPUT_NUM_CHANNELS];
  50. } ppm_state;
  51. // state of SBUS bit decoder
  52. struct {
  53. uint16_t bytes[25]; // including start bit, parity and stop bits
  54. uint16_t bit_ofs;
  55. } sbus_state;
  56. // state of DSM decoder
  57. struct {
  58. uint16_t bytes[16]; // including start bit and stop bit
  59. uint16_t bit_ofs;
  60. } dsm_state;
  61. // state of add_dsm_input
  62. struct {
  63. uint8_t frame[16];
  64. uint8_t partial_frame_count;
  65. uint32_t last_input_ms;
  66. } dsm;
  67. // state of add_sbus_input
  68. struct {
  69. uint8_t frame[25];
  70. uint8_t partial_frame_count;
  71. uint32_t last_input_ms;
  72. } sbus;
  73. int16_t _rssi = -1;
  74. };
  75. }