mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Proximity: increase MAV driver timeout to 500ms
this comes after testing with ROS/mavros and discovering the update rate is only 4hz
This commit is contained in:
parent
d9ed07919c
commit
0e0472054a
@ -21,6 +21,8 @@
|
|||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
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
|
The constructor also initialises the proximity sensor. Note that this
|
||||||
constructor is not called until detect() returns true, so we
|
constructor is not called until detect() returns true, so we
|
||||||
|
@ -3,8 +3,6 @@
|
|||||||
#include "AP_Proximity.h"
|
#include "AP_Proximity.h"
|
||||||
#include "AP_Proximity_Backend.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
|
class AP_Proximity_MAV : public AP_Proximity_Backend
|
||||||
{
|
{
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user