APM:Libraries
SRV_Channel.h
Go to the documentation of this file.
1 /*
2  control of servo output ranges, trim and servo reversal. This can
3  optionally be used to provide separation of input and output channel
4  ranges so that RCn_MIN, RCn_MAX, RCn_TRIM and RCn_REV only apply to
5  the input side of RC_Channel
6 
7  It works by running servo output calculations as normal, then
8  re-mapping the output according to the servo MIN/MAX/TRIM/REV from
9  this object
10 
11  Only 4 channels of ranges are defined as those match the input
12  channels for R/C sticks
13  */
14 #pragma once
15 
16 #include <AP_Common/AP_Common.h>
17 #include <AP_Param/AP_Param.h>
19 #include <AP_Common/Bitmask.h>
21 #include <AP_SBusOut/AP_SBusOut.h>
22 #include <AP_BLHeli/AP_BLHeli.h>
23 
24 #define NUM_SERVO_CHANNELS 16
25 
26 class SRV_Channels;
27 
28 /*
29  class SRV_Channel. The class SRV_Channels contains an array of
30  SRV_Channel objects. This is done to fit within the AP_Param limit
31  of 64 parameters per object.
32 */
33 class SRV_Channel {
34 public:
35  friend class SRV_Channels;
36 
37  // constructor
38  SRV_Channel(void);
39 
40  static const struct AP_Param::GroupInfo var_info[];
41 
42  typedef enum
43  {
44  k_none = 0,
45  k_manual = 1,
46  k_flap = 2,
48  k_aileron = 4,
49  k_unused1 = 5,
55  k_egg_drop = 11,
56  k_mount2_pan = 12,
63  k_elevator = 19,
65  k_rudder = 21,
70  k_steering = 26,
72  k_gripper = 28,
75  k_heli_rsc = 31,
77  k_motor1 = 33,
78  k_motor2 = 34,
79  k_motor3 = 35,
80  k_motor4 = 36,
81  k_motor5 = 37,
82  k_motor6 = 38,
83  k_motor7 = 39,
84  k_motor8 = 40,
85  k_motor_tilt = 41,
86  k_rcin1 = 51,
87  k_rcin2 = 52,
88  k_rcin3 = 53,
89  k_rcin4 = 54,
90  k_rcin5 = 55,
91  k_rcin6 = 56,
92  k_rcin7 = 57,
93  k_rcin8 = 58,
94  k_rcin9 = 59,
95  k_rcin10 = 60,
96  k_rcin11 = 61,
97  k_rcin12 = 62,
98  k_rcin13 = 63,
99  k_rcin14 = 64,
100  k_rcin15 = 65,
101  k_rcin16 = 66,
103  k_choke = 68,
104  k_starter = 69,
117  k_motor9 = 82,
118  k_motor10 = 83,
119  k_motor11 = 84,
120  k_motor12 = 85,
123  k_winch = 88,
126 
127  // used to get min/max/trim limit value based on reverse
128  enum LimitValue {
133  };
134 
135  // set the output value as a pwm value
136  void set_output_pwm(uint16_t pwm);
137 
138  // get the output value as a pwm value
139  uint16_t get_output_pwm(void) const { return output_pwm; }
140 
141  // set angular range of scaled output
142  void set_angle(int16_t angle);
143 
144  // set range of scaled output. Low is always zero
145  void set_range(uint16_t high);
146 
147  // return true if the channel is reversed
148  bool get_reversed(void) const {
149  return reversed?true:false;
150  }
151 
152  // set MIN/MAX parameters
153  void set_output_min(uint16_t pwm) {
154  servo_min.set(pwm);
155  }
156  void set_output_max(uint16_t pwm) {
157  servo_max.set(pwm);
158  }
159 
160  // get MIN/MAX/TRIM parameters
161  uint16_t get_output_min(void) const {
162  return servo_min;
163  }
164  uint16_t get_output_max(void) const {
165  return servo_max;
166  }
167  uint16_t get_trim(void) const {
168  return servo_trim;
169  }
170 
171  // return true if function is for a multicopter motor
172  static bool is_motor(SRV_Channel::Aux_servo_function_t function);
173 
174  // return the function of a channel
176  return (SRV_Channel::Aux_servo_function_t)function.get();
177  }
178 
179  // set and save function for channel. Used in upgrade of parameters in plane
181  function.set_and_save(int8_t(f));
182  }
183 
184  // set and save function for reversed. Used in upgrade of parameters in plane
186  reversed.set_and_save_ifchanged(r?1:0);
187  }
188 
189  // return true if the SERVOn_FUNCTION has been configured in
190  // either storage or a defaults file. This is used for upgrade of
191  // parameters in plane
192  bool function_configured(void) const {
193  return function.configured();
194  }
195 
196 private:
197  AP_Int16 servo_min;
198  AP_Int16 servo_max;
199  AP_Int16 servo_trim;
200  // reversal, following convention that 1 means reversed, 0 means normal
201  AP_Int8 reversed;
202  AP_Int8 function;
203 
204  // a pending output value as PWM
205  uint16_t output_pwm;
206 
207  // true for angle output type
208  bool type_angle:1;
209 
210  // set_range() or set_angle() has been called
211  bool type_setup:1;
212 
213  // the hal channel number
214  uint8_t ch_num;
215 
216  // high point of angle or range output
217  uint16_t high_out;
218 
219  // convert a 0..range_max to a pwm
220  uint16_t pwm_from_range(int16_t scaled_value) const;
221 
222  // convert a -angle_max..angle_max to a pwm
223  uint16_t pwm_from_angle(int16_t scaled_value) const;
224 
225  // convert a scaled output to a pwm value
226  void calc_pwm(int16_t output_scaled);
227 
228  // output value based on function
229  void output_ch(void);
230 
231  // setup output type and range based on function
232  void aux_servo_function_setup(void);
233 
234  // return PWM for a given limit value
235  uint16_t get_limit_pwm(LimitValue limit) const;
236 
237  // get normalised output from -1 to 1
238  float get_output_norm(void);
239 
240  // a bitmask type wide enough for NUM_SERVO_CHANNELS
241  typedef uint16_t servo_mask_t;
242 
243  // mask of channels where we have a output_pwm value. Cleared when a
244  // scaled value is written.
245  static servo_mask_t have_pwm_mask;
246 };
247 
248 /*
249  class SRV_Channels
250 */
252 public:
253  friend class SRV_Channel;
254 
255  // constructor
256  SRV_Channels(void);
257 
258  static const struct AP_Param::GroupInfo var_info[];
259 
260  // set the default function for a channel
261  static void set_default_function(uint8_t chan, SRV_Channel::Aux_servo_function_t function);
262 
263  // set output value for a function channel as a pwm value
264  static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value);
265 
266  // set output value for a function channel as a pwm value on the first matching channel
267  static void set_output_pwm_first(SRV_Channel::Aux_servo_function_t function, uint16_t value);
268 
269  // set output value for a specific function channel as a pwm value
270  static void set_output_pwm_chan(uint8_t chan, uint16_t value);
271 
272  // set output value for a function channel as a scaled value. This
273  // calls calc_pwm() to also set the pwm value
274  static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value);
275 
276  // get scaled output for the given function type.
277  static int16_t get_output_scaled(SRV_Channel::Aux_servo_function_t function);
278 
279  // get pwm output for the first channel of the given function type.
280  static bool get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value);
281 
282  // get normalised output (-1 to 1 for angle, 0 to 1 for range). Value is taken from pwm value
283  // return zero on error.
284  static float get_output_norm(SRV_Channel::Aux_servo_function_t function);
285 
286  // get output channel mask for a function
287  static uint16_t get_output_channel_mask(SRV_Channel::Aux_servo_function_t function);
288 
289  // limit slew rate to given limit in percent per second
290  static void limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt);
291 
292  // call output_ch() on all channels
293  static void output_ch_all(void);
294 
295  // setup output ESC scaling based on a channels MIN/MAX
296  void set_esc_scaling_for(SRV_Channel::Aux_servo_function_t function);
297 
298  // return true when auto_trim enabled
299  bool auto_trim_enabled(void) const { return auto_trim; }
300 
301  // adjust trim of a channel by a small increment
302  void adjust_trim(SRV_Channel::Aux_servo_function_t function, float v);
303 
304  // save trims
305  void save_trim(void);
306 
307  // setup for a reversible k_throttle (from -100 to 100)
309  flags.k_throttle_reversible = true;
310  }
311 
312  // set all outputs to the TRIM value
313  static void output_trim_all(void);
314 
315  // setup IO failsafe for all channels to trim
316  static void setup_failsafe_trim_all(void);
317 
318  // set output for all channels matching the given function type, allow radio_trim to center servo
319  static void set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, int16_t value);
320 
321  // set and save the trim for a function channel to the output value
322  static void set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function);
323 
324  // set the trim for a function channel to min of the channel
325  static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function);
326 
327  // set the trim for a function channel to given pwm
328  static void set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm);
329 
330  // set output to min value
331  static void set_output_to_min(SRV_Channel::Aux_servo_function_t function);
332 
333  // set output to max value
334  static void set_output_to_max(SRV_Channel::Aux_servo_function_t function);
335 
336  // set output to trim value
337  static void set_output_to_trim(SRV_Channel::Aux_servo_function_t function);
338 
339  // copy radio_in to servo out
340  static void copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool do_input_output=false);
341 
342  // copy radio_in to servo_out by channel mask
343  static void copy_radio_in_out_mask(uint16_t mask);
344 
345  // setup failsafe for an auxiliary channel function, by pwm
346  static void set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm);
347 
348  // setup failsafe for an auxiliary channel function
349  static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
350 
351  // setup safety for an auxiliary channel function (used when disarmed)
352  static void set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
353 
354  // set servo to a LimitValue
355  static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit);
356 
357  // return true if a function is assigned to a channel
358  static bool function_assigned(SRV_Channel::Aux_servo_function_t function);
359 
360  // set a servo_out value, and angle range, then calc_pwm
361  static void move_servo(SRV_Channel::Aux_servo_function_t function,
362  int16_t value, int16_t angle_min, int16_t angle_max);
363 
364  // assign and enable auxiliary channels
365  static void enable_aux_servos(void);
366 
367  // enable channels by mask
368  static void enable_by_mask(uint16_t mask);
369 
370  // return the current function for a channel
371  static SRV_Channel::Aux_servo_function_t channel_function(uint8_t channel);
372 
373  // refresh aux servo to function mapping
374  static void update_aux_servo_function(void);
375 
376  // set default channel for an auxiliary function
377  static bool set_aux_channel_default(SRV_Channel::Aux_servo_function_t function, uint8_t channel);
378 
379  // find first channel that a function is assigned to
380  static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan);
381 
382  // find first channel that a function is assigned to, returning SRV_Channel object
383  static SRV_Channel *get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1);
384 
385  // call set_angle() on matching channels
386  static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle);
387 
388  // call set_range() on matching channels
389  static void set_range(SRV_Channel::Aux_servo_function_t function, uint16_t range);
390 
391  // set output refresh frequency on a servo function
392  static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency);
393 
394  // control pass-thru of channels
395  void disable_passthrough(bool disable) {
396  disabled_passthrough = disable;
397  }
398 
399  // constrain to output min/max for function
400  static void constrain_pwm(SRV_Channel::Aux_servo_function_t function);
401 
402  // calculate PWM for all channels
403  static void calc_pwm(void);
404 
405  static SRV_Channel *srv_channel(uint8_t i) {
406  return i<NUM_SERVO_CHANNELS?&channels[i]:nullptr;
407  }
408 
409  // upgrade RC* parameters into SERVO* parameters
410  static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap);
411  static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel);
412 
413  // given a zero-based motor channel, return the k_motor function for that channel
415  if (channel < 8) {
417  }
419  }
420 
421  static void cork();
422 
423  static void push();
424 
425  // disable output to a set of channels given by a mask. This is used by the AP_BLHeli code
426  static void set_disabled_channel_mask(uint16_t mask) { disabled_mask = mask; }
427 
428 private:
429  struct {
431  } flags;
432 
433  static bool disabled_passthrough;
434 
436 
438  static bool initialised;
439 
440  // this static arrangement is to avoid having static objects in AP_Param tables
443 
444  // support for Volz protocol
447 
448  // support for SBUS protocol
451 
452 #if HAL_SUPPORT_RCOUT_SERIAL
453  // support for BLHeli protocol
454  AP_BLHeli blheli;
455  static AP_BLHeli *blheli_ptr;
456 #endif
457  static uint16_t disabled_mask;
458 
460 
461  static struct srv_function {
462  // mask of what channels this applies to
464 
465  // scaled output for this function
466  int16_t output_scaled;
468 
469  AP_Int8 auto_trim;
470  AP_Int16 default_rate;
471 
472  // return true if passthrough is disabled
473  static bool passthrough_disabled(void) {
474  return disabled_passthrough;
475  }
476 };
differential spoiler 1 (left wing)
Definition: SRV_Channel.h:60
secondary rudder channel
Definition: SRV_Channel.h:65
bool type_angle
Definition: SRV_Channel.h:208
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel)
Definition: SRV_Channel.h:414
antennatracker pitch
Definition: SRV_Channel.h:107
SRV_Channel(void)
Definition: SRV_Channel.cpp:76
void set_output_max(uint16_t pwm)
Definition: SRV_Channel.h:156
SRV_Channel::servo_mask_t channel_mask
Definition: SRV_Channel.h:463
uint16_t get_limit_pwm(LimitValue limit) const
This must be the last enum value (only add new values before this one)
Definition: SRV_Channel.h:124
static bool passthrough_disabled(void)
Definition: SRV_Channel.h:473
static bool is_motor(SRV_Channel::Aux_servo_function_t function)
SRV_Channel::Aux_servo_function_t get_function(void) const
Definition: SRV_Channel.h:175
uint16_t pwm_from_range(int16_t scaled_value) const
Definition: SRV_Channel.cpp:84
crop sprayer pump channel
Definition: SRV_Channel.h:66
void set_angle(int16_t angle)
aileron, with rc input, deprecated
Definition: SRV_Channel.h:62
bool type_setup
Definition: SRV_Channel.h:211
void set_range(uint16_t high)
engine kill switch, used for gas airplanes and helicopters
Definition: SRV_Channel.h:74
static uint16_t disabled_mask
Definition: SRV_Channel.h:457
flaperon, right wing
Definition: SRV_Channel.h:69
static AP_SBusOut * sbus_ptr
Definition: SRV_Channel.h:450
void reversed_set_and_save_ifchanged(bool r)
Definition: SRV_Channel.h:185
float get_output_norm(void)
differential spoiler 1 (right wing)
Definition: SRV_Channel.h:61
uint16_t get_output_max(void) const
Definition: SRV_Channel.h:164
uint8_t ch_num
Definition: SRV_Channel.h:214
AP_Int16 servo_trim
Definition: SRV_Channel.h:199
these are for pass-thru from arbitrary rc inputs
Definition: SRV_Channel.h:86
differential spoiler 2 (left wing)
Definition: SRV_Channel.h:121
tiltrotor motor tilt control
Definition: SRV_Channel.h:85
static bool initialised
Definition: SRV_Channel.h:438
static bool disabled_passthrough
Definition: SRV_Channel.h:433
unused function
Definition: SRV_Channel.h:49
void output_ch(void)
map a function to a servo channel and output it
void disable_passthrough(bool disable)
Definition: SRV_Channel.h:395
static uint16_t pwm
Definition: RCOutput.cpp:20
flaperon, left wing
Definition: SRV_Channel.h:68
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
crop sprayer spinner channel
Definition: SRV_Channel.h:67
uint16_t pwm_from_angle(int16_t scaled_value) const
Definition: SRV_Channel.cpp:97
static SRV_Channel * channels
Definition: SRV_Channel.h:441
mount open (deploy) / close (retract)
Definition: SRV_Channel.h:53
A system for managing and storing variables that are of general interest to the system.
AP_Int16 servo_max
Definition: SRV_Channel.h:198
AP_Int16 servo_min
Definition: SRV_Channel.h:197
AP_Int16 default_rate
Definition: SRV_Channel.h:470
void aux_servo_function_setup(void)
static SRV_Channel * srv_channel(uint8_t i)
Definition: SRV_Channel.h:405
bool k_throttle_reversible
Definition: SRV_Channel.h:430
uint16_t output_pwm
Definition: SRV_Channel.h:205
mount yaw (pan)
Definition: SRV_Channel.h:50
these allow remapping of copter motors
Definition: SRV_Channel.h:77
#define f(i)
manual, just pass-thru the RC in signal
Definition: SRV_Channel.h:45
friend class SRV_Channels
Definition: SRV_Channel.h:35
AP_SBusOut sbus
Definition: SRV_Channel.h:449
vectored thrust, left tilt
Definition: SRV_Channel.h:110
landing gear controller
Definition: SRV_Channel.h:73
helicopter tail RSC output
Definition: SRV_Channel.h:76
AP_Int8 reversed
Definition: SRV_Channel.h:201
SRV_Channel::servo_mask_t trimmed_mask
Definition: SRV_Channel.h:435
uint16_t get_output_min(void) const
Definition: SRV_Channel.h:161
void set_reversible_throttle(void)
Definition: SRV_Channel.h:308
elevator, with rc input, deprecated
Definition: SRV_Channel.h:64
float v
Definition: Printf.cpp:15
bool function_configured(void) const
Definition: SRV_Channel.h:192
vectored thrust, right tilt
Definition: SRV_Channel.h:111
Common definitions and utility routines for the ArduPilot libraries.
uint16_t get_trim(void) const
Definition: SRV_Channel.h:167
helicopter RSC output
Definition: SRV_Channel.h:75
static Bitmask function_mask
Definition: SRV_Channel.h:437
static void set_disabled_channel_mask(uint16_t mask)
Definition: SRV_Channel.h:426
void set_output_min(uint16_t pwm)
Definition: SRV_Channel.h:153
flap automated
Definition: SRV_Channel.h:47
uint16_t get_output_pwm(void) const
Definition: SRV_Channel.h:139
void function_set_and_save(SRV_Channel::Aux_servo_function_t f)
Definition: SRV_Channel.h:180
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
bool get_reversed(void) const
Definition: SRV_Channel.h:148
differential spoiler 2 (right wing)
Definition: SRV_Channel.h:122
bool auto_trim_enabled(void) const
Definition: SRV_Channel.h:299
mount2 pitch (tilt)
Definition: SRV_Channel.h:57
static servo_mask_t have_pwm_mask
Definition: SRV_Channel.h:245
float value
ground steering, used to separate from rudder
Definition: SRV_Channel.h:70
AP_Volz_Protocol volz
Definition: SRV_Channel.h:445
uint16_t servo_mask_t
Definition: SRV_Channel.h:241
static SRV_Channels * instance
Definition: SRV_Channel.h:442
AP_Int8 auto_trim
Definition: SRV_Channel.h:469
static const struct AP_Param::GroupInfo var_info[]
Definition: SRV_Channel.h:40
#define NUM_SERVO_CHANNELS
Definition: SRV_Channel.h:24
void set_output_pwm(uint16_t pwm)
antennatracker yaw
Definition: SRV_Channel.h:106
void calc_pwm(int16_t output_scaled)
uint16_t high_out
Definition: SRV_Channel.h:217
mount pitch (tilt)
Definition: SRV_Channel.h:51
static AP_Volz_Protocol * volz_ptr
Definition: SRV_Channel.h:446
mount2 open (deploy) / close (retract)
Definition: SRV_Channel.h:59
vertical booster throttle
Definition: SRV_Channel.h:116
mount2 yaw (pan)
Definition: SRV_Channel.h:56