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.h
Views: 1798
1
#pragma once
2
3
#include "AC_Fence_config.h"
4
5
#if AP_FENCE_ENABLED
6
7
#include <inttypes.h>
8
#include <AP_Common/AP_Common.h>
9
#include <AP_Common/ExpandingString.h>
10
#include <AP_Param/AP_Param.h>
11
#include <AP_Math/AP_Math.h>
12
#include <AC_Fence/AC_PolyFence_loader.h>
13
14
// bit masks for enabled fence types. Used for TYPE parameter
15
#define AC_FENCE_TYPE_ALT_MAX 1 // high alt fence which usually initiates an RTL
16
#define AC_FENCE_TYPE_CIRCLE 2 // circular horizontal fence (usually initiates an RTL)
17
#define AC_FENCE_TYPE_POLYGON 4 // polygon horizontal fence
18
#define AC_FENCE_TYPE_ALT_MIN 8 // low alt fence which usually initiates an RTL
19
#define AC_FENCE_ARMING_FENCES (AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)
20
#define AC_FENCE_ALL_FENCES (AC_FENCE_ARMING_FENCES | AC_FENCE_TYPE_ALT_MIN)
21
22
// valid actions should a fence be breached
23
#define AC_FENCE_ACTION_REPORT_ONLY 0 // report to GCS that boundary has been breached but take no further action
24
#define AC_FENCE_ACTION_RTL_AND_LAND 1 // return to launch and, if that fails, land
25
#define AC_FENCE_ACTION_ALWAYS_LAND 2 // always land
26
#define AC_FENCE_ACTION_SMART_RTL 3 // smartRTL, if that fails, RTL, it that still fails, land
27
#define AC_FENCE_ACTION_BRAKE 4 // brake, if that fails, land
28
#define AC_FENCE_ACTION_SMART_RTL_OR_LAND 5 // SmartRTL, if that fails, Land
29
#define AC_FENCE_ACTION_GUIDED 6 // guided mode, with target waypoint as fence return point
30
#define AC_FENCE_ACTION_GUIDED_THROTTLE_PASS 7 // guided mode, but pilot retains manual throttle control
31
32
// give up distance
33
#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
34
35
class AC_Fence
36
{
37
public:
38
friend class AC_PolyFence_loader;
39
40
enum class AutoEnable : uint8_t
41
{
42
ALWAYS_DISABLED = 0,
43
ENABLE_ON_AUTO_TAKEOFF = 1, // enable on auto takeoff
44
ENABLE_DISABLE_FLOOR_ONLY = 2, // enable on takeoff but disable floor on landing
45
ONLY_WHEN_ARMED = 3 // enable on arming
46
};
47
48
enum class MavlinkFenceActions : uint16_t
49
{
50
DISABLE_FENCE = 0,
51
ENABLE_FENCE = 1,
52
DISABLE_ALT_MIN_FENCE = 2
53
};
54
55
AC_Fence();
56
57
/* Do not allow copies */
58
CLASS_NO_COPY(AC_Fence);
59
60
void init() {
61
_poly_loader.init();
62
}
63
64
// get singleton instance
65
static AC_Fence *get_singleton() { return _singleton; }
66
67
/// enable - allows fence to be enabled/disabled.
68
/// returns a bitmask of fences that were changed
69
uint8_t enable(bool value, uint8_t fence_types, bool update_auto_mask = true);
70
71
/// enable_configured - allows configured fences to be enabled/disabled.
72
/// returns a bitmask of fences that were changed
73
uint8_t enable_configured(bool value) { return enable(value, _configured_fences, true); }
74
75
/// auto_enabled - automaticaly enable/disable fence depending of flight status
76
AutoEnable auto_enabled() const { return static_cast<AutoEnable>(_auto_enabled.get()); }
77
78
/// enable_floor - allows fence floor to be enabled/disabled. Note this does not update the eeprom saved value
79
void enable_floor();
80
81
/// disable_floor - allows fence floor to be enabled/disabled. Note this does not update the eeprom saved value
82
void disable_floor();
83
84
/// auto_enable_fence_on_takeoff - auto enables the fence. Called after takeoff conditions met
85
void auto_enable_fence_after_takeoff();
86
87
/// auto_enable_fences_on_arming - auto enables all applicable fences on arming
88
void auto_enable_fence_on_arming();
89
90
/// auto_disable_fences_on_disarming - auto disables all applicable fences on disarming
91
void auto_disable_fence_on_disarming();
92
93
uint8_t get_auto_disable_fences(void) const;
94
95
/// auto_enable_fence_floor - auto enables fence floor once desired altitude has been reached.
96
bool auto_enable_fence_floor();
97
98
/// enabled - returns whether fencing is enabled or not
99
bool enabled() const { return _enabled_fences; }
100
101
/// present - returns true if any of the provided types is present
102
uint8_t present() const;
103
104
/// get_enabled_fences - returns bitmask of enabled fences
105
uint8_t get_enabled_fences() const;
106
107
// should be called @10Hz to handle loading from eeprom
108
void update();
109
110
/// pre_arm_check - returns true if all pre-takeoff checks have completed successfully
111
bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;
112
113
///
114
/// methods to check we are within the boundaries and recover
115
///
116
117
/// check - returns the fence type that has been breached (if any)
118
/// disabled_fences can be used to disable fences for certain conditions (e.g. landing)
119
uint8_t check(bool disable_auto_fence = false);
120
121
// returns true if the destination is within fence (used to reject waypoints outside the fence)
122
bool check_destination_within_fence(const class Location& loc);
123
124
/// get_breaches - returns bit mask of the fence types that have been breached
125
uint8_t get_breaches() const { return _breached_fences; }
126
127
/// get_breach_time - returns time the fence was breached
128
uint32_t get_breach_time() const { return _breach_time; }
129
130
/// get_breach_count - returns number of times we have breached the fence
131
uint16_t get_breach_count() const { return _breach_count; }
132
133
/// get_breach_distance - returns maximum distance in meters outside
134
/// of the given fences. fence_type is a bitmask here.
135
float get_breach_distance(uint8_t fence_type) const;
136
137
/// get_action - getter for user requested action on limit breach
138
uint8_t get_action() const { return _action.get(); }
139
140
/// get_safe_alt - returns maximum safe altitude (i.e. alt_max - margin)
141
float get_safe_alt_max() const { return _alt_max - _margin; }
142
143
/// get_safe_alt_min - returns the minimum safe altitude (i.e. alt_min + margin)
144
float get_safe_alt_min() const { return _alt_min + _margin; }
145
146
/// get_radius - returns the fence radius in meters
147
float get_radius() const { return _circle_radius.get(); }
148
149
/// get_margin - returns the fence margin in meters
150
float get_margin() const { return _margin.get(); }
151
152
/// get_return_rally - returns whether returning to fence return point or rally point
153
uint8_t get_return_rally() const { return _ret_rally; }
154
155
/// get_return_rally - returns whether returning to fence return point or rally point
156
float get_return_altitude() const { return _ret_altitude; }
157
158
/// get a user-friendly list of fences
159
static void get_fence_names(uint8_t fences, ExpandingString& msg);
160
161
// print a message about the fences to the GCS
162
void print_fence_message(const char* msg, uint8_t fences) const;
163
164
/// manual_recovery_start - caller indicates that pilot is re-taking manual control so fence should be disabled for 10 seconds
165
/// should be called whenever the pilot changes the flight mode
166
/// has no effect if no breaches have occurred
167
void manual_recovery_start();
168
169
// methods for mavlink SYS_STATUS message (send_sys_status)
170
bool sys_status_present() const;
171
bool sys_status_enabled() const;
172
bool sys_status_failed() const;
173
174
AC_PolyFence_loader &polyfence();
175
const AC_PolyFence_loader &polyfence() const;
176
177
enum class OPTIONS {
178
DISABLE_MODE_CHANGE = 1U << 0,
179
INCLUSION_UNION = 1U << 1,
180
};
181
static bool option_enabled(OPTIONS opt, const AP_Int16 &options) {
182
return (options.get() & int16_t(opt)) != 0;
183
}
184
bool option_enabled(OPTIONS opt) const {
185
return option_enabled(opt, _options);
186
}
187
188
static const struct AP_Param::GroupInfo var_info[];
189
190
#if AP_SDCARD_STORAGE_ENABLED
191
bool failed_sdcard_storage(void) const {
192
return _poly_loader.failed_sdcard_storage();
193
}
194
#endif
195
196
private:
197
static AC_Fence *_singleton;
198
199
/// check_fence_alt_max - true if max alt fence has been newly breached
200
bool check_fence_alt_max();
201
202
/// check_fence_alt_min - true if min alt fence has been newly breached
203
bool check_fence_alt_min();
204
205
/// check_fence_polygon - true if polygon fence has been newly breached
206
bool check_fence_polygon();
207
208
/// check_fence_circle - true if circle fence has been newly breached
209
bool check_fence_circle();
210
211
/// record_breach - update breach bitmask, time and count
212
void record_breach(uint8_t fence_type);
213
214
/// clear_breach - update breach bitmask, time and count
215
void clear_breach(uint8_t fence_type);
216
217
// additional checks for the different fence types:
218
bool pre_arm_check_polygon(char *failure_msg, const uint8_t failure_msg_len) const;
219
bool pre_arm_check_circle(char *failure_msg, const uint8_t failure_msg_len) const;
220
bool pre_arm_check_alt(char *failure_msg, const uint8_t failure_msg_len) const;
221
// fence floor is enabled
222
bool floor_enabled() const { return _enabled_fences & AC_FENCE_TYPE_ALT_MIN; }
223
224
// parameters
225
uint8_t _enabled_fences; // fences that are currently enabled/disabled
226
bool _last_enabled; // value of enabled last time we checked
227
AP_Int8 _enabled; // overall feature control
228
AP_Int8 _auto_enabled; // top level flag for auto enabling fence
229
uint8_t _last_auto_enabled; // value of auto_enabled last time we checked
230
AP_Int8 _configured_fences; // bit mask holding which fences are enabled
231
AP_Int8 _action; // recovery action specified by user
232
AP_Float _alt_max; // altitude upper limit in meters
233
AP_Float _alt_min; // altitude lower limit in meters
234
AP_Float _circle_radius; // circle fence radius in meters
235
AP_Float _margin; // distance in meters that autopilot's should maintain from the fence to avoid a breach
236
AP_Int8 _total; // number of polygon points saved in eeprom
237
AP_Int8 _ret_rally; // return to fence return point or rally point/home
238
AP_Int16 _ret_altitude; // return to this altitude
239
AP_Int16 _options; // options bitmask, see OPTIONS enum
240
241
// backup fences
242
float _alt_max_backup; // backup altitude upper limit in meters used to refire the breach if the vehicle continues to move further away
243
float _alt_min_backup; // backup altitude lower limit in meters used to refire the breach if the vehicle continues to move further away
244
float _circle_radius_backup; // backup circle fence radius in meters used to refire the breach if the vehicle continues to move further away
245
246
// breach distances
247
float _alt_max_breach_distance; // distance above the altitude max
248
float _alt_min_breach_distance; // distance below the altitude min
249
float _circle_breach_distance; // distance beyond the circular fence
250
251
// other internal variables
252
float _home_distance; // distance from home in meters (provided by main code)
253
254
// breach information
255
uint8_t _breached_fences; // bitmask holding the fence type that was breached (i.e. AC_FENCE_TYPE_ALT_MIN, AC_FENCE_TYPE_CIRCLE)
256
uint32_t _breach_time; // time of last breach in milliseconds
257
uint16_t _breach_count; // number of times we have breached the fence
258
uint32_t _last_breach_notify_sent_ms; // last time we sent a message about newly-breaching the fences
259
260
uint32_t _manual_recovery_start_ms; // system time in milliseconds that pilot re-took manual control
261
262
enum class MinAltState
263
{
264
DEFAULT = 0,
265
MANUALLY_ENABLED,
266
MANUALLY_DISABLED
267
} _min_alt_state;
268
269
270
AC_PolyFence_loader _poly_loader{_total, _options}; // polygon fence
271
};
272
273
namespace AP {
274
AC_Fence *fence();
275
};
276
277
#endif // AP_FENCE_ENABLED
278
279