CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

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

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_Fence/AC_Fence.cpp
Views: 1798
1
#include "AC_Fence.h"
2
3
#if AP_FENCE_ENABLED
4
5
#include <AP_Vehicle/AP_Vehicle_Type.h>
6
7
#ifndef AC_FENCE_DUMMY_METHODS_ENABLED
8
#define AC_FENCE_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub) | (AP_FENCE_ENABLED == 1)))
9
#endif
10
11
#if !AC_FENCE_DUMMY_METHODS_ENABLED
12
13
#include <AP_AHRS/AP_AHRS.h>
14
#include <AP_HAL/AP_HAL.h>
15
#include <AP_Logger/AP_Logger.h>
16
#include <GCS_MAVLink/GCS.h>
17
18
extern const AP_HAL::HAL& hal;
19
20
#if APM_BUILD_TYPE(APM_BUILD_Rover)
21
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
22
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
23
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_POLYGON
24
#else
25
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
26
#endif
27
28
// default boundaries
29
#define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m
30
#define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters
31
#define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m
32
#define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up
33
#define AC_FENCE_ALT_MIN_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further down
34
#define AC_FENCE_MARGIN_DEFAULT 2.0f // default distance in meters that autopilot's should maintain from the fence to avoid a breach
35
#define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control
36
37
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
38
#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 100m further out
39
#define AC_FENCE_OPTIONS_DEFAULT OPTIONS::DISABLE_MODE_CHANGE
40
#else
41
#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0 // after fence is broken we recreate the fence 20m further out
42
#define AC_FENCE_OPTIONS_DEFAULT 0
43
#endif
44
45
//#define AC_FENCE_DEBUG
46
47
const AP_Param::GroupInfo AC_Fence::var_info[] = {
48
49
// @Param: ENABLE
50
// @DisplayName: Fence enable/disable
51
// @Description: Allows you to enable (1) or disable (0) the fence functionality. Fences can still be enabled and disabled via mavlink or an RC option, but these changes are not persisted.
52
// @Values: 0:Disabled,1:Enabled
53
// @User: Standard
54
AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
55
56
// @Param: TYPE
57
// @DisplayName: Fence Type
58
// @Description: Configured fence types held as bitmask. Max altitide, Circle and Polygon fences will be immediately enabled if configured. Min altitude fence will only be enabled once the minimum altitude is reached.
59
// @Bitmask{Rover}: 1:Circle Centered on Home,2:Inclusion/Exclusion Circles+Polygons
60
// @Bitmask{Copter, Plane, Sub}: 0:Max altitude,1:Circle Centered on Home,2:Inclusion/Exclusion Circles+Polygons,3:Min altitude
61
// @User: Standard
62
AP_GROUPINFO("TYPE", 1, AC_Fence, _configured_fences, AC_FENCE_TYPE_DEFAULT),
63
64
// @Param: ACTION
65
// @DisplayName: Fence Action
66
// @Description: What action should be taken when fence is breached
67
// @Values{Copter}: 0:Report Only,1:RTL or Land,2:Always Land,3:SmartRTL or RTL or Land,4:Brake or Land,5:SmartRTL or Land
68
// @Values{Rover}: 0:Report Only,1:RTL or Hold,2:Hold,3:SmartRTL or RTL or Hold,4:SmartRTL or Hold
69
// @Values{Plane}: 0:Report Only,1:RTL,6:Guided,7:GuidedThrottlePass
70
// @Values: 0:Report Only,1:RTL or Land
71
// @User: Standard
72
AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND),
73
74
// @Param{Copter, Plane, Sub}: ALT_MAX
75
// @DisplayName: Fence Maximum Altitude
76
// @Description: Maximum altitude allowed before geofence triggers
77
// @Units: m
78
// @Range: 10 1000
79
// @Increment: 1
80
// @User: Standard
81
AP_GROUPINFO_FRAME("ALT_MAX", 3, AC_Fence, _alt_max, AC_FENCE_ALT_MAX_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_SUB | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_PLANE),
82
83
// @Param: RADIUS
84
// @DisplayName: Circular Fence Radius
85
// @Description: Circle fence radius which when breached will cause an RTL
86
// @Units: m
87
// @Range: 30 10000
88
// @User: Standard
89
AP_GROUPINFO("RADIUS", 4, AC_Fence, _circle_radius, AC_FENCE_CIRCLE_RADIUS_DEFAULT),
90
91
// @Param: MARGIN
92
// @DisplayName: Fence Margin
93
// @Description: Distance that autopilot's should maintain from the fence to avoid a breach
94
// @Units: m
95
// @Range: 1 10
96
// @User: Standard
97
AP_GROUPINFO("MARGIN", 5, AC_Fence, _margin, AC_FENCE_MARGIN_DEFAULT),
98
99
// @Param: TOTAL
100
// @DisplayName: Fence polygon point total
101
// @Description: Number of polygon points saved in eeprom (do not update manually)
102
// @Range: 1 20
103
// @User: Standard
104
AP_GROUPINFO("TOTAL", 6, AC_Fence, _total, 0),
105
106
// @Param{Copter, Plane, Sub}: ALT_MIN
107
// @DisplayName: Fence Minimum Altitude
108
// @Description: Minimum altitude allowed before geofence triggers
109
// @Units: m
110
// @Range: -100 100
111
// @Increment: 1
112
// @User: Standard
113
AP_GROUPINFO_FRAME("ALT_MIN", 7, AC_Fence, _alt_min, AC_FENCE_ALT_MIN_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_SUB | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_PLANE),
114
115
// @Param{Plane}: RET_RALLY
116
// @DisplayName: Fence Return to Rally
117
// @Description: Should the vehicle return to fence return point or rally point
118
// @Values: 0:Fence Return Point,1:Nearest Rally Point
119
// @Range: 0 1
120
// @Increment: 1
121
// @User: Standard
122
AP_GROUPINFO_FRAME("RET_RALLY", 8, AC_Fence, _ret_rally, 0, AP_PARAM_FRAME_PLANE),
123
124
// @Param{Plane}: RET_ALT
125
// @DisplayName: Fence Return Altitude
126
// @Description: Altitude the vehicle will transit to when a fence breach occurs
127
// @Units: m
128
// @Range: 0 32767
129
// @Increment: 1
130
// @User: Standard
131
AP_GROUPINFO_FRAME("RET_ALT", 9, AC_Fence, _ret_altitude, 0.0f, AP_PARAM_FRAME_PLANE),
132
133
// @Param{Plane, Copter}: AUTOENABLE
134
// @DisplayName: Fence Auto-Enable
135
// @Description: Auto-enable of fences. AutoEnableOnTakeoff enables all configured fences, except the minimum altitude fence (which is enabled when the minimum altitude is reached), after autotakeoffs reach altitude. During autolandings the fences will be disabled. AutoEnableDisableFloorOnLanding enables all configured fences, except the minimum altitude fence (which is enabled when the minimum altitude is reached), after autotakeoffs reach altitude. During autolandings only the Minimum Altitude fence will be disabled. AutoEnableOnlyWhenArmed enables all configured fences on arming, except the minimum altitude fence (which is enabled when the minimum altitude is reached), but no fences are disabled during autolandings. However, fence breaches are ignored while executing prior breach recovery actions which may include autolandings.
136
// @Values{Plane, Copter}: 0:AutoEnableOff,1:AutoEnableOnTakeoff,2:AutoEnableDisableFloorOnLanding,3:AutoEnableOnlyWhenArmed
137
// @Range: 0 3
138
// @Increment: 1
139
// @User: Standard
140
AP_GROUPINFO_FRAME("AUTOENABLE", 10, AC_Fence, _auto_enabled, static_cast<uint8_t>(AutoEnable::ALWAYS_DISABLED), AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),
141
142
// @Param{Plane, Copter}: OPTIONS
143
// @DisplayName: Fence options
144
// @Description: When bit 0 is set sisable mode change following fence action until fence breach is cleared. When bit 1 is set the allowable flight areas is the union of all polygon and circle fence areas instead of the intersection, which means a fence breach occurs only if you are outside all of the fence areas.
145
// @Bitmask: 0:Disable mode change following fence action until fence breach is cleared, 1:Allow union of inclusion areas
146
// @User: Standard
147
AP_GROUPINFO_FRAME("OPTIONS", 11, AC_Fence, _options, static_cast<uint16_t>(AC_FENCE_OPTIONS_DEFAULT), AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),
148
149
AP_GROUPEND
150
};
151
152
/// Default constructor.
153
AC_Fence::AC_Fence()
154
{
155
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
156
if (_singleton != nullptr) {
157
AP_HAL::panic("Fence must be singleton");
158
}
159
#endif
160
_singleton = this;
161
AP_Param::setup_object_defaults(this, var_info);
162
if (_enabled) {
163
_enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN;
164
}
165
}
166
167
// get a user-friendly list of fences
168
void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg)
169
{
170
if (!fences) {
171
return;
172
}
173
static const char* FENCE_NAMES[] = {
174
"Max Alt",
175
"Circle",
176
"Polygon",
177
"Min Alt",
178
};
179
uint8_t i = 0;
180
uint8_t nfences = 0;
181
while (fences !=0) {
182
if (fences & 0x1) {
183
if (nfences > 0) {
184
if (!(fences & ~1U)) {
185
msg.printf(" and ");
186
} else {
187
msg.printf(", ");
188
}
189
}
190
msg.printf("%s", FENCE_NAMES[i]);
191
nfences++;
192
}
193
fences >>= 1;
194
i++;
195
}
196
msg.printf(" fence");
197
if (nfences>1) {
198
msg.printf("s");
199
}
200
}
201
202
// print a message about the passed in fences
203
void AC_Fence::print_fence_message(const char* message, uint8_t fences) const
204
{
205
if (!fences) {
206
return;
207
}
208
209
char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
210
ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
211
AC_Fence::get_fence_names(fences, e);
212
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "%s %s", e.get_writeable_string(), message);
213
}
214
215
// should be called @10Hz to handle loading from eeprom
216
void AC_Fence::update()
217
{
218
_poly_loader.update();
219
// if someone changes the parameter we want to enable or disable everything
220
if (_enabled != _last_enabled || _auto_enabled != _last_auto_enabled) {
221
// reset the auto mask since we just reconfigured all of fencing
222
_last_enabled = _enabled;
223
_last_auto_enabled = _auto_enabled;
224
if (_enabled) {
225
_enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN;
226
} else {
227
_enabled_fences = 0;
228
}
229
}
230
#ifdef AC_FENCE_DEBUG
231
static uint32_t last_msg_count = 0;
232
if (get_enabled_fences() && last_msg_count++ % 10 == 0) {
233
print_fence_message("active", get_enabled_fences());
234
print_fence_message("breached", get_breaches());
235
}
236
#endif
237
}
238
239
// enable or disable configured fences present in fence_types
240
// also updates the _min_alt_state enum if update_auto_enable is true
241
// returns a bitmask of fences that were changed
242
uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable)
243
{
244
uint8_t fences = _configured_fences.get() & fence_types;
245
uint8_t enabled_fences = _enabled_fences;
246
if (value) {
247
enabled_fences |= fences;
248
} else {
249
enabled_fences &= ~fences;
250
}
251
252
if (update_auto_enable && (fences & AC_FENCE_TYPE_ALT_MIN) != 0) {
253
// remember that min-alt fence was manually enabled/disabled
254
_min_alt_state = value ? MinAltState::MANUALLY_ENABLED : MinAltState::MANUALLY_DISABLED;
255
}
256
257
uint8_t fences_to_change = _enabled_fences ^ enabled_fences;
258
259
if (!fences_to_change) {
260
return 0;
261
}
262
263
#if HAL_LOGGING_ENABLED
264
AP::logger().Write_Event(value ? LogEvent::FENCE_ENABLE : LogEvent::FENCE_DISABLE);
265
if (fences_to_change & AC_FENCE_TYPE_ALT_MAX) {
266
AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MAX_ENABLE : LogEvent::FENCE_ALT_MAX_DISABLE);
267
}
268
if (fences_to_change & AC_FENCE_TYPE_CIRCLE) {
269
AP::logger().Write_Event(value ? LogEvent::FENCE_CIRCLE_ENABLE : LogEvent::FENCE_CIRCLE_DISABLE);
270
}
271
if (fences_to_change & AC_FENCE_TYPE_ALT_MIN) {
272
AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MIN_ENABLE : LogEvent::FENCE_ALT_MIN_DISABLE);
273
}
274
if (fences_to_change & AC_FENCE_TYPE_POLYGON) {
275
AP::logger().Write_Event(value ? LogEvent::FENCE_POLYGON_ENABLE : LogEvent::FENCE_POLYGON_DISABLE);
276
}
277
#endif
278
279
_enabled_fences = enabled_fences;
280
281
if (!value) {
282
clear_breach(fences_to_change);
283
}
284
285
return fences_to_change;
286
}
287
288
/// enable/disable fence floor only
289
void AC_Fence::enable_floor()
290
{
291
enable(true, AC_FENCE_TYPE_ALT_MIN);
292
}
293
294
void AC_Fence::disable_floor()
295
{
296
enable(false, AC_FENCE_TYPE_ALT_MIN);
297
}
298
299
/*
300
called on arming
301
*/
302
void AC_Fence::auto_enable_fence_on_arming(void)
303
{
304
if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
305
return;
306
}
307
308
// reset min alt state, after an auto-enable the min alt fence can be auto-enabled on
309
// reaching altitude
310
_min_alt_state = MinAltState::DEFAULT;
311
312
const uint8_t fences = enable(true, AC_FENCE_ARMING_FENCES, false);
313
print_fence_message("auto-enabled", fences);
314
}
315
316
/*
317
called on disarming
318
*/
319
void AC_Fence::auto_disable_fence_on_disarming(void)
320
{
321
if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
322
return;
323
}
324
325
const uint8_t fences = enable(false, AC_FENCE_ALL_FENCES, false);
326
print_fence_message("auto-disabled", fences);
327
}
328
329
/*
330
called when an auto-takeoff is complete
331
*/
332
void AC_Fence::auto_enable_fence_after_takeoff(void)
333
{
334
if (auto_enabled() != AutoEnable::ENABLE_ON_AUTO_TAKEOFF &&
335
auto_enabled() != AutoEnable::ENABLE_DISABLE_FLOOR_ONLY) {
336
return;
337
}
338
339
// reset min-alt state
340
_min_alt_state = MinAltState::DEFAULT;
341
342
const uint8_t fences = enable(true, AC_FENCE_ALL_FENCES, false);
343
print_fence_message("auto-enabled", fences);
344
}
345
346
// return fences that should be auto-disabled when requested
347
uint8_t AC_Fence::get_auto_disable_fences(void) const
348
{
349
uint8_t auto_disable = 0;
350
switch (auto_enabled()) {
351
case AC_Fence::AutoEnable::ENABLE_ON_AUTO_TAKEOFF:
352
auto_disable = AC_FENCE_ALL_FENCES;
353
break;
354
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
355
case AC_Fence::AutoEnable::ONLY_WHEN_ARMED:
356
default: // when auto disable is not set we still need to disable the altmin fence on landing
357
auto_disable = AC_FENCE_TYPE_ALT_MIN;
358
break;
359
}
360
if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {
361
// don't auto-disable min alt fence if manually enabled
362
auto_disable &= ~AC_FENCE_TYPE_ALT_MIN;
363
}
364
return auto_disable;
365
}
366
367
uint8_t AC_Fence::present() const
368
{
369
uint8_t mask = AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX;
370
if (_poly_loader.total_fence_count() > 0) {
371
mask |= AC_FENCE_TYPE_POLYGON;
372
}
373
374
return _configured_fences.get() & mask;
375
}
376
377
/// get_enabled_fences - returns bitmask of enabled fences
378
uint8_t AC_Fence::get_enabled_fences() const
379
{
380
return _enabled_fences & present();
381
}
382
383
// additional checks for the polygon fence:
384
bool AC_Fence::pre_arm_check_polygon(char *failure_msg, const uint8_t failure_msg_len) const
385
{
386
if (!(_configured_fences & AC_FENCE_TYPE_POLYGON)) {
387
// not enabled; all good
388
return true;
389
}
390
391
if (! _poly_loader.loaded()) {
392
hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence(s) invalid");
393
return false;
394
}
395
396
if (!_poly_loader.check_inclusion_circle_margin(_margin)) {
397
hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence margin is less than inclusion circle radius");
398
return false;
399
}
400
401
return true;
402
}
403
404
// additional checks for the circle fence:
405
bool AC_Fence::pre_arm_check_circle(char *failure_msg, const uint8_t failure_msg_len) const
406
{
407
if (_circle_radius < 0) {
408
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid Circle FENCE_RADIUS value");
409
return false;
410
}
411
if (_circle_radius < _margin) {
412
hal.util->snprintf(failure_msg, failure_msg_len, "Circle FENCE_MARGIN is less than FENCE_RADIUS");
413
return false;
414
}
415
416
return true;
417
}
418
419
// additional checks for the alt fence:
420
bool AC_Fence::pre_arm_check_alt(char *failure_msg, const uint8_t failure_msg_len) const
421
{
422
if (_alt_max < 0.0f) {
423
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MAX value");
424
return false;
425
}
426
427
if (_alt_min < -100.0f) {
428
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MIN value");
429
return false;
430
}
431
return true;
432
}
433
434
435
/// pre_arm_check - returns true if all pre-takeoff checks have completed successfully
436
bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const
437
{
438
// if fences are enabled but none selected fail pre-arm check
439
if (_enabled && !present()) {
440
hal.util->snprintf(failure_msg, failure_msg_len, "Fences enabled, but none selected");
441
return false;
442
}
443
444
// if AUTOENABLE = 1 or 2 warn now, but fail in a later release
445
// PARAMETER_CONVERSION - Added: Jul-2024 for ArduPilot-4.6
446
if (_auto_enabled == 1 || _auto_enabled == 2) {
447
static uint32_t last_autoenable_warn_ms;
448
const uint32_t now_ms = AP_HAL::millis();
449
if (now_ms - last_autoenable_warn_ms > 60000) {
450
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "FENCE_AUTOENABLE is %u, will be removed in 4.7, use 3", unsigned(_auto_enabled));
451
last_autoenable_warn_ms = now_ms;
452
}
453
}
454
455
// if not enabled or not fence set-up always return true
456
if ((!enabled() && !_auto_enabled) || !_configured_fences) {
457
return true;
458
}
459
460
// if we have horizontal limits enabled, check we can get a
461
// relative position from the AHRS
462
if ((_configured_fences & AC_FENCE_TYPE_CIRCLE) ||
463
(_configured_fences & AC_FENCE_TYPE_POLYGON)) {
464
Vector2f position;
465
if (!AP::ahrs().get_relative_position_NE_home(position)) {
466
hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");
467
return false;
468
}
469
}
470
471
if (!pre_arm_check_polygon(failure_msg, failure_msg_len)) {
472
return false;
473
}
474
475
if (!pre_arm_check_circle(failure_msg, failure_msg_len)) {
476
return false;
477
}
478
479
if (!pre_arm_check_alt(failure_msg, failure_msg_len)) {
480
return false;
481
}
482
483
auto breached_fences = _breached_fences;
484
if (auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
485
Location loc;
486
if (!AP::ahrs().get_location(loc)) {
487
hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");
488
return false;
489
}
490
if (_poly_loader.breached(loc)) {
491
breached_fences |= AC_FENCE_TYPE_POLYGON;
492
}
493
}
494
495
// check no limits are currently breached
496
if (breached_fences) {
497
char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
498
ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
499
AC_Fence::get_fence_names(_breached_fences, e);
500
hal.util->snprintf(failure_msg, failure_msg_len, "Vehicle breaching %s", e.get_writeable_string());
501
return false;
502
}
503
504
// validate FENCE_MARGIN parameter range
505
if (_margin < 0.0f) {
506
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_MARGIN value");
507
return false;
508
}
509
510
if (_alt_max < _alt_min) {
511
hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_ALT_MAX < FENCE_ALT_MIN");
512
return false;
513
}
514
515
if (_alt_max - _alt_min <= 2.0f * _margin) {
516
hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_MARGIN too big");
517
return false;
518
}
519
520
// if we got this far everything must be ok
521
return true;
522
}
523
524
/// returns true if we have freshly breached the maximum altitude
525
/// fence; also may set up a fallback fence which, if breached, will
526
/// cause the altitude fence to be freshly breached
527
bool AC_Fence::check_fence_alt_max()
528
{
529
// altitude fence check
530
if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {
531
// not enabled; no breach
532
return false;
533
}
534
535
float alt;
536
AP::ahrs().get_relative_position_D_home(alt);
537
const float _curr_alt = -alt; // translate Down to Up
538
539
// check if we are over the altitude fence
540
if (_curr_alt >= _alt_max) {
541
542
// record distance above breach
543
_alt_max_breach_distance = _curr_alt - _alt_max;
544
545
// check for a new breach or a breach of the backup fence
546
if (!(_breached_fences & AC_FENCE_TYPE_ALT_MAX) ||
547
(!is_zero(_alt_max_backup) && _curr_alt >= _alt_max_backup)) {
548
549
// new breach
550
record_breach(AC_FENCE_TYPE_ALT_MAX);
551
552
// create a backup fence 20m higher up
553
_alt_max_backup = _curr_alt + AC_FENCE_ALT_MAX_BACKUP_DISTANCE;
554
// new breach
555
return true;
556
}
557
// old breach
558
return false;
559
}
560
561
// not breached
562
563
// clear max alt breach if present
564
if ((_breached_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
565
clear_breach(AC_FENCE_TYPE_ALT_MAX);
566
_alt_max_backup = 0.0f;
567
_alt_max_breach_distance = 0.0f;
568
}
569
570
return false;
571
}
572
573
/// returns true if we have freshly breached the minimum altitude
574
/// fence; also may set up a fallback fence which, if breached, will
575
/// cause the altitude fence to be freshly breached
576
bool AC_Fence::check_fence_alt_min()
577
{
578
// altitude fence check
579
if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)) {
580
// not enabled; no breach
581
return false;
582
}
583
584
float alt;
585
AP::ahrs().get_relative_position_D_home(alt);
586
const float _curr_alt = -alt; // translate Down to Up
587
588
// check if we are under the altitude fence
589
if (_curr_alt <= _alt_min) {
590
591
// record distance below breach
592
_alt_min_breach_distance = _alt_min - _curr_alt;
593
594
// check for a new breach or a breach of the backup fence
595
if (!(_breached_fences & AC_FENCE_TYPE_ALT_MIN) ||
596
(!is_zero(_alt_min_backup) && _curr_alt <= _alt_min_backup)) {
597
598
// new breach
599
record_breach(AC_FENCE_TYPE_ALT_MIN);
600
601
// create a backup fence 20m lower down
602
_alt_min_backup = _curr_alt - AC_FENCE_ALT_MIN_BACKUP_DISTANCE;
603
// new breach
604
return true;
605
}
606
// old breach
607
return false;
608
}
609
610
// not breached
611
612
// clear min alt breach if present
613
if ((_breached_fences & AC_FENCE_TYPE_ALT_MIN) != 0) {
614
clear_breach(AC_FENCE_TYPE_ALT_MIN);
615
_alt_min_backup = 0.0f;
616
_alt_min_breach_distance = 0.0f;
617
}
618
619
return false;
620
}
621
622
623
/// auto enable fence floor
624
bool AC_Fence::auto_enable_fence_floor()
625
{
626
// altitude fence check
627
if (!(_configured_fences & AC_FENCE_TYPE_ALT_MIN) // not configured
628
|| (get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) // already enabled
629
|| _min_alt_state == MinAltState::MANUALLY_DISABLED // user has manually disabled the fence
630
|| (!_enabled && (auto_enabled() == AC_Fence::AutoEnable::ALWAYS_DISABLED
631
|| auto_enabled() == AutoEnable::ENABLE_ON_AUTO_TAKEOFF))) {
632
// not enabled
633
return false;
634
}
635
636
float alt;
637
AP::ahrs().get_relative_position_D_home(alt);
638
const float _curr_alt = -alt; // translate Down to Up
639
640
// check if we are over the altitude fence
641
if (!floor_enabled() && _curr_alt >= _alt_min + _margin) {
642
enable(true, AC_FENCE_TYPE_ALT_MIN, false);
643
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Min Alt fence enabled (auto enable)");
644
return true;
645
}
646
647
return false;
648
}
649
650
// check_fence_polygon - returns true if the poly fence is freshly
651
// breached. That includes being inside exclusion zones and outside
652
// inclusions zones
653
bool AC_Fence::check_fence_polygon()
654
{
655
if (!(get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {
656
// not enabled; no breach
657
clear_breach(AC_FENCE_TYPE_POLYGON);
658
return false;
659
}
660
661
const bool was_breached = _breached_fences & AC_FENCE_TYPE_POLYGON;
662
if (_poly_loader.breached()) {
663
if (!was_breached) {
664
record_breach(AC_FENCE_TYPE_POLYGON);
665
return true;
666
}
667
return false;
668
}
669
if (was_breached) {
670
clear_breach(AC_FENCE_TYPE_POLYGON);
671
}
672
return false;
673
}
674
675
/// check_fence_circle - returns true if the circle fence (defined via
676
/// parameters) has been freshly breached. May also set up a backup
677
/// fence outside the fence and return a fresh breach if that backup
678
/// fence is breached.
679
bool AC_Fence::check_fence_circle()
680
{
681
if (!(get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {
682
// not enabled; no breach
683
return false;
684
}
685
686
Vector2f home;
687
if (AP::ahrs().get_relative_position_NE_home(home)) {
688
// we (may) remain breached if we can't update home
689
_home_distance = home.length();
690
}
691
692
// check if we are outside the fence
693
if (_home_distance >= _circle_radius) {
694
695
// record distance outside the fence
696
_circle_breach_distance = _home_distance - _circle_radius;
697
698
// check for a new breach or a breach of the backup fence
699
if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) ||
700
(!is_zero(_circle_radius_backup) && _home_distance >= _circle_radius_backup)) {
701
// new breach
702
// create a backup fence 20m or 100m further out
703
record_breach(AC_FENCE_TYPE_CIRCLE);
704
_circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE;
705
return true;
706
}
707
return false;
708
}
709
710
// not currently breached
711
712
// clear circle breach if present
713
if (_breached_fences & AC_FENCE_TYPE_CIRCLE) {
714
clear_breach(AC_FENCE_TYPE_CIRCLE);
715
_circle_radius_backup = 0.0f;
716
_circle_breach_distance = 0.0f;
717
}
718
719
return false;
720
}
721
722
723
/// check - returns bitmask of fence types breached (if any)
724
uint8_t AC_Fence::check(bool disable_auto_fences)
725
{
726
uint8_t ret = 0;
727
uint8_t disabled_fences = disable_auto_fences ? get_auto_disable_fences() : 0;
728
uint8_t fences_to_disable = disabled_fences & _enabled_fences;
729
730
// clear any breach from a non-enabled fence
731
clear_breach(~_configured_fences);
732
// clear any breach from disabled fences
733
clear_breach(fences_to_disable);
734
735
if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {
736
// if user has manually enabled the min-alt fence then don't auto-disable
737
fences_to_disable &= ~AC_FENCE_TYPE_ALT_MIN;
738
}
739
740
// report on any fences that were auto-disabled
741
if (fences_to_disable) {
742
print_fence_message("auto-disabled", fences_to_disable);
743
}
744
745
#if 0
746
/*
747
this debug log message is very useful both when developing tests
748
and doing manual SITL fence testing
749
*/
750
{
751
float alt;
752
AP::ahrs().get_relative_position_D_home(alt);
753
754
AP::logger().WriteStreaming("FENC", "TimeUS,EN,AE,CF,EF,DF,Alt", "QIIIIIf",
755
AP_HAL::micros64(),
756
enabled(),
757
_auto_enabled,
758
_configured_fences,
759
get_enabled_fences(),
760
disabled_fences,
761
alt*-1);
762
}
763
#endif
764
765
// return immediately if disabled
766
if ((!enabled() && !_auto_enabled && !(_configured_fences & AC_FENCE_TYPE_ALT_MIN)) || !_configured_fences) {
767
return 0;
768
}
769
770
// disable the (temporarily) disabled fences
771
enable(false, disabled_fences, false);
772
773
// maximum altitude fence check
774
if (!(disabled_fences & AC_FENCE_TYPE_ALT_MAX) && check_fence_alt_max()) {
775
ret |= AC_FENCE_TYPE_ALT_MAX;
776
}
777
778
// minimum altitude fence check, do this before auto-disabling (e.g. because falling)
779
// so that any action can be taken
780
if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN) && check_fence_alt_min()) {
781
ret |= AC_FENCE_TYPE_ALT_MIN;
782
}
783
784
// auto enable floor unless auto enable on auto takeoff has been set (which means other behaviour is required)
785
if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN)) {
786
auto_enable_fence_floor();
787
}
788
789
// circle fence check
790
if (!(disabled_fences & AC_FENCE_TYPE_CIRCLE) && check_fence_circle()) {
791
ret |= AC_FENCE_TYPE_CIRCLE;
792
}
793
794
// polygon fence check
795
if (!(disabled_fences & AC_FENCE_TYPE_POLYGON) && check_fence_polygon()) {
796
ret |= AC_FENCE_TYPE_POLYGON;
797
}
798
799
// check if pilot is attempting to recover manually
800
// this is done last so that _breached_fences is correct
801
if (_manual_recovery_start_ms != 0) {
802
// we ignore any fence breaches during the manual recovery period which is about 10 seconds
803
if ((AP_HAL::millis() - _manual_recovery_start_ms) < AC_FENCE_MANUAL_RECOVERY_TIME_MIN) {
804
return 0;
805
}
806
// recovery period has passed so reset manual recovery time
807
// and continue with fence breach checks
808
_manual_recovery_start_ms = 0;
809
}
810
811
// return any new breaches that have occurred
812
return ret;
813
}
814
815
// returns true if the destination is within fence (used to reject waypoints outside the fence)
816
bool AC_Fence::check_destination_within_fence(const Location& loc)
817
{
818
// Altitude fence check - Fence Ceiling
819
if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {
820
int32_t alt_above_home_cm;
821
if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {
822
if ((alt_above_home_cm * 0.01f) > _alt_max) {
823
return false;
824
}
825
}
826
}
827
828
// Altitude fence check - Fence Floor
829
if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)) {
830
int32_t alt_above_home_cm;
831
if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {
832
if ((alt_above_home_cm * 0.01f) < _alt_min) {
833
return false;
834
}
835
}
836
}
837
838
// Circular fence check
839
if ((get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {
840
if (AP::ahrs().get_home().get_distance(loc) > _circle_radius) {
841
return false;
842
}
843
}
844
845
// polygon fence check
846
if ((get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {
847
if (_poly_loader.breached(loc)) {
848
return false;
849
}
850
}
851
852
return true;
853
}
854
855
/// record_breach - update breach bitmask, time and count
856
void AC_Fence::record_breach(uint8_t fence_type)
857
{
858
// if we haven't already breached a limit, update the breach time
859
if (!_breached_fences) {
860
const uint32_t now = AP_HAL::millis();
861
_breach_time = now;
862
863
// emit a message indicated we're newly-breached, but not too often
864
if (now - _last_breach_notify_sent_ms > 1000) {
865
_last_breach_notify_sent_ms = now;
866
GCS_SEND_MESSAGE(MSG_FENCE_STATUS);
867
}
868
}
869
870
// update breach count
871
if (_breach_count < 65500) {
872
_breach_count++;
873
}
874
875
// update bitmask
876
_breached_fences |= fence_type;
877
}
878
879
/// clear_breach - update breach bitmask, time and count
880
void AC_Fence::clear_breach(uint8_t fence_type)
881
{
882
_breached_fences &= ~fence_type;
883
}
884
885
/// get_breach_distance - returns maximum distance in meters outside
886
/// of the given fences. fence_type is a bitmask here.
887
float AC_Fence::get_breach_distance(uint8_t fence_type) const
888
{
889
float max = 0.0f;
890
891
if (fence_type & AC_FENCE_TYPE_ALT_MAX) {
892
max = MAX(_alt_max_breach_distance, max);
893
}
894
if (fence_type & AC_FENCE_TYPE_ALT_MIN) {
895
max = MAX(_alt_min_breach_distance, max);
896
}
897
if (fence_type & AC_FENCE_TYPE_CIRCLE) {
898
max = MAX(_circle_breach_distance, max);
899
}
900
return max;
901
}
902
903
/// manual_recovery_start - caller indicates that pilot is re-taking manual control so fence should be disabled for 10 seconds
904
/// has no effect if no breaches have occurred
905
void AC_Fence::manual_recovery_start()
906
{
907
// return immediate if we haven't breached a fence
908
if (!_breached_fences) {
909
return;
910
}
911
912
// record time pilot began manual recovery
913
_manual_recovery_start_ms = AP_HAL::millis();
914
915
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Manual recovery started");
916
}
917
918
// methods for mavlink SYS_STATUS message (send_sys_status)
919
bool AC_Fence::sys_status_present() const
920
{
921
return present();
922
}
923
924
bool AC_Fence::sys_status_enabled() const
925
{
926
if (!sys_status_present()) {
927
return false;
928
}
929
if (_action == AC_FENCE_ACTION_REPORT_ONLY) {
930
return false;
931
}
932
// Fence is only enabled when the flag is enabled
933
return enabled();
934
}
935
936
bool AC_Fence::sys_status_failed() const
937
{
938
if (!sys_status_present()) {
939
// not failed if not present; can fail if present but not enabled
940
return false;
941
}
942
if (get_breaches() != 0) {
943
return true;
944
}
945
return false;
946
}
947
948
AC_PolyFence_loader &AC_Fence::polyfence()
949
{
950
return _poly_loader;
951
}
952
const AC_PolyFence_loader &AC_Fence::polyfence() const
953
{
954
return _poly_loader;
955
}
956
957
958
#else // build type is not appropriate; provide a dummy implementation:
959
const AP_Param::GroupInfo AC_Fence::var_info[] = { AP_GROUPEND };
960
961
AC_Fence::AC_Fence() {};
962
963
uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable) { return 0; }
964
965
void AC_Fence::enable_floor() {}
966
void AC_Fence::disable_floor() {}
967
void AC_Fence::update() {}
968
969
void AC_Fence::auto_enable_fence_after_takeoff() {}
970
void AC_Fence::auto_enable_fence_on_arming() {}
971
void AC_Fence::auto_disable_fence_on_disarming() {}
972
973
uint8_t AC_Fence::present() const { return 0; }
974
975
uint8_t AC_Fence::get_enabled_fences() const { return 0; }
976
977
bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const { return true; }
978
979
uint8_t AC_Fence::check(bool disable_auto_fences) { return 0; }
980
bool AC_Fence::check_destination_within_fence(const Location& loc) { return true; }
981
float AC_Fence::get_breach_distance(uint8_t fence_type) const { return 0.0; }
982
void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg) { }
983
void AC_Fence::print_fence_message(const char* msg, uint8_t fences) const {}
984
985
void AC_Fence::manual_recovery_start() {}
986
987
bool AC_Fence::sys_status_present() const { return false; }
988
bool AC_Fence::sys_status_enabled() const { return false; }
989
bool AC_Fence::sys_status_failed() const { return false; }
990
991
AC_PolyFence_loader &AC_Fence::polyfence()
992
{
993
return _poly_loader;
994
}
995
const AC_PolyFence_loader &AC_Fence::polyfence() const
996
{
997
return _poly_loader;
998
}
999
1000
#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED
1001
1002
// singleton instance
1003
AC_Fence *AC_Fence::_singleton;
1004
1005
namespace AP
1006
{
1007
1008
AC_Fence *fence()
1009
{
1010
return AC_Fence::get_singleton();
1011
}
1012
1013
}
1014
1015
#endif // AP_FENCE_ENABLED
1016
1017