APM:Libraries
AC_PolyFence_loader.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Math/AP_Math.h>
5 
7 {
8 
9 public:
10 
11  // maximum number of fence points we can store in eeprom
12  uint8_t max_points() const;
13 
14  // create buffer to hold copy of eeprom points in RAM
15  // returns nullptr if not enough memory can be allocated
16  void* create_point_array(uint8_t element_size);
17 
18  // load boundary point from eeprom, returns true on successful load
19  bool load_point_from_eeprom(uint16_t i, Vector2l& point);
20 
21  // save a fence point to eeprom, returns true on successful save
22  bool save_point_to_eeprom(uint16_t i, const Vector2l& point);
23 
24 
25  // validate array of boundary points (expressed as either floats or long ints)
26  // contains_return_point should be true for plane which stores the return point as the first point in the array
27  // returns true if boundary is valid
28  template <typename T>
29  bool boundary_valid(uint16_t num_points, const Vector2<T>* points, bool contains_return_point) const;
30 
31  // check if a location (expressed as either floats or long ints) is within the boundary
32  // contains_return_point should be true for plane which stores the return point as the first point in the array
33  // returns true if location is outside the boundary
34  template <typename T>
35  bool boundary_breached(const Vector2<T>& location, uint16_t num_points, const Vector2<T>* points, bool contains_return_point) const;
36 
37 };
38 
bool load_point_from_eeprom(uint16_t i, Vector2l &point)
bool boundary_valid(uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
uint8_t max_points() const
bool save_point_to_eeprom(uint16_t i, const Vector2l &point)
Common definitions and utility routines for the ArduPilot libraries.
Vector2f location
Definition: location.cpp:16
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