mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 18:23:57 -04:00
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:
parent
e399f57ffa
commit
6b6d03eb8d
@ -1075,8 +1075,6 @@ void Copter::load_parameters(void)
|
|||||||
// setup AP_Param frame type flags
|
// setup AP_Param frame type flags
|
||||||
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);
|
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
|
// handle conversion of PID gains from Copter-3.3 to Copter-3.4
|
||||||
|
@ -651,4 +651,7 @@ void Copter::allocate_motors(void)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// upgrade parameters. This must be done after allocating the objects
|
||||||
|
convert_pid_parameters();
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user