CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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