mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
HAL_SITL: don't advance clock on garbage SIM input
This commit is contained in:
parent
4c96ec26e5
commit
cd66ce1c74
@ -242,10 +242,6 @@ void SITL_State::_fdm_input(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
hal.scheduler->stop_clock(d.fg_pkt.timestamp_us);
|
|
||||||
_synthetic_clock_mode = true;
|
|
||||||
got_fg_input = true;
|
|
||||||
|
|
||||||
if (d.fg_pkt.latitude == 0 ||
|
if (d.fg_pkt.latitude == 0 ||
|
||||||
d.fg_pkt.longitude == 0 ||
|
d.fg_pkt.longitude == 0 ||
|
||||||
d.fg_pkt.altitude <= 0) {
|
d.fg_pkt.altitude <= 0) {
|
||||||
@ -253,6 +249,10 @@ void SITL_State::_fdm_input(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
hal.scheduler->stop_clock(d.fg_pkt.timestamp_us);
|
||||||
|
_synthetic_clock_mode = true;
|
||||||
|
got_fg_input = true;
|
||||||
|
|
||||||
if (_sitl != NULL) {
|
if (_sitl != NULL) {
|
||||||
_sitl->state = d.fg_pkt;
|
_sitl->state = d.fg_pkt;
|
||||||
// prevent bad inputs from SIM from corrupting our state
|
// prevent bad inputs from SIM from corrupting our state
|
||||||
|
Loading…
Reference in New Issue
Block a user