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