mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: increase leddarvu8 timeout to 0.5sec
This commit is contained in:
parent
f269004610
commit
141099078c
|
@ -27,6 +27,9 @@ protected:
|
|||
// get a reading, distance returned in reading_cm
|
||||
bool get_reading(uint16_t &reading_cm) override;
|
||||
|
||||
// maximum time between readings before we change state to NoData:
|
||||
uint16_t read_timeout_ms() const override { return 500; }
|
||||
|
||||
private:
|
||||
|
||||
// function codes
|
||||
|
|
Loading…
Reference in New Issue