mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
RC_Channel: added set_radio_trimmed()
take into account trim value in set_radio()
This commit is contained in:
parent
8d54368650
commit
33e4f44434
@ -162,6 +162,24 @@ RC_Channel_aux::set_radio(RC_Channel_aux::Aux_servo_function_t function, int16_t
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
set radio_out for all channels matching the given function type, allow radio_trim to center servo
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
RC_Channel_aux::set_radio_trimmed(RC_Channel_aux::Aux_servo_function_t function, int16_t value)
|
||||||
|
{
|
||||||
|
if (!function_assigned(function)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) {
|
||||||
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
|
int16_t value2 = value - 1500 + _aux_channels[i]->radio_trim;
|
||||||
|
_aux_channels[i]->radio_out = constrain_int16(value2,_aux_channels[i]->radio_min,_aux_channels[i]->radio_max);
|
||||||
|
_aux_channels[i]->output();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set and save the trim value to radio_in for all channels matching
|
set and save the trim value to radio_in for all channels matching
|
||||||
the given function type
|
the given function type
|
||||||
|
@ -82,6 +82,9 @@ public:
|
|||||||
// set radio_out for a function channel
|
// set radio_out for a function channel
|
||||||
static void set_radio(Aux_servo_function_t function, int16_t value);
|
static void set_radio(Aux_servo_function_t function, int16_t value);
|
||||||
|
|
||||||
|
// set radio_out for all channels matching the given function type, allow radio_trim to center servo
|
||||||
|
static void set_radio_trimmed(Aux_servo_function_t function, int16_t value);
|
||||||
|
|
||||||
// set and save the trim for a function channel to radio_in
|
// set and save the trim for a function channel to radio_in
|
||||||
static void set_radio_trim(Aux_servo_function_t function);
|
static void set_radio_trim(Aux_servo_function_t function);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user