mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_InertialSensor: fixed SITL with new HIL code
This commit is contained in:
parent
aeaa3c1e04
commit
ad7c612334
@ -1078,6 +1078,7 @@ void AP_InertialSensor::set_accel(uint8_t instance, const Vector3f &accel)
|
||||
{
|
||||
if (instance < INS_MAX_INSTANCES) {
|
||||
_accel[instance] = accel;
|
||||
_accel_healthy[instance] = true;
|
||||
}
|
||||
}
|
||||
|
||||
@ -1085,6 +1086,7 @@ void AP_InertialSensor::set_gyro(uint8_t instance, const Vector3f &gyro)
|
||||
{
|
||||
if (instance < INS_MAX_INSTANCES) {
|
||||
_gyro[instance] = gyro;
|
||||
_gyro_healthy[instance] = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -33,6 +33,7 @@ bool AP_InertialSensor_HIL::_init_sensor(void)
|
||||
_imu.register_accel();
|
||||
|
||||
_product_id = AP_PRODUCT_ID_NONE;
|
||||
_imu.set_hil_mode();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user