APM:Libraries
AP_Proximity.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_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
23 
24 #define PROXIMITY_MAX_INSTANCES 1 // Maximum number of proximity sensor instances available on this platform
25 #define PROXIMITY_YAW_CORRECTION_DEFAULT 22 // default correction for sensor error in yaw
26 #define PROXIMITY_MAX_IGNORE 6 // up to six areas can be ignored
27 #define PROXIMITY_MAX_DIRECTION 8
28 #define PROXIMITY_SENSOR_ID_START 10
29 
31 
33 {
34 public:
35  friend class AP_Proximity_Backend;
36 
37  AP_Proximity(AP_SerialManager &_serial_manager);
38 
39  AP_Proximity(const AP_Proximity &other) = delete;
40  AP_Proximity &operator=(const AP_Proximity) = delete;
41 
42  // Proximity driver types
51  };
52 
57  };
58 
59  // structure holding distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
61  uint8_t orientation[PROXIMITY_MAX_DIRECTION]; // orientation (i.e. rough direction) of the distance (see MAV_SENSOR_ORIENTATION)
62  float distance[PROXIMITY_MAX_DIRECTION]; // distance in meters
63  };
64 
65  // detect and initialise any available proximity sensors
66  void init(void);
67 
68  // update state of all proximity sensors. Should be called at high rate from main loop
69  void update(void);
70 
71  // set pointer to rangefinder object
72  void set_rangefinder(const RangeFinder *rangefinder) { _rangefinder = rangefinder; }
73  const RangeFinder *get_rangefinder() const { return _rangefinder; }
74 
75  // return sensor orientation and yaw correction
76  uint8_t get_orientation(uint8_t instance) const;
77  int16_t get_yaw_correction(uint8_t instance) const;
78 
79  // return sensor health
80  Proximity_Status get_status(uint8_t instance) const;
82 
83  // Return the number of proximity sensors
84  uint8_t num_sensors(void) const {
85  return num_instances;
86  }
87 
88  // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
89  // returns true on successful read and places distance in distance
90  bool get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const;
91  bool get_horizontal_distance(float angle_deg, float &distance) const;
92 
93  // get distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
94  bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const;
95 
96  // get boundary points around vehicle for use by avoidance
97  // returns nullptr and sets num_points to zero if no boundary can be returned
98  const Vector2f* get_boundary_points(uint8_t instance, uint16_t& num_points) const;
99  const Vector2f* get_boundary_points(uint16_t& num_points) const;
100 
101  // get distance and angle to closest object (used for pre-arm check)
102  // returns true on success, false if no valid readings
103  bool get_closest_object(float& angle_deg, float &distance) const;
104 
105  // get number of objects, angle and distance - used for non-GPS avoidance
106  uint8_t get_object_count() const;
107  bool get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const;
108 
109  // get maximum and minimum distances (in meters) of primary sensor
110  float distance_max() const;
111  float distance_min() const;
112 
113  // handle mavlink DISTANCE_SENSOR messages
114  void handle_msg(mavlink_message_t *msg);
115 
116  // The Proximity_State structure is filled in by the backend driver
118  uint8_t instance; // the instance number of this proximity sensor
119  enum Proximity_Status status; // sensor status
120  };
121 
122  //
123  // support for upwardward facing sensors
124  //
125 
126  // get distance upwards in meters. returns true on success
127  bool get_upward_distance(uint8_t instance, float &distance) const;
128  bool get_upward_distance(float &distance) const;
129 
130  Proximity_Type get_type(uint8_t instance) const;
131 
132  // parameter list
133  static const struct AP_Param::GroupInfo var_info[];
134 
135  static AP_Proximity *get_singleton(void) { return _singleton; };
136 
137 private:
138  static AP_Proximity *_singleton;
142  uint8_t primary_instance:3;
143  uint8_t num_instances:3;
145 
146  // parameters for all instances
150  AP_Int16 _ignore_angle_deg[PROXIMITY_MAX_IGNORE]; // angle (in degrees) of area that should be ignored by sensor (i.e. leg shows up)
151  AP_Int8 _ignore_width_deg[PROXIMITY_MAX_IGNORE]; // width of beam (in degrees) that should be ignored
152 
153  void detect_instance(uint8_t instance);
154  void update_instance(uint8_t instance);
155 };
#define PROXIMITY_MAX_INSTANCES
Definition: AP_Proximity.h:24
AP_Int16 _ignore_angle_deg[PROXIMITY_MAX_IGNORE]
Definition: AP_Proximity.h:150
AP_Proximity & operator=(const AP_Proximity)=delete
void handle_msg(mavlink_message_t *msg)
uint8_t primary_instance
Definition: AP_Proximity.h:142
bool get_upward_distance(uint8_t instance, float &distance) const
#define PROXIMITY_MAX_IGNORE
Definition: AP_Proximity.h:26
Proximity_State state[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:139
#define PROXIMITY_MAX_DIRECTION
Definition: AP_Proximity.h:27
static AP_Proximity * _singleton
Definition: AP_Proximity.h:135
int16_t get_yaw_correction(uint8_t instance) const
const Vector2f * get_boundary_points(uint8_t instance, uint16_t &num_points) const
float distance_max() const
uint8_t get_object_count() const
void update_instance(uint8_t instance)
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Proximity.h:133
uint8_t num_sensors(void) const
Definition: AP_Proximity.h:84
bool get_object_angle_and_distance(uint8_t object_number, float &angle_deg, float &distance) const
A system for managing and storing variables that are of general interest to the system.
Proximity_Type get_type(uint8_t instance) const
bool get_closest_object(float &angle_deg, float &distance) const
AP_SerialManager & serial_manager
Definition: AP_Proximity.h:144
Proximity_Status get_status() const
uint8_t num_instances
Definition: AP_Proximity.h:143
AP_Int8 _ignore_width_deg[PROXIMITY_MAX_IGNORE]
Definition: AP_Proximity.h:151
AP_Proximity_Backend * drivers[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:140
AP_Int8 _type[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:147
const RangeFinder * get_rangefinder() const
Definition: AP_Proximity.h:73
AP_Int16 _yaw_correction[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:149
static AP_Proximity * get_singleton(void)
Definition: AP_Proximity.h:135
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
Common definitions and utility routines for the ArduPilot libraries.
uint8_t orientation[PROXIMITY_MAX_DIRECTION]
Definition: AP_Proximity.h:61
void detect_instance(uint8_t instance)
float distance[PROXIMITY_MAX_DIRECTION]
Definition: AP_Proximity.h:62
void init(void)
const RangeFinder * _rangefinder
Definition: AP_Proximity.h:141
AP_Int8 _orientation[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:148
void update(void)
float distance_min() const
Catch-all header that defines all supported RangeFinder classes.
bool get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const
AP_Proximity(AP_SerialManager &_serial_manager)
void set_rangefinder(const RangeFinder *rangefinder)
Definition: AP_Proximity.h:72
uint8_t get_orientation(uint8_t instance) const