Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_Avoidance/AC_Avoid.cpp
9459 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_m, 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_m, 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_max_ne_ms, 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_m, 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_mss, 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_m, 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_max_u_ms, 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_neu_cms, Vector3f &backup_vel_neu_cms, float kP_z, float accel_z_cmss, float dt)
138
{
139
// Only horizontal component needed for most fences, since fences are 2D
140
Vector2f desired_velocity_ne_cms{desired_vel_neu_cms.x, desired_vel_neu_cms.y};
141
142
#if AP_FENCE_ENABLED || AP_BEACON_ENABLED
143
// limit acceleration
144
const float accel_limited_cmss = 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_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
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_ne_cms;
154
155
adjust_velocity_circle_fence(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);
156
find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);
157
158
// backup_vel_fence_ne_cms is set to zero after each fence in case the velocity is unset from previous methods
159
backup_vel_fence_ne_cms.zero();
160
adjust_velocity_inclusion_and_exclusion_polygons(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);
161
find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);
162
163
backup_vel_fence_ne_cms.zero();
164
adjust_velocity_inclusion_circles(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);
165
find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);
166
167
backup_vel_fence_ne_cms.zero();
168
adjust_velocity_exclusion_circles(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);
169
find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);
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_ne_cms;
177
adjust_velocity_beacon_fence(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_beacon_ne_cms, dt);
178
find_max_quadrant_velocity(backup_vel_beacon_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);
179
}
180
#endif // AP_BEACON_ENABLED
181
182
// check for vertical fence
183
float desired_velocity_z_cms = desired_vel_neu_cms.z;
184
float desired_backup_vel_u_cms = 0.0f;
185
adjust_velocity_z(kP_z, accel_z_cmss, desired_velocity_z_cms, desired_backup_vel_u_cms, dt);
186
187
// Desired backup velocity is sum of maximum velocity component in each quadrant
188
const Vector2f desired_backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
189
backup_vel_neu_cms = Vector3f{desired_backup_vel_ne_cms.x, desired_backup_vel_ne_cms.y, desired_backup_vel_u_cms};
190
desired_vel_neu_cms = Vector3f{desired_velocity_ne_cms.x, desired_velocity_ne_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_z_cmss are for vertical axis
198
*/
199
void AC_Avoid::adjust_velocity(Vector3f &desired_vel_neu_cms, bool &backing_up, float kP, float accel_cmss, float kP_z, float accel_z_cmss, 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_neu_cms might be changed
207
const Vector3f desired_vel_original_neu_cms = desired_vel_neu_cms;
208
209
// limit acceleration
210
const float accel_limited_cmss = 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_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
214
float back_vel_up_cms = 0.0f;
215
float back_vel_down_cms = 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_neu_cms;
221
adjust_velocity_proximity(kP, accel_limited_cmss, desired_vel_neu_cms, backup_vel_proximity_neu_cms, kP_z,accel_z_cmss, dt);
222
find_max_quadrant_velocity_3D(backup_vel_proximity_neu_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, back_vel_up_cms, back_vel_down_cms);
223
}
224
225
// Avoidance in response to various fences
226
Vector3f backup_vel_fence_neu_cms;
227
adjust_velocity_fence(kP, accel_cmss, desired_vel_neu_cms, backup_vel_fence_neu_cms, kP_z, accel_z_cmss, dt);
228
find_max_quadrant_velocity_3D(backup_vel_fence_neu_cms , quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, back_vel_up_cms, back_vel_down_cms);
229
230
// Desired backup velocity is sum of maximum velocity component in each quadrant
231
const Vector2f desired_backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
232
const float desired_backup_vel_u_cms = back_vel_down_cms + back_vel_up_cms;
233
Vector3f desired_backup_vel_neu_cm{desired_backup_vel_ne_cms.x, desired_backup_vel_ne_cms.y, desired_backup_vel_u_cms};
234
235
const float backup_speed_max_ne_cms = _backup_speed_max_ne_ms * 100.0;
236
if (!desired_backup_vel_neu_cm.xy().is_zero() && is_positive(backup_speed_max_ne_cms)) {
237
backing_up = true;
238
// Constrain horizontal backing away speed
239
desired_backup_vel_neu_cm.xy().limit_length(backup_speed_max_ne_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_neu_cm.x)) {
244
if (is_positive(desired_backup_vel_neu_cm.x)) {
245
desired_vel_neu_cms.x = MAX(desired_vel_neu_cms.x, desired_backup_vel_neu_cm.x);
246
} else {
247
desired_vel_neu_cms.x = MIN(desired_vel_neu_cms.x, desired_backup_vel_neu_cm.x);
248
}
249
}
250
if (!is_zero(desired_backup_vel_neu_cm.y)) {
251
if (is_positive(desired_backup_vel_neu_cm.y)) {
252
desired_vel_neu_cms.y = MAX(desired_vel_neu_cms.y, desired_backup_vel_neu_cm.y);
253
} else {
254
desired_vel_neu_cms.y = MIN(desired_vel_neu_cms.y, desired_backup_vel_neu_cm.y);
255
}
256
}
257
}
258
259
const float backup_speed_max_u_cms = _backup_speed_max_u_ms * 100.0;
260
if (!is_zero(desired_backup_vel_neu_cm.z) && is_positive(backup_speed_max_u_cms)) {
261
backing_up = true;
262
263
// Constrain vertical backing away speed
264
desired_backup_vel_neu_cm.z = constrain_float(desired_backup_vel_neu_cm.z, -backup_speed_max_u_cms, backup_speed_max_u_cms);
265
266
if (!is_zero(desired_backup_vel_neu_cm.z)) {
267
if (is_positive(desired_backup_vel_neu_cm.z)) {
268
desired_vel_neu_cms.z = MAX(desired_vel_neu_cms.z, desired_backup_vel_neu_cm.z);
269
} else {
270
desired_vel_neu_cms.z = MIN(desired_vel_neu_cms.z, desired_backup_vel_neu_cm.z);
271
}
272
}
273
}
274
275
// limit acceleration
276
limit_accel_NEU_cm(desired_vel_original_neu_cms, desired_vel_neu_cms, dt);
277
278
if (desired_vel_original_neu_cms != desired_vel_neu_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_original_neu_cms, desired_vel_neu_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_original_neu_cms, desired_vel_neu_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_NEU_cm(const Vector3f &original_vel_neu_cms, Vector3f &modified_vel_neu_cms, float dt)
307
{
308
if (original_vel_neu_cms == modified_vel_neu_cms || is_zero(_accel_max_mss) || !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_neu_cms = original_vel_neu_cms;
316
}
317
318
// acceleration demanded by avoidance
319
const Vector3f accel_neu_cmss = (modified_vel_neu_cms - _prev_avoid_vel_neu_cms)/dt;
320
321
// max accel in cm
322
const float accel_max_cmss = _accel_max_mss * 100.0f;
323
324
if (accel_neu_cmss.length() > accel_max_cmss) {
325
// pull back on the acceleration
326
const Vector3f accel_direction_neu = accel_neu_cmss.normalized();
327
modified_vel_neu_cms = (accel_direction_neu * accel_max_cmss) * dt + _prev_avoid_vel_neu_cms;
328
}
329
330
_prev_avoid_vel_neu_cms = modified_vel_neu_cms;
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_mss, float heading_rad, float &speed_ms, float dt)
341
{
342
// convert heading and speed into velocity vector
343
Vector3f vel_neu_cms{
344
cosf(heading_rad) * speed_ms * 100.0f,
345
sinf(heading_rad) * speed_ms * 100.0f,
346
0.0f
347
};
348
349
bool backing_up = false;
350
adjust_velocity(vel_neu_cms, backing_up, kP, accel_mss * 100.0f, 0, 0, dt);
351
const Vector2f vel_ne_cms{vel_neu_cms.x, vel_neu_cms.y};
352
353
if (backing_up) {
354
// back up
355
if (fabsf(wrap_180(degrees(vel_ne_cms.angle())) - degrees(heading_rad)) > 90.0f) {
356
// Big difference between the direction of velocity vector and actual heading therefore we need to reverse the direction
357
speed_ms = -vel_ne_cms.length() * 0.01f;
358
} else {
359
speed_ms = vel_ne_cms.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_ms)) {
366
speed_ms = -vel_ne_cms.length() * 0.01f;
367
} else {
368
speed_ms = vel_ne_cms.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_cms = 0.0f;
375
adjust_velocity_z(kP, accel_cmss, climb_rate_cms, backup_speed_cms, dt);
376
if (!is_zero(backup_speed_cms)) {
377
if (is_negative(backup_speed_cms)) {
378
climb_rate_cms = MIN(climb_rate_cms, backup_speed_cms);
379
} else {
380
climb_rate_cms = MAX(climb_rate_cms, backup_speed_cms);
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_cms, 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_limited_cmss = 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_m = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit)
407
float min_alt_diff_m = 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_m;
414
_ahrs.get_relative_position_D_home(veh_alt_m);
415
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) > 0) {
416
// fence.get_safe_alt_max_m() is UP, veh_alt_m is DOWN:
417
min_alt_diff_m = -(fence->get_safe_alt_min_m() + veh_alt_m);
418
limit_min_alt = true;
419
}
420
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) > 0) {
421
// fence.get_safe_alt_max_m() is UP, veh_alt_m is DOWN:
422
max_alt_diff_m = fence->get_safe_alt_max_m() + veh_alt_m;
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_m;
431
float curr_alt_m;
432
if (_ahrs.get_hgt_ctrl_limit(alt_limit_m) &&
433
_ahrs.get_relative_position_D_origin_float(curr_alt_m)) {
434
// alt_limit_m is UP, curr_alt_m is DOWN:
435
const float ctrl_alt_diff_m = alt_limit_m + curr_alt_m;
436
if (!limit_max_alt || ctrl_alt_diff_m < max_alt_diff_m) {
437
max_alt_diff_m = ctrl_alt_diff_m;
438
limit_max_alt = true;
439
}
440
}
441
442
#if HAL_PROXIMITY_ENABLED
443
// get distance from proximity sensor
444
float proximity_alt_diff_m;
445
AP_Proximity *proximity = AP::proximity();
446
if (proximity && proximity_avoidance_enabled() && proximity->get_upward_distance(proximity_alt_diff_m)) {
447
proximity_alt_diff_m -= _margin_m;
448
if (!limit_max_alt || proximity_alt_diff_m < max_alt_diff_m) {
449
max_alt_diff_m = proximity_alt_diff_m;
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_max_u_ms * 100.0;
458
// do not allow climbing if we've breached the safe altitude
459
if (max_alt_diff_m <= 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_cms = -1*(get_max_speed(kP, accel_limited_cmss, -max_alt_diff_m * 100.0f, dt));
464
465
// Constrain to max backup speed
466
backup_speed_cms = MAX(backup_speed_cms, -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_m <= 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_cms = get_max_speed(kP, accel_limited_cmss, -min_alt_diff_m * 100.0f, dt);
475
476
// Constrain to max backup speed
477
backup_speed_cms = MIN(backup_speed_cms, 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_cms = get_max_speed(kP, accel_limited_cmss, max_alt_diff_m * 100.0f, dt);
485
climb_rate_cms = MIN(max_alt_max_speed_cms, climb_rate_cms);
486
}
487
488
if (limit_min_alt) {
489
const float max_alt_min_speed = get_max_speed(kP, accel_limited_cmss, min_alt_diff_m * 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) const
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_norm = 0.0f; // maximum positive roll value
512
float roll_negative_norm = 0.0f; // minimum negative roll value
513
float pitch_positive_norm = 0.0f; // maximum positive pitch value
514
float pitch_negative_norm = 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_norm, roll_negative_norm, pitch_positive_norm, pitch_negative_norm);
518
519
// add maximum positive and negative percentages together for roll and pitch, convert to radians
520
Vector2f rp_out_rad((roll_positive_norm + roll_negative_norm) * radians(45.0), (pitch_positive_norm + pitch_negative_norm) * 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 in the direction of the unit vector
548
* limit_direction_ne to be at most the maximum speed permitted by the limit_distance.
549
*
550
* The function is unit-agnostic — accel, desired_vel_ne, and limit_direction_ne
551
* must all use the same base unit (e.g. m, cm) for correct scaling.
552
*
553
* Uses velocity adjustment idea from Randy's second email on this thread:
554
* https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ
555
*/
556
void AC_Avoid::limit_velocity_NE(float kP, float accel, Vector2f &desired_vel_ne, const Vector2f& limit_direction_ne, float limit_distance, float dt) const
557
{
558
const float max_speed = get_max_speed(kP, accel, limit_distance, dt);
559
// project onto limit direction
560
const float speed = desired_vel_ne * limit_direction_ne;
561
if (speed > max_speed) {
562
// subtract difference between desired speed and maximum acceptable speed
563
desired_vel_ne += limit_direction_ne * (max_speed - speed);
564
}
565
}
566
567
/*
568
* Note: This method is used to limit velocity horizontally and vertically given a 3D desired velocity vector
569
* Limits the component of desired_vel_neu in the direction of the obstacle_vector_neu based on the passed value of "margin"
570
*
571
* The function is unit-agnostic — accel, desired_vel_neu, obstacle_vector_neu, margin, and accel_u
572
* must all use the same base unit (e.g. m, cm) for correct scaling.
573
*/
574
void AC_Avoid::limit_velocity_NEU(float kP, float accel, Vector3f &desired_vel_neu, const Vector3f& obstacle_vector_neu, float margin, float kP_z, float accel_u, float dt) const
575
{
576
if (desired_vel_neu.is_zero()) {
577
// nothing to limit
578
return;
579
}
580
// create a margin length vector in the direction of desired_vel_cms
581
// this will create larger margin towards the direction vehicle is travelling in
582
const Vector3f margin_vector_neu = desired_vel_neu.normalized() * margin;
583
const Vector2f limit_direction_ne{obstacle_vector_neu.x, obstacle_vector_neu.y};
584
585
if (!limit_direction_ne.is_zero()) {
586
const float distance_from_fence_xy = MAX((limit_direction_ne.length() - Vector2f{margin_vector_neu.x, margin_vector_neu.y}.length()), 0.0f);
587
Vector2f velocity_ne{desired_vel_neu.x, desired_vel_neu.y};
588
limit_velocity_NE(kP, accel, velocity_ne, limit_direction_ne.normalized(), distance_from_fence_xy, dt);
589
desired_vel_neu.x = velocity_ne.x;
590
desired_vel_neu.y = velocity_ne.y;
591
}
592
593
if (is_zero(desired_vel_neu.z) || is_zero(obstacle_vector_neu.z)) {
594
// nothing to limit vertically if desired_vel_cms.z is zero
595
// if obstacle_vector_neu.z is zero then the obstacle is probably horizontally located, and we can move vertically
596
return;
597
}
598
599
if (is_positive(desired_vel_neu.z) != is_positive(obstacle_vector_neu.z)) {
600
// why limit velocity vertically when we are going the opposite direction
601
return;
602
}
603
604
// to check if Z velocity changes
605
const float velocity_original_u = desired_vel_neu.z;
606
const float speed_u = fabsf(desired_vel_neu.z);
607
608
// obstacle_vector_neu.z and margin_vector_neu.z should be in same direction as checked above
609
const float dist_u = MAX(fabsf(obstacle_vector_neu.z) - fabsf(margin_vector_neu.z), 0.0f);
610
if (is_zero(dist_u)) {
611
// eliminate any vertical velocity
612
desired_vel_neu.z = 0.0f;
613
} else {
614
const float max_z_speed = get_max_speed(kP_z, accel_u, dist_u, dt);
615
desired_vel_neu.z = MIN(max_z_speed, speed_u);
616
}
617
618
// make sure the direction of the Z velocity did not change
619
// we are only limiting speed here, not changing directions
620
// check if original z velocity is positive or negative
621
if (is_negative(velocity_original_u)) {
622
desired_vel_neu.z = desired_vel_neu.z * -1.0f;
623
}
624
}
625
626
/*
627
* Compute the back away horizontal velocity required to avoid breaching margin
628
* INPUT: This method requires the breach in margin distance (back_distance_cm), direction towards the breach (limit_direction)
629
* 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
630
* 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
631
*/
632
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) const
633
{
634
if (limit_direction.is_zero()) {
635
// protect against divide by zero
636
return;
637
}
638
// speed required to move away the exact distance that we have breached the margin with
639
const float back_speed_cms = get_max_speed(kP, 0.4f * accel_cmss, fabsf(back_distance_cm), dt);
640
641
// direction to the obstacle
642
limit_direction.normalize();
643
644
// move in the opposite direction with the required speed
645
Vector2f back_direction_vel_cms = limit_direction * (-back_speed_cms);
646
// divide the vector into quadrants, find maximum velocity component in each quadrant
647
find_max_quadrant_velocity(back_direction_vel_cms, quad1_back_vel_cms, quad2_back_vel_cms, quad3_back_vel_cms, quad4_back_vel_cms);
648
}
649
650
/*
651
* Compute the back away velocity required to avoid breaching margin, including vertical component
652
* min_z_vel is <= 0, and stores the greatest velocity in the downwards direction
653
* max_z_vel is >= 0, and stores the greatest velocity in the upwards direction
654
* eventually max_z_vel + min_z_vel will give the final desired Z backaway velocity
655
*/
656
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,
657
float back_distance_cms, Vector3f limit_direction_neu, float kp_z, float accel_z_cmss, float back_distance_u_cm, float& min_vel_u_cms, float& max_vel_u_cms, float dt) const
658
{
659
// backup horizontally
660
if (is_positive(back_distance_cms)) {
661
Vector2f limit_direction_ne{limit_direction_neu.x, limit_direction_neu.y};
662
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_ne, dt);
663
}
664
665
// backup vertically
666
if (!is_zero(back_distance_u_cm)) {
667
float back_speed_z_cms = get_max_speed(kp_z, 0.4f * accel_z_cmss, fabsf(back_distance_u_cm), dt);
668
// Down is positive
669
if (is_positive(back_distance_u_cm)) {
670
back_speed_z_cms *= -1.0f;
671
}
672
673
// store the z backup speed into min or max z if possible
674
if (back_speed_z_cms < min_vel_u_cms) {
675
min_vel_u_cms = back_speed_z_cms;
676
}
677
if (back_speed_z_cms > max_vel_u_cms) {
678
max_vel_u_cms = back_speed_z_cms;
679
}
680
}
681
}
682
683
/*
684
* Calculate maximum velocity vector that can be formed in each quadrant
685
* This method takes the desired backup velocity, and four other velocities corresponding to each quadrant
686
* The desired velocity is then fit into one of the 4 quadrant velocities as per the sign of its components
687
* This ensures that if we have multiple backup velocities, we can get the maximum of all of those velocities in each quadrant
688
*/
689
void AC_Avoid::find_max_quadrant_velocity(Vector2f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel) const
690
{
691
if (desired_vel.is_zero()) {
692
return;
693
}
694
// first quadrant: +ve x, +ve y direction
695
if (is_positive(desired_vel.x) && is_positive(desired_vel.y)) {
696
quad1_vel = Vector2f{MAX(quad1_vel.x, desired_vel.x), MAX(quad1_vel.y,desired_vel.y)};
697
}
698
// second quadrant: -ve x, +ve y direction
699
if (is_negative(desired_vel.x) && is_positive(desired_vel.y)) {
700
quad2_vel = Vector2f{MIN(quad2_vel.x, desired_vel.x), MAX(quad2_vel.y,desired_vel.y)};
701
}
702
// third quadrant: -ve x, -ve y direction
703
if (is_negative(desired_vel.x) && is_negative(desired_vel.y)) {
704
quad3_vel = Vector2f{MIN(quad3_vel.x, desired_vel.x), MIN(quad3_vel.y,desired_vel.y)};
705
}
706
// fourth quadrant: +ve x, -ve y direction
707
if (is_positive(desired_vel.x) && is_negative(desired_vel.y)) {
708
quad4_vel = Vector2f{MAX(quad4_vel.x, desired_vel.x), MIN(quad4_vel.y,desired_vel.y)};
709
}
710
}
711
712
/*
713
Calculate maximum velocity vector that can be formed in each quadrant and separately store max & min of vertical components
714
*/
715
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) const
716
{
717
// split into horizontal and vertical components
718
Vector2f velocity_ne{desired_vel.x, desired_vel.y};
719
find_max_quadrant_velocity(velocity_ne, quad1_vel, quad2_vel, quad3_vel, quad4_vel);
720
721
// store maximum and minimum of z
722
if (is_positive(desired_vel.z) && (desired_vel.z > max_z_vel)) {
723
max_z_vel = desired_vel.z;
724
}
725
if (is_negative(desired_vel.z) && (desired_vel.z < min_z_vel)) {
726
min_z_vel = desired_vel.z;
727
}
728
}
729
730
/*
731
* Computes the speed such that the stopping distance
732
* of the vehicle will be exactly the input distance.
733
*/
734
float AC_Avoid::get_max_speed(float kP, float accel, float distance, float dt) const
735
{
736
if (is_zero(kP)) {
737
return safe_sqrt(2.0f * distance * accel);
738
} else {
739
return sqrt_controller(distance, kP, accel, dt);
740
}
741
}
742
743
#if AP_FENCE_ENABLED
744
745
/*
746
* Adjusts the desired velocity for the circular fence.
747
*/
748
void AC_Avoid::adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)
749
{
750
AC_Fence *fence = AP::fence();
751
if (fence == nullptr) {
752
return;
753
}
754
755
AC_Fence &_fence = *fence;
756
757
// exit if circular fence is not enabled
758
if ((_fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) == 0) {
759
return;
760
}
761
762
// exit if the circular fence has already been breached
763
if ((_fence.get_breaches() & AC_FENCE_TYPE_CIRCLE) != 0) {
764
return;
765
}
766
767
// get desired speed
768
const float desired_speed_cms = desired_vel_ne_cms.length();
769
if (is_zero(desired_speed_cms)) {
770
// no avoidance necessary when desired speed is zero
771
return;
772
}
773
774
const AP_AHRS &_ahrs = AP::ahrs();
775
776
// get position as a 2D offset from ahrs home
777
Vector2f position_ne_cm;
778
if (!_ahrs.get_relative_position_NE_home(position_ne_cm)) {
779
// we have no idea where we are....
780
return;
781
}
782
position_ne_cm *= 100.0f; // m -> cm
783
784
// get the fence radius in cm
785
const float fence_radius_cm = _fence.get_radius_m() * 100.0f;
786
// get the margin to the fence in cm
787
const float margin_cm = _fence.get_margin_ne_m() * 100.0f;
788
789
if (margin_cm > fence_radius_cm) {
790
return;
791
}
792
793
// get vehicle distance from home
794
const float dist_from_home_cm = position_ne_cm.length();
795
if (dist_from_home_cm > fence_radius_cm) {
796
// outside of circular fence, no velocity adjustments
797
return;
798
}
799
const float distance_to_boundary_cm = fence_radius_cm - dist_from_home_cm;
800
801
// for backing away
802
Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
803
804
// back away if vehicle has breached margin
805
if (is_negative(distance_to_boundary_cm - margin_cm)) {
806
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_cm - distance_to_boundary_cm, position_ne_cm, dt);
807
}
808
// desired backup velocity is sum of maximum velocity component in each quadrant
809
backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
810
811
// vehicle is inside the circular fence
812
switch (_behavior) {
813
case BEHAVIOR_SLIDE: {
814
// implement sliding behaviour
815
const Vector2f stopping_point_ne_cm = position_ne_cm + desired_vel_ne_cms * (get_stopping_distance(kP, accel_cmss, desired_speed_cms) / desired_speed_cms);
816
const float stopping_point_dist_from_home_ne_cm = stopping_point_ne_cm.length();
817
if (stopping_point_dist_from_home_ne_cm <= fence_radius_cm - margin_cm) {
818
// stopping before before fence so no need to adjust
819
return;
820
}
821
// unsafe desired velocity - will not be able to stop before reaching margin from fence
822
// Project stopping point radially onto fence boundary
823
// Adjusted velocity will point towards this projected point at a safe speed
824
const Vector2f target_offset_ne_cm = stopping_point_ne_cm * ((fence_radius_cm - margin_cm) / stopping_point_dist_from_home_ne_cm);
825
const Vector2f target_direction_ne_cm = target_offset_ne_cm - position_ne_cm;
826
const float distance_to_target_cm = target_direction_ne_cm.length();
827
if (is_positive(distance_to_target_cm)) {
828
const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);
829
desired_vel_ne_cms = target_direction_ne_cm * (MIN(desired_speed_cms,max_speed_cms) / distance_to_target_cm);
830
}
831
break;
832
}
833
834
case (BEHAVIOR_STOP): {
835
// implement stopping behaviour
836
// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence
837
const Vector2f stopping_point_plus_margin_ne_cm = position_ne_cm + desired_vel_ne_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed_cms))/desired_speed_cms);
838
const float stopping_point_plus_margin_dist_from_home_cm = stopping_point_plus_margin_ne_cm.length();
839
if (dist_from_home_cm >= fence_radius_cm - margin_cm) {
840
// vehicle has already breached margin around fence
841
// if stopping point is even further from home (i.e. in wrong direction) then adjust speed to zero
842
// otherwise user is backing away from fence so do not apply limits
843
if (stopping_point_plus_margin_dist_from_home_cm >= dist_from_home_cm) {
844
desired_vel_ne_cms.zero();
845
}
846
} else {
847
// shorten vector without adjusting its direction
848
Vector2f intersection_ne_cm;
849
if (Vector2f::circle_segment_intersection(position_ne_cm, stopping_point_plus_margin_ne_cm, Vector2f(0.0f,0.0f), fence_radius_cm - margin_cm, intersection_ne_cm)) {
850
const float distance_to_target_cm = (intersection_ne_cm - position_ne_cm).length();
851
const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);
852
if (max_speed_cms < desired_speed_cms) {
853
desired_vel_ne_cms *= MAX(max_speed_cms, 0.0f) / desired_speed_cms;
854
}
855
}
856
}
857
break;
858
}
859
}
860
}
861
862
/*
863
* Adjusts the desired velocity for the exclusion polygons
864
*/
865
void AC_Avoid::adjust_velocity_inclusion_and_exclusion_polygons(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)
866
{
867
const AC_Fence *fence = AP::fence();
868
if (fence == nullptr) {
869
return;
870
}
871
872
// exit if polygon fences are not enabled
873
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {
874
return;
875
}
876
877
// for backing away
878
Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
879
880
// iterate through inclusion polygons
881
const uint8_t num_inclusion_polygons = fence->polyfence().get_inclusion_polygon_count();
882
for (uint8_t i = 0; i < num_inclusion_polygons; i++) {
883
uint16_t num_points;
884
const Vector2f* boundary = fence->polyfence().get_inclusion_polygon(i, num_points);
885
Vector2f backup_vel_inc_ne_cms;
886
// adjust velocity
887
adjust_velocity_polygon(kP, accel_cmss, desired_vel_ne_cms, backup_vel_inc_ne_cms, boundary, num_points, fence->get_margin_ne_m(), dt, true);
888
find_max_quadrant_velocity(backup_vel_inc_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);
889
}
890
891
// iterate through exclusion polygons
892
const uint8_t num_exclusion_polygons = fence->polyfence().get_exclusion_polygon_count();
893
for (uint8_t i = 0; i < num_exclusion_polygons; i++) {
894
uint16_t num_points;
895
const Vector2f* boundary = fence->polyfence().get_exclusion_polygon(i, num_points);
896
Vector2f backup_vel_exc_ne_cms;
897
// adjust velocity
898
adjust_velocity_polygon(kP, accel_cmss, desired_vel_ne_cms, backup_vel_exc_ne_cms, boundary, num_points, fence->get_margin_ne_m(), dt, false);
899
find_max_quadrant_velocity(backup_vel_exc_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);
900
}
901
// desired backup velocity is sum of maximum velocity component in each quadrant
902
backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
903
}
904
905
/*
906
* Adjusts the desired velocity for the inclusion circles
907
*/
908
void AC_Avoid::adjust_velocity_inclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)
909
{
910
const AC_Fence *fence = AP::fence();
911
if (fence == nullptr) {
912
return;
913
}
914
915
// return immediately if no inclusion circles
916
const uint8_t num_circles = fence->polyfence().get_inclusion_circle_count();
917
if (num_circles == 0) {
918
return;
919
}
920
921
// exit if polygon fences are not enabled
922
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {
923
return;
924
}
925
926
// get vehicle position
927
Vector2f position_ne_cm;
928
if (!AP::ahrs().get_relative_position_NE_origin_float(position_ne_cm)) {
929
// do not limit velocity if we don't have a position estimate
930
return;
931
}
932
position_ne_cm = position_ne_cm * 100.0f; // m to cm
933
934
// get the margin to the fence in cm
935
const float margin_cm = fence->get_margin_ne_m() * 100.0f;
936
937
// get desired speed
938
const float desired_speed_cms = desired_vel_ne_cms.length();
939
940
// get stopping distance as an offset from the vehicle
941
Vector2f stopping_offset_ne_cm;
942
if (!is_zero(desired_speed_cms)) {
943
switch (_behavior) {
944
case BEHAVIOR_SLIDE:
945
stopping_offset_ne_cm = desired_vel_ne_cms * (get_stopping_distance(kP, accel_cmss, desired_speed_cms) / desired_speed_cms);
946
break;
947
case BEHAVIOR_STOP:
948
// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence
949
stopping_offset_ne_cm = desired_vel_ne_cms * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed_cms)) / desired_speed_cms);
950
break;
951
}
952
}
953
954
// for backing away
955
Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
956
957
// iterate through inclusion circles
958
for (uint8_t i = 0; i < num_circles; i++) {
959
Vector2f center_pos_ne_cm;
960
float radius_m;
961
if (fence->polyfence().get_inclusion_circle(i, center_pos_ne_cm, radius_m)) {
962
// get position relative to circle's center
963
const Vector2f position_rel_ne_cm = (position_ne_cm - center_pos_ne_cm);
964
965
// if we are outside this circle do not limit velocity for this circle
966
const float dist_sq_cm = position_rel_ne_cm.length_squared();
967
const float radius_cm = (radius_m * 100.0f);
968
if (dist_sq_cm > sq(radius_cm)) {
969
continue;
970
}
971
972
const float radius_with_margin_cm = radius_cm - margin_cm;
973
if (is_negative(radius_with_margin_cm)) {
974
return;
975
}
976
977
const float margin_breach_cm = radius_with_margin_cm - safe_sqrt(dist_sq_cm);
978
// back away if vehicle has breached margin
979
if (is_negative(margin_breach_cm)) {
980
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_breach_cm, position_rel_ne_cm, dt);
981
}
982
if (is_zero(desired_speed_cms)) {
983
// no avoidance necessary when desired speed is zero
984
continue;
985
}
986
987
switch (_behavior) {
988
case BEHAVIOR_SLIDE: {
989
// implement sliding behaviour
990
const Vector2f stopping_point_ne_cm = position_rel_ne_cm + stopping_offset_ne_cm;
991
const float stopping_point_dist_cm = stopping_point_ne_cm.length();
992
if (is_zero(stopping_point_dist_cm) || (stopping_point_dist_cm <= (radius_cm - margin_cm))) {
993
// stopping before before fence so no need to adjust for this circle
994
continue;
995
}
996
// unsafe desired velocity - will not be able to stop before reaching margin from fence
997
// project stopping point radially onto fence boundary
998
// adjusted velocity will point towards this projected point at a safe speed
999
const Vector2f target_offset_ne_cm = stopping_point_ne_cm * ((radius_cm - margin_cm) / stopping_point_dist_cm);
1000
const Vector2f target_direction_ne_cm = target_offset_ne_cm - position_rel_ne_cm;
1001
const float distance_to_target_cm = target_direction_ne_cm.length();
1002
if (is_positive(distance_to_target_cm)) {
1003
const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);
1004
desired_vel_ne_cms = target_direction_ne_cm * (MIN(desired_speed_cms, max_speed_cms) / distance_to_target_cm);
1005
}
1006
}
1007
break;
1008
case BEHAVIOR_STOP: {
1009
// implement stopping behaviour
1010
const Vector2f stopping_point_plus_margin_ne_cm = position_rel_ne_cm + stopping_offset_ne_cm;
1011
const float dist_cm = safe_sqrt(dist_sq_cm);
1012
if (dist_cm >= radius_cm - margin_cm) {
1013
// vehicle has already breached margin around fence
1014
// if stopping point is even further from center (i.e. in wrong direction) then adjust speed to zero
1015
// otherwise user is backing away from fence so do not apply limits
1016
if (stopping_point_plus_margin_ne_cm.length() >= dist_cm) {
1017
desired_vel_ne_cms.zero();
1018
// desired backup velocity is sum of maximum velocity component in each quadrant
1019
backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
1020
return;
1021
}
1022
} else {
1023
// shorten vector without adjusting its direction
1024
Vector2f intersection_ne_cm;
1025
if (Vector2f::circle_segment_intersection(position_rel_ne_cm, stopping_point_plus_margin_ne_cm, Vector2f(0.0f,0.0f), radius_cm - margin_cm, intersection_ne_cm)) {
1026
const float distance_to_target_cm = (intersection_ne_cm - position_rel_ne_cm).length();
1027
const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);
1028
if (max_speed_cms < desired_speed_cms) {
1029
desired_vel_ne_cms *= MAX(max_speed_cms, 0.0f) / desired_speed_cms;
1030
}
1031
}
1032
}
1033
}
1034
break;
1035
}
1036
}
1037
}
1038
// desired backup velocity is sum of maximum velocity component in each quadrant
1039
backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
1040
}
1041
1042
/*
1043
* Adjusts the desired velocity for the exclusion circles
1044
*/
1045
void AC_Avoid::adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)
1046
{
1047
const AC_Fence *fence = AP::fence();
1048
if (fence == nullptr) {
1049
return;
1050
}
1051
1052
// return immediately if no inclusion circles
1053
const uint8_t num_circles = fence->polyfence().get_exclusion_circle_count();
1054
if (num_circles == 0) {
1055
return;
1056
}
1057
1058
// exit if polygon fences are not enabled
1059
if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {
1060
return;
1061
}
1062
1063
// get vehicle position
1064
Vector2f position_ne_cm;
1065
if (!AP::ahrs().get_relative_position_NE_origin_float(position_ne_cm)) {
1066
// do not limit velocity if we don't have a position estimate
1067
return;
1068
}
1069
position_ne_cm = position_ne_cm * 100.0f; // m to cm
1070
1071
// get the margin to the fence in cm
1072
const float margin_cm = fence->get_margin_ne_m() * 100.0f;
1073
1074
// for backing away
1075
Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
1076
1077
// get desired speed
1078
const float desired_speed_cms = desired_vel_ne_cms.length();
1079
1080
// calculate stopping distance as an offset from the vehicle (only used for BEHAVIOR_STOP)
1081
// add a margin so we look forward far enough to intersect with circular fence
1082
Vector2f stopping_offset_ne_cm;
1083
if (!is_zero(desired_speed_cms)) {
1084
if ((AC_Avoid::BehaviourType)_behavior.get() == BEHAVIOR_STOP) {
1085
stopping_offset_ne_cm = desired_vel_ne_cms * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed_cms)) / desired_speed_cms);
1086
}
1087
}
1088
// iterate through exclusion circles
1089
for (uint8_t i = 0; i < num_circles; i++) {
1090
Vector2f center_pos_ne_cm;
1091
float radius_m;
1092
if (fence->polyfence().get_exclusion_circle(i, center_pos_ne_cm, radius_m)) {
1093
// get position relative to circle's center
1094
const Vector2f position_rel_ne_cm = (position_ne_cm - center_pos_ne_cm);
1095
1096
// if we are inside this circle do not limit velocity for this circle
1097
const float dist_sq_cm = position_rel_ne_cm.length_squared();
1098
const float radius_cm = (radius_m * 100.0f);
1099
if (radius_cm < margin_cm) {
1100
return;
1101
}
1102
if (dist_sq_cm < sq(radius_cm)) {
1103
continue;
1104
}
1105
1106
const Vector2f vector_to_center_ne_cm = center_pos_ne_cm - position_ne_cm;
1107
const float dist_to_boundary_cm = vector_to_center_ne_cm.length() - radius_cm;
1108
// back away if vehicle has breached margin
1109
if (is_negative(dist_to_boundary_cm - margin_cm)) {
1110
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_cm - dist_to_boundary_cm, vector_to_center_ne_cm, dt);
1111
}
1112
if (is_zero(desired_speed_cms)) {
1113
// no avoidance necessary when desired speed is zero
1114
continue;
1115
}
1116
1117
switch (_behavior) {
1118
case BEHAVIOR_SLIDE: {
1119
// vector from current position to circle's center
1120
Vector2f limit_direction_ne_cm = vector_to_center_ne_cm;
1121
if (limit_direction_ne_cm.is_zero()) {
1122
// vehicle is exactly on circle center so do not limit velocity
1123
continue;
1124
}
1125
// calculate distance to edge of circle
1126
const float limit_distance_cm = limit_direction_ne_cm.length() - radius_cm;
1127
if (!is_positive(limit_distance_cm)) {
1128
// vehicle is within circle so do not limit velocity
1129
continue;
1130
}
1131
// vehicle is outside the circle, adjust velocity to stay outside
1132
limit_direction_ne_cm.normalize();
1133
limit_velocity_NE(kP, accel_cmss, desired_vel_ne_cms, limit_direction_ne_cm, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
1134
}
1135
break;
1136
case BEHAVIOR_STOP: {
1137
// implement stopping behaviour
1138
const Vector2f stopping_point_plus_margin_ne_cm = position_rel_ne_cm + stopping_offset_ne_cm;
1139
const float dist_cm = safe_sqrt(dist_sq_cm);
1140
if (dist_cm < radius_cm + margin_cm) {
1141
// vehicle has already breached margin around fence
1142
// if stopping point is closer to center (i.e. in wrong direction) then adjust speed to zero
1143
// otherwise user is backing away from fence so do not apply limits
1144
if (stopping_point_plus_margin_ne_cm.length() <= dist_cm) {
1145
desired_vel_ne_cms.zero();
1146
backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
1147
return;
1148
}
1149
} else {
1150
// shorten vector without adjusting its direction
1151
Vector2f intersection_ne_cm;
1152
if (Vector2f::circle_segment_intersection(position_rel_ne_cm, stopping_point_plus_margin_ne_cm, Vector2f(0.0f,0.0f), radius_cm + margin_cm, intersection_ne_cm)) {
1153
const float distance_to_target_cm = (intersection_ne_cm - position_rel_ne_cm).length();
1154
const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);
1155
if (max_speed_cms < desired_speed_cms) {
1156
desired_vel_ne_cms *= MAX(max_speed_cms, 0.0f) / desired_speed_cms;
1157
}
1158
}
1159
}
1160
}
1161
break;
1162
}
1163
}
1164
}
1165
// desired backup velocity is sum of maximum velocity component in each quadrant
1166
backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
1167
}
1168
#endif // AP_FENCE_ENABLED
1169
1170
#if AP_BEACON_ENABLED
1171
/*
1172
* Adjusts the desired velocity for the beacon fence.
1173
*/
1174
void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)
1175
{
1176
AP_Beacon *_beacon = AP::beacon();
1177
1178
// exit if the beacon is not present
1179
if (_beacon == nullptr) {
1180
return;
1181
}
1182
1183
// get boundary from beacons
1184
uint16_t num_points = 0;
1185
const Vector2f* boundary = _beacon->get_boundary_points(num_points);
1186
if ((boundary == nullptr) || (num_points == 0)) {
1187
return;
1188
}
1189
1190
// adjust velocity using beacon
1191
float margin_m = 0;
1192
#if AP_FENCE_ENABLED
1193
if (AP::fence()) {
1194
margin_m = AP::fence()->get_margin_ne_m();
1195
}
1196
#endif
1197
adjust_velocity_polygon(kP, accel_cmss, desired_vel_ne_cms, backup_vel_ne_cms, boundary, num_points, margin_m, dt, true);
1198
}
1199
#endif // AP_BEACON_ENABLED
1200
1201
/*
1202
* Adjusts the desired velocity based on output from the proximity sensor
1203
*/
1204
void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &desired_vel_neu_cms, Vector3f &backup_vel_neu_cms, float kP_z, float accel_u_cmss, float dt)
1205
{
1206
#if HAL_PROXIMITY_ENABLED
1207
// exit immediately if proximity sensor is not present
1208
AP_Proximity *proximity = AP::proximity();
1209
if (!proximity) {
1210
return;
1211
}
1212
1213
AP_Proximity &_proximity = *proximity;
1214
// get total number of obstacles
1215
const uint8_t obstacle_num = _proximity.get_obstacle_count();
1216
if (obstacle_num == 0) {
1217
// no obstacles
1218
return;
1219
}
1220
1221
const AP_AHRS &_ahrs = AP::ahrs();
1222
1223
// for backing away
1224
Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
1225
float max_back_vel_u_cms = 0.0f;
1226
float min_back_vel_u_cms = 0.0f;
1227
1228
// rotate velocity vector from earth frame to body-frame since obstacles are in body-frame
1229
const Vector2f desired_vel_body_ne_cms = _ahrs.earth_to_body2D(Vector2f{desired_vel_neu_cms.x, desired_vel_neu_cms.y});
1230
1231
// safe_vel_ne_cms will be adjusted to stay away from Proximity Obstacles
1232
Vector3f safe_vel_neu_cms = Vector3f{desired_vel_body_ne_cms.x, desired_vel_body_ne_cms.y, desired_vel_neu_cms.z};
1233
const Vector3f safe_vel_orig_neu_cms = safe_vel_neu_cms;
1234
1235
// calc margin in cm
1236
const float margin_cm = MAX(_margin_m * 100.0f, 0.0f);
1237
Vector3f stopping_point_plus_margin_neu_cm;
1238
if (!desired_vel_neu_cms.is_zero()) {
1239
// only used for "stop mode". Pre-calculating the stopping point here makes sure we do not need to repeat the calculations under iterations.
1240
const float speed_cms = safe_vel_neu_cms.length();
1241
stopping_point_plus_margin_neu_cm = safe_vel_neu_cms * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed_cms)) / speed_cms);
1242
}
1243
1244
for (uint8_t i = 0; i<obstacle_num; i++) {
1245
// get obstacle from proximity library
1246
Vector3f vector_to_obstacle_neu;
1247
if (!_proximity.get_obstacle(i, vector_to_obstacle_neu)) {
1248
// this one is not valid
1249
continue;
1250
}
1251
1252
const float dist_to_boundary_cm = vector_to_obstacle_neu.length();
1253
if (is_zero(dist_to_boundary_cm)) {
1254
continue;
1255
}
1256
1257
// back away if vehicle has breached margin
1258
if (is_negative(dist_to_boundary_cm - margin_cm)) {
1259
const float breach_dist_cm = margin_cm - dist_to_boundary_cm;
1260
// add a deadzone so that the vehicle doesn't backup and go forward again and again
1261
const float deadzone_cm = MAX(0.0f, _backup_deadzone_m) * 100.0f;
1262
if (breach_dist_cm > deadzone_cm) {
1263
// this vector will help us decide how much we have to back away horizontally and vertically
1264
const Vector3f margin_vector_neu_cm = vector_to_obstacle_neu.normalized() * breach_dist_cm;
1265
const float xy_back_dist = margin_vector_neu_cm.xy().length();
1266
const float z_back_dist = margin_vector_neu_cm.z;
1267
calc_backup_velocity_3D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, xy_back_dist, vector_to_obstacle_neu, kP_z, accel_u_cmss, z_back_dist, min_back_vel_u_cms, max_back_vel_u_cms, dt);
1268
}
1269
}
1270
1271
if (desired_vel_neu_cms.is_zero()) {
1272
// cannot limit velocity if there is nothing to limit
1273
// backing up (if needed) has already been done
1274
continue;
1275
}
1276
1277
switch (_behavior) {
1278
case BEHAVIOR_SLIDE: {
1279
Vector3f limit_direction_neu{vector_to_obstacle_neu};
1280
// distance to closest point
1281
const float limit_distance_cm = limit_direction_neu.length();
1282
if (is_zero(limit_distance_cm)) {
1283
// We are exactly on the edge, this should ideally never be possible
1284
// i.e. do not adjust velocity.
1285
continue;
1286
}
1287
// Adjust velocity to not violate margin.
1288
limit_velocity_NEU(kP, accel_cmss, safe_vel_neu_cms, limit_direction_neu, margin_cm, kP_z, accel_u_cmss, dt);
1289
1290
break;
1291
}
1292
1293
case BEHAVIOR_STOP: {
1294
// vector from current position to obstacle
1295
Vector3f limit_direction_neu;
1296
// find closest point with line segment
1297
// also see if the vehicle will "roughly" intersect the boundary with the projected stopping point
1298
const bool intersect = _proximity.closest_point_from_segment_to_obstacle(i, Vector3f{}, stopping_point_plus_margin_neu_cm, limit_direction_neu);
1299
if (intersect) {
1300
// the vehicle is intersecting the plane formed by the boundary
1301
// distance to the closest point from the stopping point
1302
float limit_distance_cm = limit_direction_neu.length();
1303
if (is_zero(limit_distance_cm)) {
1304
// We are exactly on the edge, this should ideally never be possible
1305
// i.e. do not adjust velocity.
1306
return;
1307
}
1308
if (limit_distance_cm <= margin_cm) {
1309
// we are within the margin so stop vehicle
1310
safe_vel_neu_cms.zero();
1311
} else {
1312
// vehicle inside the given edge, adjust velocity to not violate this edge
1313
limit_velocity_NEU(kP, accel_cmss, safe_vel_neu_cms, limit_direction_neu, margin_cm, kP_z, accel_u_cmss, dt);
1314
}
1315
1316
break;
1317
}
1318
}
1319
}
1320
}
1321
1322
// desired backup velocity is sum of maximum velocity component in each quadrant
1323
const Vector2f desired_back_vel_cms_xy = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
1324
const float desired_back_vel_cms_z = max_back_vel_u_cms + min_back_vel_u_cms;
1325
1326
if (safe_vel_neu_cms == safe_vel_orig_neu_cms && desired_back_vel_cms_xy.is_zero() && is_zero(desired_back_vel_cms_z)) {
1327
// proximity avoidance did nothing, no point in doing the calculations below. Return early
1328
backup_vel_neu_cms.zero();
1329
return;
1330
}
1331
1332
// set modified desired velocity vector and back away velocity vector
1333
// vectors were in body-frame, rotate resulting vector back to earth-frame
1334
const Vector2f safe_vel_ne_cms = _ahrs.body_to_earth2D(Vector2f{safe_vel_neu_cms.x, safe_vel_neu_cms.y});
1335
desired_vel_neu_cms = Vector3f{safe_vel_ne_cms.x, safe_vel_ne_cms.y, safe_vel_neu_cms.z};
1336
const Vector2f backup_vel_ne_cms = _ahrs.body_to_earth2D(desired_back_vel_cms_xy);
1337
backup_vel_neu_cms = Vector3f{backup_vel_ne_cms.x, backup_vel_ne_cms.y, desired_back_vel_cms_z};
1338
#endif // HAL_PROXIMITY_ENABLED
1339
}
1340
1341
/*
1342
* Adjusts the desired velocity for the polygon fence.
1343
*/
1344
void AC_Avoid::adjust_velocity_polygon(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel_ne_cms, const Vector2f* boundary, uint16_t num_points, float margin, float dt, bool stay_inside)
1345
{
1346
// exit if there are no points
1347
if (boundary == nullptr || num_points == 0) {
1348
return;
1349
}
1350
1351
const AP_AHRS &_ahrs = AP::ahrs();
1352
1353
// do not adjust velocity if vehicle is outside the polygon fence
1354
Vector2f position_ne_cm;
1355
if (!_ahrs.get_relative_position_NE_origin_float(position_ne_cm)) {
1356
// boundary is in earth frame but we have no idea
1357
// where we are
1358
return;
1359
}
1360
position_ne_cm = position_ne_cm * 100.0f; // m to cm
1361
1362
1363
// return if we have already breached polygon
1364
const bool inside_polygon = !Polygon_outside(position_ne_cm, boundary, num_points);
1365
if (inside_polygon != stay_inside) {
1366
return;
1367
}
1368
1369
// Safe_vel will be adjusted to remain within fence.
1370
// We need a separate vector in case adjustment fails,
1371
// e.g. if we are exactly on the boundary.
1372
Vector2f safe_vel_ne_cms(desired_vel_cms);
1373
Vector2f desired_back_vel_cms;
1374
1375
// calc margin in cm
1376
const float margin_cm = MAX(margin * 100.0f, 0.0f);
1377
1378
// for stopping
1379
const float speed = safe_vel_ne_cms.length();
1380
Vector2f stopping_point_plus_margin_ne_cm;
1381
if (!desired_vel_cms.is_zero()) {
1382
stopping_point_plus_margin_ne_cm = position_ne_cm + safe_vel_ne_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed))/speed);
1383
}
1384
1385
// for backing away
1386
Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;
1387
1388
for (uint16_t i=0; i<num_points; i++) {
1389
uint16_t j = i+1;
1390
if (j >= num_points) {
1391
j = 0;
1392
}
1393
// end points of current edge
1394
Vector2f start = boundary[j];
1395
Vector2f end = boundary[i];
1396
Vector2f vector_to_boundary_ne_cm = Vector2f::closest_point(position_ne_cm, start, end) - position_ne_cm;
1397
// back away if vehicle has breached margin
1398
if (is_negative(vector_to_boundary_ne_cm.length() - margin_cm)) {
1399
calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_cm - vector_to_boundary_ne_cm.length(), vector_to_boundary_ne_cm, dt);
1400
}
1401
1402
// exit immediately if no desired velocity
1403
if (desired_vel_cms.is_zero()) {
1404
continue;
1405
}
1406
1407
switch (_behavior) {
1408
case (BEHAVIOR_SLIDE): {
1409
// vector from current position to closest point on current edge
1410
Vector2f limit_direction_ne_cm = vector_to_boundary_ne_cm;
1411
// distance to closest point
1412
const float limit_distance_cm = limit_direction_ne_cm.length();
1413
if (is_zero(limit_distance_cm)) {
1414
// We are exactly on the edge - treat this as a fence breach.
1415
// i.e. do not adjust velocity.
1416
return;
1417
}
1418
// We are strictly inside the given edge.
1419
// Adjust velocity to not violate this edge.
1420
limit_direction_ne_cm /= limit_distance_cm;
1421
limit_velocity_NE(kP, accel_cmss, safe_vel_ne_cms, limit_direction_ne_cm, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
1422
break;
1423
}
1424
1425
case (BEHAVIOR_STOP): {
1426
// find intersection_ne_cm with line segment
1427
Vector2f intersection_ne_cm;
1428
if (Vector2f::segment_intersection(position_ne_cm, stopping_point_plus_margin_ne_cm, start, end, intersection_ne_cm)) {
1429
// vector from current position to point on current edge
1430
Vector2f limit_direction_ne_cm = intersection_ne_cm - position_ne_cm;
1431
const float limit_distance_cm = limit_direction_ne_cm.length();
1432
if (is_zero(limit_distance_cm)) {
1433
// We are exactly on the edge - treat this as a fence breach.
1434
// i.e. do not adjust velocity.
1435
return;
1436
}
1437
if (limit_distance_cm <= margin_cm) {
1438
// we are within the margin so stop vehicle
1439
safe_vel_ne_cms.zero();
1440
} else {
1441
// vehicle inside the given edge, adjust velocity to not violate this edge
1442
limit_direction_ne_cm /= limit_distance_cm;
1443
limit_velocity_NE(kP, accel_cmss, safe_vel_ne_cms, limit_direction_ne_cm, MAX(limit_distance_cm - margin_cm, 0.0f), dt);
1444
}
1445
}
1446
break;
1447
}
1448
}
1449
}
1450
// desired backup velocity is sum of maximum velocity component in each quadrant
1451
desired_back_vel_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;
1452
1453
// set modified desired velocity vector or back away velocity vector
1454
desired_vel_cms = safe_vel_ne_cms;
1455
backup_vel_ne_cms = desired_back_vel_cms;
1456
}
1457
1458
/*
1459
* Computes distance required to stop, given current speed.
1460
*
1461
* Implementation copied from AC_PosControl.
1462
*/
1463
float AC_Avoid::get_stopping_distance(float kP, float accel_cmss, float speed_cms) const
1464
{
1465
// avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
1466
if (accel_cmss <= 0.0f || is_zero(speed_cms)) {
1467
return 0.0f;
1468
}
1469
1470
// handle linear deceleration
1471
if (kP <= 0.0f) {
1472
return 0.5f * sq(speed_cms) / accel_cmss;
1473
}
1474
1475
// calculate distance within which we can stop
1476
// accel_cmss/kP is the point at which velocity switches from linear to sqrt
1477
if (speed_cms < accel_cmss/kP) {
1478
return speed_cms/kP;
1479
} else {
1480
// accel_cmss/(2.0f*kP*kP) is the distance at which we switch from linear to sqrt response
1481
return accel_cmss/(2.0f*kP*kP) + (speed_cms*speed_cms)/(2.0f*accel_cmss);
1482
}
1483
}
1484
1485
// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes
1486
float AC_Avoid::distance_m_to_lean_norm(float dist_m) const
1487
{
1488
// ignore objects beyond DIST_MAX
1489
if (dist_m < 0.0f || dist_m >= _dist_max_m || _dist_max_m <= 0.0f) {
1490
return 0.0f;
1491
}
1492
// inverted but linear response
1493
return 1.0f - (dist_m / _dist_max_m);
1494
}
1495
1496
// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
1497
void AC_Avoid::get_proximity_roll_pitch_norm(float &roll_positive_norm, float &roll_negative_norm, float &pitch_positive_norm, float &pitch_negative_norm) const
1498
{
1499
#if HAL_PROXIMITY_ENABLED
1500
AP_Proximity *proximity = AP::proximity();
1501
if (proximity == nullptr) {
1502
return;
1503
}
1504
AP_Proximity &_proximity = *proximity;
1505
const uint8_t obj_count = _proximity.get_object_count();
1506
// if no objects return
1507
if (obj_count == 0) {
1508
return;
1509
}
1510
1511
// calculate maximum roll, pitch values from objects
1512
for (uint8_t i=0; i<obj_count; i++) {
1513
float ang_deg, dist_m;
1514
if (_proximity.get_object_angle_and_distance(i, ang_deg, dist_m)) {
1515
if (dist_m < _dist_max_m) {
1516
// convert distance to lean angle (in 0 to 1 range)
1517
const float lean_norm = distance_m_to_lean_norm(dist_m);
1518
// convert angle to roll and pitch lean percentages
1519
const float angle_rad = radians(ang_deg);
1520
const float roll_norm = -sinf(angle_rad) * lean_norm;
1521
const float pitch_norm = cosf(angle_rad) * lean_norm;
1522
// update roll, pitch maximums
1523
if (roll_norm > 0.0f) {
1524
roll_positive_norm = MAX(roll_positive_norm, roll_norm);
1525
} else if (roll_norm < 0.0f) {
1526
roll_negative_norm = MIN(roll_negative_norm, roll_norm);
1527
}
1528
if (pitch_norm > 0.0f) {
1529
pitch_positive_norm = MAX(pitch_positive_norm, pitch_norm);
1530
} else if (pitch_norm < 0.0f) {
1531
pitch_negative_norm = MIN(pitch_negative_norm, pitch_norm);
1532
}
1533
}
1534
}
1535
}
1536
#endif // HAL_PROXIMITY_ENABLED
1537
}
1538
1539
// singleton instance
1540
AC_Avoid *AC_Avoid::_singleton;
1541
1542
namespace AP {
1543
1544
AC_Avoid *ac_avoid()
1545
{
1546
return AC_Avoid::get_singleton();
1547
}
1548
1549
}
1550
1551
#endif // !APM_BUILD_Arduplane
1552
1553
#endif // AP_AVOIDANCE_ENABLED
1554
1555