19 uint32_t array_size =
max_points() * element_size;
25 return calloc(1, array_size);
63 if (points ==
nullptr) {
68 uint8_t start_num = contains_return_point ? 1 : 0;
71 if (num_points < start_num + 4) {
81 if (contains_return_point &&
Polygon_outside(points[0], &points[1], num_points-start_num)) {
93 bool contains_return_point)
const 96 if (points ==
nullptr) {
101 uint8_t start_num = contains_return_point ? 1 : 0;
104 return Polygon_outside(location, &points[start_num], num_points-start_num);
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)
bool Polygon_complete(const Vector2< T > *V, unsigned n)
uint16_t size(void) const
bool load_point_from_eeprom(uint16_t i, Vector2l &point)
void * calloc(size_t nmemb, size_t size)
bool boundary_valid(uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
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
Vector2< int32_t > Vector2l
bool Polygon_outside(const Vector2< T > &P, const Vector2< T > *V, unsigned n)
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