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_PolyFence_loader.cpp
Views: 1798
1
#include "AC_PolyFence_loader.h"
2
3
#if AP_FENCE_ENABLED
4
5
#include <AP_Vehicle/AP_Vehicle_Type.h>
6
#include <AP_BoardConfig/AP_BoardConfig.h>
7
8
#ifndef AC_FENCE_DUMMY_METHODS_ENABLED
9
#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)))
10
#endif
11
12
#if !AC_FENCE_DUMMY_METHODS_ENABLED
13
14
#include <AP_AHRS/AP_AHRS.h>
15
#include <GCS_MAVLink/GCS.h>
16
#include <AP_Logger/AP_Logger.h>
17
#include <AC_Fence/AC_Fence.h>
18
19
#include <stdio.h>
20
21
#define POLYFENCE_LOADER_DEBUGGING 0
22
23
#if POLYFENCE_LOADER_DEBUGGING
24
#define Debug(fmt, args ...) do { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } while (0)
25
#else
26
#define Debug(fmt, args ...)
27
#endif
28
29
extern const AP_HAL::HAL& hal;
30
31
static StorageAccess fence_storage(StorageManager::StorageFence);
32
33
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
34
#define AC_FENCE_SDCARD_FILENAME "APM/fence.stg"
35
#else
36
#define AC_FENCE_SDCARD_FILENAME "fence.stg"
37
#endif
38
39
void AC_PolyFence_loader::init()
40
{
41
#if AP_SDCARD_STORAGE_ENABLED
42
// check for extra storage on microsd
43
const auto *bc = AP::boardConfig();
44
if (bc != nullptr) {
45
const auto size_kb = bc->get_sdcard_fence_kb();
46
if (size_kb > 0) {
47
_failed_sdcard_storage = !fence_storage.attach_file(AC_FENCE_SDCARD_FILENAME, size_kb);
48
if (_failed_sdcard_storage) {
49
// wipe fence if storage not available, but don't
50
// save. This allows sdcard error to be fixed and
51
// reboot
52
_total.set(0);
53
}
54
}
55
}
56
#endif
57
if (!check_indexed()) {
58
// tell the user, perhaps?
59
}
60
_old_total = _total;
61
}
62
63
bool AC_PolyFence_loader::find_index_for_seq(const uint16_t seq, const FenceIndex *&entry, uint16_t &i) const
64
{
65
if (_index == nullptr) {
66
return false;
67
}
68
69
if (seq > _eeprom_item_count) {
70
return false;
71
}
72
73
i = 0;
74
for (uint16_t j=0; j<_num_fences; j++) {
75
entry = &_index[j];
76
if (seq < i + entry->count) {
77
return true;
78
}
79
i += entry->count;
80
}
81
return false;
82
}
83
84
bool AC_PolyFence_loader::find_storage_offset_for_seq(const uint16_t seq, uint16_t &offset, AC_PolyFenceType &type, uint16_t &vertex_count_offset) const
85
{
86
if (_index == nullptr) {
87
return false;
88
}
89
90
uint16_t i = 0;
91
const FenceIndex *entry = nullptr;
92
if (!find_index_for_seq(seq, entry, i)) {
93
return false;
94
}
95
96
if (entry == nullptr) {
97
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
98
return false;
99
}
100
101
const uint16_t delta = seq - i;
102
103
offset = entry->storage_offset;
104
type = entry->type;
105
offset++; // skip over type
106
switch (type) {
107
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
108
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
109
case AC_PolyFenceType::CIRCLE_INCLUSION:
110
case AC_PolyFenceType::CIRCLE_EXCLUSION:
111
if (delta != 0) {
112
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
113
return false;
114
}
115
break;
116
case AC_PolyFenceType::POLYGON_INCLUSION:
117
case AC_PolyFenceType::POLYGON_EXCLUSION:
118
vertex_count_offset = offset;
119
offset += 1; // the count of points in the fence
120
offset += (delta * 8);
121
break;
122
case AC_PolyFenceType::RETURN_POINT:
123
if (delta != 0) {
124
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
125
return false;
126
}
127
break;
128
case AC_PolyFenceType::END_OF_STORAGE:
129
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
130
return false;
131
}
132
return true;
133
}
134
135
bool AC_PolyFence_loader::get_item(const uint16_t seq, AC_PolyFenceItem &item)
136
{
137
if (!check_indexed()) {
138
return false;
139
}
140
141
uint16_t vertex_count_offset = 0; // initialised to make compiler happy
142
uint16_t offset;
143
AC_PolyFenceType type;
144
if (!find_storage_offset_for_seq(seq, offset, type, vertex_count_offset)) {
145
return false;
146
}
147
148
item.type = type;
149
150
switch (type) {
151
case AC_PolyFenceType::CIRCLE_INCLUSION:
152
case AC_PolyFenceType::CIRCLE_EXCLUSION:
153
if (!read_latlon_from_storage(offset, item.loc)) {
154
return false;
155
}
156
item.radius = fence_storage.read_float(offset);
157
break;
158
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
159
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
160
if (!read_latlon_from_storage(offset, item.loc)) {
161
return false;
162
}
163
item.radius = fence_storage.read_uint32(offset);
164
// magically change int item into a float item:
165
if (type == AC_PolyFenceType::CIRCLE_INCLUSION_INT) {
166
item.type = AC_PolyFenceType::CIRCLE_INCLUSION;
167
} else {
168
item.type = AC_PolyFenceType::CIRCLE_EXCLUSION;
169
}
170
break;
171
case AC_PolyFenceType::POLYGON_INCLUSION:
172
case AC_PolyFenceType::POLYGON_EXCLUSION:
173
if (!read_latlon_from_storage(offset, item.loc)) {
174
return false;
175
}
176
item.vertex_count = fence_storage.read_uint8(vertex_count_offset);
177
break;
178
case AC_PolyFenceType::RETURN_POINT:
179
if (!read_latlon_from_storage(offset, item.loc)) {
180
return false;
181
}
182
break;
183
case AC_PolyFenceType::END_OF_STORAGE:
184
// read end-of-storage when I should never do so
185
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
186
return false;
187
}
188
return true;
189
}
190
191
bool AC_PolyFence_loader::write_type_to_storage(uint16_t &offset, const AC_PolyFenceType type)
192
{
193
fence_storage.write_uint8(offset, (uint8_t)type);
194
offset++;
195
return true;
196
}
197
198
bool AC_PolyFence_loader::write_latlon_to_storage(uint16_t &offset, const Vector2l &latlon)
199
{
200
fence_storage.write_uint32(offset, latlon.x);
201
offset += 4;
202
fence_storage.write_uint32(offset, latlon.y);
203
offset += 4;
204
return true;
205
}
206
207
bool AC_PolyFence_loader::read_latlon_from_storage(uint16_t &read_offset, Vector2l &ret) const
208
{
209
ret.x = fence_storage.read_uint32(read_offset);
210
read_offset += 4;
211
ret.y = fence_storage.read_uint32(read_offset);
212
read_offset += 4;
213
return true;
214
}
215
216
bool AC_PolyFence_loader::breached() const
217
{
218
Location loc;
219
if (!AP::ahrs().get_location(loc)) {
220
return false;
221
}
222
223
return breached(loc);
224
}
225
226
// check if a position (expressed as lat/lng) is within the boundary
227
// returns true if location is outside the boundary
228
bool AC_PolyFence_loader::breached(const Location& loc) const
229
{
230
if (!loaded() || total_fence_count() == 0) {
231
return false;
232
}
233
234
Vector2l pos;
235
pos.x = loc.lat;
236
pos.y = loc.lng;
237
238
const uint16_t num_inclusion = _num_loaded_circle_inclusion_boundaries + _num_loaded_inclusion_boundaries;
239
uint16_t num_inclusion_outside = 0;
240
241
// check we are inside each inclusion zone:
242
for (uint8_t i=0; i<_num_loaded_inclusion_boundaries; i++) {
243
const InclusionBoundary &boundary = _loaded_inclusion_boundary[i];
244
if (Polygon_outside(pos, boundary.points_lla, boundary.count)) {
245
num_inclusion_outside++;
246
}
247
}
248
249
// check we are outside each exclusion zone:
250
for (uint8_t i=0; i<_num_loaded_exclusion_boundaries; i++) {
251
const ExclusionBoundary &boundary = _loaded_exclusion_boundary[i];
252
if (!Polygon_outside(pos, boundary.points_lla, boundary.count)) {
253
return true;
254
}
255
}
256
257
for (uint8_t i=0; i<_num_loaded_circle_exclusion_boundaries; i++) {
258
const ExclusionCircle &circle = _loaded_circle_exclusion_boundary[i];
259
Location circle_center;
260
circle_center.lat = circle.point.x;
261
circle_center.lng = circle.point.y;
262
const float diff_cm = loc.get_distance(circle_center)*100.0f;
263
if (diff_cm < circle.radius * 100.0f) {
264
return true;
265
}
266
}
267
268
for (uint8_t i=0; i<_num_loaded_circle_inclusion_boundaries; i++) {
269
const InclusionCircle &circle = _loaded_circle_inclusion_boundary[i];
270
Location circle_center;
271
circle_center.lat = circle.point.x;
272
circle_center.lng = circle.point.y;
273
const float diff_cm = loc.get_distance(circle_center)*100.0f;
274
if (diff_cm > circle.radius * 100.0f) {
275
num_inclusion_outside++;
276
}
277
}
278
279
if (AC_Fence::option_enabled(AC_Fence::OPTIONS::INCLUSION_UNION, _options)) {
280
// using union of inclusion areas, we are outside the fence if
281
// there is at least one inclusion areas and we are outside
282
// all of them
283
if (num_inclusion > 0 && num_inclusion == num_inclusion_outside) {
284
return true;
285
}
286
} else {
287
// using intersection of inclusion areas. We are outside if we
288
// are outside any of them
289
if (num_inclusion_outside > 0) {
290
return true;
291
}
292
}
293
294
// no fence breached
295
return false;
296
}
297
298
bool AC_PolyFence_loader::formatted() const
299
{
300
return (fence_storage.read_uint8(0) == new_fence_storage_magic &&
301
fence_storage.read_uint8(1) == 0 &&
302
fence_storage.read_uint8(2) == 0 &&
303
fence_storage.read_uint8(3) == 0);
304
}
305
306
uint16_t AC_PolyFence_loader::max_items() const
307
{
308
// this is 84 items on PixHawk
309
return fence_storage.size() / sizeof(Vector2l);
310
}
311
312
bool AC_PolyFence_loader::format()
313
{
314
uint16_t offset = 0;
315
fence_storage.write_uint32(offset, 0);
316
fence_storage.write_uint8(offset, new_fence_storage_magic);
317
offset += 4;
318
void_index();
319
_eeprom_fence_count = 0;
320
_eeprom_item_count = 0;
321
return write_eos_to_storage(offset);
322
}
323
324
bool AC_PolyFence_loader::scale_latlon_from_origin(const Location &origin, const Vector2l &point, Vector2f &pos_cm)
325
{
326
Location tmp_loc;
327
tmp_loc.lat = point.x;
328
tmp_loc.lng = point.y;
329
pos_cm = origin.get_distance_NE(tmp_loc) * 100.0f;
330
return true;
331
}
332
333
bool AC_PolyFence_loader::read_polygon_from_storage(const Location &origin, uint16_t &read_offset, const uint8_t vertex_count, Vector2f *&next_storage_point, Vector2l *&next_storage_point_lla)
334
{
335
for (uint8_t i=0; i<vertex_count; i++) {
336
// read from storage to lat/lon
337
if (!read_latlon_from_storage(read_offset, *next_storage_point_lla)) {
338
return false;
339
}
340
// convert lat/lon to position in cm from origin
341
if (!scale_latlon_from_origin(origin, *next_storage_point_lla, *next_storage_point)) {
342
return false;
343
}
344
345
next_storage_point_lla++;
346
next_storage_point++;
347
}
348
return true;
349
}
350
351
bool AC_PolyFence_loader::scan_eeprom(scan_fn_t scan_fn)
352
{
353
uint16_t read_offset = 0; // skipping reserved first 4 bytes
354
if (!formatted()) {
355
return false;
356
}
357
read_offset += 4;
358
bool all_done = false;
359
while (!all_done) {
360
if (read_offset > fence_storage.size()) {
361
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
362
AP_HAL::panic("did not find end-of-storage-marker before running out of space");
363
#endif
364
return false;
365
}
366
const AC_PolyFenceType type = (AC_PolyFenceType)fence_storage.read_uint8(read_offset);
367
// validate what we've just pulled back from storage:
368
switch (type) {
369
case AC_PolyFenceType::END_OF_STORAGE:
370
case AC_PolyFenceType::POLYGON_INCLUSION:
371
case AC_PolyFenceType::POLYGON_EXCLUSION:
372
case AC_PolyFenceType::CIRCLE_INCLUSION:
373
case AC_PolyFenceType::CIRCLE_EXCLUSION:
374
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
375
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
376
case AC_PolyFenceType::RETURN_POINT:
377
break;
378
default:
379
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
380
AP_HAL::panic("Fence corrupt (offset=%u)", read_offset);
381
#endif
382
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Fence corrupt");
383
return false;
384
}
385
386
scan_fn(type, read_offset);
387
read_offset++;
388
switch (type) {
389
case AC_PolyFenceType::END_OF_STORAGE:
390
_eos_offset = read_offset-1;
391
all_done = true;
392
break;
393
case AC_PolyFenceType::POLYGON_INCLUSION:
394
case AC_PolyFenceType::POLYGON_EXCLUSION: {
395
const uint8_t vertex_count = fence_storage.read_uint8(read_offset);
396
read_offset += 1; // for the count we just read
397
read_offset += vertex_count*8;
398
break;
399
}
400
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
401
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
402
case AC_PolyFenceType::CIRCLE_INCLUSION:
403
case AC_PolyFenceType::CIRCLE_EXCLUSION: {
404
read_offset += 8; // for latlon
405
read_offset += 4; // for radius
406
break;
407
}
408
case AC_PolyFenceType::RETURN_POINT:
409
read_offset += 8; // for latlon
410
break;
411
}
412
}
413
return true;
414
}
415
416
// note read_offset here isn't const and ALSO is not a reference
417
void AC_PolyFence_loader::scan_eeprom_count_fences(const AC_PolyFenceType type, uint16_t read_offset)
418
{
419
if (type == AC_PolyFenceType::END_OF_STORAGE) {
420
return;
421
}
422
_eeprom_fence_count++;
423
switch (type) {
424
case AC_PolyFenceType::END_OF_STORAGE:
425
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
426
break;
427
case AC_PolyFenceType::POLYGON_EXCLUSION:
428
case AC_PolyFenceType::POLYGON_INCLUSION: {
429
const uint8_t vertex_count = fence_storage.read_uint8(read_offset+1); // skip type
430
_eeprom_item_count += vertex_count;
431
break;
432
}
433
case AC_PolyFenceType::CIRCLE_INCLUSION:
434
case AC_PolyFenceType::CIRCLE_EXCLUSION:
435
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
436
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
437
case AC_PolyFenceType::RETURN_POINT:
438
_eeprom_item_count++;
439
break;
440
}
441
}
442
443
bool AC_PolyFence_loader::count_eeprom_fences()
444
{
445
_eeprom_fence_count = 0;
446
_eeprom_item_count = 0;
447
const bool ret = scan_eeprom(FUNCTOR_BIND_MEMBER(&AC_PolyFence_loader::scan_eeprom_count_fences, void, const AC_PolyFenceType, uint16_t));
448
return ret;
449
}
450
451
void AC_PolyFence_loader::scan_eeprom_index_fences(const AC_PolyFenceType type, uint16_t read_offset)
452
{
453
if (_index == nullptr) {
454
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
455
return;
456
}
457
if (type == AC_PolyFenceType::END_OF_STORAGE) {
458
return;
459
}
460
FenceIndex &index = _index[_num_fences++];
461
index.type = type;
462
index.storage_offset = read_offset;
463
switch (type) {
464
case AC_PolyFenceType::END_OF_STORAGE:
465
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
466
break;
467
case AC_PolyFenceType::POLYGON_EXCLUSION:
468
case AC_PolyFenceType::POLYGON_INCLUSION: {
469
const uint8_t vertex_count = fence_storage.read_uint8(read_offset+1);
470
index.count = vertex_count;
471
break;
472
}
473
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
474
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
475
case AC_PolyFenceType::CIRCLE_INCLUSION:
476
case AC_PolyFenceType::CIRCLE_EXCLUSION:
477
index.count = 1;
478
break;
479
case AC_PolyFenceType::RETURN_POINT:
480
index.count = 1;
481
break;
482
}
483
}
484
485
bool AC_PolyFence_loader::index_eeprom()
486
{
487
if (!formatted()) {
488
if (!format()) {
489
return false;
490
}
491
}
492
493
if (!count_eeprom_fences()) {
494
return false;
495
}
496
497
void_index();
498
499
if (_eeprom_fence_count == 0) {
500
_num_fences = 0;
501
_load_attempted = false;
502
return true;
503
}
504
505
Debug("Fence: Allocating %u bytes for index",
506
(unsigned)(_eeprom_fence_count*sizeof(FenceIndex)));
507
_index = NEW_NOTHROW FenceIndex[_eeprom_fence_count];
508
if (_index == nullptr) {
509
return false;
510
}
511
512
_num_fences = 0;
513
if (!scan_eeprom(FUNCTOR_BIND_MEMBER(&AC_PolyFence_loader::scan_eeprom_index_fences, void, const AC_PolyFenceType, uint16_t))) {
514
void_index();
515
return false;
516
}
517
518
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
519
if (_num_fences != _eeprom_fence_count) {
520
AP_HAL::panic("indexed fences not equal to eeprom fences");
521
}
522
#endif
523
524
_load_attempted = false;
525
526
return true;
527
}
528
529
bool AC_PolyFence_loader::check_indexed()
530
{
531
if (!_index_attempted) {
532
_indexed = index_eeprom();
533
_index_attempted = true;
534
}
535
return _indexed;
536
}
537
538
void AC_PolyFence_loader::unload()
539
{
540
delete[] _loaded_offsets_from_origin;
541
_loaded_offsets_from_origin = nullptr;
542
543
delete[] _loaded_points_lla;
544
_loaded_points_lla = nullptr;
545
546
delete[] _loaded_inclusion_boundary;
547
_loaded_inclusion_boundary = nullptr;
548
_num_loaded_inclusion_boundaries = 0;
549
550
delete[] _loaded_exclusion_boundary;
551
_loaded_exclusion_boundary = nullptr;
552
_num_loaded_exclusion_boundaries = 0;
553
554
delete[] _loaded_circle_inclusion_boundary;
555
_loaded_circle_inclusion_boundary = nullptr;
556
_num_loaded_circle_inclusion_boundaries = 0;
557
558
delete[] _loaded_circle_exclusion_boundary;
559
_loaded_circle_exclusion_boundary = nullptr;
560
_num_loaded_circle_exclusion_boundaries = 0;
561
562
_loaded_return_point = nullptr;
563
_loaded_return_point_lla = nullptr;
564
_load_time_ms = 0;
565
}
566
567
// return the number of fences of type type in the index:
568
uint16_t AC_PolyFence_loader::index_fence_count(const AC_PolyFenceType type)
569
{
570
uint16_t ret = 0;
571
for (uint8_t i=0; i<_eeprom_fence_count; i++) {
572
const FenceIndex &index = _index[i];
573
if (index.type == type) {
574
ret++;
575
}
576
}
577
return ret;
578
}
579
580
uint16_t AC_PolyFence_loader::sum_of_polygon_point_counts_and_returnpoint()
581
{
582
uint16_t ret = 0;
583
for (uint8_t i=0; i<_eeprom_fence_count; i++) {
584
const FenceIndex &index = _index[i];
585
switch (index.type) {
586
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
587
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
588
case AC_PolyFenceType::CIRCLE_INCLUSION:
589
case AC_PolyFenceType::CIRCLE_EXCLUSION:
590
break;
591
case AC_PolyFenceType::RETURN_POINT:
592
ret += 1;
593
break;
594
case AC_PolyFenceType::POLYGON_INCLUSION:
595
case AC_PolyFenceType::POLYGON_EXCLUSION:
596
ret += index.count;
597
break;
598
case AC_PolyFenceType::END_OF_STORAGE:
599
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
600
break;
601
}
602
}
603
return ret;
604
}
605
606
bool AC_PolyFence_loader::load_from_eeprom()
607
{
608
if (!check_indexed()) {
609
return false;
610
}
611
612
if (_load_attempted) {
613
return _load_time_ms != 0;
614
}
615
616
Location ekf_origin{};
617
if (!AP::ahrs().get_origin(ekf_origin)) {
618
// Debug("fence load requires origin");
619
return false;
620
}
621
622
// find indexes of each fence:
623
if (!get_loaded_fence_semaphore().take_nonblocking()) {
624
return false;
625
}
626
627
_load_attempted = true;
628
629
unload();
630
631
if (_eeprom_item_count == 0) {
632
get_loaded_fence_semaphore().give();
633
_load_time_ms = AP_HAL::millis();
634
return true;
635
}
636
637
{ // allocate array to hold offsets-from-origin
638
const uint16_t count = sum_of_polygon_point_counts_and_returnpoint();
639
Debug("Fence: Allocating %u bytes for points",
640
(unsigned)(count * sizeof(Vector2f)));
641
_loaded_offsets_from_origin = NEW_NOTHROW Vector2f[count];
642
_loaded_points_lla = NEW_NOTHROW Vector2l[count];
643
if (_loaded_offsets_from_origin == nullptr || _loaded_points_lla == nullptr) {
644
unload();
645
get_loaded_fence_semaphore().give();
646
return false;
647
}
648
}
649
650
// FIXME: find some way of factoring out all of these allocation routines.
651
652
{ // allocate storage for inclusion polyfences:
653
const auto count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION);
654
Debug("Fence: Allocating %u bytes for inc. fences",
655
(unsigned)(count * sizeof(InclusionBoundary)));
656
_loaded_inclusion_boundary = NEW_NOTHROW InclusionBoundary[count];
657
if (_loaded_inclusion_boundary == nullptr) {
658
unload();
659
get_loaded_fence_semaphore().give();
660
return false;
661
}
662
}
663
664
{ // allocate storage for exclusion polyfences:
665
const auto count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION);
666
Debug("Fence: Allocating %u bytes for exc. fences",
667
(unsigned)(count * sizeof(ExclusionBoundary)));
668
_loaded_exclusion_boundary = NEW_NOTHROW ExclusionBoundary[count];
669
if (_loaded_exclusion_boundary == nullptr) {
670
unload();
671
get_loaded_fence_semaphore().give();
672
return false;
673
}
674
}
675
676
{ // allocate storage for circular inclusion fences:
677
uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION);
678
count += index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION_INT)
679
Debug("Fence: Allocating %u bytes for circ. inc. fences",
680
(unsigned)(count * sizeof(InclusionCircle)));
681
_loaded_circle_inclusion_boundary = NEW_NOTHROW InclusionCircle[count];
682
if (_loaded_circle_inclusion_boundary == nullptr) {
683
unload();
684
get_loaded_fence_semaphore().give();
685
return false;
686
}
687
}
688
689
{ // allocate storage for circular exclusion fences:
690
uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION);
691
count += index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION_INT)
692
Debug("Fence: Allocating %u bytes for circ. exc. fences",
693
(unsigned)(count * sizeof(ExclusionCircle)));
694
_loaded_circle_exclusion_boundary = NEW_NOTHROW ExclusionCircle[count];
695
if (_loaded_circle_exclusion_boundary == nullptr) {
696
unload();
697
get_loaded_fence_semaphore().give();
698
return false;
699
}
700
}
701
702
Vector2f *next_storage_point = _loaded_offsets_from_origin;
703
Vector2l *next_storage_point_lla = _loaded_points_lla;
704
705
// use index to load fences from eeprom
706
bool storage_valid = true;
707
for (uint8_t i=0; i<_eeprom_fence_count; i++) {
708
if (!storage_valid) {
709
break;
710
}
711
const FenceIndex &index = _index[i];
712
uint16_t storage_offset = index.storage_offset;
713
storage_offset += 1; // skip type
714
switch (index.type) {
715
case AC_PolyFenceType::END_OF_STORAGE:
716
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
717
AP_HAL::panic("indexed end of storage found");
718
#endif
719
storage_valid = false;
720
break;
721
case AC_PolyFenceType::POLYGON_INCLUSION: {
722
// FIXME: consider factoring this with the EXCLUSION case
723
InclusionBoundary &boundary = _loaded_inclusion_boundary[_num_loaded_inclusion_boundaries];
724
boundary.points = next_storage_point;
725
boundary.points_lla = next_storage_point_lla;
726
boundary.count = index.count;
727
if (index.count < 3) {
728
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: invalid polygon vertex count %u", index.count);
729
storage_valid = false;
730
break;
731
}
732
storage_offset += 1; // skip vertex count
733
if (!read_polygon_from_storage(ekf_origin, storage_offset, index.count, next_storage_point, next_storage_point_lla)) {
734
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: polygon read failed");
735
storage_valid = false;
736
break;
737
}
738
_num_loaded_inclusion_boundaries++;
739
break;
740
}
741
case AC_PolyFenceType::POLYGON_EXCLUSION: {
742
ExclusionBoundary &boundary = _loaded_exclusion_boundary[_num_loaded_exclusion_boundaries];
743
boundary.points = next_storage_point;
744
boundary.points_lla = next_storage_point_lla;
745
boundary.count = index.count;
746
if (index.count < 3) {
747
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: invalid polygon vertex count %u", index.count);
748
storage_valid = false;
749
break;
750
}
751
storage_offset += 1; // skip vertex count
752
if (!read_polygon_from_storage(ekf_origin, storage_offset, index.count, next_storage_point, next_storage_point_lla)) {
753
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: polygon read failed");
754
storage_valid = false;
755
break;
756
}
757
_num_loaded_exclusion_boundaries++;
758
break;
759
}
760
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
761
case AC_PolyFenceType::CIRCLE_EXCLUSION: {
762
ExclusionCircle &circle = _loaded_circle_exclusion_boundary[_num_loaded_circle_exclusion_boundaries];
763
if (!read_latlon_from_storage(storage_offset, circle.point)) {
764
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");
765
storage_valid = false;
766
break;
767
}
768
if (!scale_latlon_from_origin(ekf_origin, circle.point, circle.pos_cm)) {
769
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");
770
storage_valid = false;
771
break;
772
}
773
// now read the radius
774
if (index.type == AC_PolyFenceType::CIRCLE_EXCLUSION_INT) {
775
circle.radius = fence_storage.read_uint32(storage_offset);
776
} else {
777
circle.radius = fence_storage.read_float(storage_offset);
778
}
779
if (!is_positive(circle.radius)) {
780
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: non-positive circle radius");
781
storage_valid = false;
782
break;
783
}
784
_num_loaded_circle_exclusion_boundaries++;
785
break;
786
}
787
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
788
case AC_PolyFenceType::CIRCLE_INCLUSION: {
789
InclusionCircle &circle = _loaded_circle_inclusion_boundary[_num_loaded_circle_inclusion_boundaries];
790
if (!read_latlon_from_storage(storage_offset, circle.point)) {
791
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");
792
storage_valid = false;
793
break;
794
}
795
if (!scale_latlon_from_origin(ekf_origin, circle.point, circle.pos_cm)){
796
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");
797
storage_valid = false;
798
break;
799
}
800
// now read the radius
801
if (index.type == AC_PolyFenceType::CIRCLE_INCLUSION_INT) {
802
circle.radius = fence_storage.read_uint32(storage_offset);
803
} else {
804
circle.radius = fence_storage.read_float(storage_offset);
805
}
806
if (!is_positive(circle.radius)) {
807
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: non-positive circle radius");
808
storage_valid = false;
809
break;
810
}
811
_num_loaded_circle_inclusion_boundaries++;
812
break;
813
}
814
case AC_PolyFenceType::RETURN_POINT:
815
if (_loaded_return_point != nullptr) {
816
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: Multiple return points found");
817
storage_valid = false;
818
break;
819
}
820
_loaded_return_point = next_storage_point;
821
if (_loaded_return_point_lla != nullptr) {
822
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: Multiple return points found");
823
storage_valid = false;
824
break;
825
}
826
_loaded_return_point_lla = next_storage_point_lla;
827
// Read the point from storage
828
if (!read_latlon_from_storage(storage_offset, *next_storage_point_lla)) {
829
storage_valid = false;
830
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: latlon read failed");
831
break;
832
}
833
if (!scale_latlon_from_origin(ekf_origin, *next_storage_point_lla, *next_storage_point)) {
834
storage_valid = false;
835
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: latlon read failed");
836
break;
837
}
838
next_storage_point++;
839
next_storage_point_lla++;
840
break;
841
}
842
}
843
844
if (!storage_valid) {
845
unload();
846
get_loaded_fence_semaphore().give();
847
return false;
848
}
849
850
_load_time_ms = AP_HAL::millis();
851
852
get_loaded_fence_semaphore().give();
853
return true;
854
}
855
856
/// returns pointer to array of exclusion polygon points and num_points is filled in with the number of points in the polygon
857
/// points are offsets in cm from EKF origin in NE frame
858
Vector2f* AC_PolyFence_loader::get_exclusion_polygon(uint16_t index, uint16_t &num_points) const
859
{
860
if (index >= _num_loaded_exclusion_boundaries) {
861
num_points = 0;
862
return nullptr;
863
}
864
const ExclusionBoundary &boundary = _loaded_exclusion_boundary[index];
865
num_points = boundary.count;
866
867
return boundary.points;
868
}
869
870
/// returns pointer to array of inclusion polygon points and num_points is filled in with the number of points in the polygon
871
/// points are offsets in cm from EKF origin in NE frame
872
Vector2f* AC_PolyFence_loader::get_inclusion_polygon(uint16_t index, uint16_t &num_points) const
873
{
874
if (index >= _num_loaded_inclusion_boundaries) {
875
num_points = 0;
876
return nullptr;
877
}
878
const InclusionBoundary &boundary = _loaded_inclusion_boundary[index];
879
num_points = boundary.count;
880
881
return boundary.points;
882
}
883
884
/// returns the specified exclusion circle
885
/// circle center offsets in cm from EKF origin in NE frame, radius is in meters
886
bool AC_PolyFence_loader::get_exclusion_circle(uint8_t index, Vector2f &center_pos_cm, float &radius) const
887
{
888
if (index >= _num_loaded_circle_exclusion_boundaries) {
889
return false;
890
}
891
center_pos_cm = _loaded_circle_exclusion_boundary[index].pos_cm;
892
radius = _loaded_circle_exclusion_boundary[index].radius;
893
return true;
894
}
895
896
/// returns the specified inclusion circle
897
/// circle centre offsets in cm from EKF origin in NE frame, radius is in meters
898
bool AC_PolyFence_loader::get_inclusion_circle(uint8_t index, Vector2f &center_pos_cm, float &radius) const
899
{
900
if (index >= _num_loaded_circle_inclusion_boundaries) {
901
return false;
902
}
903
center_pos_cm = _loaded_circle_inclusion_boundary[index].pos_cm;
904
radius = _loaded_circle_inclusion_boundary[index].radius;
905
return true;
906
}
907
908
bool AC_PolyFence_loader::check_inclusion_circle_margin(float margin) const
909
{
910
// check circular includes
911
for (uint8_t i=0; i<_num_loaded_circle_inclusion_boundaries; i++) {
912
const InclusionCircle &circle = _loaded_circle_inclusion_boundary[i];
913
if (circle.radius < margin) {
914
// circle radius should never be less than margin
915
return false;
916
}
917
}
918
return true;
919
}
920
921
bool AC_PolyFence_loader::validate_fence(const AC_PolyFenceItem *new_items, uint16_t count) const
922
{
923
// validate the fence items...
924
AC_PolyFenceType expecting_type = AC_PolyFenceType::END_OF_STORAGE;
925
uint16_t expected_type_count = 0;
926
uint16_t orig_expected_type_count = 0;
927
bool seen_return_point = false;
928
929
for (uint16_t i=0; i<count; i++) {
930
bool validate_latlon = false;
931
932
switch (new_items[i].type) {
933
case AC_PolyFenceType::END_OF_STORAGE:
934
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
935
AP_HAL::panic("passed in an END_OF_STORAGE");
936
#endif
937
return false;
938
939
case AC_PolyFenceType::POLYGON_INCLUSION:
940
case AC_PolyFenceType::POLYGON_EXCLUSION:
941
if (new_items[i].vertex_count < 3) {
942
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Invalid vertex count (%u)", new_items[i].vertex_count);
943
return false;
944
}
945
if (expected_type_count == 0) {
946
expected_type_count = new_items[i].vertex_count;
947
orig_expected_type_count = expected_type_count;
948
expecting_type = new_items[i].type;
949
} else {
950
if (new_items[i].type != expecting_type) {
951
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Received incorrect vertex type (want=%u got=%u)", (unsigned)expecting_type, (unsigned)new_items[i].type);
952
return false;
953
} else if (new_items[i].vertex_count != orig_expected_type_count) {
954
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Unexpected vertex count want=%u got=%u\n", orig_expected_type_count, new_items[i].vertex_count);
955
return false;
956
}
957
}
958
expected_type_count--;
959
validate_latlon = true;
960
break;
961
962
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
963
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
964
// should never have AC_PolyFenceItems of these types
965
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
966
return false;
967
case AC_PolyFenceType::CIRCLE_INCLUSION:
968
case AC_PolyFenceType::CIRCLE_EXCLUSION:
969
if (expected_type_count) {
970
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Received incorrect type (want=%u got=%u)", (unsigned)expecting_type, (unsigned)new_items[i].type);
971
return false;
972
}
973
if (!is_positive(new_items[i].radius)) {
974
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Non-positive circle radius");
975
return false;
976
}
977
validate_latlon = true;
978
break;
979
980
case AC_PolyFenceType::RETURN_POINT:
981
if (expected_type_count) {
982
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Received incorrect type (want=%u got=%u)", (unsigned)expecting_type, (unsigned)new_items[i].type);
983
return false;
984
}
985
986
// spec says only one return point allowed
987
if (seen_return_point) {
988
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Multiple return points");
989
return false;
990
}
991
seen_return_point = true;
992
validate_latlon = true;
993
// TODO: ensure return point is within all fences and
994
// outside all exclusion zones
995
break;
996
}
997
998
if (validate_latlon) {
999
if (!check_latlng(new_items[i].loc[0], new_items[i].loc[1])) {
1000
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Bad lat or lon");
1001
return false;
1002
}
1003
}
1004
}
1005
1006
if (expected_type_count) {
1007
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Incorrect item count");
1008
return false;
1009
}
1010
1011
return true;
1012
}
1013
1014
uint16_t AC_PolyFence_loader::fence_storage_space_required(const AC_PolyFenceItem *new_items, uint16_t count)
1015
{
1016
uint16_t ret = 4; // for the format header
1017
uint16_t i = 0;
1018
while (i < count) {
1019
ret += 1; // one byte for type
1020
switch (new_items[i].type) {
1021
case AC_PolyFenceType::POLYGON_INCLUSION:
1022
case AC_PolyFenceType::POLYGON_EXCLUSION:
1023
ret += 1 + 8 * new_items[i].vertex_count; // 1 count, 4 lat, 4 lon for each point
1024
i += new_items[i].vertex_count - 1; // i is incremented down below
1025
break;
1026
case AC_PolyFenceType::END_OF_STORAGE:
1027
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
1028
break;
1029
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
1030
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
1031
// should never have AC_PolyFenceItems of these types
1032
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
1033
break;
1034
case AC_PolyFenceType::CIRCLE_INCLUSION:
1035
case AC_PolyFenceType::CIRCLE_EXCLUSION:
1036
ret += 12; // 4 radius, 4 lat, 4 lon
1037
break;
1038
case AC_PolyFenceType::RETURN_POINT:
1039
ret += 8; // 4 lat, 4 lon
1040
break;
1041
}
1042
i++;
1043
}
1044
return ret;
1045
}
1046
1047
bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_t count)
1048
{
1049
if (!validate_fence(new_items, count)) {
1050
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Fence validation failed");
1051
return false;
1052
}
1053
1054
if (fence_storage_space_required(new_items, count) > fence_storage.size()) {
1055
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Fence exceeds storage size");
1056
return false;
1057
}
1058
1059
if (!format()) {
1060
return false;
1061
}
1062
1063
uint16_t total_vertex_count = 0;
1064
uint16_t offset = 4; // skipping magic
1065
uint8_t vertex_count = 0;
1066
for (uint16_t i=0; i<count; i++) {
1067
const AC_PolyFenceItem new_item = new_items[i];
1068
switch (new_item.type) {
1069
case AC_PolyFenceType::POLYGON_INCLUSION:
1070
case AC_PolyFenceType::POLYGON_EXCLUSION:
1071
if (vertex_count == 0) {
1072
// write out new polygon count
1073
vertex_count = new_item.vertex_count;
1074
total_vertex_count += vertex_count;
1075
if (!write_type_to_storage(offset, new_item.type)) {
1076
return false;
1077
}
1078
fence_storage.write_uint8(offset, vertex_count);
1079
offset++;
1080
}
1081
vertex_count--;
1082
if (!write_latlon_to_storage(offset, new_item.loc)) {
1083
return false;
1084
}
1085
break;
1086
case AC_PolyFenceType::END_OF_STORAGE:
1087
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1088
AP_HAL::panic("asked to store end-of-storage marker");
1089
#endif
1090
return false;
1091
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
1092
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
1093
// should never have AC_PolyFenceItems of these types
1094
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
1095
return false;
1096
case AC_PolyFenceType::CIRCLE_INCLUSION:
1097
case AC_PolyFenceType::CIRCLE_EXCLUSION: {
1098
total_vertex_count++; // useful to make number of lines in QGC file match FENCE_TOTAL
1099
const bool store_as_int = (new_item.radius - int(new_item.radius) < 0.001);
1100
AC_PolyFenceType store_type = new_item.type;
1101
if (store_as_int) {
1102
if (new_item.type == AC_PolyFenceType::CIRCLE_INCLUSION) {
1103
store_type = AC_PolyFenceType::CIRCLE_INCLUSION_INT;
1104
} else {
1105
store_type = AC_PolyFenceType::CIRCLE_EXCLUSION_INT;
1106
}
1107
}
1108
1109
if (!write_type_to_storage(offset, store_type)) {
1110
return false;
1111
}
1112
if (!write_latlon_to_storage(offset, new_item.loc)) {
1113
return false;
1114
}
1115
// store the radius. If the radius is very close to an
1116
// integer then we store it as an integer so users moving
1117
// from 4.1 back to 4.0 might be less-disrupted.
1118
if (store_as_int) {
1119
fence_storage.write_uint32(offset, new_item.radius);
1120
} else {
1121
fence_storage.write_float(offset, new_item.radius);
1122
}
1123
offset += 4;
1124
break;
1125
}
1126
case AC_PolyFenceType::RETURN_POINT:
1127
if (!write_type_to_storage(offset, new_item.type)) {
1128
return false;
1129
}
1130
if (!write_latlon_to_storage(offset, new_item.loc)) {
1131
return false;
1132
}
1133
break;
1134
}
1135
}
1136
if (!write_eos_to_storage(offset)) {
1137
return false;
1138
}
1139
1140
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1141
// sanity-check the EEPROM in SITL to make sure we can read what
1142
// we've just written.
1143
if (!index_eeprom()) {
1144
AP_HAL::panic("Failed to index eeprom");
1145
}
1146
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Fence Indexed OK");
1147
#endif
1148
1149
#if HAL_LOGGING_ENABLED
1150
// start logger logging new fence
1151
AP::logger().Write_Fence();
1152
#endif
1153
1154
void_index();
1155
1156
// this may be completely bogus total. If we are storing an
1157
// advanced fence then the old protocol which relies on this value
1158
// will error off if the GCS tries to fetch points. This number
1159
// should be correct for a "compatible" fence, however.
1160
uint16_t new_total = 0;
1161
if (total_vertex_count < 3) {
1162
new_total = 0;
1163
} else {
1164
new_total = total_vertex_count+2;
1165
}
1166
_total.set_and_save(new_total);
1167
1168
return true;
1169
}
1170
1171
1172
bool AC_PolyFence_loader::get_return_point(Vector2l &ret)
1173
{
1174
if (!check_indexed()) {
1175
return false;
1176
}
1177
1178
const FenceIndex *rp = find_first_fence(AC_PolyFenceType::RETURN_POINT);
1179
if (rp != nullptr) {
1180
uint16_t read_offset = rp->storage_offset + 1;
1181
return read_latlon_from_storage(read_offset, ret);
1182
}
1183
1184
const FenceIndex *inc = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);
1185
if (inc == nullptr) {
1186
return false;
1187
}
1188
1189
// we found an inclusion fence but not a return point. Calculate
1190
// and return the centroid. Note that this may not actually be
1191
// inside all inclusion fences...
1192
uint16_t offset = inc->storage_offset;
1193
if ((AC_PolyFenceType)fence_storage.read_uint8(offset) != AC_PolyFenceType::POLYGON_INCLUSION) {
1194
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1195
AP_HAL::panic("wrong type at offset");
1196
#endif
1197
return false;
1198
}
1199
offset++;
1200
const uint8_t count = fence_storage.read_uint8(offset);
1201
if (count < 3) {
1202
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1203
AP_HAL::panic("invalid count found");
1204
#endif
1205
return false;
1206
}
1207
offset++;
1208
Vector2l min_loc;
1209
if (!read_latlon_from_storage(offset, min_loc)) {
1210
return false;
1211
}
1212
if (min_loc.is_zero()) {
1213
return false;
1214
}
1215
Vector2l max_loc = min_loc;
1216
for (uint8_t i=1; i<count; i++) {
1217
Vector2l new_loc;
1218
if (!read_latlon_from_storage(offset, new_loc)) {
1219
return false;
1220
}
1221
if (new_loc.is_zero()) {
1222
return false;
1223
}
1224
if (new_loc.x < min_loc.x) {
1225
min_loc.x = new_loc.x;
1226
}
1227
if (new_loc.y < min_loc.y) {
1228
min_loc.y = new_loc.y;
1229
}
1230
if (new_loc.x > max_loc.x) {
1231
max_loc.x = new_loc.x;
1232
}
1233
if (new_loc.y > max_loc.y) {
1234
max_loc.y = new_loc.y;
1235
}
1236
}
1237
1238
// Potential for int32_t overflow when longitudes are beyond [-107, 107].
1239
// As a result, the calculated return point's longitude is calculated using overflowed figure.
1240
// Dividing first before adding avoids the potential overflow.
1241
ret.x = (min_loc.x / 2) + (max_loc.x / 2);
1242
ret.y = (min_loc.y / 2) + (max_loc.y / 2);
1243
1244
return true;
1245
}
1246
1247
AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::find_first_fence(const AC_PolyFenceType type) const
1248
{
1249
if (_index == nullptr) {
1250
return nullptr;
1251
}
1252
for (uint8_t i=0; i<_num_fences; i++) {
1253
if (_index[i].type == type) {
1254
return &_index[i];
1255
}
1256
}
1257
return nullptr;
1258
}
1259
1260
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
1261
void AC_PolyFence_loader::handle_msg_fetch_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg)
1262
{
1263
if (!check_indexed()) {
1264
return;
1265
}
1266
if (!contains_compatible_fence()) {
1267
link.send_text(MAV_SEVERITY_WARNING, "Vehicle contains advanced fences");
1268
return;
1269
}
1270
1271
if (_total != 0 && _total < 5) {
1272
link.send_text(MAV_SEVERITY_WARNING, "Invalid FENCE_TOTAL");
1273
return;
1274
}
1275
1276
mavlink_fence_fetch_point_t packet;
1277
mavlink_msg_fence_fetch_point_decode(&msg, &packet);
1278
1279
if (packet.idx >= _total) {
1280
link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, index past total(%u >= %u)", packet.idx, _total.get());
1281
return;
1282
}
1283
1284
mavlink_fence_point_t ret_packet{};
1285
ret_packet.target_system = msg.sysid;
1286
ret_packet.target_component = msg.compid;
1287
ret_packet.idx = packet.idx;
1288
ret_packet.count = _total;
1289
1290
if (packet.idx == 0) {
1291
// return point
1292
Vector2l ret;
1293
if (get_return_point(ret)) {
1294
ret_packet.lat = ret.x * 1.0e-7f;
1295
ret_packet.lng = ret.y * 1.0e-7f;
1296
} else {
1297
link.send_text(MAV_SEVERITY_WARNING, "Failed to get return point");
1298
}
1299
} else {
1300
// find the inclusion fence:
1301
const FenceIndex *inclusion_fence = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);
1302
if (inclusion_fence == nullptr) {
1303
// nothing stored yet; just send back zeroes
1304
ret_packet.lat = 0;
1305
ret_packet.lng = 0;
1306
} else {
1307
uint8_t fencepoint_offset; // 1st idx is return point
1308
if (packet.idx == _total-1) {
1309
// the is the loop closure point - send the first point again
1310
fencepoint_offset = 0;
1311
} else {
1312
fencepoint_offset = packet.idx - 1;
1313
}
1314
if (fencepoint_offset >= inclusion_fence->count) {
1315
// we haven't been given a value for this item yet; we will return zeroes
1316
} else {
1317
uint16_t storage_offset = inclusion_fence->storage_offset;
1318
storage_offset++; // skip over type
1319
storage_offset++; // skip over count
1320
storage_offset += 8*fencepoint_offset; // move to point we're interested in
1321
Vector2l bob;
1322
if (!read_latlon_from_storage(storage_offset, bob)) {
1323
link.send_text(MAV_SEVERITY_WARNING, "Fence read failed");
1324
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1325
AP_HAL::panic("read failure");
1326
#endif
1327
return;
1328
}
1329
ret_packet.lat = bob[0] * 1.0e-7f;
1330
ret_packet.lng = bob[1] * 1.0e-7f;
1331
}
1332
}
1333
}
1334
1335
link.send_message(MAVLINK_MSG_ID_FENCE_POINT, (const char*)&ret_packet);
1336
}
1337
1338
AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::get_or_create_return_point()
1339
{
1340
if (!check_indexed()) {
1341
return nullptr;
1342
}
1343
FenceIndex *return_point = find_first_fence(AC_PolyFenceType::RETURN_POINT);
1344
if (return_point != nullptr) {
1345
return return_point;
1346
}
1347
1348
// if the inclusion fence exists we will move it in storage to
1349
// avoid having to continually shift the return point forward as
1350
// we receive fence points
1351
uint16_t offset;
1352
const FenceIndex *inclusion_fence = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);
1353
if (inclusion_fence != nullptr) {
1354
offset = inclusion_fence->storage_offset;
1355
// the "9"s below represent the size of a return point in storage
1356
for (uint8_t i=0; i<inclusion_fence->count; i++) {
1357
// we are shifting the last fence point first - so 'i=0'
1358
// means the last point stored.
1359
const uint16_t point_storage_offset = offset + 2 + (inclusion_fence->count-1-i) * 8;
1360
Vector2l latlon;
1361
uint16_t tmp_read_offs = point_storage_offset;
1362
if (!read_latlon_from_storage(tmp_read_offs, latlon)) {
1363
return nullptr;
1364
}
1365
uint16_t write_offset = point_storage_offset + 9;
1366
if (!write_latlon_to_storage(write_offset, latlon)) {
1367
return nullptr;
1368
}
1369
}
1370
// read/write the count:
1371
const uint8_t count = fence_storage.read_uint8(inclusion_fence->storage_offset+1);
1372
fence_storage.write_uint8(inclusion_fence->storage_offset + 1 + 9, count);
1373
// read/write the type:
1374
const uint8_t t = fence_storage.read_uint8(inclusion_fence->storage_offset);
1375
fence_storage.write_uint8(inclusion_fence->storage_offset + 9, t);
1376
1377
uint16_t write_offset = offset + 2 + 8*inclusion_fence->count + 9;
1378
if (!write_eos_to_storage(write_offset)) {
1379
return nullptr;
1380
}
1381
} else {
1382
if (fence_storage.read_uint8(_eos_offset) != (uint8_t)AC_PolyFenceType::END_OF_STORAGE) {
1383
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1384
AP_HAL::panic("Expected end-of-storage marker at offset=%u",
1385
_eos_offset);
1386
#endif
1387
return nullptr;
1388
}
1389
offset = _eos_offset;
1390
}
1391
1392
if (!write_type_to_storage(offset, AC_PolyFenceType::RETURN_POINT)) {
1393
return nullptr;
1394
}
1395
if (!write_latlon_to_storage(offset, Vector2l{0, 0})) {
1396
return nullptr;
1397
}
1398
if (inclusion_fence == nullptr) {
1399
if (!write_eos_to_storage(offset)) {
1400
return nullptr;
1401
}
1402
}
1403
1404
if (!index_eeprom()) {
1405
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1406
AP_HAL::panic("Failed to index eeprom after moving inclusion fence for return point");
1407
#endif
1408
return nullptr;
1409
}
1410
1411
return_point = find_first_fence(AC_PolyFenceType::RETURN_POINT);
1412
if (return_point == nullptr) {
1413
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1414
AP_HAL::panic("Failed to get return point after indexing");
1415
#endif
1416
}
1417
return return_point;
1418
}
1419
1420
AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::get_or_create_include_fence()
1421
{
1422
if (!check_indexed()) {
1423
return nullptr;
1424
}
1425
FenceIndex *inclusion = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);
1426
if (inclusion != nullptr) {
1427
return inclusion;
1428
}
1429
if (_total < 5) {
1430
return nullptr;
1431
}
1432
if (!write_type_to_storage(_eos_offset, AC_PolyFenceType::POLYGON_INCLUSION)) {
1433
return nullptr;
1434
}
1435
fence_storage.write_uint8(_eos_offset, 0);
1436
_eos_offset++;
1437
if (!write_eos_to_storage(_eos_offset)) {
1438
return nullptr;
1439
}
1440
1441
if (!index_eeprom()) {
1442
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1443
AP_HAL::panic("Failed to index eeprom after creating fence");
1444
#endif
1445
return nullptr;
1446
}
1447
AC_PolyFence_loader::FenceIndex *ret = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);
1448
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1449
if (ret == nullptr) {
1450
AP_HAL::panic("Failed to index eeprom after creating fence");
1451
}
1452
#endif
1453
return ret;
1454
}
1455
1456
void AC_PolyFence_loader::handle_msg_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg)
1457
{
1458
if (!check_indexed()) {
1459
return;
1460
}
1461
1462
mavlink_fence_point_t packet;
1463
mavlink_msg_fence_point_decode(&msg, &packet);
1464
1465
if (_total != 0 && _total < 5) {
1466
link.send_text(MAV_SEVERITY_WARNING, "Invalid FENCE_TOTAL");
1467
return;
1468
}
1469
1470
if (packet.count != _total) {
1471
link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, bad count (%u vs %u)", packet.count, _total.get());
1472
return;
1473
}
1474
1475
if (packet.idx >= _total) {
1476
// this is a protocol failure
1477
link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, index past total (%u >= %u)", packet.idx, _total.get());
1478
return;
1479
}
1480
1481
if (!check_latlng(packet.lat, packet.lng)) {
1482
link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, bad lat or lng");
1483
return;
1484
}
1485
1486
if (!contains_compatible_fence()) {
1487
// the GCS has started to upload using the old protocol;
1488
// ensure we can accept it. We must be able to index the
1489
// fence, so it must be valid (minimum number of points)
1490
if (!format()) {
1491
return;
1492
}
1493
}
1494
1495
const Vector2l point{
1496
(int32_t)(packet.lat*1.0e7f),
1497
(int32_t)(packet.lng*1.0e7f)
1498
};
1499
1500
if (packet.idx == 0) {
1501
// this is the return point; if we have a return point then
1502
// update it, otherwise create a return point fence thingy
1503
const FenceIndex *return_point = get_or_create_return_point();
1504
if (return_point == nullptr) {
1505
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1506
AP_HAL::panic("Didn't get return point");
1507
#endif
1508
return;
1509
}
1510
uint16_t offset = return_point->storage_offset;
1511
offset++; // don't overwrite the type!
1512
if (!write_latlon_to_storage(offset, point)) {
1513
link.send_text(MAV_SEVERITY_WARNING, "PolyFence: storage write failed");
1514
return;
1515
}
1516
} else if (packet.idx == _total-1) {
1517
/* this is the fence closing point. We use this to set the vertex
1518
count of the inclusion fence
1519
*/
1520
const FenceIndex *inclusion_fence = get_or_create_include_fence();
1521
if (inclusion_fence == nullptr) {
1522
return;
1523
}
1524
// write type and length
1525
fence_storage.write_uint8(inclusion_fence->storage_offset, uint8_t(AC_PolyFenceType::POLYGON_INCLUSION));
1526
fence_storage.write_uint8(inclusion_fence->storage_offset+1, packet.idx-1);
1527
// and write end of storage marker
1528
fence_storage.write_uint8(inclusion_fence->storage_offset+2+(packet.idx-1)*8, uint8_t(AC_PolyFenceType::END_OF_STORAGE));
1529
void_index();
1530
} else {
1531
const FenceIndex *inclusion_fence = get_or_create_include_fence();
1532
if (inclusion_fence == nullptr) {
1533
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1534
AP_HAL::panic("no inclusion fences found");
1535
#endif
1536
return;
1537
}
1538
uint16_t offset = inclusion_fence->storage_offset;
1539
offset++; // skip type
1540
if (packet.idx > inclusion_fence->count) {
1541
// expand the storage space
1542
fence_storage.write_uint8(offset, packet.idx); // remembering that idx[0] is the return point....
1543
}
1544
offset++; // move past number of points
1545
offset += (packet.idx-1)*8;
1546
if (!write_latlon_to_storage(offset, point)) {
1547
link.send_text(MAV_SEVERITY_WARNING, "PolyFence: storage write failed");
1548
return;
1549
}
1550
if (_eos_offset < offset) {
1551
if (!write_eos_to_storage(offset)) {
1552
return;
1553
}
1554
}
1555
void_index();
1556
}
1557
}
1558
1559
bool AC_PolyFence_loader::contains_compatible_fence() const
1560
{
1561
// must contain a single inclusion fence with an optional return point
1562
if (_index == nullptr) {
1563
// this indicates no boundary points present
1564
return true;
1565
}
1566
bool seen_return_point = false;
1567
bool seen_poly_inclusion = false;
1568
for (uint16_t i=0; i<_num_fences; i++) {
1569
switch (_index[i].type) {
1570
case AC_PolyFenceType::END_OF_STORAGE:
1571
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1572
AP_HAL::panic("end-of-storage marker found in loaded list");
1573
#endif
1574
return false;
1575
case AC_PolyFenceType::POLYGON_INCLUSION:
1576
if (seen_poly_inclusion) {
1577
return false;
1578
}
1579
seen_poly_inclusion = true;
1580
break;
1581
case AC_PolyFenceType::CIRCLE_INCLUSION_INT:
1582
case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:
1583
case AC_PolyFenceType::POLYGON_EXCLUSION:
1584
case AC_PolyFenceType::CIRCLE_INCLUSION:
1585
case AC_PolyFenceType::CIRCLE_EXCLUSION:
1586
return false;
1587
case AC_PolyFenceType::RETURN_POINT:
1588
if (seen_return_point) {
1589
return false;
1590
}
1591
seen_return_point = true;
1592
break;
1593
}
1594
}
1595
return true;
1596
}
1597
1598
#endif // AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
1599
1600
bool AC_PolyFence_loader::write_eos_to_storage(uint16_t &offset)
1601
{
1602
if (!write_type_to_storage(offset, AC_PolyFenceType::END_OF_STORAGE)) {
1603
return false;
1604
}
1605
_eos_offset = offset - 1; // should point to the marker
1606
return true;
1607
}
1608
1609
/// handler for polygon fence messages with GCS
1610
void AC_PolyFence_loader::handle_msg(GCS_MAVLINK &link, const mavlink_message_t& msg)
1611
{
1612
switch (msg.msgid) {
1613
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
1614
case MAVLINK_MSG_ID_FENCE_POINT:
1615
handle_msg_fence_point(link, msg);
1616
break;
1617
case MAVLINK_MSG_ID_FENCE_FETCH_POINT:
1618
handle_msg_fetch_fence_point(link, msg);
1619
break;
1620
#endif
1621
default:
1622
break;
1623
}
1624
}
1625
1626
void AC_PolyFence_loader::update()
1627
{
1628
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
1629
// if an older GCS sets the fence point count to zero then clear the fence
1630
if (_old_total != _total) {
1631
_old_total = _total;
1632
if (_total == 0 && _eeprom_fence_count) {
1633
if (!format()) {
1634
// we are in all sorts of trouble
1635
return;
1636
}
1637
}
1638
}
1639
#endif
1640
if (!load_from_eeprom()) {
1641
return;
1642
}
1643
}
1644
1645
#else // build type is not appropriate; provide a dummy implementation:
1646
1647
void AC_PolyFence_loader::init() {};
1648
1649
bool AC_PolyFence_loader::get_item(const uint16_t seq, AC_PolyFenceItem &item) { return false; }
1650
1651
Vector2f* AC_PolyFence_loader::get_exclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; }
1652
Vector2f* AC_PolyFence_loader::get_inclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; }
1653
1654
bool AC_PolyFence_loader::get_exclusion_circle(uint8_t index, Vector2f &center_pos_cm, float &radius) const { return false; }
1655
bool AC_PolyFence_loader::get_inclusion_circle(uint8_t index, Vector2f &center_pos_cm, float &radius) const { return false; }
1656
1657
void AC_PolyFence_loader::handle_msg(GCS_MAVLINK &link, const mavlink_message_t& msg) {};
1658
1659
bool AC_PolyFence_loader::breached() const { return false; }
1660
bool AC_PolyFence_loader::breached(const Location& loc) const { return false; }
1661
1662
uint16_t AC_PolyFence_loader::max_items() const { return 0; }
1663
1664
bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_t count) { return false; }
1665
1666
void AC_PolyFence_loader::update() {};
1667
1668
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
1669
bool AC_PolyFence_loader::get_return_point(Vector2l &ret) { return false; }
1670
#endif
1671
1672
#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED
1673
#endif // AP_FENCE_ENABLED
1674
1675