mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: added set_trim_to_servo_out_for()
this will be used for new TRIM_AUTO functionality in plane
This commit is contained in:
parent
9cb672e85e
commit
cde4afd28e
|
@ -288,8 +288,8 @@ public:
|
||||||
// set output for all channels matching the given function type, allow radio_trim to center servo
|
// set output for all channels matching the given function type, allow radio_trim to center servo
|
||||||
static void set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, int16_t value);
|
static void set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, int16_t value);
|
||||||
|
|
||||||
// set and save the trim for a function channel to radio_in on matching input channel
|
// set and save the trim for a function channel to the output value
|
||||||
static void set_trim_to_radio_in_for(SRV_Channel::Aux_servo_function_t function);
|
static void set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function);
|
||||||
|
|
||||||
// set the trim for a function channel to min of the channel
|
// set the trim for a function channel to min of the channel
|
||||||
static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function);
|
static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function);
|
||||||
|
|
|
@ -211,22 +211,18 @@ SRV_Channels::set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function,
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set and save the trim value to radio_in for all channels matching
|
set and save the trim value to current output for all channels matching
|
||||||
the given function type
|
the given function type
|
||||||
*/
|
*/
|
||||||
void
|
void
|
||||||
SRV_Channels::set_trim_to_radio_in_for(SRV_Channel::Aux_servo_function_t function)
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function)
|
||||||
{
|
{
|
||||||
if (!function_assigned(function)) {
|
if (!function_assigned(function)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
if (channels[i].function.get() == function) {
|
if (channels[i].function.get() == function) {
|
||||||
RC_Channel *rc = RC_Channels::rc_channel(channels[i].ch_num);
|
channels[i].servo_trim.set_and_save_ifchanged(channels[i].output_pwm);
|
||||||
if (rc && rc->get_radio_in() != 0) {
|
|
||||||
rc->set_radio_trim(rc->get_radio_in());
|
|
||||||
rc->save_radio_trim();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue