From bdb364d4619df6002fc1f085191c125f5aec12fc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 22 Jan 2021 06:47:37 +1100 Subject: [PATCH] AP_InertialSensor: save the accelerometer ID parameters this is needed for factory accel cal --- libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp index beabfea343..3fb8d24ceb 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp @@ -483,6 +483,7 @@ void AP_InertialSensor::get_persistent_params(ExpandingString &str) const if (i > 0) { id[0] = '1'+i; } + str.printf("INS_ACC%s_ID=%u\n", id, unsigned(_accel_id[i].get())); str.printf("INS_ACC%sOFFS_X=%f\n", id, aoff.x); str.printf("INS_ACC%sOFFS_Y=%f\n", id, aoff.y); str.printf("INS_ACC%sOFFS_Z=%f\n", id, aoff.z);