APM:Libraries
AC_Fence.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_Fence.h"
4 #include <GCS_MAVLink/GCS.h>
5 
6 extern const AP_HAL::HAL& hal;
7 
9  // @Param: ENABLE
10  // @DisplayName: Fence enable/disable
11  // @Description: Allows you to enable (1) or disable (0) the fence functionality
12  // @Values: 0:Disabled,1:Enabled
13  // @User: Standard
14  AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
15 
16  // @Param: TYPE
17  // @DisplayName: Fence Type
18  // @Description: Enabled fence types held as bitmask
19  // @Values: 0:None,1:Altitude,2:Circle,3:Altitude and Circle,4:Polygon,5:Altitude and Polygon,6:Circle and Polygon,7:All
20  // @Bitmask: 0:Altitude,1:Circle,2:Polygon
21  // @User: Standard
23 
24  // @Param: ACTION
25  // @DisplayName: Fence Action
26  // @Description: What action should be taken when fence is breached
27  // @Values: 0:Report Only,1:RTL or Land
28  // @User: Standard
29  AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND),
30 
31  // @Param: ALT_MAX
32  // @DisplayName: Fence Maximum Altitude
33  // @Description: Maximum altitude allowed before geofence triggers
34  // @Units: m
35  // @Range: 10 1000
36  // @Increment: 1
37  // @User: Standard
39 
40  // @Param: RADIUS
41  // @DisplayName: Circular Fence Radius
42  // @Description: Circle fence radius which when breached will cause an RTL
43  // @Units: m
44  // @Range: 30 10000
45  // @User: Standard
46  AP_GROUPINFO("RADIUS", 4, AC_Fence, _circle_radius, AC_FENCE_CIRCLE_RADIUS_DEFAULT),
47 
48  // @Param: MARGIN
49  // @DisplayName: Fence Margin
50  // @Description: Distance that autopilot's should maintain from the fence to avoid a breach
51  // @Units: m
52  // @Range: 1 10
53  // @User: Standard
54  AP_GROUPINFO("MARGIN", 5, AC_Fence, _margin, AC_FENCE_MARGIN_DEFAULT),
55 
56  // @Param: TOTAL
57  // @DisplayName: Fence polygon point total
58  // @Description: Number of polygon points saved in eeprom (do not update manually)
59  // @Range: 1 20
60  // @User: Standard
61  AP_GROUPINFO("TOTAL", 6, AC_Fence, _total, 0),
62 
63  // @Param: ALT_MIN
64  // @DisplayName: Fence Minimum Altitude
65  // @Description: Minimum altitude allowed before geofence triggers
66  // @Units: m
67  // @Range: -100 100
68  // @Increment: 1
69  // @User: Standard
71 
73 };
74 
77  _ahrs(ahrs)
78 {
80 }
81 
83 {
84  _enabled = value;
85  if (!value) {
87  }
88 }
89 
92 {
93  if (!_enabled) {
94  return 0;
95  }
96  return _enabled_fences;
97 }
98 
99 // additional checks for the polygon fence:
100 bool AC_Fence::pre_arm_check_polygon(const char* &fail_msg) const
101 {
103  // not enabled; all good
104  return true;
105  }
106 
107  if (!_boundary_valid) {
108  fail_msg = "Polygon boundary invalid";
109  return false;
110  }
111 
112  return true;
113 }
114 
115 // additional checks for the circle fence:
116 bool AC_Fence::pre_arm_check_circle(const char* &fail_msg) const
117 {
118  if (_circle_radius < 0) {
119  fail_msg = "Invalid FENCE_RADIUS value";
120  return false;
121  }
122  return true;
123 }
124 
125 // additional checks for the alt fence:
126 bool AC_Fence::pre_arm_check_alt(const char* &fail_msg) const
127 {
128  if (_alt_max < 0.0f) {
129  fail_msg = "Invalid FENCE_ALT_MAX value";
130  return false;
131  }
132  return true;
133 }
134 
135 
137 bool AC_Fence::pre_arm_check(const char* &fail_msg) const
138 {
139  fail_msg = nullptr;
140 
141  // if not enabled or not fence set-up always return true
142  if (!_enabled || !_enabled_fences) {
143  return true;
144  }
145 
146  // check no limits are currently breached
147  if (_breached_fences) {
148  fail_msg = "vehicle outside fence";
149  return false;
150  }
151 
152  // if we have horizontal limits enabled, check we can get a
153  // relative position from the EKF
156  Vector2f position;
157  if (!_ahrs.get_relative_position_NE_home(position)) {
158  fail_msg = "fence requires position";
159  return false;
160  }
161  }
162 
163  if (!pre_arm_check_polygon(fail_msg)) {
164  return false;
165  }
166 
167  if (!pre_arm_check_circle(fail_msg)) {
168  return false;
169  }
170 
171  if (!pre_arm_check_alt(fail_msg)) {
172  return false;
173  }
174 
175  // if we got this far everything must be ok
176  return true;
177 }
178 
180 {
181  // altitude fence check
183  // not enabled; no breach
184  return false;
185  }
186 
188  _curr_alt = -_curr_alt; // translate Down to Up
189 
190  // check if we are over the altitude fence
191  if(_curr_alt >= _alt_max) {
192 
193  // record distance above breach
195 
196  // check for a new breach or a breach of the backup fence
197  if (!(_breached_fences & AC_FENCE_TYPE_ALT_MAX) ||
199 
200  // new breach
201  record_breach(AC_FENCE_TYPE_ALT_MAX);
202 
203  // create a backup fence 20m higher up
205  // new breach:
206  return true;
207  }
208  // old breach:
209  return false;
210  }
211 
212  // not breached
213 
214  // clear alt breach if present
215  if ((_breached_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
216  clear_breach(AC_FENCE_TYPE_ALT_MAX);
217  _alt_max_backup = 0.0f;
219  }
220 
221  return false;
222 }
223 
224 // check_fence_polygon - returns true if the polygon fence is freshly breached
226 {
228  // not enabled; no breach
229  return false;
230  }
231 
232  // check consistency of number of points
233  if (_boundary_num_points != _total) {
234  // Fence is currently not completely loaded. Can't breach it?!
235  _boundary_loaded = false;
237  return false;
238  }
239  if (!_boundary_valid) {
240  // fence isn't valid - can't breach it?!
241  return false;
242  }
243 
244  // check if vehicle is outside the polygon fence
245  Vector2f position;
246  if (!_ahrs.get_relative_position_NE_origin(position)) {
247  // we have no idea where we are; can't breach the fence
248  return false;
249  }
250 
251  position = position * 100.0f; // m to cm
253  // check if this is a new breach
254  if (_breached_fences & AC_FENCE_TYPE_POLYGON) {
255  // not a new breach
256  return false;
257  }
258  // record that we have breached the polygon
259  record_breach(AC_FENCE_TYPE_POLYGON);
260  return true;
261  }
262 
263  // inside boundary; clear breach if present
264  if (_breached_fences & AC_FENCE_TYPE_POLYGON) {
265  clear_breach(AC_FENCE_TYPE_POLYGON);
266  }
267 
268  return false;
269 }
270 
272 {
274  // not enabled; no breach
275  return false;
276  }
277 
278  Vector2f home;
280  // we (may) remain breached if we can't update home
281  _home_distance = home.length();
282  }
283 
284  // check if we are outside the fence
286 
287  // record distance outside the fence
289 
290  // check for a new breach or a breach of the backup fence
291  if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) ||
293  // new breach
294  // create a backup fence 20m further out
295  record_breach(AC_FENCE_TYPE_CIRCLE);
297  return true;
298  }
299  return false;
300  }
301 
302  // not currently breached
303 
304  // clear circle breach if present
305  if (_breached_fences & AC_FENCE_TYPE_CIRCLE) {
306  clear_breach(AC_FENCE_TYPE_CIRCLE);
307  _circle_radius_backup = 0.0f;
309  }
310 
311  return false;
312 }
313 
314 
317 {
318  uint8_t ret = 0;
319 
320  // return immediately if disabled
321  if (!_enabled || !_enabled_fences) {
322  return 0;
323  }
324 
325  // check if pilot is attempting to recover manually
326  if (_manual_recovery_start_ms != 0) {
327  // we ignore any fence breaches during the manual recovery period which is about 10 seconds
329  return 0;
330  }
331  // recovery period has passed so reset manual recovery time
332  // and continue with fence breach checks
334  }
335 
336  // maximum altitude fence check
337  if (check_fence_alt_max()) {
338  ret |= AC_FENCE_TYPE_ALT_MAX;
339  }
340 
341  // circle fence check
342  if (check_fence_circle()) {
343  ret |= AC_FENCE_TYPE_CIRCLE;
344  }
345 
346  // polygon fence check
347  if (check_fence_polygon()) {
348  ret |= AC_FENCE_TYPE_POLYGON;
349  }
350 
351  // return any new breaches that have occurred
352  return ret;
353 }
354 
355 // returns true if the destination is within fence (used to reject waypoints outside the fence)
357 {
358  // Altitude fence check
360  int32_t alt_above_home_cm;
361  if (loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_HOME, alt_above_home_cm)) {
362  if ((alt_above_home_cm * 0.01f) > _alt_max) {
363  return false;
364  }
365  }
366  }
367 
368  // Circular fence check
370  if ((get_distance_cm(_ahrs.get_home(), loc) * 0.01f) > _circle_radius) {
371  return false;
372  }
373  }
374 
375  // polygon fence check
377  // check ekf has a good location
378  Vector2f posNE;
379  if (loc.get_vector_xy_from_origin_NE(posNE)) {
381  return false;
382  }
383  }
384  }
385 
386  return true;
387 }
388 
390 void AC_Fence::record_breach(uint8_t fence_type)
391 {
392  // if we haven't already breached a limit, update the breach time
393  if (!_breached_fences) {
395  }
396 
397  // update breach count
398  if (_breach_count < 65500) {
399  _breach_count++;
400  }
401 
402  // update bitmask
403  _breached_fences |= fence_type;
404 }
405 
407 void AC_Fence::clear_breach(uint8_t fence_type)
408 {
409  // return immediately if this fence type was not breached
410  if ((_breached_fences & fence_type) == 0) {
411  return;
412  }
413 
414  // update bitmask
415  _breached_fences &= ~fence_type;
416 }
417 
419 float AC_Fence::get_breach_distance(uint8_t fence_type) const
420 {
421  switch (fence_type) {
424  break;
427  break;
430  }
431 
432  // we don't recognise the fence type so just return 0
433  return 0;
434 }
435 
439 {
440  // return immediate if we haven't breached a fence
441  if (!_breached_fences) {
442  return;
443  }
444 
445  // record time pilot began manual recovery
447 }
448 
450 Vector2f* AC_Fence::get_polygon_points(uint16_t& num_points) const
451 {
452  num_points = _boundary_num_points;
453  return _boundary;
454 }
455 
457 bool AC_Fence::boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points) const
458 {
459  return _poly_loader.boundary_breached(location, num_points, points, true);
460 }
461 
463 void AC_Fence::handle_msg(GCS_MAVLINK &link, mavlink_message_t* msg)
464 {
465  // exit immediately if null message
466  if (msg == nullptr) {
467  return;
468  }
469 
470  switch (msg->msgid) {
471  // receive a fence point from GCS and store in EEPROM
472  case MAVLINK_MSG_ID_FENCE_POINT: {
473  mavlink_fence_point_t packet;
474  mavlink_msg_fence_point_decode(msg, &packet);
475  if (!check_latlng(packet.lat,packet.lng)) {
476  link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, lat or lng too large");
477  } else {
478  Vector2l point;
479  point.x = packet.lat*1.0e7f;
480  point.y = packet.lng*1.0e7f;
481  if (!_poly_loader.save_point_to_eeprom(packet.idx, point)) {
482  link.send_text(MAV_SEVERITY_WARNING, "Failed to save polygon point, too many points?");
483  } else {
484  // trigger reload of points
485  _boundary_loaded = false;
486  }
487  }
488  break;
489  }
490 
491  // send a fence point to GCS
492  case MAVLINK_MSG_ID_FENCE_FETCH_POINT: {
493  mavlink_fence_fetch_point_t packet;
494  mavlink_msg_fence_fetch_point_decode(msg, &packet);
495  // attempt to retrieve from eeprom
496  Vector2l point;
497  if (_poly_loader.load_point_from_eeprom(packet.idx, point)) {
498  mavlink_msg_fence_point_send_buf(msg, link.get_chan(), msg->sysid, msg->compid, packet.idx, _total, point.x*1.0e-7f, point.y*1.0e-7f);
499  } else {
500  link.send_text(MAV_SEVERITY_WARNING, "Bad fence point");
501  }
502  break;
503  }
504 
505  default:
506  // do nothing
507  break;
508  }
509 }
510 
512 bool AC_Fence::load_polygon_from_eeprom(bool force_reload)
513 {
514  // exit immediately if already loaded
515  if (_boundary_loaded && !force_reload) {
516  return true;
517  }
518 
519  // check if we need to create array
523  }
524 
525  // exit if we could not allocate RAM for the boundary
526  if (_boundary == nullptr) {
527  return false;
528  }
529 
530  // get current location from EKF
531  Location temp_loc;
532  if (!_ahrs.get_location(temp_loc)) {
533  return false;
534  }
535  struct Location ekf_origin {};
536  _ahrs.get_origin(ekf_origin);
537 
538  // sanity check total
540 
541  // load each point from eeprom
542  Vector2l temp_latlon;
543  for (uint16_t index=0; index<_total; index++) {
544  // load boundary point as lat/lon point
545  _poly_loader.load_point_from_eeprom(index, temp_latlon);
546  // move into location structure and convert to offset from ekf origin
547  temp_loc.lat = temp_latlon.x;
548  temp_loc.lng = temp_latlon.y;
549  _boundary[index] = location_diff(ekf_origin, temp_loc) * 100.0f;
550  }
552  _boundary_loaded = true;
553 
554  // update validity of polygon
556 
557  return true;
558 }
559 
560 // methods for mavlink SYS_STATUS message (send_extended_status1)
562 {
563  return _enabled;
564 }
565 
567 {
568  if (!sys_status_present()) {
569  return false;
570  }
572  return false;
573  }
574  return true;
575 }
576 
578 {
579  if (!sys_status_present()) {
580  // not failed if not present; can fail if present but not enabled
581  return false;
582  }
583  if (get_breaches() != 0) {
584  return true;
585  }
587  if (!_boundary_valid) {
588  return true;
589  }
590  }
592  if (_circle_radius < 0) {
593  return true;
594  }
595  }
597  if (_alt_max < 0.0f) {
598  return true;
599  }
600  }
601  if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) ||
602  (_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
603  Vector2f position;
604  if (!_ahrs.get_relative_position_NE_home(position)) {
605  // both these fence types require position
606  return true;
607  }
608  }
609 
610  return false;
611 }
bool check_fence_polygon()
check_fence_polygon - true if polygon fence has been newly breached
Definition: AC_Fence.cpp:225
void get_relative_position_D_home(float &posD) const override
bool boundary_breached(const Vector2f &location, uint16_t num_points, const Vector2f *points) const
returns true if we&#39;ve breached the polygon boundary. simple passthrough to underlying _poly_loader ob...
Definition: AC_Fence.cpp:457
void record_breach(uint8_t fence_type)
record_breach - update breach bitmask, time and count
Definition: AC_Fence.cpp:390
bool check_destination_within_fence(const Location_Class &loc)
Definition: AC_Fence.cpp:356
#define AC_FENCE_ALT_MIN_DEFAULT
Definition: AC_Fence.h:23
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
bool pre_arm_check_circle(const char *&fail_msg) const
Definition: AC_Fence.cpp:116
bool pre_arm_check(const char *&fail_msg) const
pre_arm_check - returns true if all pre-takeoff checks have completed successfully ...
Definition: AC_Fence.cpp:137
float _home_distance
Definition: AC_Fence.h:163
#define AC_FENCE_ALT_MAX_DEFAULT
Definition: AC_Fence.h:22
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_Fence.h:109
bool sys_status_failed() const
Definition: AC_Fence.cpp:577
bool sys_status_present() const
Definition: AC_Fence.cpp:561
Vector2f * _boundary
Definition: AC_Fence.h:176
void handle_msg(GCS_MAVLINK &link, mavlink_message_t *msg)
handler for polygon fence messages with GCS
Definition: AC_Fence.cpp:463
#define AC_FENCE_ACTION_REPORT_ONLY
Definition: AC_Fence.h:18
Interface definition for the various Ground Control System.
#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE
Definition: AC_Fence.h:26
#define AC_FENCE_TYPE_CIRCLE
Definition: AC_Fence.h:14
#define AC_FENCE_MANUAL_RECOVERY_TIME_MIN
Definition: AC_Fence.h:31
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
uint8_t _breached_fences
Definition: AC_Fence.h:168
uint8_t get_breaches() const
get_breaches - returns bit mask of the fence types that have been breached
Definition: AC_Fence.h:65
bool get_location(struct Location &loc) const
bool pre_arm_check_polygon(const char *&fail_msg) const
Definition: AC_Fence.cpp:100
bool load_point_from_eeprom(uint16_t i, Vector2l &point)
AP_Int8 _enabled
Definition: AC_Fence.h:145
AP_Int8 _action
Definition: AC_Fence.h:147
AC_PolyFence_loader _poly_loader
Definition: AC_Fence.h:175
bool pre_arm_check_alt(const char *&fail_msg) const
Definition: AC_Fence.cpp:126
#define AC_FENCE_MARGIN_DEFAULT
Definition: AC_Fence.h:27
uint8_t check()
check - returns the fence type that has been breached (if any)
Definition: AC_Fence.cpp:316
const AP_AHRS_NavEKF & _ahrs
Definition: AC_Fence.h:142
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
float get_breach_distance(uint8_t fence_type) const
get_breach_distance - returns distance in meters outside of the given fence
Definition: AC_Fence.cpp:419
uint32_t get_distance_cm(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:44
bool boundary_valid(uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
#define AC_FENCE_CIRCLE_RADIUS_DEFAULT
Definition: AC_Fence.h:24
bool get_origin(Location &ret) const override
bool _boundary_loaded
Definition: AC_Fence.h:179
void clear_breach(uint8_t fence_type)
clear_breach - update breach bitmask, time and count
Definition: AC_Fence.cpp:407
T y
Definition: vector2.h:37
uint8_t max_points() const
bool check_fence_alt_max()
check_fence_alt_max - true if alt fence has been newly breached
Definition: AC_Fence.cpp:179
float _circle_breach_distance
Definition: AC_Fence.h:160
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
#define AC_FENCE_ALT_MAX_BACKUP_DISTANCE
Definition: AC_Fence.h:25
void manual_recovery_start()
Definition: AC_Fence.cpp:438
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
get altitude in desired frame
Definition: Location.cpp:114
bool sys_status_enabled() const
Definition: AC_Fence.cpp:566
#define f(i)
bool check_fence_circle()
check_fence_circle - true if circle fence has been newly breached
Definition: AC_Fence.cpp:271
uint32_t _manual_recovery_start_ms
Definition: AC_Fence.h:172
uint32_t millis()
Definition: system.cpp:157
bool _boundary_create_attempted
Definition: AC_Fence.h:178
float _alt_max_breach_distance
Definition: AC_Fence.h:159
Vector2f * get_polygon_points(uint16_t &num_points) const
returns pointer to array of polygon points and num_points is filled in with the total number ...
Definition: AC_Fence.cpp:450
uint16_t _breach_count
Definition: AC_Fence.h:170
uint8_t _boundary_num_points
Definition: AC_Fence.h:177
bool check_latlng(float lat, float lng)
Definition: location.cpp:231
float _circle_radius_backup
Definition: AC_Fence.h:156
bool get_relative_position_NE_origin(Vector2f &posNE) const override
float _alt_max_backup
Definition: AC_Fence.h:155
bool save_point_to_eeprom(uint16_t i, const Vector2l &point)
uint8_t get_enabled_fences() const
get_enabled_fences - returns bitmask of enabled fences
Definition: AC_Fence.cpp:91
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
Definition: AP_Param.h:96
float length(void) const
Definition: vector2.cpp:24
Vector2f location
Definition: location.cpp:16
T x
Definition: vector2.h:37
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
Definition: Location.cpp:192
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
AC_Fence(const AP_AHRS_NavEKF &ahrs)
Default constructor.
Definition: AC_Fence.cpp:76
AP_Float _alt_max
Definition: AC_Fence.h:148
float _curr_alt
Definition: AC_Fence.h:164
AP_Int8 _total
Definition: AC_Fence.h:152
#define AP_PARAM_FRAME_COPTER
Definition: AP_Param.h:77
AP_Float _circle_radius
Definition: AC_Fence.h:150
float value
#define AC_FENCE_TYPE_POLYGON
Definition: AC_Fence.h:15
AP_Int8 _enabled_fences
Definition: AC_Fence.h:146
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void * create_point_array(uint8_t element_size)
void enable(bool value)
enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value ...
Definition: AC_Fence.cpp:82
#define AC_FENCE_ACTION_RTL_AND_LAND
Definition: AC_Fence.h:19
bool _boundary_valid
Definition: AC_Fence.h:180
bool boundary_breached(const Vector2< T > &location, uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
#define AP_PARAM_FRAME_SUB
Definition: AP_Param.h:80
bool get_relative_position_NE_home(Vector2f &posNE) const override
#define AP_PARAM_FRAME_TRICOPTER
Definition: AP_Param.h:81
#define AC_FENCE_TYPE_ALT_MAX
Definition: AC_Fence.h:13
#define AP_PARAM_FRAME_HELI
Definition: AP_Param.h:82
#define AP_GROUPEND
Definition: AP_Param.h:121
Vector2l point
Definition: polygon.cpp:34
uint32_t _breach_time
Definition: AC_Fence.h:169
bool load_polygon_from_eeprom(bool force_reload=false)
load polygon points stored in eeprom into boundary array and perform validation. returns true if load...
Definition: AC_Fence.cpp:512
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214