mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Fix parameter name when saving persistent accel cals for Aux IMUs
Without this change, you get: * IMU_ACCOFFS_* * IMU_ACC2OFFS_* * IMU_ACC3OFFS_* * IMU3_ACCOFFS_* After this change, you get: * IMU_ACCOFFS_* * IMU_ACC2OFFS_* * IMU_ACC3OFFS_* * IMU4_ACCOFFS_*
This commit is contained in:
parent
1e2600c2e3
commit
9dbc61f85b
|
@ -517,7 +517,7 @@ void AP_InertialSensor::get_persistent_params(ExpandingString &str) const
|
||||||
}
|
}
|
||||||
#if INS_AUX_INSTANCES
|
#if INS_AUX_INSTANCES
|
||||||
for (uint8_t i=0; i<INS_AUX_INSTANCES; i++) {
|
for (uint8_t i=0; i<INS_AUX_INSTANCES; i++) {
|
||||||
const uint8_t imu = i+(INS_MAX_INSTANCES-INS_AUX_INSTANCES);
|
const uint8_t imu = i+(INS_MAX_INSTANCES-INS_AUX_INSTANCES)+1;
|
||||||
const Vector3f &aoff = params[i]._accel_offset.get();
|
const Vector3f &aoff = params[i]._accel_offset.get();
|
||||||
const Vector3f &ascl = params[i]._accel_scale.get();
|
const Vector3f &ascl = params[i]._accel_scale.get();
|
||||||
str.printf("INS%u_ACC_ID=%u\n", imu, unsigned(params[i]._accel_id.get()));
|
str.printf("INS%u_ACC_ID=%u\n", imu, unsigned(params[i]._accel_id.get()));
|
||||||
|
|
Loading…
Reference in New Issue