Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_Avoidance/AC_Avoid.cpp
4182 views
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 "AC_Avoidance_config.h"
17
18
#if AP_AVOIDANCE_ENABLED
19
20
#include "AC_Avoid.h"
21
#include <AP_AHRS/AP_AHRS.h> // AHRS library
22
#include <AC_Fence/AC_Fence.h> // Failsafe fence library
23
#include <AP_Proximity/AP_Proximity.h>
24
#include <AP_Beacon/AP_Beacon.h>
25
#include <AP_Logger/AP_Logger.h>
26
#include <AP_Vehicle/AP_Vehicle_Type.h>
27
#include <stdio.h>
28
29
#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane)
30
31
#if APM_BUILD_TYPE(APM_BUILD_Rover)
32
# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_STOP
33
#else
34
# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_SLIDE
35
#endif
36
37
#if APM_BUILD_COPTER_OR_HELI
38
# define AP_AVOID_ENABLE_Z 1
39
#endif
40
41
const AP_Param::GroupInfo AC_Avoid::var_info[] = {
42
43
// @Param: ENABLE
44
// @DisplayName: Avoidance control enable/disable
45
// @Description: Enabled/disable avoidance input sources
46
// @Bitmask: 0:UseFence,1:UseProximitySensor,2:UseBeaconFence
47
// @User: Standard
48
AP_GROUPINFO_FLAGS("ENABLE", 1, AC_Avoid, _enabled, AC_AVOID_DEFAULT, AP_PARAM_FLAG_ENABLE),
49
50
// @Param{Copter}: ANGLE_MAX
51
// @DisplayName: Avoidance max lean angle in non-GPS flight modes
52
// @Description: Max lean angle used to avoid obstacles while in non-GPS modes
53
// @Units: cdeg
54
// @Increment: 10
55
// @Range: 0 4500
56
// @User: Standard
57
AP_GROUPINFO_FRAME("ANGLE_MAX", 2, AC_Avoid, _angle_max_cd, 1000, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),
58
59
// @Param{Copter}: DIST_MAX
60
// @DisplayName: Avoidance distance maximum in non-GPS flight modes
61
// @Description: Distance from object at which obstacle avoidance will begin in non-GPS modes
62
// @Units: m
63
// @Range: 1 30
64
// @User: Standard
65
AP_GROUPINFO_FRAME("DIST_MAX", 3, AC_Avoid, _dist_max, AC_AVOID_NONGPS_DIST_MAX_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),
66
67
// @Param: MARGIN
68
// @DisplayName: Avoidance distance margin in GPS modes
69
// @Description: Vehicle will attempt to stay at least this distance (in meters) from objects while in GPS modes
70
// @Units: m
71
// @Range: 1 10
72
// @User: Standard
73
AP_GROUPINFO("MARGIN", 4, AC_Avoid, _margin, 2.0f),
74
75
// @Param{Copter, Rover}: BEHAVE
76
// @DisplayName: Avoidance behaviour
77
// @Description: Avoidance behaviour (slide or stop)
78
// @Values: 0:Slide,1:Stop
79
// @User: Standard
80
AP_GROUPINFO_FRAME("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_ROVER),
81
82
// @Param: BACKUP_SPD
83
// @DisplayName: Avoidance maximum horizontal backup speed
84
// @Description: Maximum speed that will be used to back away from obstacles horizontally in position control modes (m/s). Set zero to disable horizontal backup.
85
// @Units: m/s
86
// @Range: 0 2
87
// @User: Standard
88
AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_xy_max, 0.75f),
89
90
// @Param{Copter}: ALT_MIN
91
// @DisplayName: Avoidance minimum altitude
92
// @Description: Minimum altitude above which proximity based avoidance will start working. This requires a valid downward facing rangefinder reading to work. Set zero to disable
93
// @Units: m
94
// @Range: 0 6
95
// @User: Standard
96
AP_GROUPINFO_FRAME("ALT_MIN", 7, AC_Avoid, _alt_min, 0.0f, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),
97
98
// @Param: ACCEL_MAX
99
// @DisplayName: Avoidance maximum acceleration
100
// @Description: Maximum acceleration with which obstacles will be avoided with. Set zero to disable acceleration limits
101
// @Units: m/s/s
102
// @Range: 0 9
103
// @User: Standard
104
AP_GROUPINFO("ACCEL_MAX", 8, AC_Avoid, _accel_max, 3.0f),
105
106
// @Param: BACKUP_DZ
107
// @DisplayName: Avoidance deadzone between stopping and backing away from obstacle
108
// @Description: Distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles. Increase this parameter if you see vehicle going back and forth in front of obstacle.
109
// @Units: m
110
// @Range: 0 2
111
// @User: Standard
112
AP_GROUPINFO("BACKUP_DZ", 9, AC_Avoid, _backup_deadzone, 0.10f),
113
114
// @Param: BACKZ_SPD
115
// @DisplayName: Avoidance maximum vertical backup speed
116
// @Description: Maximum speed that will be used to back away from obstacles vertically in height control modes (m/s). Set zero to disable vertical backup.
117
// @Units: m/s
118
// @Range: 0 2
119
// @User: Standard
120
AP_GROUPINFO("BACKZ_SPD", 10, AC_Avoid, _backup_speed_z_max, 0.75),
121
122
AP_GROUPEND
123
};
124
125
/// Constructor
126
AC_Avoid::AC_Avoid()
127
{
128
_singleton = this;
129
130
AP_Param::setup_object_defaults(this, var_info);
131
}
132
133
/*
134
* This method limits velocity and calculates backaway velocity from various supported fences
135
* Also limits vertical velocity using adjust_velocity_z method
136
*/
137
void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt)
138
{
139
// Only horizontal component needed for most fences, since fences are 2D
140
Vector2f desired_velocity_xy_cms{desired_vel_cms.x, desired_vel_cms.y};
141
142
#if AP_FENCE_ENABLED || AP_BEACON_ENABLED
143
// limit acceleration
144
const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);
145
#endif
146
147
// maximum component of desired backup velocity in each quadrant
148
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
149
150
#if AP_FENCE_ENABLED
151
if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0) {
152
// Store velocity needed to back away from fence
153
Vector2f backup_vel_fence;
154
155
adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);
156
find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
157
158
// backup_vel_fence is set to zero after each fence in case the velocity is unset from previous methods
159
backup_vel_fence.zero();
160
adjust_velocity_inclusion_and_exclusion_polygons(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);
161
find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
162
163
backup_vel_fence.zero();
164
adjust_velocity_inclusion_circles(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);
165
find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
166
167
backup_vel_fence.zero();
168
adjust_velocity_exclusion_circles(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);
169
find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
170
}
171
#endif // AP_FENCE_ENABLED
172
173
#if AP_BEACON_ENABLED
174
if ((_enabled & AC_AVOID_STOP_AT_BEACON_FENCE) > 0) {
175
// Store velocity needed to back away from beacon fence
176
Vector2f backup_vel_beacon;
177
adjust_velocity_beacon_fence(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_beacon, dt);
178
find_max_quadrant_velocity(backup_vel_beacon, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
179
}
180
#endif // AP_BEACON_ENABLED
181
182
// check for vertical fence
183
float desired_velocity_z_cms = desired_vel_cms.z;
184
float desired_backup_vel_z = 0.0f;
185
adjust_velocity_z(kP_z, accel_cmss_z, desired_velocity_z_cms, desired_backup_vel_z, dt);
186
187
// Desired backup velocity is sum of maximum velocity component in each quadrant
188
const Vector2f desired_backup_vel_xy = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
189
backup_vel = Vector3f{desired_backup_vel_xy.x, desired_backup_vel_xy.y, desired_backup_vel_z};
190
desired_vel_cms = Vector3f{desired_velocity_xy_cms.x, desired_velocity_xy_cms.y, desired_velocity_z_cms};
191
}
192
193
/*
194
* Adjusts the desired velocity so that the vehicle can stop
195
* before the fence/object.
196
* kP, accel_cmss are for the horizontal axis
197
* kP_z, accel_cmss_z are for vertical axis
198
*/
199
void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt)
200
{
201
// exit immediately if disabled
202
if (_enabled == AC_AVOID_DISABLED) {
203
return;
204
}
205
206
// make a copy of input velocity, because desired_vel_cms might be changed
207
const Vector3f desired_vel_cms_original = desired_vel_cms;
208
209
// limit acceleration
210
const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);
211
212
// maximum component of horizontal desired backup velocity in each quadrant
213
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
214
float back_vel_up = 0.0f;
215
float back_vel_down = 0.0f;
216
217
// Avoidance in response to proximity sensor
218
if (proximity_avoidance_enabled() && _proximity_alt_enabled) {
219
// Store velocity needed to back away from physical obstacles
220
Vector3f backup_vel_proximity;
221
adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel_cms, backup_vel_proximity, kP_z,accel_cmss_z, dt);
222
find_max_quadrant_velocity_3D(backup_vel_proximity, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, back_vel_up, back_vel_down);
223
}
224
225
// Avoidance in response to various fences
226
Vector3f backup_vel_fence;
227
adjust_velocity_fence(kP, accel_cmss, desired_vel_cms, backup_vel_fence, kP_z, accel_cmss_z, dt);
228
find_max_quadrant_velocity_3D(backup_vel_fence , quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, back_vel_up, back_vel_down);
229
230
// Desired backup velocity is sum of maximum velocity component in each quadrant
231
const Vector2f desired_backup_vel_xy = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
232
const float desired_backup_vel_z = back_vel_down + back_vel_up;
233
Vector3f desired_backup_vel{desired_backup_vel_xy.x, desired_backup_vel_xy.y, desired_backup_vel_z};
234
235
const float max_back_spd_xy_cms = _backup_speed_xy_max * 100.0;
236
if (!desired_backup_vel.xy().is_zero() && is_positive(max_back_spd_xy_cms)) {
237
backing_up = true;
238
// Constrain horizontal backing away speed
239
desired_backup_vel.xy().limit_length(max_back_spd_xy_cms);
240
241
// let user take control if they are backing away at a greater speed than what we have calculated
242
// this has to be done for x,y,z separately. For eg, user is doing fine in "x" direction but might need backing up in "y".
243
if (!is_zero(desired_backup_vel.x)) {
244
if (is_positive(desired_backup_vel.x)) {
245
desired_vel_cms.x = MAX(desired_vel_cms.x, desired_backup_vel.x);
246
} else {
247
desired_vel_cms.x = MIN(desired_vel_cms.x, desired_backup_vel.x);
248
}
249
}
250
if (!is_zero(desired_backup_vel.y)) {
251
if (is_positive(desired_backup_vel.y)) {
252
desired_vel_cms.y = MAX(desired_vel_cms.y, desired_backup_vel.y);
253
} else {
254
desired_vel_cms.y = MIN(desired_vel_cms.y, desired_backup_vel.y);
255
}
256
}
257
}
258
259
const float max_back_spd_z_cms = _backup_speed_z_max * 100.0;
260
if (!is_zero(desired_backup_vel.z) && is_positive(max_back_spd_z_cms)) {
261
backing_up = true;
262
263
// Constrain vertical backing away speed
264
desired_backup_vel.z = constrain_float(desired_backup_vel.z, -max_back_spd_z_cms, max_back_spd_z_cms);
265
266
if (!is_zero(desired_backup_vel.z)) {
267
if (is_positive(desired_backup_vel.z)) {
268
desired_vel_cms.z = MAX(desired_vel_cms.z, desired_backup_vel.z);
269
} else {
270
desired_vel_cms.z = MIN(desired_vel_cms.z, desired_backup_vel.z);
271
}
272
}
273
}
274
275
// limit acceleration
276
limit_accel(desired_vel_cms_original, desired_vel_cms, dt);
277
278
if (desired_vel_cms_original != desired_vel_cms) {
279
_last_limit_time = AP_HAL::millis();
280
}
281
282
#if HAL_LOGGING_ENABLED
283
if (limits_active()) {
284
// log at not more than 10hz (adjust_velocity method can be potentially called at 400hz!)
285
uint32_t now = AP_HAL::millis();
286
if ((now - _last_log_ms) > 100) {
287
_last_log_ms = now;
288
Write_SimpleAvoidance(true, desired_vel_cms_original, desired_vel_cms, backing_up);
289
}
290
} else {
291
// avoidance isn't active anymore
292
// log once so that it registers in logs
293
if (_last_log_ms) {
294
Write_SimpleAvoidance(false, desired_vel_cms_original, desired_vel_cms, backing_up);
295
// this makes sure logging won't run again till it is active
296
_last_log_ms = 0;
297
}
298
}
299
#endif
300
}
301
302
/*
303
* Limit acceleration so that change of velocity output by avoidance library is controlled
304
* This helps reduce jerks and sudden movements in the vehicle
305
*/
306
void AC_Avoid::limit_accel(const Vector3f &original_vel, Vector3f &modified_vel, float dt)
307
{
308
if (original_vel == modified_vel || is_zero(_accel_max) || !is_positive(dt)) {
309
// we can't limit accel if any of these conditions are true
310
return;
311
}
312
313
if (AP_HAL::millis() - _last_limit_time > AC_AVOID_ACCEL_TIMEOUT_MS) {
314
// reset this velocity because its been a long time since avoidance was active
315
_prev_avoid_vel = original_vel;
316
}
317
318
// acceleration demanded by avoidance
319
const Vector3f accel = (modified_vel - _prev_avoid_vel)/dt;
320
321
// max accel in cm
322
const float max_accel_cm = _accel_max * 100.0f;
323
324
if (accel.length() > max_accel_cm) {
325
// pull back on the acceleration
326
const Vector3f accel_direction = accel.normalized();
327
modified_vel = (accel_direction * max_accel_cm) * dt + _prev_avoid_vel;
328
}
329
330
_prev_avoid_vel = modified_vel;
331
return;
332
}
333
334
// This method is used in most Rover modes and not in Copter
335
// adjust desired horizontal speed so that the vehicle stops before the fence or object
336
// accel (maximum acceleration/deceleration) is in m/s/s
337
// heading is in radians
338
// speed is in m/s
339
// kP should be zero for linear response, non-zero for non-linear response
340
void AC_Avoid::adjust_speed(float kP, float accel, float heading, float &speed, float dt)
341
{
342
// convert heading and speed into velocity vector
343
Vector3f vel{
344
cosf(heading) * speed * 100.0f,
345
sinf(heading) * speed * 100.0f,
346
0.0f
347
};
348
349
bool backing_up = false;
350
adjust_velocity(vel, backing_up, kP, accel * 100.0f, 0, 0, dt);
351
const Vector2f vel_xy{vel.x, vel.y};
352
353
if (backing_up) {
354
// back up
355
if (fabsf(wrap_180(degrees(vel_xy.angle())) - degrees(heading)) > 90.0f) {
356
// Big difference between the direction of velocity vector and actual heading therefore we need to reverse the direction
357
speed = -vel_xy.length() * 0.01f;
358
} else {
359
speed = vel_xy.length() * 0.01f;
360
}
361
return;
362
}
363
364
// No need to back up so adjust speed towards zero if needed
365
if (is_negative(speed)) {
366
speed = -vel_xy.length() * 0.01f;
367
} else {
368
speed = vel_xy.length() * 0.01f;
369
}
370
}
371
372
// adjust vertical climb rate so vehicle does not break the vertical fence
373
void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt) {
374
float backup_speed = 0.0f;
375
adjust_velocity_z(kP, accel_cmss, climb_rate_cms, backup_speed, dt);
376
if (!is_zero(backup_speed)) {
377
if (is_negative(backup_speed)) {
378
climb_rate_cms = MIN(climb_rate_cms, backup_speed);
379
} else {
380
climb_rate_cms = MAX(climb_rate_cms, backup_speed);
381
}
382
}
383
}
384
385
// adjust vertical climb rate so vehicle does not break the vertical fence
386
void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float& backup_speed, float dt)
387
{
388
#ifdef AP_AVOID_ENABLE_Z
389
390
// exit immediately if disabled
391
if (_enabled == AC_AVOID_DISABLED) {
392
return;
393
}
394
395
// do not adjust climb_rate if level
396
if (is_zero(climb_rate_cms)) {
397
return;
398
}
399
400
const AP_AHRS &_ahrs = AP::ahrs();
401
// limit acceleration
402
const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);
403
404
bool limit_min_alt = false;
405
bool limit_max_alt = false;
406
float max_alt_diff = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit)
407
float min_alt_diff = 0.0f;
408
#if AP_FENCE_ENABLED
409
// calculate distance below fence
410
AC_Fence *fence = AP::fence();
411
if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0 && fence) {
412
// calculate distance from vehicle to safe altitude
413
float veh_alt;
414
_ahrs.get_relative_position_D_home(veh_alt);
415
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) > 0) {
416
// fence.get_safe_alt_max() is UP, veh_alt is DOWN:
417
min_alt_diff = -(fence->get_safe_alt_min() + veh_alt);
418
limit_min_alt = true;
419
}
420
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) > 0) {
421
// fence.get_safe_alt_max() is UP, veh_alt is DOWN:
422
max_alt_diff = fence->get_safe_alt_max() + veh_alt;
423
limit_max_alt = true;
424
}
425
}
426
#endif
427
428
// calculate distance to (e.g.) optical flow altitude limit
429
// AHRS values are always in metres
430
float alt_limit;
431
float curr_alt;
432
if (_ahrs.get_hgt_ctrl_limit(alt_limit) &&
433
_ahrs.get_relative_position_D_origin_float(curr_alt)) {
434
// alt_limit is UP, curr_alt is DOWN:
435
const float ctrl_alt_diff = alt_limit + curr_alt;
436
if (!limit_max_alt || ctrl_alt_diff < max_alt_diff) {
437
max_alt_diff = ctrl_alt_diff;
438
limit_max_alt = true;
439
}
440
}
441
442
#if HAL_PROXIMITY_ENABLED
443
// get distance from proximity sensor
444
float proximity_alt_diff;
445
AP_Proximity *proximity = AP::proximity();
446
if (proximity && proximity_avoidance_enabled() && proximity->get_upward_distance(proximity_alt_diff)) {
447
proximity_alt_diff -= _margin;
448
if (!limit_max_alt || proximity_alt_diff < max_alt_diff) {
449
max_alt_diff = proximity_alt_diff;
450
limit_max_alt = true;
451
}
452
}
453
#endif
454
455
// limit climb rate
456
if (limit_max_alt || limit_min_alt) {
457
const float max_back_spd_cms = _backup_speed_z_max * 100.0;
458
// do not allow climbing if we've breached the safe altitude
459
if (max_alt_diff <= 0.0f && limit_max_alt) {
460
climb_rate_cms = MIN(climb_rate_cms, 0.0f);
461
// also calculate backup speed that will get us back to safe altitude
462
if (is_positive(max_back_spd_cms)) {
463
backup_speed = -1*(get_max_speed(kP, accel_cmss_limited, -max_alt_diff*100.0f, dt));
464
465
// Constrain to max backup speed
466
backup_speed = MAX(backup_speed, -max_back_spd_cms);
467
}
468
return;
469
// do not allow descending if we've breached the safe altitude
470
} else if (min_alt_diff <= 0.0f && limit_min_alt) {
471
climb_rate_cms = MAX(climb_rate_cms, 0.0f);
472
// also calculate backup speed that will get us back to safe altitude
473
if (is_positive(max_back_spd_cms)) {
474
backup_speed = get_max_speed(kP, accel_cmss_limited, -min_alt_diff*100.0f, dt);
475
476
// Constrain to max backup speed
477
backup_speed = MIN(backup_speed, max_back_spd_cms);
478
}
479
return;
480
}
481
482
// limit climb rate
483
if (limit_max_alt) {
484
const float max_alt_max_speed = get_max_speed(kP, accel_cmss_limited, max_alt_diff*100.0f, dt);
485
climb_rate_cms = MIN(max_alt_max_speed, climb_rate_cms);
486
}
487
488
if (limit_min_alt) {
489
const float max_alt_min_speed = get_max_speed(kP, accel_cmss_limited, min_alt_diff*100.0f, dt);
490
climb_rate_cms = MAX(-max_alt_min_speed, climb_rate_cms);
491
}
492
}
493
#endif
494
}
495
496
// adjust roll-pitch to push vehicle away from objects
497
// roll and pitch value are in radians
498
// veh_angle_max_rad is the user defined maximum lean angle for the vehicle in radians
499
void AC_Avoid::adjust_roll_pitch_rad(float &roll_rad, float &pitch_rad, float veh_angle_max_rad)
500
{
501
// exit immediately if proximity based avoidance is disabled
502
if (!proximity_avoidance_enabled()) {
503
return;
504
}
505
506
// exit immediately if angle max is zero
507
if (_angle_max_cd <= 0.0f || veh_angle_max_rad <= 0.0f) {
508
return;
509
}
510
511
float roll_positive = 0.0f; // maximum positive roll value
512
float roll_negative = 0.0f; // minimum negative roll value
513
float pitch_positive = 0.0f; // maximum positive pitch value
514
float pitch_negative = 0.0f; // minimum negative pitch value
515
516
// get maximum positive and negative roll and pitch percentages from proximity sensor
517
get_proximity_roll_pitch_norm(roll_positive, roll_negative, pitch_positive, pitch_negative);
518
519
// add maximum positive and negative percentages together for roll and pitch, convert to radians
520
Vector2f rp_out_rad((roll_positive + roll_negative) * radians(45.0), (pitch_positive + pitch_negative) * radians(45.0));
521
522
// apply avoidance angular limits
523
// the object avoidance lean angle is never more than 75% of the total angle-limit to allow the pilot to override
524
const float angle_limit_rad = constrain_float(cd_to_rad(_angle_max_cd), 0.0f, veh_angle_max_rad * AC_AVOID_ANGLE_MAX_PERCENT);
525
float vec_length_rad = rp_out_rad.length();
526
if (vec_length_rad > angle_limit_rad) {
527
rp_out_rad *= (angle_limit_rad / vec_length_rad);
528
}
529
530
// add passed in roll, pitch angles
531
rp_out_rad.x += roll_rad;
532
rp_out_rad.y += pitch_rad;
533
534
// apply total angular limits
535
vec_length_rad = rp_out_rad.length();
536
if (vec_length_rad > veh_angle_max_rad) {
537
rp_out_rad *= (veh_angle_max_rad / vec_length_rad);
538
}
539
540
// return adjusted roll, pitch
541
roll_rad = rp_out_rad.x;
542
pitch_rad = rp_out_rad.y;
543
}
544
545
/*
546
* Note: This method is used to limit velocity horizontally only
547
* Limits the component of desired_vel_cms in the direction of the unit vector
548
* limit_direction to be at most the maximum speed permitted by the limit_distance_cm.
549
*
550
* Uses velocity adjustment idea from Randy's second email on this thread:
551
* https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ
552
*/
553
void AC_Avoid::limit_velocity_2D(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt)
554
{
555
const float max_speed = get_max_speed(kP, accel_cmss, limit_distance_cm, dt);
556
// project onto limit direction
557
const float speed = desired_vel_cms * limit_direction;
558
if (speed > max_speed) {
559
// subtract difference between desired speed and maximum acceptable speed
560
desired_vel_cms += limit_direction*(max_speed - speed);
561
}
562
}
563
564
/*
565
* Note: This method is used to limit velocity horizontally and vertically given a 3D desired velocity vector
566
* Limits the component of desired_vel_cms in the direction of the obstacle_vector based on the passed value of "margin"
567
*/
568
void AC_Avoid::limit_velocity_3D(float kP, float accel_cmss, Vector3f &desired_vel_cms, const Vector3f& obstacle_vector, float margin_cm, float kP_z, float accel_cmss_z, float dt)
569
{
570
if (desired_vel_cms.is_zero()) {
571
// nothing to limit
572
return;
573
}
574
// create a margin_cm length vector in the direction of desired_vel_cms
575
// this will create larger margin towards the direction vehicle is travelling in
576
const Vector3f margin_vector = desired_vel_cms.normalized() * margin_cm;
577
const Vector2f limit_direction_xy{obstacle_vector.x, obstacle_vector.y};
578
579
if (!limit_direction_xy.is_zero()) {
580
const float distance_from_fence_xy = MAX((limit_direction_xy.length() - Vector2f{margin_vector.x, margin_vector.y}.length()), 0.0f);
581
Vector2f velocity_xy{desired_vel_cms.x, desired_vel_cms.y};
582
limit_velocity_2D(kP, accel_cmss, velocity_xy, limit_direction_xy.normalized(), distance_from_fence_xy, dt);
583
desired_vel_cms.x = velocity_xy.x;
584
desired_vel_cms.y = velocity_xy.y;
585
}
586
587
if (is_zero(desired_vel_cms.z) || is_zero(obstacle_vector.z)) {
588
// nothing to limit vertically if desired_vel_cms.z is zero
589
// if obstacle_vector.z is zero then the obstacle is probably horizontally located, and we can move vertically
590
return;
591
}
592
593
if (is_positive(desired_vel_cms.z) != is_positive(obstacle_vector.z)) {
594
// why limit velocity vertically when we are going the opposite direction
595
return;
596
}
597
598
// to check if Z velocity changes
599
const float velocity_z_original = desired_vel_cms.z;
600
const float z_speed = fabsf(desired_vel_cms.z);
601
602
// obstacle_vector.z and margin_vector.z should be in same direction as checked above
603
const float dist_z = MAX(fabsf(obstacle_vector.z) - fabsf(margin_vector.z), 0.0f);
604
if (is_zero(dist_z)) {
605
// eliminate any vertical velocity
606
desired_vel_cms.z = 0.0f;
607
} else {
608
const float max_z_speed = get_max_speed(kP_z, accel_cmss_z, dist_z, dt);
609
desired_vel_cms.z = MIN(max_z_speed, z_speed);
610
}
611
612
// make sure the direction of the Z velocity did not change
613
// we are only limiting speed here, not changing directions
614
// check if original z velocity is positive or negative
615
if (is_negative(velocity_z_original)) {
616
desired_vel_cms.z = desired_vel_cms.z * -1.0f;
617
}
618
}
619
620
/*
621
* Compute the back away horizontal velocity required to avoid breaching margin
622
* INPUT: This method requires the breach in margin distance (back_distance_cm), direction towards the breach (limit_direction)
623
* It then calculates the desired backup velocity and passes it on to "find_max_quadrant_velocity" method to distribute the velocity vectors into respective quadrants
624
* OUTPUT: The method then outputs four velocities (quad1/2/3/4_back_vel_cms), which correspond to the maximum horizontal desired backup velocity in each quadrant
625
*/
626
void AC_Avoid::calc_backup_velocity_2D(float kP, float accel_cmss, Vector2f &quad1_back_vel_cms, Vector2f &quad2_back_vel_cms, Vector2f &quad3_back_vel_cms, Vector2f &quad4_back_vel_cms, float back_distance_cm, Vector2f limit_direction, float dt)
627
{
628
if (limit_direction.is_zero()) {
629
// protect against divide by zero
630
return;
631
}
632
// speed required to move away the exact distance that we have breached the margin with
633
const float back_speed = get_max_speed(kP, 0.4f * accel_cmss, fabsf(back_distance_cm), dt);
634
635
// direction to the obstacle
636
limit_direction.normalize();
637
638
// move in the opposite direction with the required speed
639
Vector2f back_direction_vel = limit_direction * (-back_speed);
640
// divide the vector into quadrants, find maximum velocity component in each quadrant
641
find_max_quadrant_velocity(back_direction_vel, quad1_back_vel_cms, quad2_back_vel_cms, quad3_back_vel_cms, quad4_back_vel_cms);
642
}
643
644
/*
645
* Compute the back away velocity required to avoid breaching margin, including vertical component
646
* min_z_vel is <= 0, and stores the greatest velocity in the downwards direction
647
* max_z_vel is >= 0, and stores the greatest velocity in the upwards direction
648
* eventually max_z_vel + min_z_vel will give the final desired Z backaway velocity
649
*/
650
void AC_Avoid::calc_backup_velocity_3D(float kP, float accel_cmss, Vector2f &quad1_back_vel_cms, Vector2f &quad2_back_vel_cms, Vector2f &quad3_back_vel_cms, Vector2f &quad4_back_vel_cms, float back_distance_cms, Vector3f limit_direction, float kp_z, float accel_cmss_z, float back_distance_z, float& min_z_vel, float& max_z_vel, float dt)
651
{
652
// backup horizontally
653
if (is_positive(back_distance_cms)) {
654
Vector2f limit_direction_2d{limit_direction.x, limit_direction.y};
655
calc_backup_velocity_2D(kP, accel_cmss, quad1_back_vel_cms, quad2_back_vel_cms, quad3_back_vel_cms, quad4_back_vel_cms, back_distance_cms, limit_direction_2d, dt);
656
}
657
658
// backup vertically
659
if (!is_zero(back_distance_z)) {
660
float back_speed_z = get_max_speed(kp_z, 0.4f * accel_cmss_z, fabsf(back_distance_z), dt);
661
// Down is positive
662
if (is_positive(back_distance_z)) {
663
back_speed_z *= -1.0f;
664
}
665
666
// store the z backup speed into min or max z if possible
667
if (back_speed_z < min_z_vel) {
668
min_z_vel = back_speed_z;
669
}
670
if (back_speed_z > max_z_vel) {
671
max_z_vel = back_speed_z;
672
}
673
}
674
}
675
676
/*
677
* Calculate maximum velocity vector that can be formed in each quadrant
678
* This method takes the desired backup velocity, and four other velocities corresponding to each quadrant
679
* The desired velocity is then fit into one of the 4 quadrant velocities as per the sign of its components
680
* This ensures that if we have multiple backup velocities, we can get the maximum of all of those velocities in each quadrant
681
*/
682
void AC_Avoid::find_max_quadrant_velocity(Vector2f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel)
683
{
684
if (desired_vel.is_zero()) {
685
return;
686
}
687
// first quadrant: +ve x, +ve y direction
688
if (is_positive(desired_vel.x) && is_positive(desired_vel.y)) {
689
quad1_vel = Vector2f{MAX(quad1_vel.x, desired_vel.x), MAX(quad1_vel.y,desired_vel.y)};
690
}
691
// second quadrant: -ve x, +ve y direction
692
if (is_negative(desired_vel.x) && is_positive(desired_vel.y)) {
693
quad2_vel = Vector2f{MIN(quad2_vel.x, desired_vel.x), MAX(quad2_vel.y,desired_vel.y)};
694
}
695
// third quadrant: -ve x, -ve y direction
696
if (is_negative(desired_vel.x) && is_negative(desired_vel.y)) {
697
quad3_vel = Vector2f{MIN(quad3_vel.x, desired_vel.x), MIN(quad3_vel.y,desired_vel.y)};
698
}
699
// fourth quadrant: +ve x, -ve y direction
700
if (is_positive(desired_vel.x) && is_negative(desired_vel.y)) {
701
quad4_vel = Vector2f{MAX(quad4_vel.x, desired_vel.x), MIN(quad4_vel.y,desired_vel.y)};
702
}
703
}
704
705
/*
706
Calculate maximum velocity vector that can be formed in each quadrant and separately store max & min of vertical components
707
*/
708
void AC_Avoid::find_max_quadrant_velocity_3D(Vector3f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel, float &max_z_vel, float &min_z_vel)
709
{
710
// split into horizontal and vertical components
711
Vector2f velocity_xy{desired_vel.x, desired_vel.y};
712
find_max_quadrant_velocity(velocity_xy, quad1_vel, quad2_vel, quad3_vel, quad4_vel);
713
714
// store maximum and minimum of z
715
if (is_positive(desired_vel.z) && (desired_vel.z > max_z_vel)) {
716
max_z_vel = desired_vel.z;
717
}
718
if (is_negative(desired_vel.z) && (desired_vel.z < min_z_vel)) {
719
min_z_vel = desired_vel.z;
720
}
721
}
722
723
/*
724
* Computes the speed such that the stopping distance
725
* of the vehicle will be exactly the input distance.
726
*/
727
float AC_Avoid::get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const
728
{
729
if (is_zero(kP)) {
730
return safe_sqrt(2.0f * distance_cm * accel_cmss);
731
} else {
732
return sqrt_controller(distance_cm, kP, accel_cmss, dt);
733
}
734
}
735
736
#if AP_FENCE_ENABLED
737
738
/*
739
* Adjusts the desired velocity for the circular fence.
740
*/
741
void AC_Avoid::adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)
742
{
743
AC_Fence *fence = AP::fence();
744
if (fence == nullptr) {
745
return;
746
}
747
748
AC_Fence &_fence = *fence;
749
750
// exit if circular fence is not enabled
751
if ((_fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) == 0) {
752
return;
753
}
754
755
// exit if the circular fence has already been breached
756
if ((_fence.get_breaches() & AC_FENCE_TYPE_CIRCLE) != 0) {
757
return;
758
}
759
760
// get desired speed
761
const float desired_speed = desired_vel_cms.length();
762
if (is_zero(desired_speed)) {
763
// no avoidance necessary when desired speed is zero
764
return;
765
}
766
767
const AP_AHRS &_ahrs = AP::ahrs();
768
769
// get position as a 2D offset from ahrs home
770
Vector2f position_xy;
771
if (!_ahrs.get_relative_position_NE_home(position_xy)) {
772
// we have no idea where we are....
773
return;
774
}
775
position_xy *= 100.0f; // m -> cm
776
777
// get the fence radius in cm
778
const float fence_radius = _fence.get_radius() * 100.0f;
779
// get the margin to the fence in cm
780
const float margin_cm = _fence.get_margin() * 100.0f;
781
782
if (margin_cm > fence_radius) {
783
return;
784
}
785
786
// get vehicle distance from home
787
const float dist_from_home = position_xy.length();
788
if (dist_from_home > fence_radius) {
789
// outside of circular fence, no velocity adjustments
790
return;
791
}
792
const float distance_to_boundary = fence_radius - dist_from_home;
793
794
// for backing away
795
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
796
797
// back away if vehicle has breached margin
798
if (is_negative(distance_to_boundary - margin_cm)) {
799
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_cm - distance_to_boundary, position_xy, dt);
800
}
801
// desired backup velocity is sum of maximum velocity component in each quadrant
802
backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
803
804
// vehicle is inside the circular fence
805
switch (_behavior) {
806
case BEHAVIOR_SLIDE: {
807
// implement sliding behaviour
808
const Vector2f stopping_point = position_xy + desired_vel_cms*(get_stopping_distance(kP, accel_cmss, desired_speed)/desired_speed);
809
const float stopping_point_dist_from_home = stopping_point.length();
810
if (stopping_point_dist_from_home <= fence_radius - margin_cm) {
811
// stopping before before fence so no need to adjust
812
return;
813
}
814
// unsafe desired velocity - will not be able to stop before reaching margin from fence
815
// Project stopping point radially onto fence boundary
816
// Adjusted velocity will point towards this projected point at a safe speed
817
const Vector2f target_offset = stopping_point * ((fence_radius - margin_cm) / stopping_point_dist_from_home);
818
const Vector2f target_direction = target_offset - position_xy;
819
const float distance_to_target = target_direction.length();
820
if (is_positive(distance_to_target)) {
821
const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
822
desired_vel_cms = target_direction * (MIN(desired_speed,max_speed) / distance_to_target);
823
}
824
break;
825
}
826
827
case (BEHAVIOR_STOP): {
828
// implement stopping behaviour
829
// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence
830
const Vector2f stopping_point_plus_margin = position_xy + desired_vel_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed))/desired_speed);
831
const float stopping_point_plus_margin_dist_from_home = stopping_point_plus_margin.length();
832
if (dist_from_home >= fence_radius - margin_cm) {
833
// vehicle has already breached margin around fence
834
// if stopping point is even further from home (i.e. in wrong direction) then adjust speed to zero
835
// otherwise user is backing away from fence so do not apply limits
836
if (stopping_point_plus_margin_dist_from_home >= dist_from_home) {
837
desired_vel_cms.zero();
838
}
839
} else {
840
// shorten vector without adjusting its direction
841
Vector2f intersection;
842
if (Vector2f::circle_segment_intersection(position_xy, stopping_point_plus_margin, Vector2f(0.0f,0.0f), fence_radius - margin_cm, intersection)) {
843
const float distance_to_target = (intersection - position_xy).length();
844
const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
845
if (max_speed < desired_speed) {
846
desired_vel_cms *= MAX(max_speed, 0.0f) / desired_speed;
847
}
848
}
849
}
850
break;
851
}
852
}
853
}
854
855
/*
856
* Adjusts the desired velocity for the exclusion polygons
857
*/
858
void AC_Avoid::adjust_velocity_inclusion_and_exclusion_polygons(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)
859
{
860
const AC_Fence *fence = AP::fence();
861
if (fence == nullptr) {
862
return;
863
}
864
865
// exit if polygon fences are not enabled
866
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {
867
return;
868
}
869
870
// for backing away
871
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
872
873
// iterate through inclusion polygons
874
const uint8_t num_inclusion_polygons = fence->polyfence().get_inclusion_polygon_count();
875
for (uint8_t i = 0; i < num_inclusion_polygons; i++) {
876
uint16_t num_points;
877
const Vector2f* boundary = fence->polyfence().get_inclusion_polygon(i, num_points);
878
Vector2f backup_vel_inc;
879
// adjust velocity
880
adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, backup_vel_inc, boundary, num_points, fence->get_margin(), dt, true);
881
find_max_quadrant_velocity(backup_vel_inc, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
882
}
883
884
// iterate through exclusion polygons
885
const uint8_t num_exclusion_polygons = fence->polyfence().get_exclusion_polygon_count();
886
for (uint8_t i = 0; i < num_exclusion_polygons; i++) {
887
uint16_t num_points;
888
const Vector2f* boundary = fence->polyfence().get_exclusion_polygon(i, num_points);
889
Vector2f backup_vel_exc;
890
// adjust velocity
891
adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, backup_vel_exc, boundary, num_points, fence->get_margin(), dt, false);
892
find_max_quadrant_velocity(backup_vel_exc, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);
893
}
894
// desired backup velocity is sum of maximum velocity component in each quadrant
895
backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
896
}
897
898
/*
899
* Adjusts the desired velocity for the inclusion circles
900
*/
901
void AC_Avoid::adjust_velocity_inclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)
902
{
903
const AC_Fence *fence = AP::fence();
904
if (fence == nullptr) {
905
return;
906
}
907
908
// return immediately if no inclusion circles
909
const uint8_t num_circles = fence->polyfence().get_inclusion_circle_count();
910
if (num_circles == 0) {
911
return;
912
}
913
914
// exit if polygon fences are not enabled
915
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {
916
return;
917
}
918
919
// get vehicle position
920
Vector2f position_NE;
921
if (!AP::ahrs().get_relative_position_NE_origin_float(position_NE)) {
922
// do not limit velocity if we don't have a position estimate
923
return;
924
}
925
position_NE = position_NE * 100.0f; // m to cm
926
927
// get the margin to the fence in cm
928
const float margin_cm = fence->get_margin() * 100.0f;
929
930
// get desired speed
931
const float desired_speed = desired_vel_cms.length();
932
933
// get stopping distance as an offset from the vehicle
934
Vector2f stopping_offset;
935
if (!is_zero(desired_speed)) {
936
switch (_behavior) {
937
case BEHAVIOR_SLIDE:
938
stopping_offset = desired_vel_cms*(get_stopping_distance(kP, accel_cmss, desired_speed)/desired_speed);
939
break;
940
case BEHAVIOR_STOP:
941
// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence
942
stopping_offset = desired_vel_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed))/desired_speed);
943
break;
944
}
945
}
946
947
// for backing away
948
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
949
950
// iterate through inclusion circles
951
for (uint8_t i = 0; i < num_circles; i++) {
952
Vector2f center_pos_cm;
953
float radius;
954
if (fence->polyfence().get_inclusion_circle(i, center_pos_cm, radius)) {
955
// get position relative to circle's center
956
const Vector2f position_NE_rel = (position_NE - center_pos_cm);
957
958
// if we are outside this circle do not limit velocity for this circle
959
const float dist_sq_cm = position_NE_rel.length_squared();
960
const float radius_cm = (radius * 100.0f);
961
if (dist_sq_cm > sq(radius_cm)) {
962
continue;
963
}
964
965
const float radius_with_margin = radius_cm - margin_cm;
966
if (is_negative(radius_with_margin)) {
967
return;
968
}
969
970
const float margin_breach = radius_with_margin - safe_sqrt(dist_sq_cm);
971
// back away if vehicle has breached margin
972
if (is_negative(margin_breach)) {
973
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_breach, position_NE_rel, dt);
974
}
975
if (is_zero(desired_speed)) {
976
// no avoidance necessary when desired speed is zero
977
continue;
978
}
979
980
switch (_behavior) {
981
case BEHAVIOR_SLIDE: {
982
// implement sliding behaviour
983
const Vector2f stopping_point = position_NE_rel + stopping_offset;
984
const float stopping_point_dist = stopping_point.length();
985
if (is_zero(stopping_point_dist) || (stopping_point_dist <= (radius_cm - margin_cm))) {
986
// stopping before before fence so no need to adjust for this circle
987
continue;
988
}
989
// unsafe desired velocity - will not be able to stop before reaching margin from fence
990
// project stopping point radially onto fence boundary
991
// adjusted velocity will point towards this projected point at a safe speed
992
const Vector2f target_offset = stopping_point * ((radius_cm - margin_cm) / stopping_point_dist);
993
const Vector2f target_direction = target_offset - position_NE_rel;
994
const float distance_to_target = target_direction.length();
995
if (is_positive(distance_to_target)) {
996
const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
997
desired_vel_cms = target_direction * (MIN(desired_speed,max_speed) / distance_to_target);
998
}
999
}
1000
break;
1001
case BEHAVIOR_STOP: {
1002
// implement stopping behaviour
1003
const Vector2f stopping_point_plus_margin = position_NE_rel + stopping_offset;
1004
const float dist_cm = safe_sqrt(dist_sq_cm);
1005
if (dist_cm >= radius_cm - margin_cm) {
1006
// vehicle has already breached margin around fence
1007
// if stopping point is even further from center (i.e. in wrong direction) then adjust speed to zero
1008
// otherwise user is backing away from fence so do not apply limits
1009
if (stopping_point_plus_margin.length() >= dist_cm) {
1010
desired_vel_cms.zero();
1011
// desired backup velocity is sum of maximum velocity component in each quadrant
1012
backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
1013
return;
1014
}
1015
} else {
1016
// shorten vector without adjusting its direction
1017
Vector2f intersection;
1018
if (Vector2f::circle_segment_intersection(position_NE_rel, stopping_point_plus_margin, Vector2f(0.0f,0.0f), radius_cm - margin_cm, intersection)) {
1019
const float distance_to_target = (intersection - position_NE_rel).length();
1020
const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
1021
if (max_speed < desired_speed) {
1022
desired_vel_cms *= MAX(max_speed, 0.0f) / desired_speed;
1023
}
1024
}
1025
}
1026
}
1027
break;
1028
}
1029
}
1030
}
1031
// desired backup velocity is sum of maximum velocity component in each quadrant
1032
backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
1033
}
1034
1035
/*
1036
* Adjusts the desired velocity for the exclusion circles
1037
*/
1038
void AC_Avoid::adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)
1039
{
1040
const AC_Fence *fence = AP::fence();
1041
if (fence == nullptr) {
1042
return;
1043
}
1044
1045
// return immediately if no inclusion circles
1046
const uint8_t num_circles = fence->polyfence().get_exclusion_circle_count();
1047
if (num_circles == 0) {
1048
return;
1049
}
1050
1051
// exit if polygon fences are not enabled
1052
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {
1053
return;
1054
}
1055
1056
// get vehicle position
1057
Vector2f position_NE;
1058
if (!AP::ahrs().get_relative_position_NE_origin_float(position_NE)) {
1059
// do not limit velocity if we don't have a position estimate
1060
return;
1061
}
1062
position_NE = position_NE * 100.0f; // m to cm
1063
1064
// get the margin to the fence in cm
1065
const float margin_cm = fence->get_margin() * 100.0f;
1066
1067
// for backing away
1068
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
1069
1070
// get desired speed
1071
const float desired_speed = desired_vel_cms.length();
1072
1073
// calculate stopping distance as an offset from the vehicle (only used for BEHAVIOR_STOP)
1074
// add a margin so we look forward far enough to intersect with circular fence
1075
Vector2f stopping_offset;
1076
if (!is_zero(desired_speed)) {
1077
if ((AC_Avoid::BehaviourType)_behavior.get() == BEHAVIOR_STOP) {
1078
stopping_offset = desired_vel_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed))/desired_speed);
1079
}
1080
}
1081
// iterate through exclusion circles
1082
for (uint8_t i = 0; i < num_circles; i++) {
1083
Vector2f center_pos_cm;
1084
float radius;
1085
if (fence->polyfence().get_exclusion_circle(i, center_pos_cm, radius)) {
1086
// get position relative to circle's center
1087
const Vector2f position_NE_rel = (position_NE - center_pos_cm);
1088
1089
// if we are inside this circle do not limit velocity for this circle
1090
const float dist_sq_cm = position_NE_rel.length_squared();
1091
const float radius_cm = (radius * 100.0f);
1092
if (radius_cm < margin_cm) {
1093
return;
1094
}
1095
if (dist_sq_cm < sq(radius_cm)) {
1096
continue;
1097
}
1098
1099
const Vector2f vector_to_center = center_pos_cm - position_NE;
1100
const float dist_to_boundary = vector_to_center.length() - radius_cm;
1101
// back away if vehicle has breached margin
1102
if (is_negative(dist_to_boundary - margin_cm)) {
1103
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_cm - dist_to_boundary, vector_to_center, dt);
1104
}
1105
if (is_zero(desired_speed)) {
1106
// no avoidance necessary when desired speed is zero
1107
continue;
1108
}
1109
1110
switch (_behavior) {
1111
case BEHAVIOR_SLIDE: {
1112
// vector from current position to circle's center
1113
Vector2f limit_direction = vector_to_center;
1114
if (limit_direction.is_zero()) {
1115
// vehicle is exactly on circle center so do not limit velocity
1116
continue;
1117
}
1118
// calculate distance to edge of circle
1119
const float limit_distance_cm = limit_direction.length() - radius_cm;
1120
if (!is_positive(limit_distance_cm)) {
1121
// vehicle is within circle so do not limit velocity
1122
continue;
1123
}
1124
// vehicle is outside the circle, adjust velocity to stay outside
1125
limit_direction.normalize();
1126
limit_velocity_2D(kP, accel_cmss, desired_vel_cms, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
1127
}
1128
break;
1129
case BEHAVIOR_STOP: {
1130
// implement stopping behaviour
1131
const Vector2f stopping_point_plus_margin = position_NE_rel + stopping_offset;
1132
const float dist_cm = safe_sqrt(dist_sq_cm);
1133
if (dist_cm < radius_cm + margin_cm) {
1134
// vehicle has already breached margin around fence
1135
// if stopping point is closer to center (i.e. in wrong direction) then adjust speed to zero
1136
// otherwise user is backing away from fence so do not apply limits
1137
if (stopping_point_plus_margin.length() <= dist_cm) {
1138
desired_vel_cms.zero();
1139
backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
1140
return;
1141
}
1142
} else {
1143
// shorten vector without adjusting its direction
1144
Vector2f intersection;
1145
if (Vector2f::circle_segment_intersection(position_NE_rel, stopping_point_plus_margin, Vector2f(0.0f,0.0f), radius_cm + margin_cm, intersection)) {
1146
const float distance_to_target = (intersection - position_NE_rel).length();
1147
const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);
1148
if (max_speed < desired_speed) {
1149
desired_vel_cms *= MAX(max_speed, 0.0f) / desired_speed;
1150
}
1151
}
1152
}
1153
}
1154
break;
1155
}
1156
}
1157
}
1158
// desired backup velocity is sum of maximum velocity component in each quadrant
1159
backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
1160
}
1161
#endif // AP_FENCE_ENABLED
1162
1163
#if AP_BEACON_ENABLED
1164
/*
1165
* Adjusts the desired velocity for the beacon fence.
1166
*/
1167
void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)
1168
{
1169
AP_Beacon *_beacon = AP::beacon();
1170
1171
// exit if the beacon is not present
1172
if (_beacon == nullptr) {
1173
return;
1174
}
1175
1176
// get boundary from beacons
1177
uint16_t num_points = 0;
1178
const Vector2f* boundary = _beacon->get_boundary_points(num_points);
1179
if ((boundary == nullptr) || (num_points == 0)) {
1180
return;
1181
}
1182
1183
// adjust velocity using beacon
1184
float margin = 0;
1185
#if AP_FENCE_ENABLED
1186
if (AP::fence()) {
1187
margin = AP::fence()->get_margin();
1188
}
1189
#endif
1190
adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, backup_vel, boundary, num_points, margin, dt, true);
1191
}
1192
#endif // AP_BEACON_ENABLED
1193
1194
/*
1195
* Adjusts the desired velocity based on output from the proximity sensor
1196
*/
1197
void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt)
1198
{
1199
#if HAL_PROXIMITY_ENABLED
1200
// exit immediately if proximity sensor is not present
1201
AP_Proximity *proximity = AP::proximity();
1202
if (!proximity) {
1203
return;
1204
}
1205
1206
AP_Proximity &_proximity = *proximity;
1207
// get total number of obstacles
1208
const uint8_t obstacle_num = _proximity.get_obstacle_count();
1209
if (obstacle_num == 0) {
1210
// no obstacles
1211
return;
1212
}
1213
1214
const AP_AHRS &_ahrs = AP::ahrs();
1215
1216
// for backing away
1217
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
1218
float max_back_vel_z = 0.0f;
1219
float min_back_vel_z = 0.0f;
1220
1221
// rotate velocity vector from earth frame to body-frame since obstacles are in body-frame
1222
const Vector2f desired_vel_body_cms = _ahrs.earth_to_body2D(Vector2f{desired_vel_cms.x, desired_vel_cms.y});
1223
1224
// safe_vel will be adjusted to stay away from Proximity Obstacles
1225
Vector3f safe_vel = Vector3f{desired_vel_body_cms.x, desired_vel_body_cms.y, desired_vel_cms.z};
1226
const Vector3f safe_vel_orig = safe_vel;
1227
1228
// calc margin in cm
1229
const float margin_cm = MAX(_margin * 100.0f, 0.0f);
1230
Vector3f stopping_point_plus_margin;
1231
if (!desired_vel_cms.is_zero()) {
1232
// only used for "stop mode". Pre-calculating the stopping point here makes sure we do not need to repeat the calculations under iterations.
1233
const float speed = safe_vel.length();
1234
stopping_point_plus_margin = safe_vel * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed))/speed);
1235
}
1236
1237
for (uint8_t i = 0; i<obstacle_num; i++) {
1238
// get obstacle from proximity library
1239
Vector3f vector_to_obstacle;
1240
if (!_proximity.get_obstacle(i, vector_to_obstacle)) {
1241
// this one is not valid
1242
continue;
1243
}
1244
1245
const float dist_to_boundary = vector_to_obstacle.length();
1246
if (is_zero(dist_to_boundary)) {
1247
continue;
1248
}
1249
1250
// back away if vehicle has breached margin
1251
if (is_negative(dist_to_boundary - margin_cm)) {
1252
const float breach_dist = margin_cm - dist_to_boundary;
1253
// add a deadzone so that the vehicle doesn't backup and go forward again and again
1254
const float deadzone = MAX(0.0f, _backup_deadzone) * 100.0f;
1255
if (breach_dist > deadzone) {
1256
// this vector will help us decide how much we have to back away horizontally and vertically
1257
const Vector3f margin_vector = vector_to_obstacle.normalized() * breach_dist;
1258
const float xy_back_dist = margin_vector.xy().length();
1259
const float z_back_dist = margin_vector.z;
1260
calc_backup_velocity_3D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, xy_back_dist, vector_to_obstacle, kP_z, accel_cmss_z, z_back_dist, min_back_vel_z, max_back_vel_z, dt);
1261
}
1262
}
1263
1264
if (desired_vel_cms.is_zero()) {
1265
// cannot limit velocity if there is nothing to limit
1266
// backing up (if needed) has already been done
1267
continue;
1268
}
1269
1270
switch (_behavior) {
1271
case BEHAVIOR_SLIDE: {
1272
Vector3f limit_direction{vector_to_obstacle};
1273
// distance to closest point
1274
const float limit_distance_cm = limit_direction.length();
1275
if (is_zero(limit_distance_cm)) {
1276
// We are exactly on the edge, this should ideally never be possible
1277
// i.e. do not adjust velocity.
1278
continue;
1279
}
1280
// Adjust velocity to not violate margin.
1281
limit_velocity_3D(kP, accel_cmss, safe_vel, limit_direction, margin_cm, kP_z, accel_cmss_z, dt);
1282
1283
break;
1284
}
1285
1286
case BEHAVIOR_STOP: {
1287
// vector from current position to obstacle
1288
Vector3f limit_direction;
1289
// find closest point with line segment
1290
// also see if the vehicle will "roughly" intersect the boundary with the projected stopping point
1291
const bool intersect = _proximity.closest_point_from_segment_to_obstacle(i, Vector3f{}, stopping_point_plus_margin, limit_direction);
1292
if (intersect) {
1293
// the vehicle is intersecting the plane formed by the boundary
1294
// distance to the closest point from the stopping point
1295
float limit_distance_cm = limit_direction.length();
1296
if (is_zero(limit_distance_cm)) {
1297
// We are exactly on the edge, this should ideally never be possible
1298
// i.e. do not adjust velocity.
1299
return;
1300
}
1301
if (limit_distance_cm <= margin_cm) {
1302
// we are within the margin so stop vehicle
1303
safe_vel.zero();
1304
} else {
1305
// vehicle inside the given edge, adjust velocity to not violate this edge
1306
limit_velocity_3D(kP, accel_cmss, safe_vel, limit_direction, margin_cm, kP_z, accel_cmss_z, dt);
1307
}
1308
1309
break;
1310
}
1311
}
1312
}
1313
}
1314
1315
// desired backup velocity is sum of maximum velocity component in each quadrant
1316
const Vector2f desired_back_vel_cms_xy = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
1317
const float desired_back_vel_cms_z = max_back_vel_z + min_back_vel_z;
1318
1319
if (safe_vel == safe_vel_orig && desired_back_vel_cms_xy.is_zero() && is_zero(desired_back_vel_cms_z)) {
1320
// proximity avoidance did nothing, no point in doing the calculations below. Return early
1321
backup_vel.zero();
1322
return;
1323
}
1324
1325
// set modified desired velocity vector and back away velocity vector
1326
// vectors were in body-frame, rotate resulting vector back to earth-frame
1327
const Vector2f safe_vel_2d = _ahrs.body_to_earth2D(Vector2f{safe_vel.x, safe_vel.y});
1328
desired_vel_cms = Vector3f{safe_vel_2d.x, safe_vel_2d.y, safe_vel.z};
1329
const Vector2f backup_vel_xy = _ahrs.body_to_earth2D(desired_back_vel_cms_xy);
1330
backup_vel = Vector3f{backup_vel_xy.x, backup_vel_xy.y, desired_back_vel_cms_z};
1331
#endif // HAL_PROXIMITY_ENABLED
1332
}
1333
1334
/*
1335
* Adjusts the desired velocity for the polygon fence.
1336
*/
1337
void AC_Avoid::adjust_velocity_polygon(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, const Vector2f* boundary, uint16_t num_points, float margin, float dt, bool stay_inside)
1338
{
1339
// exit if there are no points
1340
if (boundary == nullptr || num_points == 0) {
1341
return;
1342
}
1343
1344
const AP_AHRS &_ahrs = AP::ahrs();
1345
1346
// do not adjust velocity if vehicle is outside the polygon fence
1347
Vector2f position_xy;
1348
if (!_ahrs.get_relative_position_NE_origin_float(position_xy)) {
1349
// boundary is in earth frame but we have no idea
1350
// where we are
1351
return;
1352
}
1353
position_xy = position_xy * 100.0f; // m to cm
1354
1355
1356
// return if we have already breached polygon
1357
const bool inside_polygon = !Polygon_outside(position_xy, boundary, num_points);
1358
if (inside_polygon != stay_inside) {
1359
return;
1360
}
1361
1362
// Safe_vel will be adjusted to remain within fence.
1363
// We need a separate vector in case adjustment fails,
1364
// e.g. if we are exactly on the boundary.
1365
Vector2f safe_vel(desired_vel_cms);
1366
Vector2f desired_back_vel_cms;
1367
1368
// calc margin in cm
1369
const float margin_cm = MAX(margin * 100.0f, 0.0f);
1370
1371
// for stopping
1372
const float speed = safe_vel.length();
1373
Vector2f stopping_point_plus_margin;
1374
if (!desired_vel_cms.is_zero()) {
1375
stopping_point_plus_margin = position_xy + safe_vel*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed))/speed);
1376
}
1377
1378
// for backing away
1379
Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;
1380
1381
for (uint16_t i=0; i<num_points; i++) {
1382
uint16_t j = i+1;
1383
if (j >= num_points) {
1384
j = 0;
1385
}
1386
// end points of current edge
1387
Vector2f start = boundary[j];
1388
Vector2f end = boundary[i];
1389
Vector2f vector_to_boundary = Vector2f::closest_point(position_xy, start, end) - position_xy;
1390
// back away if vehicle has breached margin
1391
if (is_negative(vector_to_boundary.length() - margin_cm)) {
1392
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_cm-vector_to_boundary.length(), vector_to_boundary, dt);
1393
}
1394
1395
// exit immediately if no desired velocity
1396
if (desired_vel_cms.is_zero()) {
1397
continue;
1398
}
1399
1400
switch (_behavior) {
1401
case (BEHAVIOR_SLIDE): {
1402
// vector from current position to closest point on current edge
1403
Vector2f limit_direction = vector_to_boundary;
1404
// distance to closest point
1405
const float limit_distance_cm = limit_direction.length();
1406
if (is_zero(limit_distance_cm)) {
1407
// We are exactly on the edge - treat this as a fence breach.
1408
// i.e. do not adjust velocity.
1409
return;
1410
}
1411
// We are strictly inside the given edge.
1412
// Adjust velocity to not violate this edge.
1413
limit_direction /= limit_distance_cm;
1414
limit_velocity_2D(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
1415
break;
1416
}
1417
1418
case (BEHAVIOR_STOP): {
1419
// find intersection with line segment
1420
Vector2f intersection;
1421
if (Vector2f::segment_intersection(position_xy, stopping_point_plus_margin, start, end, intersection)) {
1422
// vector from current position to point on current edge
1423
Vector2f limit_direction = intersection - position_xy;
1424
const float limit_distance_cm = limit_direction.length();
1425
if (is_zero(limit_distance_cm)) {
1426
// We are exactly on the edge - treat this as a fence breach.
1427
// i.e. do not adjust velocity.
1428
return;
1429
}
1430
if (limit_distance_cm <= margin_cm) {
1431
// we are within the margin so stop vehicle
1432
safe_vel.zero();
1433
} else {
1434
// vehicle inside the given edge, adjust velocity to not violate this edge
1435
limit_direction /= limit_distance_cm;
1436
limit_velocity_2D(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
1437
}
1438
}
1439
break;
1440
}
1441
}
1442
}
1443
// desired backup velocity is sum of maximum velocity component in each quadrant
1444
desired_back_vel_cms = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;
1445
1446
// set modified desired velocity vector or back away velocity vector
1447
desired_vel_cms = safe_vel;
1448
backup_vel = desired_back_vel_cms;
1449
}
1450
1451
/*
1452
* Computes distance required to stop, given current speed.
1453
*
1454
* Implementation copied from AC_PosControl.
1455
*/
1456
float AC_Avoid::get_stopping_distance(float kP, float accel_cmss, float speed_cms) const
1457
{
1458
// avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
1459
if (accel_cmss <= 0.0f || is_zero(speed_cms)) {
1460
return 0.0f;
1461
}
1462
1463
// handle linear deceleration
1464
if (kP <= 0.0f) {
1465
return 0.5f * sq(speed_cms) / accel_cmss;
1466
}
1467
1468
// calculate distance within which we can stop
1469
// accel_cmss/kP is the point at which velocity switches from linear to sqrt
1470
if (speed_cms < accel_cmss/kP) {
1471
return speed_cms/kP;
1472
} else {
1473
// accel_cmss/(2.0f*kP*kP) is the distance at which we switch from linear to sqrt response
1474
return accel_cmss/(2.0f*kP*kP) + (speed_cms*speed_cms)/(2.0f*accel_cmss);
1475
}
1476
}
1477
1478
// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes
1479
float AC_Avoid::distance_to_lean_norm(float dist_m)
1480
{
1481
// ignore objects beyond DIST_MAX
1482
if (dist_m < 0.0f || dist_m >= _dist_max || _dist_max <= 0.0f) {
1483
return 0.0f;
1484
}
1485
// inverted but linear response
1486
return 1.0f - (dist_m / _dist_max);
1487
}
1488
1489
// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
1490
void AC_Avoid::get_proximity_roll_pitch_norm(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative)
1491
{
1492
#if HAL_PROXIMITY_ENABLED
1493
AP_Proximity *proximity = AP::proximity();
1494
if (proximity == nullptr) {
1495
return;
1496
}
1497
AP_Proximity &_proximity = *proximity;
1498
const uint8_t obj_count = _proximity.get_object_count();
1499
// if no objects return
1500
if (obj_count == 0) {
1501
return;
1502
}
1503
1504
// calculate maximum roll, pitch values from objects
1505
for (uint8_t i=0; i<obj_count; i++) {
1506
float ang_deg, dist_m;
1507
if (_proximity.get_object_angle_and_distance(i, ang_deg, dist_m)) {
1508
if (dist_m < _dist_max) {
1509
// convert distance to lean angle (in 0 to 1 range)
1510
const float lean_pct = distance_to_lean_norm(dist_m);
1511
// convert angle to roll and pitch lean percentages
1512
const float angle_rad = radians(ang_deg);
1513
const float roll_pct = -sinf(angle_rad) * lean_pct;
1514
const float pitch_pct = cosf(angle_rad) * lean_pct;
1515
// update roll, pitch maximums
1516
if (roll_pct > 0.0f) {
1517
roll_positive = MAX(roll_positive, roll_pct);
1518
} else if (roll_pct < 0.0f) {
1519
roll_negative = MIN(roll_negative, roll_pct);
1520
}
1521
if (pitch_pct > 0.0f) {
1522
pitch_positive = MAX(pitch_positive, pitch_pct);
1523
} else if (pitch_pct < 0.0f) {
1524
pitch_negative = MIN(pitch_negative, pitch_pct);
1525
}
1526
}
1527
}
1528
}
1529
#endif // HAL_PROXIMITY_ENABLED
1530
}
1531
1532
// singleton instance
1533
AC_Avoid *AC_Avoid::_singleton;
1534
1535
namespace AP {
1536
1537
AC_Avoid *ac_avoid()
1538
{
1539
return AC_Avoid::get_singleton();
1540
}
1541
1542
}
1543
1544
#endif // !APM_BUILD_Arduplane
1545
1546
#endif // AP_AVOIDANCE_ENABLED
1547
1548