2016-02-17 21:25:44 -04:00
|
|
|
#pragma once
|
2015-08-28 06:52:34 -03:00
|
|
|
|
|
|
|
#include "RangeFinder.h"
|
|
|
|
#include "RangeFinder_Backend.h"
|
2016-05-24 15:51:54 -03:00
|
|
|
#include <AP_HAL/I2CDevice.h>
|
2015-08-28 06:52:34 -03:00
|
|
|
|
|
|
|
class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// static detection function
|
2017-08-07 00:41:01 -03:00
|
|
|
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
|
2019-02-03 22:21:58 -04:00
|
|
|
AP_RangeFinder_Params &_params,
|
2017-08-07 00:41:01 -03:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
2015-08-28 06:52:34 -03:00
|
|
|
|
|
|
|
// update state
|
2018-11-07 07:01:51 -04:00
|
|
|
void update(void) override;
|
2015-08-28 06:52:34 -03:00
|
|
|
|
2017-08-08 04:32:53 -03:00
|
|
|
protected:
|
|
|
|
|
|
|
|
virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
|
|
|
|
return MAV_DISTANCE_SENSOR_LASER;
|
|
|
|
}
|
|
|
|
|
2015-08-28 06:52:34 -03:00
|
|
|
private:
|
2016-05-24 15:51:54 -03:00
|
|
|
// constructor
|
2018-07-04 11:22:17 -03:00
|
|
|
AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
2016-05-24 15:51:54 -03:00
|
|
|
|
2016-12-06 16:02:58 -04:00
|
|
|
void init();
|
2017-01-13 15:26:14 -04:00
|
|
|
void timer();
|
|
|
|
|
2015-08-28 06:52:34 -03:00
|
|
|
// get a reading
|
|
|
|
bool get_reading(uint16_t &reading_cm);
|
2016-05-24 15:51:54 -03:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
|
2015-08-28 06:52:34 -03:00
|
|
|
};
|