APM:Libraries
AP_Avoidance.cpp
Go to the documentation of this file.
1 #include "AP_Avoidance.h"
2 
3 extern const AP_HAL::HAL& hal;
4 
5 #include <limits>
6 #include <GCS_MAVLink/GCS.h>
7 
8 #define AVOIDANCE_DEBUGGING 0
9 
10 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
11  #define AP_AVOIDANCE_WARN_TIME_DEFAULT 30
12  #define AP_AVOIDANCE_FAIL_TIME_DEFAULT 30
13  #define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 1000
14  #define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 300
15  #define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 300
16  #define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 100
17  #define AP_AVOIDANCE_RECOVERY_DEFAULT AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER
18  #define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT
19 #else // APM_BUILD_TYPE(APM_BUILD_ArduCopter), Rover, Boat
20  #define AP_AVOIDANCE_WARN_TIME_DEFAULT 30
21  #define AP_AVOIDANCE_FAIL_TIME_DEFAULT 30
22  #define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 300
23  #define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 300
24  #define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 100
25  #define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 100
26  #define AP_AVOIDANCE_RECOVERY_DEFAULT AP_AVOIDANCE_RECOVERY_RTL
27  #define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT
28 #endif
29 
30 #if AVOIDANCE_DEBUGGING
31 #include <stdio.h>
32 #define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
33 #else
34 #define debug(fmt, args ...)
35 #endif
36 
37 // table of user settable parameters
39 
40  // @Param: ENABLE
41  // @DisplayName: Enable Avoidance using ADSB
42  // @Description: Enable Avoidance using ADSB
43  // @Values: 0:Disabled,1:Enabled
44  // @User: Advanced
45  AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Avoidance, _enabled, 0, AP_PARAM_FLAG_ENABLE),
46 
47  // @Param: F_ACTION
48  // @DisplayName: Collision Avoidance Behavior
49  // @Description: Specifies aircraft behaviour when a collision is imminent
50  // The following values should come from the mavlink COLLISION_ACTION enum
51  // @Values: 0:None,1:Report,2:Climb Or Descend,3:Move Horizontally,4:Move Perpendicularly in 3D,5:RTL,6:Hover
52  // @User: Advanced
53  AP_GROUPINFO("F_ACTION", 2, AP_Avoidance, _fail_action, AP_AVOIDANCE_FAIL_ACTION_DEFAULT),
54 
55  // @Param: W_ACTION
56  // @DisplayName: Collision Avoidance Behavior - Warn
57  // @Description: Specifies aircraft behaviour when a collision may occur
58  // The following values should come from the mavlink COLLISION_ACTION enum
59  // @Values: 0:None,1:Report
60  // @User: Advanced
61  AP_GROUPINFO("W_ACTION", 3, AP_Avoidance, _warn_action, MAV_COLLISION_ACTION_REPORT),
62 
63  // @Param: F_RCVRY
64  // @DisplayName: Recovery behaviour after a fail event
65  // @Description: Determines what the aircraft will do after a fail event is resolved
66  // @Values: 0:Remain in AVOID_ADSB,1:Resume previous flight mode,2:RTL,3:Resume if AUTO else Loiter
67  // @User: Advanced
68  AP_GROUPINFO("F_RCVRY", 4, AP_Avoidance, _fail_recovery, AP_AVOIDANCE_RECOVERY_DEFAULT),
69 
70  // @Param: OBS_MAX
71  // @DisplayName: Maximum number of obstacles to track
72  // @Description: Maximum number of obstacles to track
73  // @User: Advanced
74  AP_GROUPINFO("OBS_MAX", 5, AP_Avoidance, _obstacles_max, 20),
75 
76  // @Param: W_TIME
77  // @DisplayName: Time Horizon Warn
78  // @Description: Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than W_DIST_XY or W_DIST_Z then W_ACTION is undertaken (assuming F_ACTION is not undertaken)
79  // @Units: s
80  // @User: Advanced
81  AP_GROUPINFO("W_TIME", 6, AP_Avoidance, _warn_time_horizon, AP_AVOIDANCE_WARN_TIME_DEFAULT),
82 
83  // @Param: F_TIME
84  // @DisplayName: Time Horizon Fail
85  // @Description: Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than F_DIST_XY or F_DIST_Z then F_ACTION is undertaken
86  // @Units: s
87  // @User: Advanced
88  AP_GROUPINFO("F_TIME", 7, AP_Avoidance, _fail_time_horizon, AP_AVOIDANCE_FAIL_TIME_DEFAULT),
89 
90  // @Param: W_DIST_XY
91  // @DisplayName: Distance Warn XY
92  // @Description: Closest allowed projected distance before W_ACTION is undertaken
93  // @Units: m
94  // @User: Advanced
95  AP_GROUPINFO("W_DIST_XY", 8, AP_Avoidance, _warn_distance_xy, AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT),
96 
97  // @Param: F_DIST_XY
98  // @DisplayName: Distance Fail XY
99  // @Description: Closest allowed projected distance before F_ACTION is undertaken
100  // @Units: m
101  // @User: Advanced
102  AP_GROUPINFO("F_DIST_XY", 9, AP_Avoidance, _fail_distance_xy, AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT),
103 
104  // @Param: W_DIST_Z
105  // @DisplayName: Distance Warn Z
106  // @Description: Closest allowed projected distance before BEHAVIOUR_W is undertaken
107  // @Units: m
108  // @User: Advanced
109  AP_GROUPINFO("W_DIST_Z", 10, AP_Avoidance, _warn_distance_z, AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT),
110 
111  // @Param: F_DIST_Z
112  // @DisplayName: Distance Fail Z
113  // @Description: Closest allowed projected distance before BEHAVIOUR_F is undertaken
114  // @Units: m
115  // @User: Advanced
116  AP_GROUPINFO("F_DIST_Z", 11, AP_Avoidance, _fail_distance_z, AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT),
117 
118  // @Param: F_ALT_MIN
119  // @DisplayName: ADS-B avoidance minimum altitude
120  // @Description: Minimum altitude for ADS-B avoidance. If the vehicle is below this altitude, no avoidance action will take place. Useful to prevent ADS-B avoidance from activating while below the tree line or around structures. Default of 0 is no minimum.
121  // @Units: m
122  // @User: Advanced
123  AP_GROUPINFO("F_ALT_MIN", 12, AP_Avoidance, _fail_altitude_minimum, 0),
124 
126 };
127 
129  _ahrs(ahrs),
130  _adsb(adsb)
131 {
133 }
134 
135 /*
136  * Initialize variables and allocate memory for array
137  */
139 {
140  debug("ADSB initialisation: %d obstacles", _obstacles_max.get());
141  if (_obstacles == nullptr) {
143 
144  if (_obstacles == nullptr) {
145  // dynamic RAM allocation of _obstacles[] failed, disable gracefully
146  hal.console->printf("Unable to initialize Avoidance obstacle list\n");
147  // disable ourselves to avoid repeated allocation attempts
148  _enabled.set(0);
149  return;
150  }
152  }
153  _obstacle_count = 0;
155  _threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
158 }
159 
160 /*
161  * de-initialize and free up some memory
162  */
164 {
165  if (_obstacles != nullptr) {
166  delete [] _obstacles;
167  _obstacles = nullptr;
170  }
171  _obstacle_count = 0;
172 }
173 
175 {
176  if (!_enabled) {
177  if (_obstacles != nullptr) {
178  deinit();
179  }
180  // nothing to do
181  return false;
182  }
183  if (_obstacles == nullptr) {
184  init();
185  }
186  return _obstacles != nullptr;
187 }
188 
189 // vel is north/east/down!
190 void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,
191  const MAV_COLLISION_SRC src,
192  const uint32_t src_id,
193  const Location &loc,
194  const Vector3f &vel_ned)
195 {
196  if (! check_startup()) {
197  return;
198  }
199  uint32_t oldest_timestamp = std::numeric_limits<uint32_t>::max();
200  uint8_t oldest_index = 255; // avoid compiler warning with initialisation
201  int16_t index = -1;
202  uint8_t i;
203  for (i=0; i<_obstacle_count; i++) {
204  if (_obstacles[i].src_id == src_id &&
205  _obstacles[i].src == src) {
206  // pre-existing obstacle found; we will update its information
207  index = i;
208  break;
209  }
210  if (_obstacles[i].timestamp_ms < oldest_timestamp) {
211  oldest_timestamp = _obstacles[i].timestamp_ms;
212  oldest_index = i;
213  }
214  }
215  if (index == -1) {
216  // existing obstacle not found. See if we can store it anyway:
217  if (i <_obstacles_allocated) {
218  // have room to store more vehicles...
219  index = _obstacle_count++;
220  } else if (oldest_timestamp < obstacle_timestamp_ms) {
221  // replace this very old entry with this new data
222  index = oldest_index;
223  } else {
224  // no room for this (old?!) data
225  return;
226  }
227 
228  _obstacles[index].src = src;
229  _obstacles[index].src_id = src_id;
230  }
231 
232  _obstacles[index]._location = loc;
233  _obstacles[index]._velocity = vel_ned;
234  _obstacles[index].timestamp_ms = obstacle_timestamp_ms;
235 }
236 
237 void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,
238  const MAV_COLLISION_SRC src,
239  const uint32_t src_id,
240  const Location &loc,
241  const float cog,
242  const float hspeed,
243  const float vspeed)
244 {
245  Vector3f vel;
246  vel[0] = hspeed * cosf(radians(cog));
247  vel[1] = hspeed * sinf(radians(cog));
248  vel[2] = vspeed;
249  // debug("cog=%f hspeed=%f veln=%f vele=%f", cog, hspeed, vel[0], vel[1]);
250  return add_obstacle(obstacle_timestamp_ms, src, src_id, loc, vel);
251 }
252 
254 {
255  // TODO: need to include squawk code and callsign
256  return vehicle.info.ICAO_address;
257 }
258 
260 {
262  while (_adsb.next_sample(vehicle)) {
263  uint32_t src_id = src_id_for_adsb_vehicle(vehicle);
264  Location loc = _adsb.get_location(vehicle);
266  MAV_COLLISION_SRC_ADSB,
267  src_id,
268  loc,
269  vehicle.info.heading/100.0f,
270  vehicle.info.hor_velocity/100.0f,
271  -vehicle.info.ver_velocity/1000.0f); // convert mm-up to m-down
272  }
273 }
274 
275 float closest_approach_xy(const Location &my_loc,
276  const Vector3f &my_vel,
277  const Location &obstacle_loc,
278  const Vector3f &obstacle_vel,
279  const uint8_t time_horizon)
280 {
281 
282  Vector2f delta_vel_ne = Vector2f(obstacle_vel[0] - my_vel[0], obstacle_vel[1] - my_vel[1]);
283  Vector2f delta_pos_ne = location_diff(obstacle_loc, my_loc);
284 
285  Vector2f line_segment_ne = delta_vel_ne * time_horizon;
286 
288  (line_segment_ne,
289  delta_pos_ne);
290 
291  debug(" time_horizon: (%d)", time_horizon);
292  debug(" delta pos: (y=%f,x=%f)", delta_pos_ne[0], delta_pos_ne[1]);
293  debug(" delta vel: (y=%f,x=%f)", delta_vel_ne[0], delta_vel_ne[1]);
294  debug(" line segment: (y=%f,x=%f)", line_segment_ne[0], line_segment_ne[1]);
295  debug(" closest: (%f)", ret);
296 
297  return ret;
298 }
299 
300 // returns the closest these objects will get in the body z axis (in metres)
301 float closest_approach_z(const Location &my_loc,
302  const Vector3f &my_vel,
303  const Location &obstacle_loc,
304  const Vector3f &obstacle_vel,
305  const uint8_t time_horizon)
306 {
307 
308  float delta_vel_d = obstacle_vel[2] - my_vel[2];
309  float delta_pos_d = obstacle_loc.alt - my_loc.alt;
310 
311  float ret;
312  if (delta_pos_d >= 0 && delta_vel_d >= 0) {
313  ret = delta_pos_d;
314  } else if (delta_pos_d <= 0 && delta_vel_d <= 0) {
315  ret = fabsf(delta_pos_d);
316  } else {
317  ret = fabsf(delta_pos_d - delta_vel_d * time_horizon);
318  }
319 
320  debug(" time_horizon: (%d)", time_horizon);
321  debug(" delta pos: (%f) metres", delta_pos_d/100.0f);
322  debug(" delta vel: (%f) m/s", delta_vel_d);
323  debug(" closest: (%f) metres", ret/100.0f);
324 
325  return ret/100.0f;
326 }
327 
329  const Vector3f &my_vel,
330  AP_Avoidance::Obstacle &obstacle)
331 {
332 
333  Location &obstacle_loc = obstacle._location;
334  Vector3f &obstacle_vel = obstacle._velocity;
335 
336  obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
337 
338  const uint32_t obstacle_age = AP_HAL::millis() - obstacle.timestamp_ms;
339  float closest_xy = closest_approach_xy(my_loc, my_vel, obstacle_loc, obstacle_vel, _fail_time_horizon + obstacle_age/1000);
340  if (closest_xy < _fail_distance_xy) {
341  obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_HIGH;
342  } else {
343  closest_xy = closest_approach_xy(my_loc, my_vel, obstacle_loc, obstacle_vel, _warn_time_horizon + obstacle_age/1000);
344  if (closest_xy < _warn_distance_xy) {
345  obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;
346  }
347  }
348 
349  // check for vertical separation; our threat level is the minimum
350  // of vertical and horizontal threat levels
351  float closest_z = closest_approach_z(my_loc, my_vel, obstacle_loc, obstacle_vel, _warn_time_horizon + obstacle_age/1000);
352  if (obstacle.threat_level != MAV_COLLISION_THREAT_LEVEL_NONE) {
353  if (closest_z > _warn_distance_z) {
354  obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
355  } else {
356  closest_z = closest_approach_z(my_loc, my_vel, obstacle_loc, obstacle_vel, _fail_time_horizon + obstacle_age/1000);
357  if (closest_z > _fail_distance_z) {
358  obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;
359  }
360  }
361  }
362 
363  // If we haven't heard from a vehicle then assume it is no threat
364  if (obstacle_age > MAX_OBSTACLE_AGE_MS) {
365  obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
366  }
367 
368  // could optimise this to not calculate a lot of this if threat
369  // level is none - but only *once the GCS has been informed*!
370  obstacle.closest_approach_xy = closest_xy;
371  obstacle.closest_approach_z = closest_z;
372  float current_distance = get_distance(my_loc, obstacle_loc);
373  obstacle.distance_to_closest_approach = current_distance - closest_xy;
374  Vector2f net_velocity_ne = Vector2f(my_vel[0] - obstacle_vel[0], my_vel[1] - obstacle_vel[1]);
375  obstacle.time_to_closest_approach = 0.0f;
376  if (!is_zero(obstacle.distance_to_closest_approach) &&
377  ! is_zero(net_velocity_ne.length())) {
378  obstacle.time_to_closest_approach = obstacle.distance_to_closest_approach / net_velocity_ne.length();
379  }
380 }
381 
382 MAV_COLLISION_THREAT_LEVEL AP_Avoidance::current_threat_level() const {
383  if (_obstacles == nullptr) {
384  return MAV_COLLISION_THREAT_LEVEL_NONE;
385  }
386  if (_current_most_serious_threat == -1) {
387  return MAV_COLLISION_THREAT_LEVEL_NONE;
388  }
390 }
391 
393 {
394  if (threat == nullptr) {
395  return;
396  }
397 
398  uint32_t now = AP_HAL::millis();
399  if (threat->threat_level == MAV_COLLISION_THREAT_LEVEL_NONE) {
400  // only send cleared messages for a few seconds:
403  }
405  return;
406  }
407  } else {
409  }
410  if (now - threat->last_gcs_report_time > _gcs_notify_interval * 1000) {
412  threat->last_gcs_report_time = now;
413  }
414 
415 }
416 
418 {
419  if (_current_most_serious_threat == -1) {
420  // any threat is more of a threat than no threat
421  return true;
422  }
424  if (obstacle.threat_level > current.threat_level) {
425  // threat_level is updated by update_threat_level
426  return true;
427  }
428  if (obstacle.threat_level == current.threat_level &&
430  return true;
431  }
432  return false;
433 }
434 
436 {
437  Location my_loc;
438  if (!_ahrs.get_position(my_loc)) {
439  // if we don't know our own location we can't determine any threat level
440  return;
441  }
442 
443  Vector3f my_vel;
444  if (!_ahrs.get_velocity_NED(my_vel)) {
445  // assuming our own velocity to be zero here may cause us to
446  // fly into something. Better not to attempt to avoid in this
447  // case.
448  return;
449  }
450 
451  // we always check all obstacles to see if they are threats since it
452  // is most likely our own position and/or velocity have changed
453  // determine the current most-serious-threat
455  for (uint8_t i=0; i<_obstacle_count; i++) {
456 
457  AP_Avoidance::Obstacle &obstacle = _obstacles[i];
458  const uint32_t obstacle_age = AP_HAL::millis() - obstacle.timestamp_ms;
459  debug("i=%d src_id=%d timestamp=%u age=%d", i, obstacle.src_id, obstacle.timestamp_ms, obstacle_age);
460 
461  update_threat_level(my_loc, my_vel, obstacle);
462  debug(" threat-level=%d", obstacle.threat_level);
463 
464  // ignore any really old data:
465  if (obstacle_age > MAX_OBSTACLE_AGE_MS) {
466  // shrink list if this is the last entry:
467  if (i == _obstacle_count-1) {
468  _obstacle_count -= 1;
469  }
470  continue;
471  }
472 
473  if (obstacle_is_more_serious_threat(obstacle)) {
475  }
476  }
477  if (_current_most_serious_threat != -1) {
478  debug("Current most serious threat: %d level=%d", _current_most_serious_threat, _obstacles[_current_most_serious_threat].threat_level);
479  }
480 }
481 
482 
484 {
486  // we *really_ should not have been called!
487  return nullptr;
488  }
490 }
491 
492 
494 {
495  if (!check_startup()) {
496  return;
497  }
498 
499  if (_adsb.enabled()) {
501  }
502 
504 
505  // notify GCS of most serious thread
507 
508  // avoid object (if necessary)
510 }
511 
513 {
514  MAV_COLLISION_THREAT_LEVEL new_threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
515  MAV_COLLISION_ACTION action = MAV_COLLISION_ACTION_NONE;
516 
517  if (threat != nullptr) {
518  new_threat_level = threat->threat_level;
519  if (new_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {
520  action = (MAV_COLLISION_ACTION)_fail_action.get();
521  Location my_loc;
522  if (action != MAV_COLLISION_ACTION_NONE && _fail_altitude_minimum > 0 &&
523  _ahrs.get_position(my_loc) && ((my_loc.alt*0.01f) < _fail_altitude_minimum)) {
524  // disable avoidance when close to ground, report only
525  action = MAV_COLLISION_ACTION_REPORT;
526  }
527  }
528  }
529 
530  uint32_t now = AP_HAL::millis();
531 
532  if (new_threat_level != _threat_level) {
533  // transition to higher states immediately, recovery to lower states more slowly
534  if (((now - _last_state_change_ms) > AP_AVOIDANCE_STATE_RECOVERY_TIME_MS) || (new_threat_level > _threat_level)) {
535  // handle recovery from high threat level
536  if (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {
538  _latest_action = MAV_COLLISION_ACTION_NONE;
539  }
540 
541  // update state
542  _last_state_change_ms = now;
543  _threat_level = new_threat_level;
544  }
545  }
546 
547  // handle ongoing threat by calling vehicle specific handler
548  if ((threat != nullptr) && (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) && (action > MAV_COLLISION_ACTION_REPORT)) {
549  _latest_action = handle_avoidance(threat, action);
550  }
551 }
552 
553 
554 void AP_Avoidance::handle_msg(const mavlink_message_t &msg)
555 {
556  if (!check_startup()) {
557  // avoidance is not active / allocated
558  return;
559  }
560 
561  if (msg.msgid != MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {
562  // we only take position from GLOBAL_POSITION_INT
563  return;
564  }
565 
566  if (msg.sysid == mavlink_system.sysid) {
567  // we do not obstruct ourselves....
568  return;
569  }
570 
571  // inform AP_Avoidance we have a new player
572  mavlink_global_position_int_t packet;
573  mavlink_msg_global_position_int_decode(&msg, &packet);
574  Location loc;
575  loc.lat = packet.lat;
576  loc.lng = packet.lon;
577  loc.alt = packet.alt / 10; // mm -> cm
578  loc.flags.relative_alt = false;
579  Vector3f vel = Vector3f(packet.vx/100.0f, // cm to m
580  packet.vy/100.0f,
581  packet.vz/100.0f);
583  MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT,
584  msg.sysid,
585  loc,
586  vel);
587 }
588 
589 // get unit vector away from the nearest obstacle
591 {
592  if (obstacle == nullptr) {
593  // why where we called?!
594  return false;
595  }
596 
597  Location my_abs_pos;
598  if (!_ahrs.get_position(my_abs_pos)) {
599  // we should not get to here! If we don't know our position
600  // we can't know if there are any threats, for starters!
601  return false;
602  }
603 
604  // if their velocity is moving around close to zero then flying
605  // perpendicular to that velocity may mean we do weird things.
606  // Instead, we will fly directly away from them
607  if (obstacle->_velocity.length() < _low_velocity_threshold) {
608  const Vector2f delta_pos_xy = location_diff(obstacle->_location, my_abs_pos);
609  const float delta_pos_z = my_abs_pos.alt - obstacle->_location.alt;
610  Vector3f delta_pos_xyz = Vector3f(delta_pos_xy.x, delta_pos_xy.y, delta_pos_z);
611  // avoid div by zero
612  if (delta_pos_xyz.is_zero()) {
613  return false;
614  }
615  delta_pos_xyz.normalize();
616  vec_neu = delta_pos_xyz;
617  return true;
618  } else {
619  vec_neu = perpendicular_xyz(obstacle->_location, obstacle->_velocity, my_abs_pos);
620  // avoid div by zero
621  if (vec_neu.is_zero()) {
622  return false;
623  }
624  vec_neu.normalize();
625  return true;
626  }
627 }
628 
629 // helper functions to calculate 3D destination to get us away from obstacle
630 // v1 is NED
632 {
633  Vector2f delta_p_2d = location_diff(p1, p2);
634  Vector3f delta_p_xyz = Vector3f(delta_p_2d[0],delta_p_2d[1],(p2.alt-p1.alt)/100.0f); //check this line
635  Vector3f v1_xyz = Vector3f(v1[0], v1[1], -v1[2]);
636  Vector3f ret = Vector3f::perpendicular(delta_p_xyz, v1_xyz);
637  return ret;
638 }
639 
640 // helper functions to calculate horizontal destination to get us away from obstacle
641 // v1 is NED
643 {
644  Vector2f delta_p = location_diff(p1, p2);
645  Vector2f delta_p_n = Vector2f(delta_p[0],delta_p[1]);
646  Vector2f v1n(v1[0],v1[1]);
647  Vector2f ret_xy = Vector2f::perpendicular(delta_p_n, v1n);
648  return ret_xy;
649 }
AP_Avoidance::Obstacle * most_serious_threat()
virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action)=0
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
const AP_AHRS & _ahrs
Definition: AP_Avoidance.h:137
Vector2< float > Vector2f
Definition: vector2.h:239
bool check_startup()
AP_Int8 _obstacles_max
Definition: AP_Avoidance.h:185
bool next_sample(adsb_vehicle_t &obstacle)
Definition: AP_ADSB.cpp:810
Vector3< float > Vector3f
Definition: vector3.h:246
uint32_t _last_state_change_ms
Definition: AP_Avoidance.h:109
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
AP_Int8 _fail_recovery
Definition: AP_Avoidance.h:188
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
class AP_ADSB & _adsb
Definition: AP_Avoidance.h:181
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define AP_AVOIDANCE_FAIL_ACTION_DEFAULT
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
static int max(int a, int b)
Definition: compat.h:35
static float closest_distance_between_radial_and_point(const Vector2< T > &w, const Vector2< T > &p)
Definition: vector2.h:216
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Avoidance.h:92
AP_Int8 _warn_time_horizon
Definition: AP_Avoidance.h:195
AP_Int8 _enabled
Definition: AP_Avoidance.h:184
const uint32_t MAX_OBSTACLE_AGE_MS
Definition: AP_Avoidance.h:142
const uint8_t _low_velocity_threshold
Definition: AP_Avoidance.h:147
float closest_approach_xy(const Location &my_loc, const Vector3f &my_vel, const Location &obstacle_loc, const Vector3f &obstacle_vel, const uint8_t time_horizon)
MAV_COLLISION_ACTION _latest_action
Definition: AP_Avoidance.h:178
float distance_to_closest_approach
Definition: AP_Avoidance.h:58
void check_for_threats()
static Vector2< T > perpendicular(const Vector2< T > &pos_delta, const Vector2< T > &v1)
Definition: vector2.h:173
#define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT
uint32_t last_gcs_report_time
Definition: AP_Avoidance.h:59
#define debug(fmt, args ...)
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint32_t _gcs_cleared_messages_first_sent
Definition: AP_Avoidance.h:115
MAV_COLLISION_THREAT_LEVEL current_threat_level() const
AP_Int8 _fail_time_horizon
Definition: AP_Avoidance.h:189
static Vector3< T > perpendicular(const Vector3< T > &p1, const Vector3< T > &v1)
Definition: vector3.h:228
T y
Definition: vector2.h:37
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
void handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)
void handle_avoidance_local(AP_Avoidance::Obstacle *threat)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
#define AP_AVOIDANCE_RECOVERY_RTL
Definition: AP_Avoidance.h:34
uint32_t millis()
Definition: system.cpp:157
uint8_t _obstacles_allocated
Definition: AP_Avoidance.h:175
mavlink_adsb_vehicle_t info
Definition: AP_ADSB.h:44
AP_Int16 _fail_altitude_minimum
Definition: AP_Avoidance.h:192
Location_Class get_location(const adsb_vehicle_t &vehicle) const
Definition: AP_ADSB.cpp:302
static DummyVehicle vehicle
Definition: AHRS_Test.cpp:35
MAV_COLLISION_THREAT_LEVEL _threat_level
Definition: AP_Avoidance.h:110
AP_Int16 _fail_distance_xy
Definition: AP_Avoidance.h:190
void normalize()
Definition: vector3.h:176
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
virtual void handle_recovery(uint8_t recovery_action)=0
float length(void) const
Definition: vector3.cpp:288
uint8_t _obstacle_count
Definition: AP_Avoidance.h:176
bool enabled() const
Definition: AP_ADSB.h:75
float length(void) const
Definition: vector2.cpp:24
T x
Definition: vector2.h:37
#define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
uint32_t src_id_for_adsb_vehicle(AP_ADSB::adsb_vehicle_t vehicle) const
static Vector2f perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2)
MAV_COLLISION_THREAT_LEVEL threat_level
Definition: AP_Avoidance.h:54
uint32_t last_update_ms
Definition: AP_ADSB.h:45
static constexpr float radians(float deg)
Definition: AP_Math.h:158
#define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT
#define AP_AVOIDANCE_RECOVERY_DEFAULT
static const uint8_t _gcs_cleared_messages_duration
Definition: AP_Avoidance.h:114
bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu)
float closest_approach_z(const Location &my_loc, const Vector3f &my_vel, const Location &obstacle_loc, const Vector3f &obstacle_vel, const uint8_t time_horizon)
bool is_zero(void) const
Definition: vector3.h:159
MAV_COLLISION_SRC src
Definition: AP_Avoidance.h:46
static const uint8_t _gcs_notify_interval
Definition: AP_Avoidance.h:143
AP_Int16 _fail_distance_z
Definition: AP_Avoidance.h:191
#define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS
Definition: AP_Avoidance.h:37
AP_Int8 _fail_action
Definition: AP_Avoidance.h:187
bool obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const
static Vector3f perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2)
MAV_COLLISION_ACTION mav_avoidance_action()
Definition: AP_Avoidance.h:123
AP_Float _warn_distance_xy
Definition: AP_Avoidance.h:196
AP_Float _warn_distance_z
Definition: AP_Avoidance.h:197
void update_threat_level(const Location &my_loc, const Vector3f &my_vel, AP_Avoidance::Obstacle &obstacle)
#define AP_AVOIDANCE_WARN_TIME_DEFAULT
AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb)
void get_adsb_samples()
#define AP_AVOIDANCE_FAIL_TIME_DEFAULT
void handle_msg(const mavlink_message_t &msg)
void add_obstacle(uint32_t obstacle_timestamp_ms, const MAV_COLLISION_SRC src, uint32_t src_id, const Location &loc, const Vector3f &vel_ned)
AP_Avoidance::Obstacle * _obstacles
Definition: AP_Avoidance.h:174
#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
#define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT
int8_t _current_most_serious_threat
Definition: AP_Avoidance.h:177