mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
SRV_Channel: added a SERVO_32_ENABLE parameter
save on param count for most users
This commit is contained in:
parent
ed01d33ef8
commit
e185e1252b
@ -641,6 +641,9 @@ private:
|
||||
AP_Int8 dshot_rate;
|
||||
AP_Int8 dshot_esc_type;
|
||||
AP_Int32 gpio_mask;
|
||||
#if NUM_SERVO_CHANNELS >= 17
|
||||
AP_Int8 enable_32_channels;
|
||||
#endif
|
||||
|
||||
// return true if passthrough is disabled
|
||||
static bool passthrough_disabled(void) {
|
||||
|
@ -76,7 +76,13 @@ void SRV_Channel::output_ch(void)
|
||||
*/
|
||||
void SRV_Channels::output_ch_all(void)
|
||||
{
|
||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||
uint8_t max_chan = NUM_SERVO_CHANNELS;
|
||||
#if NUM_SERVO_CHANNELS >= 17
|
||||
if (_singleton != nullptr && _singleton->enable_32_channels.get() <= 0) {
|
||||
max_chan = 16;
|
||||
}
|
||||
#endif
|
||||
for (uint8_t i = 0; i < max_chan; i++) {
|
||||
channels[i].output_ch();
|
||||
}
|
||||
}
|
||||
|
@ -242,7 +242,16 @@ const AP_Param::GroupInfo SRV_Channels::var_info[] = {
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("_GPIO_MASK", 26, SRV_Channels, gpio_mask, 0),
|
||||
|
||||
|
||||
#if (NUM_SERVO_CHANNELS >= 17)
|
||||
// @Param: _32_ENABLE
|
||||
// @DisplayName: Enable outputs 17 to 31
|
||||
// @Description: This allows for up to 32 outputs, enabling parameters for outputs above 16
|
||||
// @User: Advanced
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
AP_GROUPINFO_FLAGS("_32_ENABLE", 43, SRV_Channels, enable_32_channels, 0, AP_PARAM_FLAG_ENABLE),
|
||||
#endif
|
||||
|
||||
#if (NUM_SERVO_CHANNELS >= 17)
|
||||
// @Group: 17_
|
||||
// @Path: SRV_Channel.cpp
|
||||
|
Loading…
Reference in New Issue
Block a user