mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_OpticalFlow: fixed reversed timestamp
thanks to Randy
This commit is contained in:
parent
d2634a26bd
commit
aff01c6d09
@ -65,7 +65,7 @@ void OpticalFlow::update(void)
|
||||
backend->update();
|
||||
}
|
||||
// only healthy if the data is less than 0.5s old
|
||||
_flags.healthy = (_last_update_ms - hal.scheduler->millis() < 500);
|
||||
_flags.healthy = (hal.scheduler->millis() - _last_update_ms < 500);
|
||||
}
|
||||
|
||||
void OpticalFlow::setHIL(const struct OpticalFlow::OpticalFlow_state &state)
|
||||
|
Loading…
Reference in New Issue
Block a user