Copter: fixed upgrade of parameters

now that we dynamically allocate many key objects in copter we need to
move the parameter upgrade code to after when the objects are allocated
This commit is contained in:
Andrew Tridgell 2017-02-13 20:37:51 +11:00 committed by Randy Mackay
parent e399f57ffa
commit 6b6d03eb8d
2 changed files with 3 additions and 2 deletions

View File

@ -1075,8 +1075,6 @@ void Copter::load_parameters(void)
// setup AP_Param frame type flags
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);
// upgrade parameters
convert_pid_parameters();
}
// handle conversion of PID gains from Copter-3.3 to Copter-3.4

View File

@ -651,4 +651,7 @@ void Copter::allocate_motors(void)
}
#endif
}
// upgrade parameters. This must be done after allocating the objects
convert_pid_parameters();
}