mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: increased timeout on DroneCAN airspeed data
the data is sent at 20Hz, which means a single lost packet with 10Hz reading resulted in an unhealthy sensor
This commit is contained in:
parent
faa4d28851
commit
44c5754e36
@ -148,7 +148,7 @@ bool AP_Airspeed_DroneCAN::get_differential_pressure(float &pressure)
|
|||||||
{
|
{
|
||||||
WITH_SEMAPHORE(_sem_airspeed);
|
WITH_SEMAPHORE(_sem_airspeed);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - _last_sample_time_ms) > 250) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user