mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_InertialSensor: fixed 2nd IMU in Replay
this makes for much more accurate replay runs
This commit is contained in:
parent
ad8480d5f7
commit
b3ce56d34d
@ -1136,6 +1136,9 @@ void AP_InertialSensor::set_accel(uint8_t instance, const Vector3f &accel)
|
|||||||
if (instance < INS_MAX_INSTANCES) {
|
if (instance < INS_MAX_INSTANCES) {
|
||||||
_accel[instance] = accel;
|
_accel[instance] = accel;
|
||||||
_accel_healthy[instance] = true;
|
_accel_healthy[instance] = true;
|
||||||
|
if (_accel_count <= instance) {
|
||||||
|
_accel_count = instance+1;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1144,6 +1147,9 @@ void AP_InertialSensor::set_gyro(uint8_t instance, const Vector3f &gyro)
|
|||||||
if (instance < INS_MAX_INSTANCES) {
|
if (instance < INS_MAX_INSTANCES) {
|
||||||
_gyro[instance] = gyro;
|
_gyro[instance] = gyro;
|
||||||
_gyro_healthy[instance] = true;
|
_gyro_healthy[instance] = true;
|
||||||
|
if (_gyro_count <= instance) {
|
||||||
|
_gyro_count = instance+1;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user