ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSeri...

36 lines
925 B
C
Raw Normal View History

#pragma once
#include "RangeFinder.h"
#include "RangeFinder_Backend.h"
class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend
{
public:
// constructor
AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
2019-02-03 22:21:58 -04:00
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);
// static detection function
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance);
// update state
void update(void) override;
protected:
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
return MAV_DISTANCE_SENSOR_ULTRASOUND;
}
private:
// get a reading
bool get_reading(uint16_t &reading_cm);
AP_HAL::UARTDriver *uart = nullptr;
char linebuf[10];
uint8_t linebuf_len = 0;
};