ardupilot/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h

40 lines
833 B
C
Raw Normal View History

2016-05-04 00:02:44 -03:00
#pragma once
#include "RangeFinder.h"
#include "RangeFinder_Backend.h"
// Data timeout
#define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500
2016-05-04 00:02:44 -03:00
class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend
2016-05-04 00:02:44 -03:00
{
public:
// constructor
AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state);
2016-05-04 00:02:44 -03:00
// static detection function
static bool detect();
2016-05-04 00:02:44 -03:00
// update state
void update(void) override;
2016-05-04 00:02:44 -03:00
// Get update from mavlink
void handle_msg(mavlink_message_t *msg) override;
2016-05-04 00:02:44 -03:00
protected:
MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override {
return sensor_type;
}
2016-05-04 00:02:44 -03:00
private:
uint16_t distance_cm;
2016-05-04 00:02:44 -03:00
// start a reading
static bool start_reading(void);
static bool get_reading(uint16_t &reading_cm);
MAV_DISTANCE_SENSOR sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN;
2016-05-04 00:02:44 -03:00
};