APM:Libraries
AC_PolyFence_loader.cpp
Go to the documentation of this file.
1 #include "AC_PolyFence_loader.h"
2 
3 extern const AP_HAL::HAL& hal;
4 
6 
7 /*
8  maximum number of fencepoints
9  */
11 {
12  return MIN(255U, fence_storage.size() / sizeof(Vector2l));
13 }
14 
15 // create buffer to hold copy of eeprom points in RAM
16 // returns nullptr if not enough memory can be allocated
17 void* AC_PolyFence_loader::create_point_array(uint8_t element_size)
18 {
19  uint32_t array_size = max_points() * element_size;
20  if (hal.util->available_memory() < 100U + array_size) {
21  // too risky to enable as we could run out of stack
22  return nullptr;
23  }
24 
25  return calloc(1, array_size);
26 }
27 
28 // load boundary point from eeprom, returns true on successful load
30 {
31  // sanity check index
32  if (i >= max_points()) {
33  return false;
34  }
35 
36  // read fence point
37  point.x = fence_storage.read_uint32(i * sizeof(Vector2l));
38  point.y = fence_storage.read_uint32(i * sizeof(Vector2l) + sizeof(uint32_t));
39  return true;
40 }
41 
42 // save a fence point to eeprom, returns true on successful save
44 {
45  // sanity check index
46  if (i >= max_points()) {
47  return false;
48  }
49 
50  // write point to eeprom
51  fence_storage.write_uint32(i * sizeof(Vector2l), point.x);
52  fence_storage.write_uint32(i * sizeof(Vector2l)+sizeof(uint32_t), point.y);
53  return true;
54 }
55 
56 // validate array of boundary points (expressed as either floats or long ints)
57 // contains_return_point should be true for plane which stores the return point as the first point in the array
58 // returns true if boundary is valid
59 template <typename T>
60 bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2<T>* points, bool contains_return_point) const
61 {
62  // exit immediate if no points
63  if (points == nullptr) {
64  return false;
65  }
66 
67  // start from 2nd point if boundary contains return point (as first point)
68  uint8_t start_num = contains_return_point ? 1 : 0;
69 
70  // a boundary requires at least 4 point (a triangle and last point equals first)
71  if (num_points < start_num + 4) {
72  return false;
73  }
74 
75  // point 1 and last point must be the same. Note: 0th point is reserved as the return point
76  if (!Polygon_complete(&points[start_num], num_points-start_num)) {
77  return false;
78  }
79 
80  // check return point is within the fence
81  if (contains_return_point && Polygon_outside(points[0], &points[1], num_points-start_num)) {
82  return false;
83  }
84 
85  return true;
86 }
87 
88 // check if a location (expressed as either floats or long ints) is within the boundary
89 // contains_return_point should be true for plane which stores the return point as the first point in the array
90 // returns true if location is outside the boundary
91 template <typename T>
92 bool AC_PolyFence_loader::boundary_breached(const Vector2<T>& location, uint16_t num_points, const Vector2<T>* points,
93  bool contains_return_point) const
94 {
95  // exit immediate if no points
96  if (points == nullptr) {
97  return false;
98  }
99 
100  // start from 2nd point if boundary contains return point (as first point)
101  uint8_t start_num = contains_return_point ? 1 : 0;
102 
103  // check location is within the fence
104  return Polygon_outside(location, &points[start_num], num_points-start_num);
105 }
106 
107 // declare type specific methods
108 template bool AC_PolyFence_loader::boundary_valid<int32_t>(uint16_t num_points, const Vector2l* points, bool contains_return_point) const;
109 template bool AC_PolyFence_loader::boundary_valid<float>(uint16_t num_points, const Vector2f* points, bool contains_return_point) const;
110 template bool AC_PolyFence_loader::boundary_breached<int32_t>(const Vector2l& location, uint16_t num_points,
111  const Vector2l* points, bool contains_return_point) const;
112 template bool AC_PolyFence_loader::boundary_breached<float>(const Vector2f& location, uint16_t num_points,
113  const Vector2f* points, bool contains_return_point) const;
virtual uint32_t available_memory(void)
Definition: Util.h:121
bool Polygon_complete(const Vector2< T > *V, unsigned n)
Definition: polygon.cpp:86
uint16_t size(void) const
AP_HAL::Util * util
Definition: HAL.h:115
bool load_point_from_eeprom(uint16_t i, Vector2l &point)
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
#define MIN(a, b)
Definition: usb_conf.h:215
bool boundary_valid(uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
T y
Definition: vector2.h:37
uint8_t max_points() const
static const StorageAccess fence_storage(StorageManager::StorageFence)
bool save_point_to_eeprom(uint16_t i, const Vector2l &point)
uint32_t read_uint32(uint16_t loc) const
void write_uint32(uint16_t loc, uint32_t value) const
Vector2f location
Definition: location.cpp:16
T x
Definition: vector2.h:37
Vector2< int32_t > Vector2l
Definition: vector2.h:237
bool Polygon_outside(const Vector2< T > &P, const Vector2< T > *V, unsigned n)
Definition: polygon.cpp:38
void * create_point_array(uint8_t element_size)
bool boundary_breached(const Vector2< T > &location, uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
Vector2l point
Definition: polygon.cpp:34