From 718a5b70e3d8bba78aa263324ea9fef5550c8f1f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Feb 2012 10:39:57 +1100 Subject: [PATCH] AP_Param: fixed saving of sensor calibration this fixes the saving of the accel and gyro calibration to EEPROM, which was initially broken by the AP_Param conversion --- ArduCopter/Parameters.h | 2 +- ArduCopter/Parameters.pde | 3 ++- ArduPlane/Parameters.h | 2 +- ArduPlane/Parameters.pde | 3 ++- 4 files changed, 6 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index a4e952f6f5..5023882a99 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -92,7 +92,7 @@ public: // // 140: Sensor parameters // - k_param_IMU_calibration = 140, + k_param_imu = 140, // sensor calibration k_param_battery_monitoring, k_param_volt_div_ratio, k_param_curr_amp_per_volt, diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 27470800e9..f6520830b2 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -142,7 +142,8 @@ static const AP_Param::Info var_info[] PROGMEM = { // variables not in the g class which contain EEPROM saved variables GOBJECT(compass, "COMPASS_", Compass), GOBJECT(gcs0, "SR0_", GCS_MAVLINK), - GOBJECT(gcs3, "SR3_", GCS_MAVLINK) + GOBJECT(gcs3, "SR3_", GCS_MAVLINK), + GOBJECT(imu, "IMU_", IMU) }; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index e2d9043e09..f508e6c38d 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -68,7 +68,7 @@ public: // // 130: Sensor parameters // - k_param_IMU_calibration = 130, + k_param_imu = 130, // sensor calibration k_param_altitude_mix, k_param_airspeed_ratio, k_param_ground_temperature, diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 08248072d5..4b0bda9ae0 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -123,7 +123,8 @@ static const AP_Param::Info var_info[] PROGMEM = { // variables not in the g class which contain EEPROM saved variables GOBJECT(compass, "COMPASS_", Compass), GOBJECT(gcs0, "SR0_", GCS_MAVLINK), - GOBJECT(gcs3, "SR3_", GCS_MAVLINK) + GOBJECT(gcs3, "SR3_", GCS_MAVLINK), + GOBJECT(imu, "IMU_", IMU) };