APM:Libraries
AP_Proximity_SITL.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_Proximity.h"
4 #include "AP_Proximity_Backend.h"
5 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 #include <SITL/SITL.h>
8 
10 {
11 
12 public:
13  // constructor
15 
16  // update state
17  void update(void) override;
18 
19  // get maximum and minimum distances (in meters) of sensor
20  float distance_max() const;
21  float distance_min() const;
22 
23  // get distance upwards in meters. returns true on success
24  bool get_upward_distance(float &distance) const;
25 
26 private:
29  AP_Int8 *fence_count;
30  AP_Float *fence_alt_max;
31  uint32_t last_load_ms;
34 
35  // latest sector updated
36  uint8_t last_sector;
37 
38  void load_fence(void);
39 
40  // get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction)
41  bool get_distance_to_fence(float angle_deg, float &distance) const;
42 
43 };
44 #endif // CONFIG_HAL_BOARD
bool get_distance_to_fence(float angle_deg, float &distance) const
float distance_max() const
bool get_upward_distance(float &distance) const
float distance
Definition: location.cpp:94
float distance_min() const
AP_Float * fence_alt_max
AC_PolyFence_loader fence_loader
AP_Proximity_SITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)
void update(void) override