AP_Rangefinder: make backend get_reading() pure virtual

This commit is contained in:
Pierre Kancir 2021-06-04 18:33:29 +02:00 committed by Randy Mackay
parent 88b5ff8c6f
commit 117ca8a6ef
1 changed files with 1 additions and 1 deletions

View File

@ -29,7 +29,7 @@ protected:
// it is essential that anyone relying on the base-class update to
// implement this:
virtual bool get_reading(uint16_t &reading_cm) { return false; }
virtual bool get_reading(uint16_t &reading_cm) = 0;
// maximum time between readings before we change state to NoData:
virtual uint16_t read_timeout_ms() const { return 200; }