APM:Libraries
RCInput.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <atomic>
4 
5 #include "AP_HAL_Linux.h"
6 
7 #define LINUX_RC_INPUT_NUM_CHANNELS 16
8 
9 namespace Linux {
10 
11 class RCInput : public AP_HAL::RCInput {
12 public:
13  RCInput();
14 
15  static RCInput *from(AP_HAL::RCInput *rcinput) {
16  return static_cast<RCInput*>(rcinput);
17  }
18 
19  virtual void init();
20  bool new_input();
21  uint8_t num_channels();
22  uint16_t read(uint8_t ch);
23  uint8_t read(uint16_t* periods, uint8_t len);
24 
25  int16_t get_rssi(void) override {
26  return _rssi;
27  }
28 
29  bool set_override(uint8_t channel, int16_t override);
30  void clear_overrides();
31 
32  // default empty _timer_tick, this is overridden by board
33  // specific implementations
34  virtual void _timer_tick() {}
35 
36  // add some DSM input bytes, for RCInput over a serial port
37  bool add_dsm_input(const uint8_t *bytes, size_t nbytes);
38 
39  // add some SBUS input bytes, for RCInput over a serial port
40  void add_sbus_input(const uint8_t *bytes, size_t nbytes);
41 
42  // add some SUMD input bytes, for RCInput over a serial port
43  bool add_sumd_input(const uint8_t *bytes, size_t nbytes);
44 
45  // add some st24 input bytes, for RCInput over a serial port
46  bool add_st24_input(const uint8_t *bytes, size_t nbytes);
47 
48  // add some srxl input bytes, for RCInput over a serial port
49  bool add_srxl_input(const uint8_t *bytes, size_t nbytes);
50 
51 protected:
52  void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1);
53  void _update_periods(uint16_t *periods, uint8_t len);
54 
55  std::atomic<unsigned int> rc_input_count;
56  std::atomic<unsigned int> last_rc_input_count;
57 
59  uint8_t _num_channels;
60 
61  void _process_ppmsum_pulse(uint16_t width);
62  void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1);
63  void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1);
64 
65  /* override state */
67 
68  // state of ppm decoder
69  struct {
72  } ppm_state;
73 
74  // state of SBUS bit decoder
75  struct {
76  uint16_t bytes[25]; // including start bit, parity and stop bits
77  uint16_t bit_ofs;
78  } sbus_state;
79 
80  // state of DSM decoder
81  struct {
82  uint16_t bytes[16]; // including start bit and stop bit
83  uint16_t bit_ofs;
84  } dsm_state;
85 
86  // state of add_dsm_input
87  struct {
88  uint8_t frame[16];
90  uint32_t last_input_ms;
91  } dsm;
92 
93  // state of add_sbus_input
94  struct {
95  uint8_t frame[25];
96  uint8_t partial_frame_count;
97  uint32_t last_input_ms;
98  } sbus;
99 
100  int16_t _rssi = -1;
101 };
102 
103 }
uint16_t _pulse_capt[LINUX_RC_INPUT_NUM_CHANNELS]
Definition: RCInput.h:71
#define LINUX_RC_INPUT_NUM_CHANNELS
Definition: RCInput.h:7
bool set_override(uint8_t channel, int16_t override)
Definition: RCInput.cpp:71
virtual void init()
Definition: RCInput.cpp:33
std::atomic< unsigned int > rc_input_count
Definition: RCInput.h:55
bool add_st24_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:449
int16_t _rssi
Definition: RCInput.h:100
uint8_t num_channels()
Definition: RCInput.cpp:46
void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:227
bool new_input()
Definition: RCInput.cpp:37
struct Linux::RCInput::@96 dsm
void _process_ppmsum_pulse(uint16_t width)
Definition: RCInput.cpp:95
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:308
struct Linux::RCInput::@93 ppm_state
bool add_srxl_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:480
uint32_t last_input_ms
Definition: RCInput.h:90
void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:144
int8_t _channel_counter
Definition: RCInput.h:70
std::atomic< unsigned int > last_rc_input_count
Definition: RCInput.h:56
uint16_t bit_ofs
Definition: RCInput.h:77
bool add_sumd_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:418
struct Linux::RCInput::@94 sbus_state
static RCInput * from(AP_HAL::RCInput *rcinput)
Definition: RCInput.h:15
struct Linux::RCInput::@95 dsm_state
virtual void _timer_tick()
Definition: RCInput.h:34
uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS]
Definition: RCInput.h:58
uint8_t partial_frame_count
Definition: RCInput.h:89
int16_t get_rssi(void) override
Definition: RCInput.h:25
uint16_t _override[LINUX_RC_INPUT_NUM_CHANNELS]
Definition: RCInput.h:66
bool add_dsm_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:349
uint16_t read(uint8_t ch)
Definition: RCInput.cpp:51
struct Linux::RCInput::@97 sbus
uint16_t bytes[25]
Definition: RCInput.h:76
uint8_t frame[16]
Definition: RCInput.h:88
uint8_t _num_channels
Definition: RCInput.h:59
void _update_periods(uint16_t *periods, uint8_t len)
Definition: RCInput.cpp:333
void add_sbus_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:511
void clear_overrides()
Definition: RCInput.cpp:84