APM:Libraries
AP_Proximity_Backend.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include "AP_Proximity.h"
20 
21 #define PROXIMITY_SECTORS_MAX 12 // maximum number of sectors
22 #define PROXIMITY_BOUNDARY_DIST_MIN 0.6f // minimum distance for a boundary point. This ensures the object avoidance code doesn't think we are outside the boundary.
23 #define PROXIMITY_BOUNDARY_DIST_DEFAULT 100 // if we have no data for a sector, boundary is placed 100m out
24 
26 {
27 public:
28  // constructor. This incorporates initialisation as well.
30 
31  // we declare a virtual destructor so that Proximity drivers can
32  // override with a custom destructor if need be
33  virtual ~AP_Proximity_Backend(void) {}
34 
35  // update the state structure
36  virtual void update() = 0;
37 
38  // get maximum and minimum distances (in meters) of sensor
39  virtual float distance_max() const = 0;
40  virtual float distance_min() const = 0;
41 
42  // get distance upwards in meters. returns true on success
43  virtual bool get_upward_distance(float &distance) const { return false; }
44 
45  // handle mavlink DISTANCE_SENSOR messages
46  virtual void handle_msg(mavlink_message_t *msg) {}
47 
48  // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
49  // returns true on successful read and places distance in distance
50  bool get_horizontal_distance(float angle_deg, float &distance) const;
51 
52  // get boundary points around vehicle for use by avoidance
53  // returns nullptr and sets num_points to zero if no boundary can be returned
54  const Vector2f* get_boundary_points(uint16_t& num_points) const;
55 
56  // get distance and angle to closest object (used for pre-arm check)
57  // returns true on success, false if no valid readings
58  bool get_closest_object(float& angle_deg, float &distance) const;
59 
60  // get number of objects, angle and distance - used for non-GPS avoidance
61  uint8_t get_object_count() const;
62  bool get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const;
63 
64  // get distances in 8 directions. used for sending distances to ground station
66 
67 protected:
68 
69  // set status and update valid_count
71 
72  // find which sector a given angle falls into
73  bool convert_angle_to_sector(float angle_degrees, uint8_t &sector) const;
74 
75  // initialise the boundary and sector_edge_vector array used for object avoidance
76  // should be called if the sector_middle_deg or _setor_width_deg arrays are changed
77  void init_boundary();
78 
79  // update boundary points used for object avoidance based on a single sector's distance changing
80  // the boundary points lie on the line between sectors meaning two boundary points may be updated based on a single sector's distance changing
81  // the boundary point is set to the shortest distance found in the two adjacent sectors, this is a conservative boundary around the vehicle
82  void update_boundary_for_sector(uint8_t sector);
83 
84  // get ignore area info
85  uint8_t get_ignore_area_count() const;
86  bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const;
87  bool get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const;
88 
90  AP_Proximity::Proximity_State &state; // reference to this instances state
91 
92  // sectors
94  uint16_t _sector_middle_deg[PROXIMITY_SECTORS_MAX] = {0, 45, 90, 135, 180, 225, 270, 315, 0, 0, 0, 0}; // middle angle of each sector
95  uint8_t _sector_width_deg[PROXIMITY_SECTORS_MAX] = {45, 45, 45, 45, 45, 45, 45, 45, 0, 0, 0, 0}; // width (in degrees) of each sector
96 
97  // sensor data
98  float _angle[PROXIMITY_SECTORS_MAX]; // angle to closest object within each sector
99  float _distance[PROXIMITY_SECTORS_MAX]; // distance to closest object within each sector
100  bool _distance_valid[PROXIMITY_SECTORS_MAX]; // true if a valid distance received for each sector
101 
102  // fence boundary
103  Vector2f _sector_edge_vector[PROXIMITY_SECTORS_MAX]; // vector for right-edge of each sector, used to speed up calculation of boundary
104  Vector2f _boundary_point[PROXIMITY_SECTORS_MAX]; // bounding polygon around the vehicle calculated conservatively for object avoidance
105 };
bool _distance_valid[PROXIMITY_SECTORS_MAX]
float _angle[PROXIMITY_SECTORS_MAX]
#define PROXIMITY_MAX_DIRECTION
Definition: AP_Proximity.h:27
uint16_t _sector_middle_deg[PROXIMITY_SECTORS_MAX]
void set_status(AP_Proximity::Proximity_Status status)
float distance
Definition: location.cpp:94
Vector2f _boundary_point[PROXIMITY_SECTORS_MAX]
bool convert_angle_to_sector(float angle_degrees, uint8_t &sector) const
uint8_t get_ignore_area_count() const
float _distance[PROXIMITY_SECTORS_MAX]
virtual bool get_upward_distance(float &distance) const
bool get_closest_object(float &angle_deg, float &distance) const
Vector2f _sector_edge_vector[PROXIMITY_SECTORS_MAX]
bool get_object_angle_and_distance(uint8_t object_number, float &angle_deg, float &distance) const
bool get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const
virtual float distance_max() const =0
virtual ~AP_Proximity_Backend(void)
virtual float distance_min() const =0
Common definitions and utility routines for the ArduPilot libraries.
AP_Proximity::Proximity_State & state
virtual void handle_msg(mavlink_message_t *msg)
bool get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const
uint8_t _sector_width_deg[PROXIMITY_SECTORS_MAX]
bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const
void update_boundary_for_sector(uint8_t sector)
#define PROXIMITY_SECTORS_MAX
bool get_horizontal_distance(float angle_deg, float &distance) const
AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)
const Vector2f * get_boundary_points(uint16_t &num_points) const
virtual void update()=0
uint8_t get_object_count() const