AP_RangeFinder: move update function to serial base class

This commit is contained in:
Peter Barker 2019-11-01 21:59:50 +11:00 committed by Peter Barker
parent b18f1a8e22
commit 60cbefc1ae
11 changed files with 31 additions and 9 deletions

View File

@ -27,7 +27,7 @@ private:
void send_message(uint16_t msgid, const uint8_t *payload, uint16_t payload_len);
// read a distance from the sensor
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
// process one byte received on serial port
// returns true if a distance message has been successfully parsed

View File

@ -26,7 +26,7 @@ private:
// get a reading
// distance returned in reading_cm
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
uint8_t linebuf[10];
uint8_t linebuf_len;

View File

@ -26,7 +26,7 @@ protected:
private:
// get a reading
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
uint8_t buf[6];
uint8_t buf_len = 0;

View File

@ -55,7 +55,7 @@ protected:
private:
// get a reading
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
// CRC16
bool CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck);

View File

@ -21,7 +21,7 @@ protected:
private:
// get a reading
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
char linebuf[10];
uint8_t linebuf_len = 0;

View File

@ -21,7 +21,7 @@ protected:
private:
// get a reading
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
char linebuf[10];
uint8_t linebuf_len = 0;

View File

@ -44,7 +44,7 @@ private:
};
// get a reading
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
// add a single character to the buffer and attempt to decode
// returns true if a complete sentence was successfully decoded

View File

@ -47,7 +47,7 @@ private:
wasp_configuration_stage configuration_state = WASP_CFG_PROTOCOL;
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
void parse_response(void);

View File

@ -32,7 +32,7 @@ private:
bool detect_version(void);
// get a reading
bool get_reading(uint16_t &reading_cm);
bool get_reading(uint16_t &reading_cm) override;
uint8_t _linebuf[6];
uint8_t _linebuf_len;

View File

@ -51,3 +51,18 @@ bool AP_RangeFinder_Backend_Serial::detect(uint8_t serial_instance)
{
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
}
/*
update the state of the sensor
*/
void AP_RangeFinder_Backend_Serial::update(void)
{
if (get_reading(state.distance_cm)) {
// update range_valid state based on distance measured
state.last_reading_ms = AP_HAL::millis();
update_status();
} else if (AP_HAL::millis() - state.last_reading_ms > 200) {
set_status(RangeFinder::Status::NoData);
}
}

View File

@ -23,4 +23,11 @@ protected:
virtual uint16_t tx_bufsize() const { return 0; }
AP_HAL::UARTDriver *uart = nullptr;
// update state; not all backends call this!
virtual void update(void) override;
// it is essential that anyone relying on the base-class update to
// implement this:
virtual bool get_reading(uint16_t &reading_cm) { return 0; }
};