APM:Libraries
SRV_Channel_aux.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  SRV_Channel_aux.cpp - handling of servo auxillary functions
17  */
18 #include "SRV_Channel.h"
19 
20 #include <AP_Math/AP_Math.h>
21 #include <AP_HAL/AP_HAL.h>
22 #include <RC_Channel/RC_Channel.h>
24 
25 extern const AP_HAL::HAL& hal;
26 
29 {
30  int8_t passthrough_from = -1;
31 
32  // take care of special function cases
33  switch(function)
34  {
35  case k_manual: // manual
36  passthrough_from = ch_num;
37  break;
38  case k_rcin1 ... k_rcin16: // rc pass-thru
39  passthrough_from = int8_t(function - k_rcin1);
40  break;
41  }
42  if (passthrough_from != -1) {
43  // we are doing passthrough from input to output for this channel
44  RC_Channel *rc = RC_Channels::rc_channel(passthrough_from);
45  if (rc) {
47  output_pwm = rc->get_radio_trim();
48  } else {
49  output_pwm = rc->get_radio_in();
50  }
51  }
52  }
53  if (!(SRV_Channels::disabled_mask & (1U<<ch_num))) {
55  }
56 }
57 
58 /*
59  call output_ch() on all channels
60  */
62 {
63  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
64  channels[i].output_ch();
65  }
66 }
67 
68 /*
69  return the current function for a channel
70 */
72 {
73  if (channel < NUM_SERVO_CHANNELS) {
74  return (SRV_Channel::Aux_servo_function_t)channels[channel].function.get();
75  }
76  return SRV_Channel::k_none;
77 }
78 
79 /*
80  setup a channels aux servo function
81 */
83 {
84  if (type_setup) {
85  return;
86  }
87  switch (function) {
88  case k_flap:
89  case k_flap_auto:
90  case k_egg_drop:
91  set_range(100);
92  break;
93  case k_heli_rsc:
94  case k_heli_tail_rsc:
95  case k_motor_tilt:
96  case k_boost_throttle:
97  set_range(1000);
98  break;
101  case k_aileron:
102  case k_elevator:
103  case k_dspoilerLeft1:
104  case k_dspoilerLeft2:
105  case k_dspoilerRight1:
106  case k_dspoilerRight2:
107  case k_rudder:
108  case k_steering:
109  case k_flaperon_left:
110  case k_flaperon_right:
111  case k_tiltMotorLeft:
112  case k_tiltMotorRight:
113  case k_elevon_left:
114  case k_elevon_right:
115  case k_vtail_left:
116  case k_vtail_right:
117  set_angle(4500);
118  break;
119  case k_throttle:
120  case k_throttleLeft:
121  case k_throttleRight:
122  // fixed wing throttle
123  set_range(100);
124  break;
125  default:
126  break;
127  }
128 }
129 
132 {
133  if (!channels) {
134  return;
135  }
136  function_mask.clearall();
137 
138  for (uint8_t i = 0; i < SRV_Channel::k_nr_aux_servo_functions; i++) {
139  functions[i].channel_mask = 0;
140  }
141 
142  // set auxiliary ranges
143  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
144  if ((uint8_t)channels[i].function.get() < SRV_Channel::k_nr_aux_servo_functions) {
145  channels[i].aux_servo_function_setup();
146  function_mask.set((uint8_t)channels[i].function.get());
147  functions[channels[i].function.get()].channel_mask |= 1U<<i;
148  }
149  }
150  initialised = true;
151 }
152 
155 {
156  hal.rcout->set_default_rate(uint16_t(instance->default_rate.get()));
157 
158  update_aux_servo_function();
159 
160  // enable all channels that are set to a valid function. This
161  // includes k_none servos, which allows those to get their initial
162  // trim value on startup
163  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
164  // see if it is a valid function
165  if ((uint8_t)channels[i].function.get() < SRV_Channel::k_nr_aux_servo_functions) {
166  hal.rcout->enable_ch(channels[i].ch_num);
167  }
168  }
169 
170 #if HAL_SUPPORT_RCOUT_SERIAL
171  blheli_ptr->update();
172 #endif
173 }
174 
176 void SRV_Channels::enable_by_mask(uint16_t mask)
177 {
178  for (uint8_t i = 0; i < 16; i++) {
179  if (mask & (1U<<i)) {
180  hal.rcout->enable_ch(i);
181  }
182  }
183 }
184 
185 /*
186  set radio_out for all channels matching the given function type
187  */
189 {
190  if (!function_assigned(function)) {
191  return;
192  }
193  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
194  if (channels[i].function.get() == function) {
195  channels[i].set_output_pwm(value);
196  channels[i].output_ch();
197  }
198  }
199 }
200 
201 /*
202  set radio_out for all channels matching the given function type
203  trim the output assuming a 1500 center on the given value
204  */
205 void
207 {
208  if (!function_assigned(function)) {
209  return;
210  }
211  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
212  if (channels[i].function.get() == function) {
213  int16_t value2 = value - 1500 + channels[i].get_trim();
214  channels[i].set_output_pwm(constrain_int16(value2,channels[i].get_output_min(),channels[i].get_output_max()));
215  channels[i].output_ch();
216  }
217  }
218 }
219 
220 /*
221  set and save the trim value to current output for all channels matching
222  the given function type
223  */
224 void
226 {
227  if (!function_assigned(function)) {
228  return;
229  }
230  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
231  if (channels[i].function.get() == function) {
232  channels[i].servo_trim.set_and_save_ifchanged(channels[i].output_pwm);
233  }
234  }
235 }
236 
237 /*
238  copy radio_in to radio_out for a given function
239  */
240 void
242 {
243  if (!function_assigned(function)) {
244  return;
245  }
246  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
247  if (channels[i].function.get() == function) {
249  if (rc == nullptr) {
250  continue;
251  }
252  if (do_input_output) {
253  rc->read();
254  }
255  channels[i].set_output_pwm(rc->get_radio_in());
256  if (do_input_output) {
257  channels[i].output_ch();
258  }
259  }
260  }
261 }
262 
263 /*
264  copy radio_in to radio_out for a channel mask
265  */
266 void
268 {
269  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
270  if ((1U<<i) & mask) {
272  if (rc == nullptr) {
273  continue;
274  }
275  channels[i].set_output_pwm(rc->get_radio_in());
276  }
277  }
278 
279 }
280 
281 /*
282  setup failsafe value for an auxiliary function type to a LimitValue
283  */
284 void
286 {
287  if (!function_assigned(function)) {
288  return;
289  }
290  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
291  const SRV_Channel &ch = channels[i];
292  if (ch.function.get() == function) {
293  hal.rcout->set_failsafe_pwm(1U<<ch.ch_num, pwm);
294  }
295  }
296 }
297 
298 /*
299  setup failsafe value for an auxiliary function type to a LimitValue
300  */
301 void
303 {
304  if (!function_assigned(function)) {
305  return;
306  }
307  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
308  const SRV_Channel &ch = channels[i];
309  if (ch.function.get() == function) {
310  uint16_t pwm = ch.get_limit_pwm(limit);
311  hal.rcout->set_failsafe_pwm(1U<<ch.ch_num, pwm);
312  }
313  }
314 }
315 
316 /*
317  setup safety value for an auxiliary function type to a LimitValue
318  */
319 void
321 {
322  if (!function_assigned(function)) {
323  return;
324  }
325  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
326  const SRV_Channel &ch = channels[i];
327  if (ch.function.get() == function) {
328  uint16_t pwm = ch.get_limit_pwm(limit);
329  hal.rcout->set_safety_pwm(1U<<ch.ch_num, pwm);
330  }
331  }
332 }
333 
334 /*
335  set radio output value for an auxiliary function type to a LimitValue
336  */
337 void
339 {
340  if (!function_assigned(function)) {
341  return;
342  }
343  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
344  SRV_Channel &ch = channels[i];
345  if (ch.function.get() == function) {
346  uint16_t pwm = ch.get_limit_pwm(limit);
347  ch.set_output_pwm(pwm);
348  if (ch.function.get() == SRV_Channel::k_manual) {
350  if (rc != nullptr) {
351  // in order for output_ch() to work for k_manual we
352  // also have to override radio_in
353  rc->set_radio_in(pwm);
354  }
355  }
356  }
357  }
358 }
359 
360 /*
361  return true if a particular function is assigned to at least one RC channel
362  */
363 bool
365 {
366  return function_mask.get(uint16_t(function));
367 }
368 
369 /*
370  set servo_out and angle_min/max, then calc_pwm and output a
371  value. This is used to move a AP_Mount servo
372  */
373 void
375  int16_t value, int16_t angle_min, int16_t angle_max)
376 {
377  if (!function_assigned(function)) {
378  return;
379  }
380  if (angle_max <= angle_min) {
381  return;
382  }
383  float v = float(value - angle_min) / float(angle_max - angle_min);
384  v = constrain_float(v, 0.0f, 1.0f);
385  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
386  SRV_Channel &ch = channels[i];
387  if (ch.function.get() == function) {
388  float v2 = ch.get_reversed()? (1-v) : v;
389  uint16_t pwm = ch.servo_min + v2 * (ch.servo_max - ch.servo_min);
390  ch.set_output_pwm(pwm);
391  }
392  }
393 }
394 
395 /*
396  set the default channel an auxiliary output function should be on
397  */
399 {
400  if (!initialised) {
401  update_aux_servo_function();
402  }
403  if (function_assigned(function)) {
404  // already assigned
405  return true;
406  }
407  if (channels[channel].function != SRV_Channel::k_none) {
408  if (channels[channel].function == function) {
409  return true;
410  }
411  hal.console->printf("Channel %u already assigned %u\n",
412  (unsigned)channel,
413  (unsigned)channels[channel].function);
414  return false;
415  }
416  channels[channel].type_setup = false;
417  channels[channel].function.set(function);
418  channels[channel].aux_servo_function_setup();
419  function_mask.set((uint8_t)function);
420  functions[function].channel_mask |= 1U<<channel;
421  return true;
422 }
423 
424 // find first channel that a function is assigned to
426 {
427  if (!initialised) {
428  update_aux_servo_function();
429  }
430  if (!function_assigned(function)) {
431  return false;
432  }
433  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
434  if (channels[i].function == function) {
435  chan = channels[i].ch_num;
436  return true;
437  }
438  }
439  return false;
440 }
441 
442 /*
443  get a pointer to first auxillary channel for a channel function
444 */
446 {
447  uint8_t chan;
448  if (default_chan >= 0) {
449  set_aux_channel_default(function, default_chan);
450  }
451  if (!find_channel(function, chan)) {
452  return nullptr;
453  }
454  return &channels[chan];
455 }
456 
458 {
459  if (function < SRV_Channel::k_nr_aux_servo_functions) {
460  functions[function].output_scaled = value;
461  SRV_Channel::have_pwm_mask &= ~functions[function].channel_mask;
462  }
463 }
464 
466 {
467  if (function < SRV_Channel::k_nr_aux_servo_functions) {
468  return functions[function].output_scaled;
469  }
470  return 0;
471 }
472 
473 /*
474  get mask of output channels for a function
475  */
477 {
478  if (!initialised) {
479  update_aux_servo_function();
480  }
481  if (function < SRV_Channel::k_nr_aux_servo_functions) {
482  return functions[function].channel_mask;
483  }
484  return 0;
485 }
486 
487 
488 // set the trim for a function channel to given pwm
490 {
491  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
492  if (channels[i].function == function) {
493  channels[i].servo_trim.set(pwm);
494  }
495  }
496 }
497 
498 // set the trim for a function channel to min output
500 {
501  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
502  if (channels[i].function == function) {
503  channels[i].servo_trim.set(channels[i].get_reversed()?channels[i].servo_max:channels[i].servo_min);
504  }
505  }
506 }
507 
508 /*
509  set the default function for a channel
510 */
512 {
513  if (chan < NUM_SERVO_CHANNELS) {
514  int8_t old = channels[chan].function;
515  channels[chan].function.set_default((uint8_t)function);
516  if (old != channels[chan].function && channels[chan].function == function) {
517  function_mask.set((uint8_t)function);
518  }
519  }
520 }
521 
523 {
524  uint8_t chan;
525  if (find_channel(function, chan)) {
527  }
528 }
529 
530 /*
531  auto-adjust channel trim from an integrator value. Positive v means
532  adjust trim up. Negative means decrease
533  */
535 {
536  if (is_zero(v)) {
537  return;
538  }
539  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
540  SRV_Channel &c = channels[i];
541  if (function != (SRV_Channel::Aux_servo_function_t)(c.function.get())) {
542  continue;
543  }
544  float change = c.reversed?-v:v;
545  uint16_t new_trim = c.servo_trim;
546  float trim_scaled = float(c.servo_trim - c.servo_min) / (c.servo_max - c.servo_min);
547  if (change > 0 && trim_scaled < 0.6f) {
548  new_trim++;
549  } else if (change < 0 && trim_scaled > 0.4f) {
550  new_trim--;
551  } else {
552  return;
553  }
554  c.servo_trim.set(new_trim);
555 
556  trimmed_mask |= 1U<<i;
557  }
558 }
559 
560 // get pwm output for the first channel of the given function type.
562 {
563  uint8_t chan;
564  if (!find_channel(function, chan)) {
565  return false;
566  }
567  channels[chan].calc_pwm(functions[function].output_scaled);
568  value = channels[chan].output_pwm;
569  return true;
570 }
571 
572 // set output pwm to trim for the given function
574 {
575  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
576  if (channels[i].function == function) {
577  channels[i].set_output_pwm(channels[i].servo_trim);
578  }
579  }
580 }
581 
582 // set output pwm to for first matching channel
584 {
585  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
586  if (channels[i].function == function) {
587  channels[i].set_output_pwm(pwm);
588  break;
589  }
590  }
591 }
592 
593 /*
594  get the normalised output for a channel function from the pwm value
595  of the first matching channel
596  */
598 {
599  uint8_t chan;
600  if (!find_channel(function, chan)) {
601  return 0;
602  }
603  channels[chan].calc_pwm(functions[function].output_scaled);
604  return channels[chan].get_output_norm();
605 }
606 
607 /*
608  limit slew rate for an output function to given rate in percent per
609  second. This assumes output has not yet done to the hal
610  */
611 void SRV_Channels::limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt)
612 {
613  if (slew_rate <= 0) {
614  // nothing to do
615  return;
616  }
617  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
618  SRV_Channel &ch = channels[i];
619  if (ch.function == function) {
620  ch.calc_pwm(functions[function].output_scaled);
621  uint16_t last_pwm = hal.rcout->read_last_sent(ch.ch_num);
622  if (last_pwm == ch.output_pwm) {
623  continue;
624  }
625  uint16_t max_change = (ch.get_output_max() - ch.get_output_min()) * slew_rate * dt * 0.01f;
626  if (max_change == 0 || dt > 1) {
627  // always allow some change. If dt > 1 then assume we
628  // are just starting out, and only allow a small
629  // change for this loop
630  max_change = 1;
631  }
632  ch.output_pwm = constrain_int16(ch.output_pwm, last_pwm-max_change, last_pwm+max_change);
633  }
634  }
635 }
636 
637 // call set_angle() on matching channels
639 {
640  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
641  if (channels[i].function == function) {
642  channels[i].set_angle(angle);
643  }
644  }
645 }
646 
647 // call set_range() on matching channels
649 {
650  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
651  if (channels[i].function == function) {
652  channels[i].set_range(range);
653  }
654  }
655 }
656 
657 // constrain to output min/max for function
659 {
660  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
661  SRV_Channel &ch = channels[i];
662  if (ch.function == function) {
664  }
665  }
666 }
667 
668 /*
669  upgrade RC* parameters into SERVO* parameters. This does the following:
670 
671  - copies MIN/MAX/TRIM values from old RC parameters into new RC* parameters and SERVO* parameters.
672  - copies RCn_FUNCTION to SERVOn_FUNCTION
673  - maps old RCn_REV to SERVOn_REVERSE and RCn_REVERSE
674 
675  aux_channel_mask is a bitmask of which channels were RC_Channel_aux channels
676 
677  Note that this code is highly dependent on the parameter indexing of
678  the old RC_Channel and RC_Channel_aux objects.
679 
680  If rcmap is passed in then the vehicle code also wants functions for
681  the first 4 output channels to be remapped
682 
683  We return true if an upgrade has been done. This allows the caller
684  to make any vehicle specific upgrades that may be needed
685 */
686 bool SRV_Channels::upgrade_parameters(const uint8_t rc_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap)
687 {
688  // use SERVO16_FUNCTION as a marker to say that we have run the upgrade already
689  if (channels[15].function.configured_in_storage()) {
690  // upgrade already done
691  return false;
692  }
693 
694  // old system had 14 RC channels
695  for (uint8_t i=0; i<14; i++) {
696  uint8_t k = rc_keys[i];
697  if (k == 0) {
698  // missing parameter. Some vehicle types didn't have all parameters
699  continue;
700  }
701  SRV_Channel &srv_chan = channels[i];
702  RC_Channel &rc_chan = RC_Channels::channels[i];
703  enum {
704  FLAG_NONE=0,
705  FLAG_IS_REVERSE=1,
706  FLAG_AUX_ONLY=2
707  };
708  const struct mapping {
709  uint8_t old_index;
710  AP_Param *new_srv_param;
711  AP_Param *new_rc_param;
712  enum ap_var_type type;
713  uint8_t flags;
714  } mapping[] = {
715  { 0, &srv_chan.servo_min, &rc_chan.radio_min, AP_PARAM_INT16, FLAG_NONE },
716  { 1, &srv_chan.servo_trim, &rc_chan.radio_trim, AP_PARAM_INT16, FLAG_NONE },
717  { 2, &srv_chan.servo_max, &rc_chan.radio_max, AP_PARAM_INT16, FLAG_NONE },
718  { 3, &srv_chan.reversed, &rc_chan.reversed, AP_PARAM_INT8, FLAG_IS_REVERSE },
719  { 1, &srv_chan.function, nullptr, AP_PARAM_INT8, FLAG_AUX_ONLY },
720  };
721  bool is_aux = aux_channel_mask & (1U<<i);
722 
723  for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) {
724  const struct mapping &m = mapping[j];
726  AP_Int8 v8;
727  AP_Int16 v16;
728  AP_Param *v = m.type == AP_PARAM_INT16?(AP_Param*)&v16:(AP_Param*)&v8;
729  bool aux_only = (m.flags & FLAG_AUX_ONLY)!=0;
730  if (!is_aux && aux_only) {
731  continue;
732  }
733  info.old_key = k;
734  info.type = m.type;
735  info.new_name = nullptr;
736 
737  // if this was an aux channel we need to shift by 6 bits, but not for RCn_FUNCTION
738  info.old_group_element = (is_aux && !aux_only)?(m.old_index<<6):m.old_index;
739 
740  if (!AP_Param::find_old_parameter(&info, v)) {
741  // the parameter wasn't set in the old eeprom
742  continue;
743  }
744 
745  if (m.flags & FLAG_IS_REVERSE) {
746  // special mapping from RCn_REV to RCn_REVERSED
747  v8.set(v8.get() == -1?1:0);
748  }
749 
750  if (!m.new_srv_param->configured_in_storage()) {
751  // not configured yet in new eeprom
752  if (m.type == AP_PARAM_INT16) {
753  ((AP_Int16 *)m.new_srv_param)->set_and_save_ifchanged(v16.get());
754  } else {
755  ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get());
756  }
757  }
758  if (m.new_rc_param && !m.new_rc_param->configured_in_storage()) {
759  // not configured yet in new eeprom
760  if (m.type == AP_PARAM_INT16) {
761  ((AP_Int16 *)m.new_rc_param)->set_and_save_ifchanged(v16.get());
762  } else {
763  ((AP_Int8 *)m.new_rc_param)->set_and_save_ifchanged(v8.get());
764  }
765  }
766  }
767  }
768 
769  if (rcmap != nullptr) {
770  // we need to make the output functions from the rcmapped inputs
771  const int8_t func_map[4] = { channels[0].function.get(),
772  channels[1].function.get(),
773  channels[2].function.get(),
774  channels[3].function.get() };
775  const uint8_t map[4] = { rcmap->roll(), rcmap->pitch(), rcmap->throttle(), rcmap->yaw() };
776  for (uint8_t i=0; i<4; i++) {
777  uint8_t m = uint8_t(map[i]-1);
778  if (m != i && m < 4) {
779  channels[m].function.set_and_save_ifchanged(func_map[i]);
780  }
781  }
782  }
783 
784  // mark the upgrade as having been done
785  channels[15].function.set_and_save(channels[15].function.get());
786 
787  return true;
788 }
789 
790 /*
791  Upgrade servo MIN/MAX/TRIM/REVERSE parameters for a single AP_Motors
792  RC_Channel servo from previous firmwares, setting the equivalent
793  parameter in the new SRV_Channels object
794 */
795 void SRV_Channels::upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel)
796 {
797  SRV_Channel &srv_chan = channels[new_channel];
798  enum {
799  FLAG_NONE=0,
800  FLAG_IS_REVERSE=1
801  };
802  const struct mapping {
803  uint8_t old_index;
804  AP_Param *new_srv_param;
805  enum ap_var_type type;
806  uint8_t flags;
807  } mapping[] = {
808  { 0, &srv_chan.servo_min, AP_PARAM_INT16, FLAG_NONE },
809  { 1, &srv_chan.servo_trim, AP_PARAM_INT16, FLAG_NONE },
810  { 2, &srv_chan.servo_max, AP_PARAM_INT16, FLAG_NONE },
811  { 3, &srv_chan.reversed, AP_PARAM_INT8, FLAG_IS_REVERSE },
812  };
813 
814  for (uint8_t j=0; j<ARRAY_SIZE(mapping); j++) {
815  const struct mapping &m = mapping[j];
817  AP_Int8 v8;
818  AP_Int16 v16;
819  AP_Param *v = m.type == AP_PARAM_INT16?(AP_Param*)&v16:(AP_Param*)&v8;
820 
821  info.old_key = ap_motors_key;
822  info.type = m.type;
823  info.new_name = nullptr;
824  info.old_group_element = ap_motors_idx | (m.old_index<<6);
825 
826  if (!AP_Param::find_old_parameter(&info, v)) {
827  // the parameter wasn't set in the old eeprom
828  continue;
829  }
830 
831  if (m.flags & FLAG_IS_REVERSE) {
832  // special mapping from RCn_REV to RCn_REVERSED
833  v8.set(v8.get() == -1?1:0);
834  }
835 
836  // we save even if there is already a value in the new eeprom,
837  // as that may come from the equivalent RC channel, not the
838  // old motor servo channel
839  if (m.type == AP_PARAM_INT16) {
840  ((AP_Int16 *)m.new_srv_param)->set_and_save_ifchanged(v16.get());
841  } else {
842  ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get());
843  }
844  }
845 }
846 
847 // set RC output frequency on a function output
849 {
850  uint16_t mask = 0;
851  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
852  SRV_Channel &ch = channels[i];
853  if (ch.function == function) {
854  mask |= (1U<<ch.ch_num);
855  }
856  }
857  if (mask != 0) {
858  hal.rcout->set_freq(mask, frequency_hz);
859  }
860 }
differential spoiler 1 (left wing)
Definition: SRV_Channel.h:60
static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle)
secondary rudder channel
Definition: SRV_Channel.h:65
static void copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool do_input_output=false)
const char * new_name
Definition: AP_Param.h:173
AP_Int8 reversed
Definition: RC_Channel.h:117
static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel)
static void move_servo(SRV_Channel::Aux_servo_function_t function, int16_t value, int16_t angle_min, int16_t angle_max)
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
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static bool passthrough_disabled(void)
Definition: SRV_Channel.h:473
AP_Int16 radio_min
Definition: RC_Channel.h:113
static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function)
int16_t get_radio_trim() const
Definition: RC_Channel.h:94
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
static int16_t get_output_scaled(SRV_Channel::Aux_servo_function_t function)
ap_var_type
Definition: AP_Param.h:124
static void set_output_pwm_first(SRV_Channel::Aux_servo_function_t function, uint16_t value)
void set_angle(int16_t angle)
aileron, with rc input, deprecated
Definition: SRV_Channel.h:62
bool type_setup
Definition: SRV_Channel.h:211
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
Definition: AP_Param.cpp:1606
void set_range(uint16_t high)
static uint16_t disabled_mask
Definition: SRV_Channel.h:457
flaperon, right wing
Definition: SRV_Channel.h:69
static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static void set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function)
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
Definition: RCOutput.h:111
int16_t get_radio_in() const
Definition: RC_Channel.h:79
static RC_Channel * rc_channel(uint8_t chan)
Definition: RC_Channel.h:145
static bool set_aux_channel_default(SRV_Channel::Aux_servo_function_t function, uint8_t channel)
static void limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt)
virtual void set_freq(uint32_t chmask, uint16_t freq_hz)=0
differential spoiler 1 (right wing)
Definition: SRV_Channel.h:61
static void set_output_to_trim(SRV_Channel::Aux_servo_function_t function)
uint16_t get_output_max(void) const
Definition: SRV_Channel.h:164
uint8_t ch_num
Definition: SRV_Channel.h:214
static void set_range(SRV_Channel::Aux_servo_function_t function, uint16_t range)
AP_Int8 function
Definition: SRV_Channel.h:202
AP_Int16 servo_trim
Definition: SRV_Channel.h:199
void set_radio_in(int16_t val)
Definition: RC_Channel.h:80
these are for pass-thru from arbitrary rc inputs
Definition: SRV_Channel.h:86
differential spoiler 2 (left wing)
Definition: SRV_Channel.h:121
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
virtual uint16_t read_last_sent(uint8_t ch)
Definition: RCOutput.h:74
tiltrotor motor tilt control
Definition: SRV_Channel.h:85
static bool get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value)
void output_ch(void)
map a function to a servo channel and output it
static void constrain_pwm(SRV_Channel::Aux_servo_function_t function)
static RC_Channel * rc
Definition: RC_Channel.cpp:17
uint8_t roll() const
roll - return input channel number for roll / aileron input
Definition: AP_RCMapper.h:16
static uint16_t pwm
Definition: RCOutput.cpp:20
flaperon, left wing
Definition: SRV_Channel.h:68
static void update_aux_servo_function(void)
setup the output range types of all functions
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan)
uint8_t yaw() const
yaw - return input channel number for yaw / rudder input
Definition: AP_RCMapper.h:25
virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us)
Definition: RCOutput.h:81
uint8_t pitch() const
pitch - return input channel number for pitch / elevator input
Definition: AP_RCMapper.h:19
static void output_ch_all(void)
virtual void enable_ch(uint8_t ch)=0
AP_Int16 servo_max
Definition: SRV_Channel.h:198
AP_Int16 servo_min
Definition: SRV_Channel.h:197
void aux_servo_function_setup(void)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint16_t output_pwm
Definition: SRV_Channel.h:205
virtual void set_default_rate(uint16_t rate_hz)
Definition: RCOutput.h:185
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
RC_Channel manager, with EEPROM-backed storage of constants.
Object managing one RC channel.
Definition: RC_Channel.h:15
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
manual, just pass-thru the RC in signal
Definition: SRV_Channel.h:45
virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
Definition: RCOutput.h:86
vectored thrust, left tilt
Definition: SRV_Channel.h:110
AP_Int16 radio_max
Definition: RC_Channel.h:115
helicopter tail RSC output
Definition: SRV_Channel.h:76
AP_Int8 reversed
Definition: SRV_Channel.h:201
AP_Int16 radio_trim
Definition: RC_Channel.h:114
uint16_t get_output_min(void) const
Definition: SRV_Channel.h:161
virtual void write(uint8_t ch, uint16_t period_us)=0
elevator, with rc input, deprecated
Definition: SRV_Channel.h:64
float v
Definition: Printf.cpp:15
static void enable_aux_servos(void)
Should be called after the the servo functions have been initialized.
static void set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
static void copy_radio_in_out_mask(uint16_t mask)
vectored thrust, right tilt
Definition: SRV_Channel.h:111
static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
uint16_t read() const
Definition: RC_Channel.cpp:325
helicopter RSC output
Definition: SRV_Channel.h:75
void adjust_trim(SRV_Channel::Aux_servo_function_t function, float v)
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency)
static RC_Channel * channels
Definition: RC_Channel.h:162
flap automated
Definition: SRV_Channel.h:47
uint32_t old_group_element
Definition: AP_Param.h:171
static uint16_t get_output_channel_mask(SRV_Channel::Aux_servo_function_t function)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void set_esc_scaling_for(SRV_Channel::Aux_servo_function_t function)
static float get_output_norm(SRV_Channel::Aux_servo_function_t function)
enum ap_var_type type
Definition: AP_Param.h:172
bool get_reversed(void) const
Definition: SRV_Channel.h:148
differential spoiler 2 (right wing)
Definition: SRV_Channel.h:122
uint8_t throttle() const
throttle - return input channel number for throttle input
Definition: AP_RCMapper.h:22
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
static servo_mask_t have_pwm_mask
Definition: SRV_Channel.h:245
float value
static void set_default_function(uint8_t chan, SRV_Channel::Aux_servo_function_t function)
ground steering, used to separate from rudder
Definition: SRV_Channel.h:70
static SRV_Channel::Aux_servo_function_t channel_function(uint8_t channel)
#define NUM_SERVO_CHANNELS
Definition: SRV_Channel.h:24
void set_output_pwm(uint16_t pwm)
static void enable_by_mask(uint16_t mask)
enable output channels using a channel mask
void calc_pwm(int16_t output_scaled)
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)
static void set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, int16_t value)
static void set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm)
static void set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm)
vertical booster throttle
Definition: SRV_Channel.h:116