Browse Source

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
mission-4.1.18
Andrew Tridgell 8 years ago committed by Randy Mackay
parent
commit
6b6d03eb8d
  1. 2
      ArduCopter/Parameters.cpp
  2. 3
      ArduCopter/system.cpp

2
ArduCopter/Parameters.cpp

@ -1075,8 +1075,6 @@ void Copter::load_parameters(void) @@ -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

3
ArduCopter/system.cpp

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

Loading…
Cancel
Save