ardupilot/libraries/AC_Fence/AC_PolyFence_loader.h
Michael du Breuil 983a330cd5 AC_Fence: Remove unused duplicate methods
The Vector2l methods completely duplicate the code of the Vector2f
methods, but aren't used anywhere. They are therefore subject to bitrot
and aren't adding any value. (Also shrinks the build by 8 bytes for some
reason, given that it's unused code I expected to see no difference in
binary size).
2017-11-21 17:04:11 +09:00

39 lines
1.4 KiB
C++

#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
class AC_PolyFence_loader
{
public:
// maximum number of fence points we can store in eeprom
uint8_t max_points() const;
// create buffer to hold copy of eeprom points in RAM
// returns nullptr if not enough memory can be allocated
void* create_point_array(uint8_t element_size);
// load boundary point from eeprom, returns true on successful load
bool load_point_from_eeprom(uint16_t i, Vector2l& point);
// save a fence point to eeprom, returns true on successful save
bool save_point_to_eeprom(uint16_t i, const Vector2l& point);
// validate array of boundary points (expressed as either floats or long ints)
// contains_return_point should be true for plane which stores the return point as the first point in the array
// returns true if boundary is valid
template <typename T>
bool boundary_valid(uint16_t num_points, const Vector2<T>* points, bool contains_return_point) const;
// check if a location (expressed as either floats or long ints) is within the boundary
// contains_return_point should be true for plane which stores the return point as the first point in the array
// returns true if location is outside the boundary
template <typename T>
bool boundary_breached(const Vector2<T>& location, uint16_t num_points, const Vector2<T>* points, bool contains_return_point) const;
};