APM:Libraries
AP_Proximity_MAV.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_Proximity.h"
4 #include "AP_Proximity_Backend.h"
5 
6 #define PROXIMITY_MAV_TIMEOUT_MS 200 // requests timeout after 0.2 seconds
7 
9 {
10 
11 public:
12  // constructor
14 
15  // update state
16  void update(void);
17 
18  // get maximum and minimum distances (in meters) of sensor
19  float distance_max() const { return _distance_max; }
20  float distance_min() const { return _distance_min; };
21 
22  // get distance upwards in meters. returns true on success
23  bool get_upward_distance(float &distance) const;
24 
25  // handle mavlink DISTANCE_SENSOR messages
26  void handle_msg(mavlink_message_t *msg) override;
27 
28 private:
29 
30  // initialise sensor (returns true if sensor is succesfully initialised)
31  bool initialise();
32 
33  // horizontal distance support
34  uint32_t _last_update_ms; // system time of last DISTANCE_SENSOR message received
35  float _distance_max; // max range of sensor in meters
36  float _distance_min; // min range of sensor in meters
37 
38  // upward distance support
39  uint32_t _last_upward_update_ms; // system time of last update distance
40  float _distance_upward; // upward distance in meters
41 };
float distance_min() const
float distance
Definition: location.cpp:94
float distance_max() const
bool get_upward_distance(float &distance) const
uint32_t _last_upward_update_ms
uint32_t _last_update_ms
void handle_msg(mavlink_message_t *msg) override
AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)