Browse Source

AP_InertialSensor: save the accelerometer ID parameters

this is needed for factory accel cal
c415-sdk
Andrew Tridgell 4 years ago
parent
commit
bdb364d461
  1. 1
      libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp

1
libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp

@ -483,6 +483,7 @@ void AP_InertialSensor::get_persistent_params(ExpandingString &str) const
if (i > 0) { if (i > 0) {
id[0] = '1'+i; 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_X=%f\n", id, aoff.x);
str.printf("INS_ACC%sOFFS_Y=%f\n", id, aoff.y); str.printf("INS_ACC%sOFFS_Y=%f\n", id, aoff.y);
str.printf("INS_ACC%sOFFS_Z=%f\n", id, aoff.z); str.printf("INS_ACC%sOFFS_Z=%f\n", id, aoff.z);

Loading…
Cancel
Save