APM:Libraries
RC_Channel.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Common/AP_Common.h>
6 #include <AP_Param/AP_Param.h>
7 
8 #define RC_CHANNEL_TYPE_ANGLE 0
9 #define RC_CHANNEL_TYPE_RANGE 1
10 
11 #define NUM_RC_CHANNELS 16
12 
15 class RC_Channel {
16 public:
17  friend class SRV_Channels;
18  friend class RC_Channels;
19  // Constructor
20  RC_Channel(void);
21 
22  // used to get min/max/trim limit value based on _reverse
23  enum LimitValue {
27  };
28 
29  // startup
30  void load_eeprom(void);
31  void save_eeprom(void);
32  void save_trim(void);
33 
34  // setup the control preferences
35  void set_range(uint16_t high);
36  void set_angle(uint16_t angle);
37  bool get_reverse(void) const;
38  void set_default_dead_zone(int16_t dzone);
39  uint16_t get_dead_zone(void) const { return dead_zone; }
40 
41  // get the center stick position expressed as a control_in value
42  int16_t get_control_mid() const;
43 
44  // read input from hal.rcin - create a control_in value
45  void set_pwm(int16_t pwm);
47 
48  // calculate an angle given dead_zone and trim. This is used by the quadplane code
49  // for hover throttle
50  int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim);
51 
52  /*
53  return a normalised input for a channel, in range -1 to 1,
54  centered around the channel trim. Ignore deadzone.
55  */
56  float norm_input();
57 
58  /*
59  return a normalised input for a channel, in range -1 to 1,
60  centered around the channel trim. Take into account the deadzone
61  */
62  float norm_input_dz();
63 
64  uint8_t percent_input();
65  int16_t pwm_to_range();
66  int16_t pwm_to_range_dz(uint16_t dead_zone);
67 
68  // read the input value from hal.rcin for this channel
69  uint16_t read() const;
70 
71  // read input from hal.rcin and set as pwm input for channel
72  void input();
73 
74  static const struct AP_Param::GroupInfo var_info[];
75 
76  // return true if input is within deadzone of trim
77  bool in_trim_dz();
78 
79  int16_t get_radio_in() const { return radio_in;}
80  void set_radio_in(int16_t val) {radio_in = val;}
81 
82  int16_t get_control_in() const { return control_in;}
83  void set_control_in(int16_t val) { control_in = val;}
84 
85  // get control input with zero deadzone
86  int16_t get_control_in_zero_dz(void);
87 
88  int16_t get_radio_min() const {return radio_min.get();}
89  void set_radio_min(int16_t val) { radio_min = val;}
90 
91  int16_t get_radio_max() const {return radio_max.get();}
92  void set_radio_max(int16_t val) {radio_max = val;}
93 
94  int16_t get_radio_trim() const { return radio_trim.get();}
95  void set_radio_trim(int16_t val) { radio_trim.set(val);}
96  void save_radio_trim() { radio_trim.save();}
97 
98  void set_and_save_trim() { radio_trim.set_and_save_ifchanged(radio_in);}
99 
100  // set and save trim if changed
101  void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);}
102 
103  bool min_max_configured() const;
104 
105 private:
106 
107  // pwm is stored here
108  int16_t radio_in;
109 
110  // value generated from PWM normalised to configured scale
111  int16_t control_in;
112 
113  AP_Int16 radio_min;
114  AP_Int16 radio_trim;
115  AP_Int16 radio_max;
116 
117  AP_Int8 reversed;
118  AP_Int16 dead_zone;
119 
120  uint8_t type_in;
121  int16_t high_in;
122 
123  // the input channel this corresponds to
124  uint8_t ch_in;
125 
126  // bits set when channel has been identified as configured
127  static uint32_t configured_mask;
128 
129  int16_t pwm_to_angle();
130  int16_t pwm_to_angle_dz(uint16_t dead_zone);
131 };
132 
133 
134 /*
135  class RC_Channels. Hold the full set of RC_Channel objects
136 */
137 class RC_Channels {
138 public:
139  friend class SRV_Channels;
140  // constructor
141  RC_Channels(void);
142 
143  static const struct AP_Param::GroupInfo var_info[];
144 
145  static RC_Channel *rc_channel(uint8_t chan) {
146  return (chan < NUM_RC_CHANNELS)?&channels[chan]:nullptr;
147  }
148 
149  static uint16_t get_radio_in(const uint8_t chan); // returns the last read radio_in value from a chan, 0 if the channel is out of range
150  static uint8_t get_radio_in(uint16_t *chans, const uint8_t num_channels); // reads a block of chanel radio_in values starting from channel 0
151  // returns the number of valid channels
152 
153  static uint8_t get_valid_channel_count(void); // returns the number of valid channels in the last read
154  static int16_t get_receiver_rssi(void); // returns [0, 255] for receiver RSSI (0 is no link) if present, otherwise -1
155  static bool read_input(void); // returns true if new input has been read in
156  static void clear_overrides(void); // clears any active overrides
157  static bool receiver_bind(const int dsmMode); // puts the reciever in bind mode if present, returns true if success
158  static bool set_override(const uint8_t chan, const int16_t value); // set a channels override value
159 
160 private:
161  // this static arrangement is to avoid static pointers in AP_Param tables
164 };
int16_t pwm_to_angle_dz(uint16_t dead_zone)
Definition: RC_Channel.cpp:205
AP_Int8 reversed
Definition: RC_Channel.h:117
uint8_t percent_input()
Definition: RC_Channel.cpp:303
void input()
Definition: RC_Channel.cpp:319
uint8_t type_in
Definition: RC_Channel.h:120
void set_range(uint16_t high)
Definition: RC_Channel.cpp:86
void set_radio_min(int16_t val)
Definition: RC_Channel.h:89
bool in_trim_dz()
Definition: RC_Channel.cpp:333
AP_Int16 radio_min
Definition: RC_Channel.h:113
int16_t get_radio_trim() const
Definition: RC_Channel.h:94
int16_t get_control_mid() const
Definition: RC_Channel.cpp:143
void recompute_pwm_no_deadzone()
Definition: RC_Channel.cpp:129
int16_t get_radio_in() const
Definition: RC_Channel.h:79
static RC_Channel * rc_channel(uint8_t chan)
Definition: RC_Channel.h:145
void set_pwm(int16_t pwm)
Definition: RC_Channel.cpp:113
void set_radio_max(int16_t val)
Definition: RC_Channel.h:92
void set_radio_in(int16_t val)
Definition: RC_Channel.h:80
int16_t control_in
Definition: RC_Channel.h:111
void set_angle(uint16_t angle)
Definition: RC_Channel.cpp:93
void set_radio_trim(int16_t val)
Definition: RC_Channel.h:95
void set_and_save_trim()
Definition: RC_Channel.h:98
static uint16_t pwm
Definition: RCOutput.cpp:20
void load_eeprom(void)
Definition: RC_Channel.cpp:162
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
void set_control_in(int16_t val)
Definition: RC_Channel.h:83
uint16_t get_dead_zone(void) const
Definition: RC_Channel.h:39
void set_and_save_radio_trim(int16_t val)
Definition: RC_Channel.h:101
int16_t pwm_to_angle()
Definition: RC_Channel.cpp:215
A system for managing and storing variables that are of general interest to the system.
#define NUM_RC_CHANNELS
Definition: RC_Channel.h:11
int16_t get_control_in() const
Definition: RC_Channel.h:82
friend class RC_Channels
Definition: RC_Channel.h:18
static const struct AP_Param::GroupInfo var_info[]
Definition: RC_Channel.h:74
Object managing one RC channel.
Definition: RC_Channel.h:15
int16_t pwm_to_range()
Definition: RC_Channel.cpp:247
bool min_max_configured() const
Definition: RC_Channel.cpp:339
AP_Int16 radio_max
Definition: RC_Channel.h:115
AP_Int16 radio_trim
Definition: RC_Channel.h:114
AP_Int16 dead_zone
Definition: RC_Channel.h:118
float norm_input()
Definition: RC_Channel.cpp:264
uint16_t read() const
Definition: RC_Channel.cpp:325
float norm_input_dz()
Definition: RC_Channel.cpp:283
Common definitions and utility routines for the ArduPilot libraries.
int16_t get_control_in_zero_dz(void)
Definition: RC_Channel.cpp:253
static RC_Channel * channels
Definition: RC_Channel.h:162
bool get_reverse(void) const
Definition: RC_Channel.cpp:106
int16_t radio_in
Definition: RC_Channel.h:108
RC_Channel(void)
Definition: RC_Channel.cpp:80
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
int16_t get_radio_min() const
Definition: RC_Channel.h:88
int16_t get_radio_max() const
Definition: RC_Channel.h:91
int16_t pwm_to_range_dz(uint16_t dead_zone)
Definition: RC_Channel.cpp:226
void save_radio_trim()
Definition: RC_Channel.h:96
float value
int16_t high_in
Definition: RC_Channel.h:121
uint8_t ch_in
Definition: RC_Channel.h:124
void save_trim(void)
int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim)
Definition: RC_Channel.cpp:185
static uint32_t configured_mask
Definition: RC_Channel.h:127
void save_eeprom(void)
Definition: RC_Channel.cpp:171
void set_default_dead_zone(int16_t dzone)
Definition: RC_Channel.cpp:100