APM:Libraries
RC_PPM_parser.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "RC_parser.h"
4 #include "RCInput.h"
5 
6 
7 
8 // helper class with PPM/SBUS parsers to localize all internal data
10 public:
12  : _ch(0)
13  , last_pulse({0,0})
14  , _got_ppm(false)
15  , _got_dsm(false)
16  , _was_ppm(false)
17  , _was_dsm(false)
19  {}
20 
21  void init(uint8_t ch);
22 
23  struct SbusState {
24  uint16_t bytes[25]; // including start bit, parity and stop bits
25  uint16_t bit_ofs;
27  };
28 
29 protected:
30  void parse_pulses(void);
31  void start_ioc(void);
32 
33 private:
34  void rxIntRC(uint16_t value0, uint16_t value1, bool state);
35 
36  bool _process_ppmsum_pulse(uint16_t value);
37  void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1);
38  void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, struct PPM_parser::SbusState &state);
39 
40 
41  void add_dsm_input(); // add some DSM input bytes, for RCInput over a PPMSUM line
42  void add_sbus_input(); // add some SBUS input bytes, for RCInput over a PPMSUM line
43 
44  uint8_t _ch;
45 
47  uint8_t channel_ctr;
48 
49  bool _got_ppm;
50  bool _got_dsm;
51 
52  bool _was_ppm;
53  bool _was_dsm;
54 
55  // state of add_dsm_input
56  struct DSM {
57  uint8_t frame[16];
59  uint64_t last_input_ms;
60  } dsm;
61 
62  // state of add_sbus_input
63  struct SBUS {
64  uint8_t frame[26];
66  uint32_t last_input_ms;
67  } sbus;
68 
69 
70  // state of SBUS bit decoder
71  struct SbusState sbus_state[2];
72 
73  // state of DSM bit decoder
74  struct DSM_State {
75  uint16_t bytes[16]; // including start bit and stop bit
76  uint16_t bit_ofs;
77  } dsm_state;
78 
80 
81  uint8_t _ioc;
82 };
83 
BOARD_RC_MODE
Definition: RCInput.h:23
struct SbusState sbus_state[2]
Definition: RC_PPM_parser.h:71
bool _process_ppmsum_pulse(uint16_t value)
static int state
Definition: Util.cpp:20
void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, struct PPM_parser::SbusState &state)
void init(uint8_t ch)
Definition: pwm_in.h:40
float value
void rxIntRC(uint16_t value0, uint16_t value1, bool state)
struct F4Light::PPM_parser::DSM dsm
void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
enum BOARD_RC_MODE _rc_mode
Definition: RC_PPM_parser.h:79
struct F4Light::PPM_parser::SBUS sbus
struct F4Light::PPM_parser::DSM_State dsm_state