2016-06-23 04:41:33 -03:00
|
|
|
#include "AC_PolyFence_loader.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
static const StorageAccess fence_storage(StorageManager::StorageFence);
|
|
|
|
|
|
|
|
/*
|
|
|
|
maximum number of fencepoints
|
|
|
|
*/
|
|
|
|
uint8_t AC_PolyFence_loader::max_points() const
|
|
|
|
{
|
|
|
|
return MIN(255U, fence_storage.size() / sizeof(Vector2l));
|
|
|
|
}
|
|
|
|
|
|
|
|
// create buffer to hold copy of eeprom points in RAM
|
2016-10-30 02:24:21 -03:00
|
|
|
// returns nullptr if not enough memory can be allocated
|
2016-06-23 04:41:33 -03:00
|
|
|
void* AC_PolyFence_loader::create_point_array(uint8_t element_size)
|
|
|
|
{
|
|
|
|
uint32_t array_size = max_points() * element_size;
|
|
|
|
if (hal.util->available_memory() < 100U + array_size) {
|
|
|
|
// too risky to enable as we could run out of stack
|
2016-10-30 02:24:21 -03:00
|
|
|
return nullptr;
|
2016-06-23 04:41:33 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
return calloc(1, array_size);
|
|
|
|
}
|
|
|
|
|
|
|
|
// load boundary point from eeprom, returns true on successful load
|
|
|
|
bool AC_PolyFence_loader::load_point_from_eeprom(uint16_t i, Vector2l& point)
|
|
|
|
{
|
|
|
|
// sanity check index
|
|
|
|
if (i >= max_points()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// read fence point
|
|
|
|
point.x = fence_storage.read_uint32(i * sizeof(Vector2l));
|
2016-08-04 02:52:48 -03:00
|
|
|
point.y = fence_storage.read_uint32(i * sizeof(Vector2l) + sizeof(uint32_t));
|
2016-06-23 04:41:33 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// save a fence point to eeprom, returns true on successful save
|
|
|
|
bool AC_PolyFence_loader::save_point_to_eeprom(uint16_t i, const Vector2l& point)
|
|
|
|
{
|
|
|
|
// sanity check index
|
|
|
|
if (i >= max_points()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// write point to eeprom
|
|
|
|
fence_storage.write_uint32(i * sizeof(Vector2l), point.x);
|
2016-08-04 02:52:48 -03:00
|
|
|
fence_storage.write_uint32(i * sizeof(Vector2l)+sizeof(uint32_t), point.y);
|
2016-06-23 04:41:33 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-05-29 10:02:04 -03:00
|
|
|
// validate array of boundary points
|
2016-06-23 04:41:33 -03:00
|
|
|
// returns true if boundary is valid
|
2019-05-29 10:02:04 -03:00
|
|
|
bool AC_PolyFence_loader::calculate_boundary_valid() const
|
2016-06-23 04:41:33 -03:00
|
|
|
{
|
|
|
|
// exit immediate if no points
|
2019-05-29 10:02:04 -03:00
|
|
|
if (_boundary == nullptr) {
|
2016-06-23 04:41:33 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-02-04 02:18:26 -04:00
|
|
|
// start from 2nd point as boundary contains return point (as first point)
|
|
|
|
uint8_t start_num = 1;
|
2016-06-23 04:41:33 -03:00
|
|
|
|
|
|
|
// a boundary requires at least 4 point (a triangle and last point equals first)
|
2019-05-29 10:02:04 -03:00
|
|
|
if (_boundary_num_points < start_num + 4) {
|
2016-06-23 04:41:33 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// point 1 and last point must be the same. Note: 0th point is reserved as the return point
|
2019-05-29 10:02:04 -03:00
|
|
|
if (!Polygon_complete(&_boundary[start_num], _boundary_num_points-start_num)) {
|
2016-06-23 04:41:33 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check return point is within the fence
|
2019-05-29 10:02:04 -03:00
|
|
|
if (Polygon_outside(_boundary[0], &_boundary[1], _boundary_num_points-start_num)) {
|
2016-06-23 04:41:33 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-05-29 10:02:04 -03:00
|
|
|
bool AC_PolyFence_loader::breached()
|
|
|
|
{
|
|
|
|
// check if vehicle is outside the polygon fence
|
|
|
|
Vector2f position;
|
|
|
|
if (!AP::ahrs().get_relative_position_NE_origin(position)) {
|
|
|
|
// we have no idea where we are; can't breach the fence
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
position = position * 100.0f; // m to cm
|
|
|
|
return breached(position);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AC_PolyFence_loader::breached(const Location& loc)
|
|
|
|
{
|
|
|
|
Vector2f posNE;
|
|
|
|
if (!loc.get_vector_xy_from_origin_NE(posNE)) {
|
|
|
|
// not breached if we don't now where we are
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return breached(posNE);
|
|
|
|
}
|
|
|
|
|
2016-06-23 04:41:33 -03:00
|
|
|
// returns true if location is outside the boundary
|
2019-05-29 10:02:04 -03:00
|
|
|
bool AC_PolyFence_loader::breached(const Vector2f& location)
|
2016-06-23 04:41:33 -03:00
|
|
|
{
|
2019-05-29 10:02:04 -03:00
|
|
|
// check consistency of number of points
|
|
|
|
if (_boundary_num_points != _total) {
|
|
|
|
// Fence is currently not completely loaded. Can't breach it?!
|
|
|
|
load_from_eeprom();
|
|
|
|
return false;
|
|
|
|
}
|
2016-06-23 04:41:33 -03:00
|
|
|
// exit immediate if no points
|
2019-05-29 10:02:04 -03:00
|
|
|
if (_boundary == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (!_valid) {
|
|
|
|
// fence isn't valid - can't breach it?!
|
2016-06-23 04:41:33 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-02-04 02:18:26 -04:00
|
|
|
// start from 2nd point as boundary contains return point (as first point)
|
|
|
|
uint8_t start_num = 1;
|
2016-06-23 04:41:33 -03:00
|
|
|
|
|
|
|
// check location is within the fence
|
2019-05-29 10:02:04 -03:00
|
|
|
return Polygon_outside(location, &_boundary[start_num], _boundary_num_points-start_num);
|
2016-06-23 04:41:33 -03:00
|
|
|
}
|