Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_Fence/AC_PolyFence_loader.h
9700 views
1
#pragma once
2
3
#include "AC_Fence_config.h"
4
#include <AP_Math/AP_Math.h>
5
6
// CIRCLE_INCLUSION_INT stores the radius an a 32-bit integer in
7
// metres. This was a bug, and CIRCLE_INCLUSION was created to store
8
// as a 32-bit float instead. We save as _INT in the case that the
9
// radius looks like an integer as a backwards-compatibility measure.
10
// For 4.2 we might consider only loading _INT and always saving as
11
// float, and in 4.3 considering _INT invalid
12
13
// CODE_REMOVAL
14
// ArduPilot 4.7 no longer stores circle radiuses that look like
15
// integers as integer item types, so any time a fence is saved the
16
// use of the deprecated types is fixed.
17
// ArduPilot 4.8 warns if it loads an integer item, warns user to re-upload the fence
18
// ArduPilot 4.9 warns if it loads an integer item, warns user to re-upload the fence
19
// ArduPilot 4.10 removes support for them
20
21
enum class AC_PolyFenceType : uint8_t {
22
END_OF_STORAGE = 99,
23
POLYGON_INCLUSION = 98,
24
POLYGON_EXCLUSION = 97,
25
#if AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED
26
CIRCLE_EXCLUSION_INT = 96,
27
#endif // AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED
28
RETURN_POINT = 95,
29
#if AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED
30
CIRCLE_INCLUSION_INT = 94,
31
#endif // #if AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED
32
CIRCLE_EXCLUSION = 93,
33
CIRCLE_INCLUSION = 92,
34
};
35
36
// a FenceItem is just a means of passing data about an item into
37
// and out of the polyfence loader. It uses a AC_PolyFenceType to
38
// indicate the item type, assuming each fence type is made up of
39
// only one sort of item.
40
// TODO: make this a union (or use subclasses) to save memory
41
class AC_PolyFenceItem {
42
public:
43
AC_PolyFenceType type;
44
Vector2l loc;
45
uint8_t vertex_count;
46
float radius;
47
};
48
49
#if AP_FENCE_ENABLED
50
51
#include <AP_Common/AP_Common.h>
52
#include <AP_Common/Location.h>
53
#include <GCS_MAVLink/GCS_MAVLink.h>
54
55
class AC_PolyFence_loader
56
{
57
58
public:
59
60
AC_PolyFence_loader(AP_Int8 &total, const AP_Int16 &options) :
61
_total(total),
62
_options(options) {}
63
64
/* Do not allow copies */
65
CLASS_NO_COPY(AC_PolyFence_loader);
66
67
void init();
68
69
// methods primarily for MissionItemProtocol_Fence to use:
70
// return the total number of points stored
71
uint16_t num_stored_items() const { return _eeprom_item_count; }
72
bool get_item(const uint16_t seq, AC_PolyFenceItem &item) WARN_IF_UNUSED;
73
74
///
75
/// exclusion polygons
76
///
77
/// returns number of polygon exclusion zones defined
78
uint8_t get_exclusion_polygon_count() const {
79
return _num_loaded_exclusion_boundaries;
80
}
81
82
/// returns pointer to array of exclusion polygon points and num_points is filled in with the number of points in the polygon
83
/// points are offsets in cm from EKF origin in NE frame
84
Vector2f* get_exclusion_polygon(uint16_t index, uint16_t &num_points) const;
85
86
/// return system time of last update to the exclusion polygon points
87
uint32_t get_exclusion_polygon_update_ms() const {
88
return _load_time_ms;
89
}
90
91
///
92
/// inclusion polygons
93
///
94
/// returns number of polygon inclusion zones defined
95
uint8_t get_inclusion_polygon_count() const {
96
return _num_loaded_inclusion_boundaries;
97
}
98
99
/// returns pointer to array of inclusion polygon points and num_points is filled in with the number of points in the polygon
100
/// points are offsets in cm from EKF origin in NE frame
101
Vector2f* get_inclusion_polygon(uint16_t index, uint16_t &num_points) const;
102
103
/// return system time of last update to the inclusion polygon points
104
uint32_t get_inclusion_polygon_update_ms() const {
105
return _load_time_ms;
106
}
107
108
///
109
/// exclusion circles
110
///
111
/// returns number of exclusion circles defined
112
uint8_t get_exclusion_circle_count() const {
113
return _num_loaded_circle_exclusion_boundaries;
114
}
115
116
/// returns the specified exclusion circle
117
/// center is offsets in cm from EKF origin in NE frame, radius is in meters
118
bool get_exclusion_circle(uint8_t index, Vector2f &center_pos_cm, float &radius) const;
119
120
/// return system time of last update to the exclusion circles
121
uint32_t get_exclusion_circle_update_ms() const {
122
return _load_time_ms;
123
}
124
125
///
126
/// inclusion circles
127
///
128
/// returns number of inclusion circles defined
129
uint8_t get_inclusion_circle_count() const {
130
return _num_loaded_circle_inclusion_boundaries;
131
}
132
133
/// returns the specified inclusion circle
134
/// center is offsets in cm from EKF origin in NE frame, radius is in meters
135
bool get_inclusion_circle(uint8_t index, Vector2f &center_pos_cm, float &radius) const;
136
137
// false if margin < fence radius
138
bool check_inclusion_circle_margin(float margin) const;
139
140
///
141
/// mavlink
142
///
143
/// handler for polygon fence messages with GCS
144
void handle_msg(class GCS_MAVLINK &link, const mavlink_message_t& msg);
145
146
// breached() - returns true if the vehicle has breached any fence
147
bool breached() const WARN_IF_UNUSED;
148
// returns true if location is outside the boundary also returns the minimum distance to the fence
149
bool breached(const Location& loc, float& distance_outside_fence, Vector2f& fence_direction) const WARN_IF_UNUSED;
150
// breached(Location&) - returns true if location is outside the boundary
151
bool breached(const Location& loc) const WARN_IF_UNUSED
152
{
153
float distance_outside_fence;
154
Vector2f breach_direction;
155
return breached(loc, distance_outside_fence, breach_direction);
156
}
157
158
// returns true if a polygonal include fence could be returned
159
bool inclusion_boundary_available() const WARN_IF_UNUSED {
160
return _num_loaded_inclusion_boundaries != 0;
161
}
162
163
// loaded - returns true if the fences have been loaded from
164
// storage and are available for use
165
bool loaded() const WARN_IF_UNUSED {
166
return _load_time_ms != 0;
167
};
168
169
// maximum number of fence points we can store in eeprom
170
uint16_t max_items() const;
171
172
// write_fence - validate and write count new_items to permanent storage
173
bool write_fence(const AC_PolyFenceItem *new_items, uint16_t count) WARN_IF_UNUSED;
174
175
/*
176
* Loaded Fence functionality
177
*
178
* methods and members to do with fences stored in memory. The
179
* locations are translated into offset-from-origin-in-metres
180
*/
181
182
// load polygon points stored in eeprom into
183
// _loaded_offsets_from_origin and perform validation. returns
184
// true if load successfully completed
185
bool load_from_storage() WARN_IF_UNUSED;
186
187
// allow threads to lock against AHRS update
188
HAL_Semaphore &get_loaded_fence_semaphore(void) {
189
return _loaded_fence_sem;
190
}
191
192
// call @10Hz to check for fence load being valid
193
void update();
194
195
// get_return_point - returns latitude/longitude of return point.
196
// This works with storage - the returned vector is absolute
197
// lat/lon.
198
bool get_return_point(Vector2l &ret) WARN_IF_UNUSED;
199
200
// return total number of fences - polygons and circles
201
uint16_t total_fence_count() const {
202
return (get_exclusion_polygon_count() +
203
get_inclusion_polygon_count() +
204
get_exclusion_circle_count() +
205
get_inclusion_circle_count());
206
}
207
208
209
#if AP_SDCARD_STORAGE_ENABLED
210
bool failed_sdcard_storage(void) const {
211
return _failed_sdcard_storage;
212
}
213
#endif
214
215
private:
216
// multi-thread access support
217
HAL_Semaphore _loaded_fence_sem;
218
219
/*
220
* Fence storage Index related functions
221
*/
222
// FenceIndex - a class used to store information about a fence in
223
// fence storage.
224
class FenceIndex {
225
public:
226
AC_PolyFenceType type;
227
uint16_t count;
228
uint16_t storage_offset;
229
};
230
// index_fence_count - returns the number of fences of type
231
// currently in the index
232
uint16_t index_fence_count(const AC_PolyFenceType type);
233
234
// void_index - free resources for the index, forcing a reindex
235
// (typically via check_indexed)
236
void void_index() {
237
delete[] _index;
238
_index = nullptr;
239
_index_attempted = false;
240
_indexed = false;
241
}
242
243
// check_indexed - read eeprom and create index if the index does
244
// not already exist
245
bool check_indexed() WARN_IF_UNUSED;
246
247
// find_first_fence - return first fence in index of specific type
248
FenceIndex *find_first_fence(const AC_PolyFenceType type) const;
249
250
// find_index_for_seq - returns true if seq is contained within a
251
// fence. If it is, entry will be the relevant FenceIndex. i
252
// will be the offset within _loaded_offsets_from_origin where the
253
// first point in the fence is found
254
bool find_index_for_seq(const uint16_t seq, const FenceIndex *&entry, uint16_t &i) const WARN_IF_UNUSED;
255
// find_storage_offset_for_seq - uses the index to return an
256
// offset into storage for an item
257
bool find_storage_offset_for_seq(const uint16_t seq, uint16_t &offset, AC_PolyFenceType &type, uint16_t &vertex_count_offset) const WARN_IF_UNUSED;
258
259
uint16_t sum_of_polygon_point_counts_and_returnpoint();
260
261
/*
262
* storage-related methods - dealing with fence_storage
263
*/
264
265
// new_fence_storage_magic - magic number indicating fence storage
266
// has been formatted for use by polygon fence storage code.
267
// FIXME: ensure this is out-of-band for old lat/lon point storage
268
static const uint8_t new_fence_storage_magic = 235;
269
270
// validate_fence - returns true if new_items look completely valid
271
bool validate_fence(const AC_PolyFenceItem *new_items, uint16_t count) const WARN_IF_UNUSED;
272
273
// _eos_offset - stores the offset in storage of the
274
// end-of-storage marker. Used by low-level manipulation code to
275
// extend storage
276
uint16_t _eos_offset;
277
278
// formatted - returns true if the fence storage space seems to be
279
// formatted for new-style fence storage
280
bool formatted() const WARN_IF_UNUSED;
281
// format - format the storage space for use by
282
// the new polyfence code
283
bool format() WARN_IF_UNUSED;
284
285
286
/*
287
* Loaded Fence functionality
288
*
289
* methods and members to do with fences stored in memory. The
290
* locations are translated into offset-from-origin-in-metres
291
*/
292
293
// remove resources dedicated to the transformed fences - for
294
// example, in _loaded_offsets_from_origin
295
void unload();
296
297
// pointer into _loaded_offsets_from_origin where the return point
298
// can be found:
299
Vector2f *_loaded_return_point;
300
301
// pointer into _loaded_points_lla where the return point
302
// can be found:
303
Vector2l *_loaded_return_point_lla;
304
305
class InclusionBoundary {
306
public:
307
Vector2f *points; // pointer into the _loaded_offsets_from_origin array
308
Vector2l *points_lla; // pointer into the _loaded_points_lla array
309
uint8_t count; // count of points in the boundary
310
};
311
InclusionBoundary *_loaded_inclusion_boundary;
312
313
uint8_t _num_loaded_inclusion_boundaries;
314
315
class ExclusionBoundary {
316
public:
317
Vector2f *points; // pointer into the _loaded_offsets_from_origin array
318
Vector2l *points_lla; // pointer into the _loaded_points_lla_lla array
319
uint8_t count; // count of points in the boundary
320
};
321
ExclusionBoundary *_loaded_exclusion_boundary;
322
323
uint8_t _num_loaded_exclusion_boundaries;
324
325
// _loaded_offsets_from_origin - stores x/y offset-from-origin
326
// coordinate pairs. Various items store their locations in this
327
// allocation - the polygon boundaries and the return point, for
328
// example.
329
Vector2f *_loaded_offsets_from_origin;
330
Vector2l *_loaded_points_lla;
331
Location loaded_origin; // origin at the time the boundary was loaded
332
333
class ExclusionCircle {
334
public:
335
Vector2f pos_cm; // vector offset from home in cm
336
Vector2l point; // lat/lng of zone
337
float radius;
338
};
339
ExclusionCircle *_loaded_circle_exclusion_boundary;
340
341
uint8_t _num_loaded_circle_exclusion_boundaries;
342
343
class InclusionCircle {
344
public:
345
Vector2f pos_cm; // vector offset from home in cm
346
Vector2l point; // lat/lng of zone
347
float radius;
348
};
349
InclusionCircle *_loaded_circle_inclusion_boundary;
350
351
uint8_t _num_loaded_circle_inclusion_boundaries;
352
353
// _load_attempted - true if we have attempted to load the fences
354
// from storage into _loaded_circle_exclusion_boundary,
355
// _loaded_offsets_from_origin etc etc
356
bool _load_attempted;
357
358
// _load_time_ms - from millis(), system time when fence load last
359
// succeeded. Will be zero if fences are not loaded
360
uint32_t _load_time_ms;
361
362
// scale_latlon_from_origin - given a latitude/longitude
363
// transforms the point to an offset-from-origin and deposits
364
// the result into pos_cm.
365
bool scale_latlon_from_origin(const Location &origin,
366
const Vector2l &point,
367
Vector2f &pos_cm) const WARN_IF_UNUSED;
368
369
// read_polygon_from_storage - reads vertex_count
370
// latitude/longitude points from offset in permanent storage,
371
// transforms them into an offset-from-origin and deposits the
372
// results into next_storage_point.
373
bool read_polygon_from_storage(const Location &origin,
374
uint16_t &read_offset,
375
const uint8_t vertex_count,
376
Vector2f *&next_storage_point,
377
Vector2l *&next_storage_point_lla) WARN_IF_UNUSED;
378
379
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
380
/*
381
* FENCE_POINT protocol compatibility
382
*/
383
void handle_msg_fetch_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg);
384
void handle_msg_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg);
385
// contains_compatible_fence - returns true if the permanent fence
386
// storage contains fences that are compatible with the old
387
// FENCE_POINT protocol.
388
bool contains_compatible_fence() const WARN_IF_UNUSED;
389
390
// get_or_create_include_fence - returns a point to an include
391
// fence to be used for the FENCE_POINT-supplied polygon. May
392
// format the storage appropriately.
393
FenceIndex *get_or_create_include_fence();
394
// get_or_create_include_fence - returns a point to a return point
395
// to be used for the FENCE_POINT-supplied return point. May
396
// format the storage appropriately.
397
FenceIndex *get_or_create_return_point();
398
#endif
399
400
// primitives to write parts of fencepoints out:
401
bool write_type_to_storage(uint16_t &offset, AC_PolyFenceType type) WARN_IF_UNUSED;
402
bool write_latlon_to_storage(uint16_t &offset, const Vector2l &latlon) WARN_IF_UNUSED;
403
bool read_latlon_from_storage(uint16_t &read_offset, Vector2l &latlon) const WARN_IF_UNUSED;
404
405
// methods to write specific types of fencepoint out:
406
bool write_eos_to_storage(uint16_t &offset);
407
408
// _total - reference to FENCE_TOTAL parameter. This is used
409
// solely for compatibility with the FENCE_POINT protocol
410
AP_Int8 &_total;
411
const AP_Int16 &_options;
412
uint8_t _old_total;
413
414
415
// scan_eeprom - a method that traverses the fence storage area,
416
// calling the supplied callback for each fence found. If the
417
// scan fails (for example, the storage is corrupt), then this
418
// method will return false.
419
FUNCTOR_TYPEDEF(scan_fn_t, void, const AC_PolyFenceType, uint16_t);
420
bool scan_eeprom(scan_fn_t scan_fn) WARN_IF_UNUSED;
421
// scan_eeprom_count_fences - a static function designed to be
422
// massed to scan_eeprom which counts the number of fences and
423
// fence items present. The results of this counting appear in _eeprom_fence_count and _eeprom_item_count
424
void scan_eeprom_count_fences(const AC_PolyFenceType type, uint16_t read_offset);
425
uint16_t _eeprom_fence_count;
426
uint16_t _eeprom_item_count;
427
428
// scan_eeprom_index_fences - a static function designed to be
429
// passed to scan_eeprom. _index must be a pointer to
430
// memory sufficient to hold information about all fences present
431
// in storage - so it is expected that scan_eeprom_count_fences
432
// has been used to count those fences and the allocation already
433
// made. After this method has been called _index will
434
// be filled with information about the fences in the fence
435
// storage - type, item counts and storage offset.
436
void scan_eeprom_index_fences(const AC_PolyFenceType type, uint16_t read_offset);
437
// array specifying type of each fence in storage (and a count of
438
// items in that fence)
439
FenceIndex *_index;
440
bool _indexed; // true if indexing successful
441
bool _index_attempted; // true if we attempted to index the eeprom
442
// _num_fences - count of the number of fences in _index. This
443
// should be equal to _eeprom_fence_count
444
uint16_t _num_fences;
445
446
// count_eeprom_fences - refresh the count of fences in permanent storage
447
bool count_eeprom_fences() WARN_IF_UNUSED;
448
// index_eeprom - (re)allocate and fill in _index
449
bool index_eeprom() WARN_IF_UNUSED;
450
451
uint16_t fence_storage_space_required(const AC_PolyFenceItem *new_items, uint16_t count);
452
453
#if AP_SDCARD_STORAGE_ENABLED
454
// true if we failed to load SDCard storage on init
455
bool _failed_sdcard_storage;
456
#endif
457
};
458
459
#endif // AP_FENCE_ENABLED
460
461