diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index c80f714455..9915fa7264 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1072,6 +1072,9 @@ void Copter::load_parameters(void) AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before)); + // setup AP_Param frame type flags + AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER); + // upgrade parameters convert_pid_parameters(); } diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 1c218d3faf..565a2d2426 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -551,6 +551,7 @@ void Copter::allocate_motors(void) case AP_Motors::MOTOR_FRAME_TRI: motors = new AP_MotorsTri(MAIN_LOOP_RATE); var_info = AP_MotorsTri::var_info; + AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER); break; case AP_Motors::MOTOR_FRAME_SINGLE: motors = new AP_MotorsSingle(MAIN_LOOP_RATE); @@ -565,6 +566,7 @@ void Copter::allocate_motors(void) default: motors = new AP_MotorsHeli_Single(MAIN_LOOP_RATE); var_info = AP_MotorsHeli::var_info; + AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI); break; #endif }