APM:Libraries
AP_Proximity_RangeFinder.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_RANGEFIDER_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 private:
26 
27  // horizontal distance support
28  uint32_t _last_update_ms; // system time of last RangeFinder reading
29  float _distance_max; // max range of sensor in meters
30  float _distance_min; // min range of sensor in meters
31 
32  // upward distance support
33  uint32_t _last_upward_update_ms; // system time of last update distance
34  float _distance_upward; // upward distance in meters, negative if the last reading was out of range
35 };
AP_Proximity_RangeFinder(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)
float distance
Definition: location.cpp:94
bool get_upward_distance(float &distance) const