2016-05-04 00:02:44 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "RangeFinder.h"
|
|
|
|
#include "RangeFinder_Backend.h"
|
|
|
|
|
|
|
|
// Data timeout
|
2016-05-03 23:55:05 -03:00
|
|
|
#define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500
|
2016-05-04 00:02:44 -03:00
|
|
|
|
2016-05-03 23:55:05 -03:00
|
|
|
class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend
|
2016-05-04 00:02:44 -03:00
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// constructor
|
2016-05-03 23:55:05 -03:00
|
|
|
AP_RangeFinder_MAVLink(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state);
|
2016-05-04 00:02:44 -03:00
|
|
|
|
|
|
|
// static detection function
|
|
|
|
static bool detect(RangeFinder &ranger, uint8_t instance);
|
|
|
|
|
|
|
|
// update state
|
|
|
|
void update(void);
|
|
|
|
|
|
|
|
// Get update from mavlink
|
|
|
|
void handle_msg(mavlink_message_t *msg);
|
|
|
|
|
|
|
|
private:
|
2016-05-03 23:55:05 -03:00
|
|
|
uint16_t distance_cm;
|
2016-05-04 00:02:44 -03:00
|
|
|
uint32_t last_update_ms;
|
|
|
|
|
|
|
|
// start a reading
|
|
|
|
static bool start_reading(void);
|
|
|
|
static bool get_reading(uint16_t &reading_cm);
|
|
|
|
};
|