AP_InertialSensor: save the accelerometer ID parameters

this is needed for factory accel cal
This commit is contained in:
Andrew Tridgell 2021-01-22 06:47:37 +11:00
parent 87528f47c8
commit bdb364d461

View File

@ -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);