diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index fa41849be8..264ac82aeb 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -600,9 +600,6 @@ private: bool standby_active; - // set when we are upgrading parameters from 3.4 - bool upgrading_frame_params; - static const AP_Scheduler::Task scheduler_tasks[]; static const AP_Param::Info var_info[]; static const struct LogStructure log_structure[]; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 0e331dadb1..150d1b89fc 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1292,19 +1292,8 @@ void Copter::convert_pid_parameters(void) AP_Param::convert_old_parameters(¬chfilt_conversion_info[i], 1.0f); } - const uint8_t old_rc_keys[14] = { Parameters::k_param_rc_1_old, Parameters::k_param_rc_2_old, - Parameters::k_param_rc_3_old, Parameters::k_param_rc_4_old, - Parameters::k_param_rc_5_old, Parameters::k_param_rc_6_old, - Parameters::k_param_rc_7_old, Parameters::k_param_rc_8_old, - Parameters::k_param_rc_9_old, Parameters::k_param_rc_10_old, - Parameters::k_param_rc_11_old, Parameters::k_param_rc_12_old, - Parameters::k_param_rc_13_old, Parameters::k_param_rc_14_old }; - const uint16_t old_aux_chan_mask = 0x3FF0; - // note that we don't pass in rcmap as we don't want output channel functions changed based on rcmap - if (SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, nullptr)) { - // the rest needs to be done after motors allocation - upgrading_frame_params = true; - } + // make any SRV_Channel upgrades needed + SRV_Channels::upgrade_parameters(); } /* diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 811e1dba34..b0fc14d654 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -642,31 +642,6 @@ void Copter::allocate_motors(void) g.rc_speed.set_default(16000); } - if (upgrading_frame_params) { - // do frame specific upgrade. This is only done the first time we run the new firmware -#if FRAME_CONFIG == HELI_FRAME - SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 12, CH_1); - SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 13, CH_2); - SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 14, CH_3); - SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 15, CH_4); -#else - if (g2.frame_class == AP_Motors::MOTOR_FRAME_TRI) { - const AP_Param::ConversionInfo tri_conversion_info[] = { - { Parameters::k_param_motors, 32, AP_PARAM_INT16, "SERVO7_TRIM" }, - { Parameters::k_param_motors, 33, AP_PARAM_INT16, "SERVO7_MIN" }, - { Parameters::k_param_motors, 34, AP_PARAM_INT16, "SERVO7_MAX" }, - { Parameters::k_param_motors, 35, AP_PARAM_FLOAT, "MOT_YAW_SV_ANGLE" }, - }; - // we need to use CONVERT_FLAG_FORCE as the SERVO7_* parameters will already be set from RC7_* - AP_Param::convert_old_parameters(tri_conversion_info, ARRAY_SIZE(tri_conversion_info), AP_Param::CONVERT_FLAG_FORCE); - const AP_Param::ConversionInfo tri_conversion_info_rev { Parameters::k_param_motors, 31, AP_PARAM_INT8, "SERVO7_REVERSED" }; - AP_Param::convert_old_parameter(&tri_conversion_info_rev, 1, AP_Param::CONVERT_FLAG_REVERSE | AP_Param::CONVERT_FLAG_FORCE); - // AP_MotorsTri was converted from having nested var_info to one level - AP_Param::convert_parent_class(Parameters::k_param_motors, motors, motors->var_info); - } -#endif - } - // upgrade parameters. This must be done after allocating the objects convert_pid_parameters(); #if FRAME_CONFIG == HELI_FRAME