mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
RC_Channel: added channel_function()
this is used in the plane mixing code
This commit is contained in:
parent
913004beb0
commit
16fd113020
@ -350,10 +350,8 @@ static uint8_t oldSwitchPosition = 254;
|
||||
// This is used to enable the inverted flight feature
|
||||
static bool inverted_flight = false;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
// This is used to enable the PX4IO override for testing
|
||||
static bool px4io_override_enabled = false;
|
||||
#endif
|
||||
static bool px4io_override_enabled = false;
|
||||
|
||||
static struct {
|
||||
// These are trim values used for elevon control
|
||||
|
@ -65,6 +65,19 @@ void RC_Channel_aux::disable_aux_channel(uint8_t channel)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
return the current function for a channel
|
||||
*/
|
||||
RC_Channel_aux::Aux_servo_function_t RC_Channel_aux::channel_function(uint8_t channel)
|
||||
{
|
||||
for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) {
|
||||
if (_aux_channels[i] && _aux_channels[i]->_ch_out == channel) {
|
||||
return (RC_Channel_aux::Aux_servo_function_t)_aux_channels[i]->function.get();
|
||||
}
|
||||
}
|
||||
return RC_Channel_aux::k_none;
|
||||
}
|
||||
|
||||
/// Update the _aux_channels array of pointers to rc_x channels
|
||||
/// This is to be done before rc_init so that the channels get correctly initialized.
|
||||
/// It also should be called periodically because the user might change the configuration and
|
||||
|
@ -121,6 +121,9 @@ public:
|
||||
// prevent a channel from being used for auxillary functions
|
||||
static void disable_aux_channel(uint8_t channel);
|
||||
|
||||
// return the current function for a channel
|
||||
static Aux_servo_function_t channel_function(uint8_t channel);
|
||||
|
||||
private:
|
||||
static uint32_t _function_mask;
|
||||
static RC_Channel_aux *_aux_channels[RC_AUX_MAX_CHANNELS];
|
||||
|
Loading…
Reference in New Issue
Block a user