AP_RangeFinder: increase leddarvu8 timeout to 0.5sec

This commit is contained in:
Randy Mackay 2020-01-20 17:14:04 +09:00 committed by Andrew Tridgell
parent f269004610
commit 141099078c
1 changed files with 3 additions and 0 deletions

View File

@ -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