From e2d4182c757351aebe1f14548f9194ae72d844ed Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 16 Aug 2017 12:04:10 +0900 Subject: [PATCH] Rover: fix parameter conversion --- APMrover2/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 80b3fd8b6d..8e694198b8 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -575,6 +575,7 @@ void Rover::load_parameters(void) const uint32_t before = micros(); // Load all auto-loaded EEPROM variables AP_Param::load_all(); + AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); AP_Param::set_frame_type_flags(AP_PARAM_FRAME_ROVER);