2016-12-23 02:03:21 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_Proximity.h"
|
|
|
|
#include "AP_Proximity_Backend.h"
|
|
|
|
|
|
|
|
class AP_Proximity_MAV : public AP_Proximity_Backend
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// constructor
|
|
|
|
AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
|
|
|
|
|
|
|
|
// update state
|
|
|
|
void update(void);
|
|
|
|
|
|
|
|
// get maximum and minimum distances (in meters) of sensor
|
|
|
|
float distance_max() const { return _distance_max; }
|
|
|
|
float distance_min() const { return _distance_min; };
|
|
|
|
|
2017-01-16 02:58:14 -04:00
|
|
|
// get distance upwards in meters. returns true on success
|
|
|
|
bool get_upward_distance(float &distance) const;
|
|
|
|
|
2016-12-23 02:03:21 -04:00
|
|
|
// handle mavlink DISTANCE_SENSOR messages
|
2017-01-09 23:09:18 -04:00
|
|
|
void handle_msg(mavlink_message_t *msg) override;
|
2016-12-23 02:03:21 -04:00
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
// initialise sensor (returns true if sensor is succesfully initialised)
|
|
|
|
bool initialise();
|
|
|
|
|
2017-01-16 02:58:14 -04:00
|
|
|
// horizontal distance support
|
2016-12-23 02:03:21 -04:00
|
|
|
uint32_t _last_update_ms; // system time of last DISTANCE_SENSOR message received
|
|
|
|
float _distance_max; // max range of sensor in meters
|
|
|
|
float _distance_min; // min range of sensor in meters
|
2017-01-16 02:58:14 -04:00
|
|
|
|
|
|
|
// upward distance support
|
|
|
|
uint32_t _last_upward_update_ms; // system time of last update distance
|
|
|
|
float _distance_upward; // upward distance in meters
|
2016-12-23 02:03:21 -04:00
|
|
|
};
|