APM:Libraries
RCInput.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_VRBRAIN.h"
4 #include <drivers/drv_rc_input.h>
5 #include <systemlib/perf_counter.h>
6 #include <pthread.h>
7 
8 
9 #ifndef RC_INPUT_MAX_CHANNELS
10 #define RC_INPUT_MAX_CHANNELS 18
11 #endif
12 
14 public:
15  void init() override;
16  bool new_input() override;
17  uint8_t num_channels() override;
18  uint16_t read(uint8_t ch) override;
19  uint8_t read(uint16_t* periods, uint8_t len) override;
20 
21  int16_t get_rssi(void) override {
22  return _rssi;
23  }
24 
25 
26  bool set_override(uint8_t channel, int16_t override) override;
27  void clear_overrides() override;
28 
29  void _timer_tick(void);
30 
31  bool rc_bind(int dsmMode) override;
32 
33 private:
34  /* override state */
36  struct rc_input_values _rcin;
37  int _rc_sub;
38  uint64_t _last_read;
40  perf_counter_t _perf_rcin;
41  pthread_mutex_t rcin_mutex;
42  int16_t _rssi = -1;
43 
44  uint8_t last_input_source = input_rc_s::RC_INPUT_SOURCE_UNKNOWN;
45  const char *input_source_name(uint8_t id) const;
46 };
uint8_t last_input_source
Definition: RCInput.h:44
perf_counter_t _perf_rcin
Definition: RCInput.h:40
uint8_t num_channels() override
Definition: RCInput.cpp:50
void _timer_tick(void)
Definition: RCInput.cpp:135
#define RC_INPUT_MAX_CHANNELS
Definition: RCInput.h:10
bool set_override(uint8_t channel, int16_t override) override
Definition: RCInput.cpp:89
bool rc_bind(int dsmMode) override
Definition: RCInput.cpp:153
uint16_t read(uint8_t ch) override
Definition: RCInput.cpp:58
void clear_overrides() override
Definition: RCInput.cpp:104
bool new_input() override
Definition: RCInput.cpp:28
pthread_mutex_t rcin_mutex
Definition: RCInput.h:41
int16_t get_rssi(void) override
Definition: RCInput.h:21
uint16_t _override[RC_INPUT_MAX_CHANNELS]
Definition: RCInput.h:35
const char * input_source_name(uint8_t id) const
Definition: RCInput.cpp:111
struct rc_input_values _rcin
Definition: RCInput.h:36
void init() override
Definition: RCInput.cpp:17