APM:Libraries
RC_Channel.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * RC_Channel.cpp - class for one RC channel input
18  */
19 
20 #include <stdlib.h>
21 #include <cmath>
22 
23 #include <AP_HAL/AP_HAL.h>
24 extern const AP_HAL::HAL& hal;
25 
26 #include <AP_Math/AP_Math.h>
27 
28 #include "RC_Channel.h"
29 
31 
33  // @Param: MIN
34  // @DisplayName: RC min PWM
35  // @Description: RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
36  // @Units: PWM
37  // @Range: 800 2200
38  // @Increment: 1
39  // @User: Advanced
40  AP_GROUPINFO("MIN", 1, RC_Channel, radio_min, 1100),
41 
42  // @Param: TRIM
43  // @DisplayName: RC trim PWM
44  // @Description: RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
45  // @Units: PWM
46  // @Range: 800 2200
47  // @Increment: 1
48  // @User: Advanced
49  AP_GROUPINFO("TRIM", 2, RC_Channel, radio_trim, 1500),
50 
51  // @Param: MAX
52  // @DisplayName: RC max PWM
53  // @Description: RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
54  // @Units: PWM
55  // @Range: 800 2200
56  // @Increment: 1
57  // @User: Advanced
58  AP_GROUPINFO("MAX", 3, RC_Channel, radio_max, 1900),
59 
60  // @Param: REVERSED
61  // @DisplayName: RC reversed
62  // @Description: Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
63  // @Values: 0:Normal,1:Reversed
64  // @User: Advanced
65  AP_GROUPINFO("REVERSED", 4, RC_Channel, reversed, 0),
66 
67  // @Param: DZ
68  // @DisplayName: RC dead-zone
69  // @Description: PWM dead zone in microseconds around trim or bottom
70  // @Units: PWM
71  // @Range: 0 200
72  // @User: Advanced
73  AP_GROUPINFO("DZ", 5, RC_Channel, dead_zone, 0),
74 
76 };
77 
78 
79 // constructor
81 {
83 }
84 
85 void
86 RC_Channel::set_range(uint16_t high)
87 {
89  high_in = high;
90 }
91 
92 void
93 RC_Channel::set_angle(uint16_t angle)
94 {
96  high_in = angle;
97 }
98 
99 void
101 {
102  dead_zone.set_default(abs(dzone));
103 }
104 
105 bool
107 {
108  return bool(reversed.get());
109 }
110 
111 // read input from APM_RC - create a control_in value
112 void
114 {
115  radio_in = pwm;
116 
119  } else {
120  //RC_CHANNEL_TYPE_ANGLE
122  }
123 }
124 
125 // recompute control values with no deadzone
126 // When done this way the control_in value can be used as servo_out
127 // to give the same output as input
128 void
130 {
133  } else {
134  //RC_CHANNEL_ANGLE
136  }
137 }
138 
139 /*
140  return the center stick position expressed as a control_in value
141  used for thr_mid in copter
142  */
144 {
146  int16_t r_in = (radio_min.get() + radio_max.get())/2;
147 
148  if (reversed) {
149  r_in = radio_max.get() - (r_in - radio_min.get());
150  }
151 
152  int16_t radio_trim_low = radio_min + dead_zone;
153 
154  return (((int32_t)(high_in) * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_max - radio_trim_low));
155  } else {
156  return 0;
157  }
158 }
159 
160 // ------------------------------------------
161 
163 {
164  radio_min.load();
165  radio_trim.load();
166  radio_max.load();
167  reversed.load();
168  dead_zone.load();
169 }
170 
172 {
173  radio_min.save();
174  radio_trim.save();
175  radio_max.save();
176  reversed.save();
177  dead_zone.save();
178 }
179 
180 /*
181  return an "angle in centidegrees" (normally -4500 to 4500) from
182  the current radio_in value using the specified dead_zone
183  */
184 int16_t
185 RC_Channel::pwm_to_angle_dz_trim(uint16_t _dead_zone, uint16_t _trim)
186 {
187  int16_t radio_trim_high = _trim + _dead_zone;
188  int16_t radio_trim_low = _trim - _dead_zone;
189 
190  int16_t reverse_mul = (reversed?-1:1);
191  if (radio_in > radio_trim_high && radio_max != radio_trim_high) {
192  return reverse_mul * ((int32_t)high_in * (int32_t)(radio_in - radio_trim_high)) / (int32_t)(radio_max - radio_trim_high);
193  } else if (radio_in < radio_trim_low && radio_trim_low != radio_min) {
194  return reverse_mul * ((int32_t)high_in * (int32_t)(radio_in - radio_trim_low)) / (int32_t)(radio_trim_low - radio_min);
195  } else {
196  return 0;
197  }
198 }
199 
200 /*
201  return an "angle in centidegrees" (normally -4500 to 4500) from
202  the current radio_in value using the specified dead_zone
203  */
204 int16_t
205 RC_Channel::pwm_to_angle_dz(uint16_t _dead_zone)
206 {
207  return pwm_to_angle_dz_trim(_dead_zone, radio_trim);
208 }
209 
210 /*
211  return an "angle in centidegrees" (normally -4500 to 4500) from
212  the current radio_in value
213  */
214 int16_t
216 {
217  return pwm_to_angle_dz(dead_zone);
218 }
219 
220 
221 /*
222  convert a pulse width modulation value to a value in the configured
223  range, using the specified deadzone
224  */
225 int16_t
226 RC_Channel::pwm_to_range_dz(uint16_t _dead_zone)
227 {
228  int16_t r_in = constrain_int16(radio_in, radio_min.get(), radio_max.get());
229 
230  if (reversed) {
231  r_in = radio_max.get() - (r_in - radio_min.get());
232  }
233 
234  int16_t radio_trim_low = radio_min + _dead_zone;
235 
236  if (r_in > radio_trim_low) {
237  return (((int32_t)(high_in) * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_max - radio_trim_low));
238  }
239  return 0;
240 }
241 
242 /*
243  convert a pulse width modulation value to a value in the configured
244  range
245  */
246 int16_t
248 {
249  return pwm_to_range_dz(dead_zone);
250 }
251 
252 
254 {
256  return pwm_to_range_dz(0);
257  }
258  return pwm_to_angle_dz(0);
259 }
260 
261 // ------------------------------------------
262 
263 float
265 {
266  float ret;
267  int16_t reverse_mul = (reversed?-1:1);
268  if (radio_in < radio_trim) {
269  if (radio_min >= radio_trim) {
270  return 0.0f;
271  }
272  ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_trim - radio_min);
273  } else {
274  if (radio_max <= radio_trim) {
275  return 0.0f;
276  }
277  ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_max - radio_trim);
278  }
279  return constrain_float(ret, -1.0f, 1.0f);
280 }
281 
282 float
284 {
285  int16_t dz_min = radio_trim - dead_zone;
286  int16_t dz_max = radio_trim + dead_zone;
287  float ret;
288  int16_t reverse_mul = (reversed?-1:1);
289  if (radio_in < dz_min && dz_min > radio_min) {
290  ret = reverse_mul * (float)(radio_in - dz_min) / (float)(dz_min - radio_min);
291  } else if (radio_in > dz_max && radio_max > dz_max) {
292  ret = reverse_mul * (float)(radio_in - dz_max) / (float)(radio_max - dz_max);
293  } else {
294  ret = 0;
295  }
296  return constrain_float(ret, -1.0f, 1.0f);
297 }
298 
299 /*
300  get percentage input from 0 to 100. This ignores the trim value.
301  */
302 uint8_t
304 {
305  if (radio_in <= radio_min) {
306  return reversed?100:0;
307  }
308  if (radio_in >= radio_max) {
309  return reversed?0:100;
310  }
311  uint8_t ret = 100.0f * (radio_in - radio_min) / (float)(radio_max - radio_min);
312  if (reversed) {
313  ret = 100 - ret;
314  }
315  return ret;
316 }
317 
318 void
320 {
321  radio_in = hal.rcin->read(ch_in);
322 }
323 
324 uint16_t
326 {
327  return hal.rcin->read(ch_in);
328 }
329 
330 /*
331  Return true if the channel is at trim and within the DZ
332 */
334 {
336 }
337 
338 
340 {
341  if (configured_mask & (1U << ch_in)) {
342  return true;
343  }
344  if (radio_min.configured() && radio_max.configured()) {
345  // once a channel is known to be configured it has to stay
346  // configured due to the nature of AP_Param
347  configured_mask |= (1U<<ch_in);
348  return true;
349  }
350  return false;
351 }
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
bool in_trim_dz()
Definition: RC_Channel.cpp:333
AP_Int16 radio_min
Definition: RC_Channel.h:113
int16_t get_control_mid() const
Definition: RC_Channel.cpp:143
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
void recompute_pwm_no_deadzone()
Definition: RC_Channel.cpp:129
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RC_Channel.cpp:12
void set_pwm(int16_t pwm)
Definition: RC_Channel.cpp:113
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
int16_t control_in
Definition: RC_Channel.h:111
void set_angle(uint16_t angle)
Definition: RC_Channel.cpp:93
virtual uint16_t read(uint8_t ch)=0
static uint16_t pwm
Definition: RCOutput.cpp:20
void load_eeprom(void)
Definition: RC_Channel.cpp:162
int16_t pwm_to_angle()
Definition: RC_Channel.cpp:215
#define RC_CHANNEL_TYPE_ANGLE
Definition: RC_Channel.h:8
bool is_bounded_int32(int32_t value, int32_t lower_bound, int32_t upper_bound)
Definition: AP_Common.cpp:29
RC_Channel manager, with EEPROM-backed storage of constants.
static const struct AP_Param::GroupInfo var_info[]
Definition: RC_Channel.h:74
Object managing one RC channel.
Definition: RC_Channel.h:15
#define f(i)
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
int16_t get_control_in_zero_dz(void)
Definition: RC_Channel.cpp:253
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
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
int16_t pwm_to_range_dz(uint16_t dead_zone)
Definition: RC_Channel.cpp:226
int16_t high_in
Definition: RC_Channel.h:121
uint8_t ch_in
Definition: RC_Channel.h:124
AP_HAL::RCInput * rcin
Definition: HAL.h:112
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
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
#define RC_CHANNEL_TYPE_RANGE
Definition: RC_Channel.h:9