diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 9e79a7ff1f..5cd234b26d 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -768,6 +768,7 @@ private: void load_parameters(void); void convert_pid_parameters(void); void convert_lgr_parameters(void); + void convert_tradheli_parameters(void); // precision_landing.cpp void init_precland(); diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index bbdf372399..ca21a826d2 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1300,3 +1300,43 @@ void Copter::convert_lgr_parameters(void) servo_reversed->set_and_save_ifchanged(1); } } + +#if FRAME_CONFIG == HELI_FRAME +// handle conversion of tradheli parameters from Copter-3.6 to Copter-3.7 +void Copter::convert_tradheli_parameters(void) +{ + if (g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) { + // single heli conversion info + const AP_Param::ConversionInfo singleheli_conversion_info[] = { + { Parameters::k_param_motors, 1, AP_PARAM_INT16, "H_SW_H3_SV1_POS" }, + { Parameters::k_param_motors, 2, AP_PARAM_INT16, "H_SW_H3_SV2_POS" }, + { Parameters::k_param_motors, 3, AP_PARAM_INT16, "H_SW_H3_SV3_POS" }, + { Parameters::k_param_motors, 7, AP_PARAM_INT16, "H_SW_H3_PHANG" }, + }; + + // convert single heli paramters without scaling + uint8_t table_size = ARRAY_SIZE(singleheli_conversion_info); + for (uint8_t i=0; i