APM:Libraries
AP_Proximity.cpp
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 
16 #include "AP_Proximity.h"
18 #include "AP_Proximity_RPLidarA2.h"
21 #include "AP_Proximity_MAV.h"
22 #include "AP_Proximity_SITL.h"
23 
24 extern const AP_HAL::HAL &hal;
25 
26 // table of user settable parameters
28  // 0 is reserved for possible addition of an ENABLED parameter
29 
30  // @Param: _TYPE
31  // @DisplayName: Proximity type
32  // @Description: What type of proximity sensor is connected
33  // @Values: 0:None,1:LightWareSF40C,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2
34  // @RebootRequired: True
35  // @User: Standard
36  AP_GROUPINFO("_TYPE", 1, AP_Proximity, _type[0], 0),
37 
38  // @Param: _ORIENT
39  // @DisplayName: Proximity sensor orientation
40  // @Description: Proximity sensor orientation
41  // @Values: 0:Default,1:Upside Down
42  // @User: Standard
43  AP_GROUPINFO("_ORIENT", 2, AP_Proximity, _orientation[0], 0),
44 
45  // @Param: _YAW_CORR
46  // @DisplayName: Proximity sensor yaw correction
47  // @Description: Proximity sensor yaw correction
48  // @Units: deg
49  // @Range: -180 180
50  // @User: Standard
51  AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity, _yaw_correction[0], PROXIMITY_YAW_CORRECTION_DEFAULT),
52 
53  // @Param: _IGN_ANG1
54  // @DisplayName: Proximity sensor ignore angle 1
55  // @Description: Proximity sensor ignore angle 1
56  // @Units: deg
57  // @Range: 0 360
58  // @User: Standard
59  AP_GROUPINFO("_IGN_ANG1", 4, AP_Proximity, _ignore_angle_deg[0], 0),
60 
61  // @Param: _IGN_WID1
62  // @DisplayName: Proximity sensor ignore width 1
63  // @Description: Proximity sensor ignore width 1
64  // @Units: deg
65  // @Range: 0 45
66  // @User: Standard
67  AP_GROUPINFO("_IGN_WID1", 5, AP_Proximity, _ignore_width_deg[0], 0),
68 
69  // @Param: _IGN_ANG2
70  // @DisplayName: Proximity sensor ignore angle 2
71  // @Description: Proximity sensor ignore angle 2
72  // @Units: deg
73  // @Range: 0 360
74  // @User: Standard
75  AP_GROUPINFO("_IGN_ANG2", 6, AP_Proximity, _ignore_angle_deg[1], 0),
76 
77  // @Param: _IGN_WID2
78  // @DisplayName: Proximity sensor ignore width 2
79  // @Description: Proximity sensor ignore width 2
80  // @Units: deg
81  // @Range: 0 45
82  // @User: Standard
83  AP_GROUPINFO("_IGN_WID2", 7, AP_Proximity, _ignore_width_deg[1], 0),
84 
85  // @Param: _IGN_ANG3
86  // @DisplayName: Proximity sensor ignore angle 3
87  // @Description: Proximity sensor ignore angle 3
88  // @Units: deg
89  // @Range: 0 360
90  // @User: Standard
91  AP_GROUPINFO("_IGN_ANG3", 8, AP_Proximity, _ignore_angle_deg[2], 0),
92 
93  // @Param: _IGN_WID3
94  // @DisplayName: Proximity sensor ignore width 3
95  // @Description: Proximity sensor ignore width 3
96  // @Units: deg
97  // @Range: 0 45
98  // @User: Standard
99  AP_GROUPINFO("_IGN_WID3", 9, AP_Proximity, _ignore_width_deg[2], 0),
100 
101  // @Param: _IGN_ANG4
102  // @DisplayName: Proximity sensor ignore angle 4
103  // @Description: Proximity sensor ignore angle 4
104  // @Units: deg
105  // @Range: 0 360
106  // @User: Standard
107  AP_GROUPINFO("_IGN_ANG4", 10, AP_Proximity, _ignore_angle_deg[3], 0),
108 
109  // @Param: _IGN_WID4
110  // @DisplayName: Proximity sensor ignore width 4
111  // @Description: Proximity sensor ignore width 4
112  // @Units: deg
113  // @Range: 0 45
114  // @User: Standard
115  AP_GROUPINFO("_IGN_WID4", 11, AP_Proximity, _ignore_width_deg[3], 0),
116 
117  // @Param: _IGN_ANG5
118  // @DisplayName: Proximity sensor ignore angle 5
119  // @Description: Proximity sensor ignore angle 5
120  // @Units: deg
121  // @Range: 0 360
122  // @User: Standard
123  AP_GROUPINFO("_IGN_ANG5", 12, AP_Proximity, _ignore_angle_deg[4], 0),
124 
125  // @Param: _IGN_WID5
126  // @DisplayName: Proximity sensor ignore width 5
127  // @Description: Proximity sensor ignore width 5
128  // @Units: deg
129  // @Range: 0 45
130  // @User: Standard
131  AP_GROUPINFO("_IGN_WID5", 13, AP_Proximity, _ignore_width_deg[4], 0),
132 
133  // @Param: _IGN_ANG6
134  // @DisplayName: Proximity sensor ignore angle 6
135  // @Description: Proximity sensor ignore angle 6
136  // @Units: deg
137  // @Range: 0 360
138  // @User: Standard
139  AP_GROUPINFO("_IGN_ANG6", 14, AP_Proximity, _ignore_angle_deg[5], 0),
140 
141  // @Param: _IGN_WID6
142  // @DisplayName: Proximity sensor ignore width 6
143  // @Description: Proximity sensor ignore width 6
144  // @Units: deg
145  // @Range: 0 45
146  // @User: Standard
147  AP_GROUPINFO("_IGN_WID6", 15, AP_Proximity, _ignore_width_deg[5], 0),
148 
149 #if PROXIMITY_MAX_INSTANCES > 1
150  // @Param: 2_TYPE
151  // @DisplayName: Second Proximity type
152  // @Description: What type of proximity sensor is connected
153  // @Values: 0:None,1:LightWareSF40C,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2
154  // @User: Advanced
155  // @RebootRequired: True
156  AP_GROUPINFO("2_TYPE", 16, AP_Proximity, _type[1], 0),
157 
158  // @Param: 2_ORIENT
159  // @DisplayName: Second Proximity sensor orientation
160  // @Description: Second Proximity sensor orientation
161  // @Values: 0:Default,1:Upside Down
162  // @User: Standard
163  AP_GROUPINFO("2_ORIENT", 17, AP_Proximity, _orientation[1], 0),
164 
165  // @Param: 2_YAW_CORR
166  // @DisplayName: Second Proximity sensor yaw correction
167  // @Description: Second Proximity sensor yaw correction
168  // @Units: deg
169  // @Range: -180 180
170  // @User: Standard
171  AP_GROUPINFO("2_YAW_CORR", 18, AP_Proximity, _yaw_correction[1], PROXIMITY_YAW_CORRECTION_DEFAULT),
172 #endif
173 
175 };
176 
178  serial_manager(_serial_manager)
179 {
181 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
182  if (_singleton != nullptr) {
183  AP_HAL::panic("AP_Proximity must be singleton");
184  }
185 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
186  _singleton = this;
187 }
188 
189 // initialise the Proximity class. We do detection of attached sensors here
190 // we don't allow for hot-plugging of sensors (i.e. reboot required)
192 {
193  if (num_instances != 0) {
194  // init called a 2nd time?
195  return;
196  }
197  for (uint8_t i=0; i<PROXIMITY_MAX_INSTANCES; i++) {
198  detect_instance(i);
199  if (drivers[i] != nullptr) {
200  // we loaded a driver for this instance, so it must be
201  // present (although it may not be healthy)
202  num_instances = i+1;
203  }
204 
205  // initialise status
207  }
208 }
209 
210 // update Proximity state for all instances. This should be called at a high rate by the main loop
212 {
213  for (uint8_t i=0; i<num_instances; i++) {
214  if (drivers[i] != nullptr) {
215  if (_type[i] == Proximity_Type_None) {
216  // allow user to disable a proximity sensor at runtime
218  continue;
219  }
220  drivers[i]->update();
221  }
222  }
223 
224  // work out primary instance - first sensor returning good data
225  for (int8_t i=num_instances-1; i>=0; i--) {
226  if (drivers[i] != nullptr && (state[i].status == Proximity_Good)) {
227  primary_instance = i;
228  }
229  }
230 }
231 
232 // return sensor orientation
233 uint8_t AP_Proximity::get_orientation(uint8_t instance) const
234 {
235  if (instance >= PROXIMITY_MAX_INSTANCES) {
236  return 0;
237  }
238 
239  return _orientation[instance].get();
240 }
241 
242 // return sensor yaw correction
243 int16_t AP_Proximity::get_yaw_correction(uint8_t instance) const
244 {
245  if (instance >= PROXIMITY_MAX_INSTANCES) {
246  return 0;
247  }
248 
249  return _yaw_correction[instance].get();
250 }
251 
252 // return sensor health
254 {
255  // sanity check instance number
256  if (instance >= num_instances) {
257  return Proximity_NotConnected;
258  }
259 
260  return state[instance].status;
261 }
262 
264 {
266 }
267 
268 // handle mavlink DISTANCE_SENSOR messages
269 void AP_Proximity::handle_msg(mavlink_message_t *msg)
270 {
271  for (uint8_t i=0; i<num_instances; i++) {
272  if ((drivers[i] != nullptr) && (_type[i] != Proximity_Type_None)) {
273  drivers[i]->handle_msg(msg);
274  }
275  }
276 }
277 
278 // detect if an instance of a proximity sensor is connected.
279 void AP_Proximity::detect_instance(uint8_t instance)
280 {
281  uint8_t type = _type[instance];
282  if (type == Proximity_Type_SF40C) {
284  state[instance].instance = instance;
285  drivers[instance] = new AP_Proximity_LightWareSF40C(*this, state[instance], serial_manager);
286  return;
287  }
288  }
289  if (type == Proximity_Type_RPLidarA2) {
291  state[instance].instance = instance;
292  drivers[instance] = new AP_Proximity_RPLidarA2(*this, state[instance], serial_manager);
293  return;
294  }
295  }
296  if (type == Proximity_Type_MAV) {
297  state[instance].instance = instance;
298  drivers[instance] = new AP_Proximity_MAV(*this, state[instance]);
299  return;
300  }
301  if (type == Proximity_Type_TRTOWER) {
303  state[instance].instance = instance;
304  drivers[instance] = new AP_Proximity_TeraRangerTower(*this, state[instance], serial_manager);
305  return;
306  }
307  }
308  if (type == Proximity_Type_RangeFinder) {
309  state[instance].instance = instance;
310  drivers[instance] = new AP_Proximity_RangeFinder(*this, state[instance]);
311  return;
312  }
313 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
314  if (type == Proximity_Type_SITL) {
315  state[instance].instance = instance;
316  drivers[instance] = new AP_Proximity_SITL(*this, state[instance]);
317  return;
318  }
319 #endif
320 }
321 
322 // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
323 // returns true on successful read and places distance in distance
324 bool AP_Proximity::get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const
325 {
326  if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None)) {
327  return false;
328  }
329  // get distance from backend
330  return drivers[instance]->get_horizontal_distance(angle_deg, distance);
331 }
332 
333 // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
334 // returns true on successful read and places distance in distance
335 bool AP_Proximity::get_horizontal_distance(float angle_deg, float &distance) const
336 {
337  return get_horizontal_distance(primary_instance, angle_deg, distance);
338 }
339 
340 // get distances in 8 directions. used for sending distances to ground station
342 {
344  return false;
345  }
346  // get distances from backend
347  return drivers[primary_instance]->get_horizontal_distances(prx_dist_array);
348 }
349 
350 // get boundary points around vehicle for use by avoidance
351 // returns nullptr and sets num_points to zero if no boundary can be returned
352 const Vector2f* AP_Proximity::get_boundary_points(uint8_t instance, uint16_t& num_points) const
353 {
354  if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None)) {
355  num_points = 0;
356  return nullptr;
357  }
358  // get boundary from backend
359  return drivers[instance]->get_boundary_points(num_points);
360 }
361 
362 const Vector2f* AP_Proximity::get_boundary_points(uint16_t& num_points) const
363 {
364  return get_boundary_points(primary_instance, num_points);
365 }
366 
367 // get distance and angle to closest object (used for pre-arm check)
368 // returns true on success, false if no valid readings
369 bool AP_Proximity::get_closest_object(float& angle_deg, float &distance) const
370 {
372  return false;
373  }
374  // get closest object from backend
375  return drivers[primary_instance]->get_closest_object(angle_deg, distance);
376 }
377 
378 // get number of objects, used for non-GPS avoidance
380 {
382  return 0;
383  }
384  // get count from backend
386 }
387 
388 // get an object's angle and distance, used for non-GPS avoidance
389 // returns false if no angle or distance could be returned for some reason
390 bool AP_Proximity::get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const
391 {
393  return false;
394  }
395  // get angle and distance from backend
396  return drivers[primary_instance]->get_object_angle_and_distance(object_number, angle_deg, distance);
397 }
398 
399 // get maximum and minimum distances (in meters) of primary sensor
401 {
403  return 0.0f;
404  }
405  // get maximum distance from backend
407 }
409 {
411  return 0.0f;
412  }
413  // get minimum distance from backend
415 }
416 
417 // get distance in meters upwards, returns true on success
418 bool AP_Proximity::get_upward_distance(uint8_t instance, float &distance) const
419 {
420  if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None)) {
421  return false;
422  }
423  // get upward distance from backend
424  return drivers[instance]->get_upward_distance(distance);
425 }
426 
428 {
429  return get_upward_distance(primary_instance, distance);
430 }
431 
433 {
434  if (instance < PROXIMITY_MAX_INSTANCES) {
435  return (Proximity_Type)((uint8_t)_type[instance]);
436  }
437  return Proximity_Type_None;
438 }
439 
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
#define PROXIMITY_MAX_INSTANCES
Definition: AP_Proximity.h:24
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
Proximity_State state[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:139
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
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
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
float distance
Definition: location.cpp:94
float distance_max() const
enum Proximity_Status status
Definition: AP_Proximity.h:119
uint8_t get_object_count() const
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Proximity.h:133
bool get_object_angle_and_distance(uint8_t object_number, float &angle_deg, float &distance) const
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
#define PROXIMITY_YAW_CORRECTION_DEFAULT
Definition: AP_Proximity.h:25
virtual bool get_upward_distance(float &distance) const
Proximity_Status get_status() const
static bool detect(AP_SerialManager &serial_manager)
bool get_closest_object(float &angle_deg, float &distance) const
uint8_t num_instances
Definition: AP_Proximity.h:143
AP_Proximity_Backend * drivers[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:140
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
AP_Int8 _type[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:147
AP_Int16 _yaw_correction[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:149
virtual float distance_min() const =0
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
static bool detect(AP_SerialManager &serial_manager)
void detect_instance(uint8_t instance)
void init(void)
virtual void handle_msg(mavlink_message_t *msg)
AP_Int8 _orientation[PROXIMITY_MAX_INSTANCES]
Definition: AP_Proximity.h:148
bool get_horizontal_distance(float angle_deg, float &distance) const
const Vector2f * get_boundary_points(uint16_t &num_points) const
void update(void)
static bool detect(AP_SerialManager &serial_manager)
virtual void update()=0
float distance_min() const
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const
uint8_t get_object_count() const
AP_Proximity(AP_SerialManager &_serial_manager)
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
uint8_t get_orientation(uint8_t instance) const