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