From 0e0472054ac9630024cbfed99407d13d0ca3a532 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 24 Oct 2018 11:42:09 +0900 Subject: [PATCH] AP_Proximity: increase MAV driver timeout to 500ms this comes after testing with ROS/mavros and discovering the update rate is only 4hz --- libraries/AP_Proximity/AP_Proximity_MAV.cpp | 2 ++ libraries/AP_Proximity/AP_Proximity_MAV.h | 2 -- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.cpp b/libraries/AP_Proximity/AP_Proximity_MAV.cpp index 5a547d766b..f711c3f82d 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MAV.cpp @@ -21,6 +21,8 @@ extern const AP_HAL::HAL& hal; +#define PROXIMITY_MAV_TIMEOUT_MS 500 // distance messages must arrive within this many milliseconds + /* The constructor also initialises the proximity sensor. Note that this constructor is not called until detect() returns true, so we diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.h b/libraries/AP_Proximity/AP_Proximity_MAV.h index 6e75f7c5f3..1bd86909e1 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.h +++ b/libraries/AP_Proximity/AP_Proximity_MAV.h @@ -3,8 +3,6 @@ #include "AP_Proximity.h" #include "AP_Proximity_Backend.h" -#define PROXIMITY_MAV_TIMEOUT_MS 200 // requests timeout after 0.2 seconds - class AP_Proximity_MAV : public AP_Proximity_Backend {