mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_RPM: Move timeout check into synthetic quality check.
This commit is contained in:
parent
fd106b20c7
commit
59a44008d7
@ -135,10 +135,6 @@ bool AP_RPM::healthy(uint8_t instance) const
|
||||
if (instance >= num_instances) {
|
||||
return false;
|
||||
}
|
||||
// assume we get readings at at least 1Hz
|
||||
if (AP_HAL::millis() - state[instance].last_reading_ms > 1000) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// check that data quality is above minimum required
|
||||
if (state[instance].signal_quality < _quality_min[0]) {
|
||||
|
@ -120,6 +120,11 @@ void AP_RPM_PX4_PWM::update(void)
|
||||
if (count != 0) {
|
||||
state.last_reading_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
// assume we get readings at at least 1Hz, otherwise reset quality to zero
|
||||
if (AP_HAL::millis() - state.last_reading_ms > 1000) {
|
||||
state.signal_quality = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
Loading…
Reference in New Issue
Block a user