mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
AP_AHRS: use SIM_ODOM_ENABLE to enable visual odom in SITL
This commit is contained in:
parent
67404e9660
commit
28030dd85c
@ -300,6 +300,8 @@ void AP_AHRS_NavEKF::update_SITL(void)
|
||||
_accel_ef_ekf_blended = _accel_ef_ekf[0];
|
||||
|
||||
}
|
||||
|
||||
if (_sitl->odom_enable) {
|
||||
// use SITL states to write body frame odometry data at 20Hz
|
||||
uint32_t timeStamp_ms = AP_HAL::millis();
|
||||
if (timeStamp_ms - _last_body_odm_update_ms > 50) {
|
||||
@ -321,6 +323,7 @@ void AP_AHRS_NavEKF::update_SITL(void)
|
||||
EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
// accelerometer values in the earth frame in m/s/s
|
||||
|
Loading…
Reference in New Issue
Block a user