APM:Libraries
AC_Fence.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <inttypes.h>
4 #include <AP_Common/AP_Common.h>
5 #include <AP_Param/AP_Param.h>
6 #include <AP_Math/AP_Math.h>
8 #include <AP_AHRS/AP_AHRS.h>
10 #include <AP_Common/Location.h>
11 
12 // bit masks for enabled fence types. Used for TYPE parameter
13 #define AC_FENCE_TYPE_ALT_MAX 1 // high alt fence which usually initiates an RTL
14 #define AC_FENCE_TYPE_CIRCLE 2 // circular horizontal fence (usually initiates an RTL)
15 #define AC_FENCE_TYPE_POLYGON 4 // polygon horizontal fence
16 
17 // valid actions should a fence be breached
18 #define AC_FENCE_ACTION_REPORT_ONLY 0 // report to GCS that boundary has been breached but take no further action
19 #define AC_FENCE_ACTION_RTL_AND_LAND 1 // return to launch and, if that fails, land
20 
21 // default boundaries
22 #define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m
23 #define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters
24 #define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m
25 #define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up
26 #define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further out
27 #define AC_FENCE_MARGIN_DEFAULT 2.0f // default distance in meters that autopilot's should maintain from the fence to avoid a breach
28 
29 // give up distance
30 #define AC_FENCE_GIVE_UP_DISTANCE 100.0f // distance outside the fence at which we should give up and just land. Note: this is not used by library directly but is intended to be used by the main code
31 #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
32 
33 class AC_Fence
34 {
35 public:
37 
38  /* Do not allow copies */
39  AC_Fence(const AC_Fence &other) = delete;
40  AC_Fence &operator=(const AC_Fence&) = delete;
41 
43  void enable(bool value);
44 
46  bool enabled() const { return _enabled; }
47 
49  uint8_t get_enabled_fences() const;
50 
52  bool pre_arm_check(const char* &fail_msg) const;
53 
57 
59  uint8_t check();
60 
61  // returns true if the destination is within fence (used to reject waypoints outside the fence)
63 
65  uint8_t get_breaches() const { return _breached_fences; }
66 
68  uint32_t get_breach_time() const { return _breach_time; }
69 
71  uint16_t get_breach_count() const { return _breach_count; }
72 
74  float get_breach_distance(uint8_t fence_type) const;
75 
77  uint8_t get_action() const { return _action.get(); }
78 
80  float get_safe_alt_max() const { return _alt_max - _margin; }
81 
83  float get_safe_alt_min() const { return _alt_min + _margin; }
84 
86  float get_radius() const { return _circle_radius.get(); }
87 
89  float get_margin() const { return _margin.get(); }
90 
94  void manual_recovery_start();
95 
99 
101  Vector2f* get_polygon_points(uint16_t& num_points) const;
102 
104  bool boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points) const;
105 
107  void handle_msg(GCS_MAVLINK &link, mavlink_message_t* msg);
108 
109  static const struct AP_Param::GroupInfo var_info[];
110 
111  // methods for mavlink SYS_STATUS message (send_extended_status1)
112  bool sys_status_present() const;
113  bool sys_status_enabled() const;
114  bool sys_status_failed() const;
115 
116 private:
117 
119  bool check_fence_alt_max();
120 
122  bool check_fence_polygon();
123 
125  bool check_fence_circle();
126 
128  void record_breach(uint8_t fence_type);
129 
131  void clear_breach(uint8_t fence_type);
132 
133  // additional checks for the different fence types:
134  bool pre_arm_check_polygon(const char* &fail_msg) const;
135  bool pre_arm_check_circle(const char* &fail_msg) const;
136  bool pre_arm_check_alt(const char* &fail_msg) const;
137 
139  bool load_polygon_from_eeprom(bool force_reload = false);
140 
141  // pointers to other objects we depend upon
143 
144  // parameters
145  AP_Int8 _enabled; // top level enable/disable control
146  AP_Int8 _enabled_fences; // bit mask holding which fences are enabled
147  AP_Int8 _action; // recovery action specified by user
148  AP_Float _alt_max; // altitude upper limit in meters
149  AP_Float _alt_min; // altitude lower limit in meters
150  AP_Float _circle_radius; // circle fence radius in meters
151  AP_Float _margin; // distance in meters that autopilot's should maintain from the fence to avoid a breach
152  AP_Int8 _total; // number of polygon points saved in eeprom
153 
154  // backup fences
155  float _alt_max_backup; // backup altitude upper limit in meters used to refire the breach if the vehicle continues to move further away
156  float _circle_radius_backup; // backup circle fence radius in meters used to refire the breach if the vehicle continues to move further away
157 
158  // breach distances
159  float _alt_max_breach_distance; // distance above the altitude max
160  float _circle_breach_distance; // distance beyond the circular fence
161 
162  // other internal variables
163  float _home_distance; // distance from home in meters (provided by main code)
164  float _curr_alt;
165 
166 
167  // breach information
168  uint8_t _breached_fences; // bitmask holding the fence type that was breached (i.e. AC_FENCE_TYPE_ALT_MIN, AC_FENCE_TYPE_CIRCLE)
169  uint32_t _breach_time; // time of last breach in milliseconds
170  uint16_t _breach_count; // number of times we have breached the fence
171 
172  uint32_t _manual_recovery_start_ms; // system time in milliseconds that pilot re-took manual control
173 
174  // polygon fence variables
175  AC_PolyFence_loader _poly_loader; // helper for loading/saving polygon points
176  Vector2f *_boundary = nullptr; // array of boundary points. Note: point 0 is the return point
177  uint8_t _boundary_num_points = 0; // number of points in the boundary array (should equal _total parameter after load has completed)
178  bool _boundary_create_attempted = false; // true if we have attempted to create the boundary array
179  bool _boundary_loaded = false; // true if boundary array has been loaded from eeprom
180  bool _boundary_valid = false; // true if boundary forms a closed polygon
181 };
bool check_fence_polygon()
check_fence_polygon - true if polygon fence has been newly breached
Definition: AC_Fence.cpp:225
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
AC_Fence & operator=(const AC_Fence &)=delete
bool check_destination_within_fence(const Location_Class &loc)
Definition: AC_Fence.cpp:356
AP_Float _margin
Definition: AC_Fence.h:151
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
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
AP_Float _alt_min
Definition: AC_Fence.h:149
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 pre_arm_check_polygon(const char *&fail_msg) const
Definition: AC_Fence.cpp:100
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
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
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
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
uint16_t get_breach_count() const
get_breach_count - returns number of times we have breached the fence
Definition: AC_Fence.h:71
A system for managing and storing variables that are of general interest to the system.
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
void manual_recovery_start()
Definition: AC_Fence.cpp:438
bool sys_status_enabled() const
Definition: AC_Fence.cpp:566
uint8_t get_action() const
get_action - getter for user requested action on limit breach
Definition: AC_Fence.h:77
bool check_fence_circle()
check_fence_circle - true if circle fence has been newly breached
Definition: AC_Fence.cpp:271
float get_radius() const
get_radius - returns the fence radius in meters
Definition: AC_Fence.h:86
uint32_t _manual_recovery_start_ms
Definition: AC_Fence.h:172
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
float _circle_radius_backup
Definition: AC_Fence.h:156
float _alt_max_backup
Definition: AC_Fence.h:155
uint8_t get_enabled_fences() const
get_enabled_fences - returns bitmask of enabled fences
Definition: AC_Fence.cpp:91
float get_margin() const
get_margin - returns the fence margin in meters
Definition: AC_Fence.h:89
float get_safe_alt_max() const
get_safe_alt - returns maximum safe altitude (i.e. alt_max - margin)
Definition: AC_Fence.h:80
Common definitions and utility routines for the ArduPilot libraries.
Vector2f location
Definition: location.cpp:16
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
AP_Float _circle_radius
Definition: AC_Fence.h:150
float get_safe_alt_min() const
get_safe_alt_min - returns the minimum safe altitude (i.e. alt_min - margin)
Definition: AC_Fence.h:83
float value
AP_Int8 _enabled_fences
Definition: AC_Fence.h:146
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
bool _boundary_valid
Definition: AC_Fence.h:180
uint32_t get_breach_time() const
get_breach_time - returns time the fence was breached
Definition: AC_Fence.h:68
bool enabled() const
enabled - returns true if fence is enabled
Definition: AC_Fence.h:46
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