From 1cbad0c86e14e903d4eb954018b4600c2eb6174a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Jan 2020 15:45:32 +1100 Subject: [PATCH] SRV_Channel: change function to AP_Int16 this also removes the old parameter conversion code used for when we first added the SERVO parameters. This was needed for conversion from Copter 3.4 and Plane 3.7 --- libraries/SRV_Channel/SRV_Channel.h | 7 +- libraries/SRV_Channel/SRV_Channel_aux.cpp | 179 +--------------------- 2 files changed, 10 insertions(+), 176 deletions(-) diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index b2b612b5bf..966fb5980c 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -241,7 +241,7 @@ private: AP_Int16 servo_trim; // reversal, following convention that 1 means reversed, 0 means normal AP_Int8 reversed; - AP_Int8 function; + AP_Int16 function; // a pending output value as PWM uint16_t output_pwm; @@ -455,9 +455,8 @@ public: return iradio_min, AP_PARAM_INT16, FLAG_NONE }, - { 1, &srv_chan.servo_trim, &rc_chan->radio_trim, AP_PARAM_INT16, FLAG_NONE }, - { 2, &srv_chan.servo_max, &rc_chan->radio_max, AP_PARAM_INT16, FLAG_NONE }, - { 3, &srv_chan.reversed, &rc_chan->reversed, AP_PARAM_INT8, FLAG_IS_REVERSE }, - { 1, &srv_chan.function, nullptr, AP_PARAM_INT8, FLAG_AUX_ONLY }, - }; - bool is_aux = aux_channel_mask & (1U<configured_in_storage()) { - // not configured yet in new eeprom - if (m.type == AP_PARAM_INT16) { - ((AP_Int16 *)m.new_srv_param)->set_and_save_ifchanged(v16.get()); - } else { - ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get()); - } - } - if (m.new_rc_param && !m.new_rc_param->configured_in_storage()) { - // not configured yet in new eeprom - if (m.type == AP_PARAM_INT16) { - ((AP_Int16 *)m.new_rc_param)->set_and_save_ifchanged(v16.get()); - } else { - ((AP_Int8 *)m.new_rc_param)->set_and_save_ifchanged(v8.get()); - } - } - } - } - - if (rcmap != nullptr) { - // we need to make the output functions from the rcmapped inputs - const int8_t func_map[4] = { channels[0].function.get(), - channels[1].function.get(), - channels[2].function.get(), - channels[3].function.get() }; - const uint8_t map[4] = { rcmap->roll(), rcmap->pitch(), rcmap->throttle(), rcmap->yaw() }; - for (uint8_t i=0; i<4; i++) { - uint8_t m = uint8_t(map[i]-1); - if (m != i && m < 4) { - channels[m].function.set_and_save_ifchanged(func_map[i]); - } - } - } - - // mark the upgrade as having been done - channels[15].function.set_and_save(channels[15].function.get()); - - return true; -} - -/* - Upgrade servo MIN/MAX/TRIM/REVERSE parameters for a single AP_Motors - RC_Channel servo from previous firmwares, setting the equivalent - parameter in the new SRV_Channels object -*/ -void SRV_Channels::upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel) -{ - SRV_Channel &srv_chan = channels[new_channel]; - enum { - FLAG_NONE=0, - FLAG_IS_REVERSE=1 - }; - const struct mapping { - uint8_t old_index; - AP_Param *new_srv_param; - enum ap_var_type type; - uint8_t flags; - } mapping[] = { - { 0, &srv_chan.servo_min, AP_PARAM_INT16, FLAG_NONE }, - { 1, &srv_chan.servo_trim, AP_PARAM_INT16, FLAG_NONE }, - { 2, &srv_chan.servo_max, AP_PARAM_INT16, FLAG_NONE }, - { 3, &srv_chan.reversed, AP_PARAM_INT8, FLAG_IS_REVERSE }, - }; - - for (uint8_t j=0; jset_and_save_ifchanged(v16.get()); - } else { - ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get()); - } + for (uint8_t i=0; i