From 6b6d03eb8df8643798fa1e8d53b815df5b7f7e06 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Feb 2017 20:37:51 +1100 Subject: [PATCH] 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 --- ArduCopter/Parameters.cpp | 2 -- ArduCopter/system.cpp | 3 +++ 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 9915fa7264..b33c0f5ded 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -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 diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 565a2d2426..61e9b34e80 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -651,4 +651,7 @@ void Copter::allocate_motors(void) } #endif } + + // upgrade parameters. This must be done after allocating the objects + convert_pid_parameters(); }