mirror of https://github.com/ArduPilot/ardupilot
AP_Rangefinder: make backend get_reading() pure virtual
This commit is contained in:
parent
88b5ff8c6f
commit
117ca8a6ef
|
@ -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; }
|
||||
|
|
Loading…
Reference in New Issue