Browse Source

AP_Proximity: increase MAV driver timeout to 500ms

this comes after testing with ROS/mavros and discovering the update rate is only 4hz
mission-4.1.18
Randy Mackay 6 years ago
parent
commit
7fa592e673
  1. 2
      libraries/AP_Proximity/AP_Proximity_MAV.cpp
  2. 2
      libraries/AP_Proximity/AP_Proximity_MAV.h

2
libraries/AP_Proximity/AP_Proximity_MAV.cpp

@ -21,6 +21,8 @@ @@ -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

2
libraries/AP_Proximity/AP_Proximity_MAV.h

@ -3,8 +3,6 @@ @@ -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
{

Loading…
Cancel
Save