APM:Libraries
RC_parser.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "Config.h"
4 
5 class F4Light::_parser { // universal parser interface
6 public:
7  _parser() {};
8  virtual ~_parser() {};
9 
10  virtual void init(uint8_t ch) = 0;
11  virtual void late_init(uint8_t b) {}
12 
13  virtual uint64_t get_last_signal() const { noInterrupts(); uint64_t t= _last_signal; interrupts(); return t; }
14  virtual uint64_t get_last_change() const { noInterrupts(); uint64_t t= _last_change; interrupts(); return t; }
15  virtual uint8_t get_valid_channels() const { noInterrupts(); uint8_t t= _channels; interrupts(); return t; }
16  virtual uint16_t get_val(uint8_t ch) const { noInterrupts(); uint16_t t= _val[ch]; interrupts(); return t; }
17 
18  virtual bool bind(int dsmMode) const { return true; }
19 
20 protected:
21  volatile uint64_t _last_signal;
22  volatile uint16_t _val[F4Light_RC_INPUT_NUM_CHANNELS];
23  uint64_t _last_change;
24  volatile uint8_t _channels;
25 
26 };
virtual uint64_t get_last_signal() const
Definition: RC_parser.h:13
static INLINE void noInterrupts()
Definition: exti.h:120
virtual void late_init(uint8_t b)
Definition: RC_parser.h:11
static INLINE void interrupts()
Definition: exti.h:106
virtual uint64_t get_last_change() const
Definition: RC_parser.h:14
virtual uint16_t get_val(uint8_t ch) const
Definition: RC_parser.h:16
virtual void init(uint8_t ch)=0
volatile uint8_t _channels
Definition: RC_parser.h:24
volatile uint16_t _val[F4Light_RC_INPUT_NUM_CHANNELS]
Definition: RC_parser.h:22
volatile uint64_t _last_signal
Definition: RC_parser.h:21
virtual bool bind(int dsmMode) const
Definition: RC_parser.h:18
virtual uint8_t get_valid_channels() const
Definition: RC_parser.h:15
#define F4Light_RC_INPUT_NUM_CHANNELS
Definition: Config.h:12
uint64_t _last_change
Definition: RC_parser.h:23
virtual ~_parser()
Definition: RC_parser.h:8