Copter: setup frame type parameter flags

This commit is contained in:
Andrew Tridgell 2017-02-08 10:47:36 +11:00
parent 0fc04b0158
commit d8972d5344
2 changed files with 5 additions and 0 deletions

View File

@ -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();
}

View File

@ -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
}