APM:Libraries
|
#include <AC_PolyFence_loader.h>
Public Member Functions | |
uint8_t | max_points () const |
void * | create_point_array (uint8_t element_size) |
bool | load_point_from_eeprom (uint16_t i, Vector2l &point) |
bool | save_point_to_eeprom (uint16_t i, const Vector2l &point) |
template<typename T > | |
bool | boundary_valid (uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const |
template<typename T > | |
bool | boundary_breached (const Vector2< T > &location, uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const |
Definition at line 6 of file AC_PolyFence_loader.h.
template bool AC_PolyFence_loader::boundary_breached< float > | ( | const Vector2< T > & | location, |
uint16_t | num_points, | ||
const Vector2< T > * | points, | ||
bool | contains_return_point | ||
) | const |
Definition at line 92 of file AC_PolyFence_loader.cpp.
Referenced by AC_Fence::boundary_breached(), AC_Fence::check_destination_within_fence(), AC_Fence::check_fence_polygon(), and AP_Proximity_SITL::get_distance_to_fence().
template bool AC_PolyFence_loader::boundary_valid< float > | ( | uint16_t | num_points, |
const Vector2< T > * | points, | ||
bool | contains_return_point | ||
) | const |
Definition at line 60 of file AC_PolyFence_loader.cpp.
Referenced by AP_Proximity_SITL::get_distance_to_fence(), AC_Fence::load_polygon_from_eeprom(), and AP_Proximity_SITL::update().
void * AC_PolyFence_loader::create_point_array | ( | uint8_t | element_size | ) |
Definition at line 17 of file AC_PolyFence_loader.cpp.
Referenced by AP_Proximity_SITL::load_fence(), and AC_Fence::load_polygon_from_eeprom().
bool AC_PolyFence_loader::load_point_from_eeprom | ( | uint16_t | i, |
Vector2l & | point | ||
) |
Definition at line 29 of file AC_PolyFence_loader.cpp.
Referenced by AC_Fence::handle_msg(), AP_Proximity_SITL::load_fence(), and AC_Fence::load_polygon_from_eeprom().
uint8_t AC_PolyFence_loader::max_points | ( | ) | const |
Definition at line 10 of file AC_PolyFence_loader.cpp.
Referenced by create_point_array(), load_point_from_eeprom(), AC_Fence::load_polygon_from_eeprom(), and save_point_to_eeprom().
bool AC_PolyFence_loader::save_point_to_eeprom | ( | uint16_t | i, |
const Vector2l & | point | ||
) |
Definition at line 43 of file AC_PolyFence_loader.cpp.
Referenced by AC_Fence::handle_msg().