mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: increased DroneCAN airspeed timeout
This commit is contained in:
parent
88f7246c7f
commit
d48b95c4a7
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user