diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 20ee360b23..4ebd141a21 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -270,7 +270,7 @@ private: AP_Int16 servo_trim; // reversal, following convention that 1 means reversed, 0 means normal AP_Int8 reversed; - AP_Int16 function; + AP_Enum16 function; // a pending output value as PWM uint16_t output_pwm; diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 6f77ca8c9d..a25311192a 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -34,13 +34,13 @@ void SRV_Channel::output_ch(void) int8_t passthrough_from = -1; // take care of special function cases - switch(function) + switch(function.get()) { case k_manual: // manual passthrough_from = ch_num; break; case k_rcin1 ... k_rcin16: // rc pass-thru - passthrough_from = int8_t(function - k_rcin1); + passthrough_from = int8_t((int16_t)function - k_rcin1); break; } if (passthrough_from != -1) { @@ -87,7 +87,7 @@ void SRV_Channels::output_ch_all(void) SRV_Channel::Aux_servo_function_t SRV_Channels::channel_function(uint8_t channel) { if (channel < NUM_SERVO_CHANNELS) { - return (SRV_Channel::Aux_servo_function_t)channels[channel].function.get(); + return channels[channel].function; } return SRV_Channel::k_none; } @@ -100,7 +100,7 @@ void SRV_Channel::aux_servo_function_setup(void) if (type_setup) { return; } - switch (function) { + switch (function.get()) { case k_flap: case k_flap_auto: case k_egg_drop: @@ -181,11 +181,14 @@ void SRV_Channels::update_aux_servo_function(void) // set auxiliary ranges for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { - if ((uint16_t)channels[i].function.get() < SRV_Channel::k_nr_aux_servo_functions) { - channels[i].aux_servo_function_setup(); - function_mask.set((uint16_t)channels[i].function.get()); - functions[channels[i].function.get()].channel_mask |= 1U<= SRV_Channel::k_nr_aux_servo_functions) { + // invalid function number + continue; } + channels[i].aux_servo_function_setup(); + function_mask.set(function_num); + functions[function_num].channel_mask |= 1U<enable_ch(c.ch_num); } // output some servo functions before we fiddle with the // parameter values: - if (c.function.get() == SRV_Channel::k_min) { + if (c.function == SRV_Channel::k_min) { c.set_output_pwm(c.servo_min); c.output_ch(); - } else if (c.function.get() == SRV_Channel::k_trim) { + } else if (c.function == SRV_Channel::k_trim) { c.set_output_pwm(c.servo_trim); c.output_ch(); - } else if (c.function.get() == SRV_Channel::k_max) { + } else if (c.function == SRV_Channel::k_max) { c.set_output_pwm(c.servo_max); c.output_ch(); } @@ -277,7 +280,7 @@ void SRV_Channels::set_output_pwm(SRV_Channel::Aux_servo_function_t function, ui return; } for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { - if (channels[i].function.get() == function) { + if (channels[i].function == function) { channels[i].set_output_pwm(value); channels[i].output_ch(); } @@ -296,7 +299,7 @@ SRV_Channels::set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, return; } for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { - if (channels[i].function.get() == function) { + if (channels[i].function == function) { int16_t value2; if (channels[i].get_reversed()) { value2 = 1500 - value + channels[i].get_trim(); @@ -320,7 +323,7 @@ SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t functi return; } for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { - if (channels[i].function.get() == function) { + if (channels[i].function == function) { channels[i].servo_trim.set_and_save_ifchanged(channels[i].get_output_pwm()); } } @@ -336,7 +339,7 @@ SRV_Channels::copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool return; } for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { - if (channels[i].function.get() == function) { + if (channels[i].function == function) { RC_Channel *c = rc().channel(channels[i].ch_num); if (c == nullptr) { continue; @@ -378,7 +381,7 @@ SRV_Channels::set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint1 } for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { const SRV_Channel &c = channels[i]; - if (c.function.get() == function) { + if (c.function == function) { hal.rcout->set_failsafe_pwm(1U<set_failsafe_pwm(1U<printf("Channel %u already assigned function %u\n", (unsigned)(channel + 1), - (unsigned)channels[channel].function); + (unsigned)channels[channel].function.get()); return false; } channels[channel].type_setup = false; @@ -579,8 +582,8 @@ void SRV_Channels::set_trim_to_min_for(SRV_Channel::Aux_servo_function_t functio void SRV_Channels::set_default_function(uint8_t chan, SRV_Channel::Aux_servo_function_t function) { if (chan < NUM_SERVO_CHANNELS) { - int8_t old = channels[chan].function; - channels[chan].function.set_default((uint16_t)function); + const SRV_Channel::Aux_servo_function_t old = channels[chan].function; + channels[chan].function.set_default(function); if (old != channels[chan].function && channels[chan].function == function) { function_mask.set((uint16_t)function); } @@ -606,7 +609,7 @@ void SRV_Channels::adjust_trim(SRV_Channel::Aux_servo_function_t function, float } for (uint8_t i=0; i