mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
RC_Channel: add method to get current radio out for a function
This commit is contained in:
parent
23480a92ad
commit
319cfa766b
@ -208,6 +208,24 @@ RC_Channel_aux::set_radio(RC_Channel_aux::Aux_servo_function_t function, int16_t
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
get radio_out for *first* channel matching the given function type.
|
||||
Returns true if a value was found.
|
||||
*/
|
||||
bool RC_Channel_aux::get_radio(RC_Channel_aux::Aux_servo_function_t function, int16_t &value)
|
||||
{
|
||||
if (!function_assigned(function)) {
|
||||
return false;
|
||||
}
|
||||
for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) {
|
||||
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||
value = _aux_channels[i]->get_radio_out();
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
set radio_out for all channels matching the given function type, allow radio_trim to center servo
|
||||
*/
|
||||
|
@ -107,6 +107,9 @@ public:
|
||||
// set radio_out for a function channel
|
||||
static void set_radio(Aux_servo_function_t function, int16_t value);
|
||||
|
||||
// get radio_out for *first* channel matching the given function type.
|
||||
static bool get_radio(RC_Channel_aux::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);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user