AP_Airspeed: increased DroneCAN airspeed timeout

This commit is contained in:
Andrew Tridgell 2023-08-11 14:04:00 +10:00 committed by Peter Barker
parent dfad23cc81
commit e78b1d4514
1 changed files with 1 additions and 1 deletions

View File

@ -172,7 +172,7 @@ bool AP_Airspeed_UAVCAN::get_differential_pressure(float &pressure)
{
WITH_SEMAPHORE(_sem_airspeed);
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
if ((AP_HAL::millis() - _last_sample_time_ms) > 250) {
return false;
}