Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_Fence/AC_PolyFence_loader.cpp
Views: 1798
#include "AC_PolyFence_loader.h"12#if AP_FENCE_ENABLED34#include <AP_Vehicle/AP_Vehicle_Type.h>5#include <AP_BoardConfig/AP_BoardConfig.h>67#ifndef AC_FENCE_DUMMY_METHODS_ENABLED8#define AC_FENCE_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub) | (AP_FENCE_ENABLED == 1)))9#endif1011#if !AC_FENCE_DUMMY_METHODS_ENABLED1213#include <AP_AHRS/AP_AHRS.h>14#include <GCS_MAVLink/GCS.h>15#include <AP_Logger/AP_Logger.h>16#include <AC_Fence/AC_Fence.h>1718#include <stdio.h>1920#define POLYFENCE_LOADER_DEBUGGING 02122#if POLYFENCE_LOADER_DEBUGGING23#define Debug(fmt, args ...) do { GCS_SEND_TEXT(MAV_SEVERITY_INFO, fmt, ## args); } while (0)24#else25#define Debug(fmt, args ...)26#endif2728extern const AP_HAL::HAL& hal;2930static StorageAccess fence_storage(StorageManager::StorageFence);3132#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS33#define AC_FENCE_SDCARD_FILENAME "APM/fence.stg"34#else35#define AC_FENCE_SDCARD_FILENAME "fence.stg"36#endif3738void AC_PolyFence_loader::init()39{40#if AP_SDCARD_STORAGE_ENABLED41// check for extra storage on microsd42const auto *bc = AP::boardConfig();43if (bc != nullptr) {44const auto size_kb = bc->get_sdcard_fence_kb();45if (size_kb > 0) {46_failed_sdcard_storage = !fence_storage.attach_file(AC_FENCE_SDCARD_FILENAME, size_kb);47if (_failed_sdcard_storage) {48// wipe fence if storage not available, but don't49// save. This allows sdcard error to be fixed and50// reboot51_total.set(0);52}53}54}55#endif56if (!check_indexed()) {57// tell the user, perhaps?58}59_old_total = _total;60}6162bool AC_PolyFence_loader::find_index_for_seq(const uint16_t seq, const FenceIndex *&entry, uint16_t &i) const63{64if (_index == nullptr) {65return false;66}6768if (seq > _eeprom_item_count) {69return false;70}7172i = 0;73for (uint16_t j=0; j<_num_fences; j++) {74entry = &_index[j];75if (seq < i + entry->count) {76return true;77}78i += entry->count;79}80return false;81}8283bool AC_PolyFence_loader::find_storage_offset_for_seq(const uint16_t seq, uint16_t &offset, AC_PolyFenceType &type, uint16_t &vertex_count_offset) const84{85if (_index == nullptr) {86return false;87}8889uint16_t i = 0;90const FenceIndex *entry = nullptr;91if (!find_index_for_seq(seq, entry, i)) {92return false;93}9495if (entry == nullptr) {96INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);97return false;98}99100const uint16_t delta = seq - i;101102offset = entry->storage_offset;103type = entry->type;104offset++; // skip over type105switch (type) {106case AC_PolyFenceType::CIRCLE_INCLUSION_INT:107case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:108case AC_PolyFenceType::CIRCLE_INCLUSION:109case AC_PolyFenceType::CIRCLE_EXCLUSION:110if (delta != 0) {111INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);112return false;113}114break;115case AC_PolyFenceType::POLYGON_INCLUSION:116case AC_PolyFenceType::POLYGON_EXCLUSION:117vertex_count_offset = offset;118offset += 1; // the count of points in the fence119offset += (delta * 8);120break;121case AC_PolyFenceType::RETURN_POINT:122if (delta != 0) {123INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);124return false;125}126break;127case AC_PolyFenceType::END_OF_STORAGE:128INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);129return false;130}131return true;132}133134bool AC_PolyFence_loader::get_item(const uint16_t seq, AC_PolyFenceItem &item)135{136if (!check_indexed()) {137return false;138}139140uint16_t vertex_count_offset = 0; // initialised to make compiler happy141uint16_t offset;142AC_PolyFenceType type;143if (!find_storage_offset_for_seq(seq, offset, type, vertex_count_offset)) {144return false;145}146147item.type = type;148149switch (type) {150case AC_PolyFenceType::CIRCLE_INCLUSION:151case AC_PolyFenceType::CIRCLE_EXCLUSION:152if (!read_latlon_from_storage(offset, item.loc)) {153return false;154}155item.radius = fence_storage.read_float(offset);156break;157case AC_PolyFenceType::CIRCLE_INCLUSION_INT:158case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:159if (!read_latlon_from_storage(offset, item.loc)) {160return false;161}162item.radius = fence_storage.read_uint32(offset);163// magically change int item into a float item:164if (type == AC_PolyFenceType::CIRCLE_INCLUSION_INT) {165item.type = AC_PolyFenceType::CIRCLE_INCLUSION;166} else {167item.type = AC_PolyFenceType::CIRCLE_EXCLUSION;168}169break;170case AC_PolyFenceType::POLYGON_INCLUSION:171case AC_PolyFenceType::POLYGON_EXCLUSION:172if (!read_latlon_from_storage(offset, item.loc)) {173return false;174}175item.vertex_count = fence_storage.read_uint8(vertex_count_offset);176break;177case AC_PolyFenceType::RETURN_POINT:178if (!read_latlon_from_storage(offset, item.loc)) {179return false;180}181break;182case AC_PolyFenceType::END_OF_STORAGE:183// read end-of-storage when I should never do so184INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);185return false;186}187return true;188}189190bool AC_PolyFence_loader::write_type_to_storage(uint16_t &offset, const AC_PolyFenceType type)191{192fence_storage.write_uint8(offset, (uint8_t)type);193offset++;194return true;195}196197bool AC_PolyFence_loader::write_latlon_to_storage(uint16_t &offset, const Vector2l &latlon)198{199fence_storage.write_uint32(offset, latlon.x);200offset += 4;201fence_storage.write_uint32(offset, latlon.y);202offset += 4;203return true;204}205206bool AC_PolyFence_loader::read_latlon_from_storage(uint16_t &read_offset, Vector2l &ret) const207{208ret.x = fence_storage.read_uint32(read_offset);209read_offset += 4;210ret.y = fence_storage.read_uint32(read_offset);211read_offset += 4;212return true;213}214215bool AC_PolyFence_loader::breached() const216{217Location loc;218if (!AP::ahrs().get_location(loc)) {219return false;220}221222return breached(loc);223}224225// check if a position (expressed as lat/lng) is within the boundary226// returns true if location is outside the boundary227bool AC_PolyFence_loader::breached(const Location& loc) const228{229if (!loaded() || total_fence_count() == 0) {230return false;231}232233Vector2l pos;234pos.x = loc.lat;235pos.y = loc.lng;236237const uint16_t num_inclusion = _num_loaded_circle_inclusion_boundaries + _num_loaded_inclusion_boundaries;238uint16_t num_inclusion_outside = 0;239240// check we are inside each inclusion zone:241for (uint8_t i=0; i<_num_loaded_inclusion_boundaries; i++) {242const InclusionBoundary &boundary = _loaded_inclusion_boundary[i];243if (Polygon_outside(pos, boundary.points_lla, boundary.count)) {244num_inclusion_outside++;245}246}247248// check we are outside each exclusion zone:249for (uint8_t i=0; i<_num_loaded_exclusion_boundaries; i++) {250const ExclusionBoundary &boundary = _loaded_exclusion_boundary[i];251if (!Polygon_outside(pos, boundary.points_lla, boundary.count)) {252return true;253}254}255256for (uint8_t i=0; i<_num_loaded_circle_exclusion_boundaries; i++) {257const ExclusionCircle &circle = _loaded_circle_exclusion_boundary[i];258Location circle_center;259circle_center.lat = circle.point.x;260circle_center.lng = circle.point.y;261const float diff_cm = loc.get_distance(circle_center)*100.0f;262if (diff_cm < circle.radius * 100.0f) {263return true;264}265}266267for (uint8_t i=0; i<_num_loaded_circle_inclusion_boundaries; i++) {268const InclusionCircle &circle = _loaded_circle_inclusion_boundary[i];269Location circle_center;270circle_center.lat = circle.point.x;271circle_center.lng = circle.point.y;272const float diff_cm = loc.get_distance(circle_center)*100.0f;273if (diff_cm > circle.radius * 100.0f) {274num_inclusion_outside++;275}276}277278if (AC_Fence::option_enabled(AC_Fence::OPTIONS::INCLUSION_UNION, _options)) {279// using union of inclusion areas, we are outside the fence if280// there is at least one inclusion areas and we are outside281// all of them282if (num_inclusion > 0 && num_inclusion == num_inclusion_outside) {283return true;284}285} else {286// using intersection of inclusion areas. We are outside if we287// are outside any of them288if (num_inclusion_outside > 0) {289return true;290}291}292293// no fence breached294return false;295}296297bool AC_PolyFence_loader::formatted() const298{299return (fence_storage.read_uint8(0) == new_fence_storage_magic &&300fence_storage.read_uint8(1) == 0 &&301fence_storage.read_uint8(2) == 0 &&302fence_storage.read_uint8(3) == 0);303}304305uint16_t AC_PolyFence_loader::max_items() const306{307// this is 84 items on PixHawk308return fence_storage.size() / sizeof(Vector2l);309}310311bool AC_PolyFence_loader::format()312{313uint16_t offset = 0;314fence_storage.write_uint32(offset, 0);315fence_storage.write_uint8(offset, new_fence_storage_magic);316offset += 4;317void_index();318_eeprom_fence_count = 0;319_eeprom_item_count = 0;320return write_eos_to_storage(offset);321}322323bool AC_PolyFence_loader::scale_latlon_from_origin(const Location &origin, const Vector2l &point, Vector2f &pos_cm)324{325Location tmp_loc;326tmp_loc.lat = point.x;327tmp_loc.lng = point.y;328pos_cm = origin.get_distance_NE(tmp_loc) * 100.0f;329return true;330}331332bool AC_PolyFence_loader::read_polygon_from_storage(const Location &origin, uint16_t &read_offset, const uint8_t vertex_count, Vector2f *&next_storage_point, Vector2l *&next_storage_point_lla)333{334for (uint8_t i=0; i<vertex_count; i++) {335// read from storage to lat/lon336if (!read_latlon_from_storage(read_offset, *next_storage_point_lla)) {337return false;338}339// convert lat/lon to position in cm from origin340if (!scale_latlon_from_origin(origin, *next_storage_point_lla, *next_storage_point)) {341return false;342}343344next_storage_point_lla++;345next_storage_point++;346}347return true;348}349350bool AC_PolyFence_loader::scan_eeprom(scan_fn_t scan_fn)351{352uint16_t read_offset = 0; // skipping reserved first 4 bytes353if (!formatted()) {354return false;355}356read_offset += 4;357bool all_done = false;358while (!all_done) {359if (read_offset > fence_storage.size()) {360#if CONFIG_HAL_BOARD == HAL_BOARD_SITL361AP_HAL::panic("did not find end-of-storage-marker before running out of space");362#endif363return false;364}365const AC_PolyFenceType type = (AC_PolyFenceType)fence_storage.read_uint8(read_offset);366// validate what we've just pulled back from storage:367switch (type) {368case AC_PolyFenceType::END_OF_STORAGE:369case AC_PolyFenceType::POLYGON_INCLUSION:370case AC_PolyFenceType::POLYGON_EXCLUSION:371case AC_PolyFenceType::CIRCLE_INCLUSION:372case AC_PolyFenceType::CIRCLE_EXCLUSION:373case AC_PolyFenceType::CIRCLE_INCLUSION_INT:374case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:375case AC_PolyFenceType::RETURN_POINT:376break;377default:378#if CONFIG_HAL_BOARD == HAL_BOARD_SITL379AP_HAL::panic("Fence corrupt (offset=%u)", read_offset);380#endif381GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Fence corrupt");382return false;383}384385scan_fn(type, read_offset);386read_offset++;387switch (type) {388case AC_PolyFenceType::END_OF_STORAGE:389_eos_offset = read_offset-1;390all_done = true;391break;392case AC_PolyFenceType::POLYGON_INCLUSION:393case AC_PolyFenceType::POLYGON_EXCLUSION: {394const uint8_t vertex_count = fence_storage.read_uint8(read_offset);395read_offset += 1; // for the count we just read396read_offset += vertex_count*8;397break;398}399case AC_PolyFenceType::CIRCLE_INCLUSION_INT:400case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:401case AC_PolyFenceType::CIRCLE_INCLUSION:402case AC_PolyFenceType::CIRCLE_EXCLUSION: {403read_offset += 8; // for latlon404read_offset += 4; // for radius405break;406}407case AC_PolyFenceType::RETURN_POINT:408read_offset += 8; // for latlon409break;410}411}412return true;413}414415// note read_offset here isn't const and ALSO is not a reference416void AC_PolyFence_loader::scan_eeprom_count_fences(const AC_PolyFenceType type, uint16_t read_offset)417{418if (type == AC_PolyFenceType::END_OF_STORAGE) {419return;420}421_eeprom_fence_count++;422switch (type) {423case AC_PolyFenceType::END_OF_STORAGE:424INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);425break;426case AC_PolyFenceType::POLYGON_EXCLUSION:427case AC_PolyFenceType::POLYGON_INCLUSION: {428const uint8_t vertex_count = fence_storage.read_uint8(read_offset+1); // skip type429_eeprom_item_count += vertex_count;430break;431}432case AC_PolyFenceType::CIRCLE_INCLUSION:433case AC_PolyFenceType::CIRCLE_EXCLUSION:434case AC_PolyFenceType::CIRCLE_INCLUSION_INT:435case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:436case AC_PolyFenceType::RETURN_POINT:437_eeprom_item_count++;438break;439}440}441442bool AC_PolyFence_loader::count_eeprom_fences()443{444_eeprom_fence_count = 0;445_eeprom_item_count = 0;446const bool ret = scan_eeprom(FUNCTOR_BIND_MEMBER(&AC_PolyFence_loader::scan_eeprom_count_fences, void, const AC_PolyFenceType, uint16_t));447return ret;448}449450void AC_PolyFence_loader::scan_eeprom_index_fences(const AC_PolyFenceType type, uint16_t read_offset)451{452if (_index == nullptr) {453INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);454return;455}456if (type == AC_PolyFenceType::END_OF_STORAGE) {457return;458}459FenceIndex &index = _index[_num_fences++];460index.type = type;461index.storage_offset = read_offset;462switch (type) {463case AC_PolyFenceType::END_OF_STORAGE:464INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);465break;466case AC_PolyFenceType::POLYGON_EXCLUSION:467case AC_PolyFenceType::POLYGON_INCLUSION: {468const uint8_t vertex_count = fence_storage.read_uint8(read_offset+1);469index.count = vertex_count;470break;471}472case AC_PolyFenceType::CIRCLE_INCLUSION_INT:473case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:474case AC_PolyFenceType::CIRCLE_INCLUSION:475case AC_PolyFenceType::CIRCLE_EXCLUSION:476index.count = 1;477break;478case AC_PolyFenceType::RETURN_POINT:479index.count = 1;480break;481}482}483484bool AC_PolyFence_loader::index_eeprom()485{486if (!formatted()) {487if (!format()) {488return false;489}490}491492if (!count_eeprom_fences()) {493return false;494}495496void_index();497498if (_eeprom_fence_count == 0) {499_num_fences = 0;500_load_attempted = false;501return true;502}503504Debug("Fence: Allocating %u bytes for index",505(unsigned)(_eeprom_fence_count*sizeof(FenceIndex)));506_index = NEW_NOTHROW FenceIndex[_eeprom_fence_count];507if (_index == nullptr) {508return false;509}510511_num_fences = 0;512if (!scan_eeprom(FUNCTOR_BIND_MEMBER(&AC_PolyFence_loader::scan_eeprom_index_fences, void, const AC_PolyFenceType, uint16_t))) {513void_index();514return false;515}516517#if CONFIG_HAL_BOARD == HAL_BOARD_SITL518if (_num_fences != _eeprom_fence_count) {519AP_HAL::panic("indexed fences not equal to eeprom fences");520}521#endif522523_load_attempted = false;524525return true;526}527528bool AC_PolyFence_loader::check_indexed()529{530if (!_index_attempted) {531_indexed = index_eeprom();532_index_attempted = true;533}534return _indexed;535}536537void AC_PolyFence_loader::unload()538{539delete[] _loaded_offsets_from_origin;540_loaded_offsets_from_origin = nullptr;541542delete[] _loaded_points_lla;543_loaded_points_lla = nullptr;544545delete[] _loaded_inclusion_boundary;546_loaded_inclusion_boundary = nullptr;547_num_loaded_inclusion_boundaries = 0;548549delete[] _loaded_exclusion_boundary;550_loaded_exclusion_boundary = nullptr;551_num_loaded_exclusion_boundaries = 0;552553delete[] _loaded_circle_inclusion_boundary;554_loaded_circle_inclusion_boundary = nullptr;555_num_loaded_circle_inclusion_boundaries = 0;556557delete[] _loaded_circle_exclusion_boundary;558_loaded_circle_exclusion_boundary = nullptr;559_num_loaded_circle_exclusion_boundaries = 0;560561_loaded_return_point = nullptr;562_loaded_return_point_lla = nullptr;563_load_time_ms = 0;564}565566// return the number of fences of type type in the index:567uint16_t AC_PolyFence_loader::index_fence_count(const AC_PolyFenceType type)568{569uint16_t ret = 0;570for (uint8_t i=0; i<_eeprom_fence_count; i++) {571const FenceIndex &index = _index[i];572if (index.type == type) {573ret++;574}575}576return ret;577}578579uint16_t AC_PolyFence_loader::sum_of_polygon_point_counts_and_returnpoint()580{581uint16_t ret = 0;582for (uint8_t i=0; i<_eeprom_fence_count; i++) {583const FenceIndex &index = _index[i];584switch (index.type) {585case AC_PolyFenceType::CIRCLE_INCLUSION_INT:586case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:587case AC_PolyFenceType::CIRCLE_INCLUSION:588case AC_PolyFenceType::CIRCLE_EXCLUSION:589break;590case AC_PolyFenceType::RETURN_POINT:591ret += 1;592break;593case AC_PolyFenceType::POLYGON_INCLUSION:594case AC_PolyFenceType::POLYGON_EXCLUSION:595ret += index.count;596break;597case AC_PolyFenceType::END_OF_STORAGE:598INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);599break;600}601}602return ret;603}604605bool AC_PolyFence_loader::load_from_eeprom()606{607if (!check_indexed()) {608return false;609}610611if (_load_attempted) {612return _load_time_ms != 0;613}614615Location ekf_origin{};616if (!AP::ahrs().get_origin(ekf_origin)) {617// Debug("fence load requires origin");618return false;619}620621// find indexes of each fence:622if (!get_loaded_fence_semaphore().take_nonblocking()) {623return false;624}625626_load_attempted = true;627628unload();629630if (_eeprom_item_count == 0) {631get_loaded_fence_semaphore().give();632_load_time_ms = AP_HAL::millis();633return true;634}635636{ // allocate array to hold offsets-from-origin637const uint16_t count = sum_of_polygon_point_counts_and_returnpoint();638Debug("Fence: Allocating %u bytes for points",639(unsigned)(count * sizeof(Vector2f)));640_loaded_offsets_from_origin = NEW_NOTHROW Vector2f[count];641_loaded_points_lla = NEW_NOTHROW Vector2l[count];642if (_loaded_offsets_from_origin == nullptr || _loaded_points_lla == nullptr) {643unload();644get_loaded_fence_semaphore().give();645return false;646}647}648649// FIXME: find some way of factoring out all of these allocation routines.650651{ // allocate storage for inclusion polyfences:652const auto count = index_fence_count(AC_PolyFenceType::POLYGON_INCLUSION);653Debug("Fence: Allocating %u bytes for inc. fences",654(unsigned)(count * sizeof(InclusionBoundary)));655_loaded_inclusion_boundary = NEW_NOTHROW InclusionBoundary[count];656if (_loaded_inclusion_boundary == nullptr) {657unload();658get_loaded_fence_semaphore().give();659return false;660}661}662663{ // allocate storage for exclusion polyfences:664const auto count = index_fence_count(AC_PolyFenceType::POLYGON_EXCLUSION);665Debug("Fence: Allocating %u bytes for exc. fences",666(unsigned)(count * sizeof(ExclusionBoundary)));667_loaded_exclusion_boundary = NEW_NOTHROW ExclusionBoundary[count];668if (_loaded_exclusion_boundary == nullptr) {669unload();670get_loaded_fence_semaphore().give();671return false;672}673}674675{ // allocate storage for circular inclusion fences:676uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION);677count += index_fence_count(AC_PolyFenceType::CIRCLE_INCLUSION_INT)678Debug("Fence: Allocating %u bytes for circ. inc. fences",679(unsigned)(count * sizeof(InclusionCircle)));680_loaded_circle_inclusion_boundary = NEW_NOTHROW InclusionCircle[count];681if (_loaded_circle_inclusion_boundary == nullptr) {682unload();683get_loaded_fence_semaphore().give();684return false;685}686}687688{ // allocate storage for circular exclusion fences:689uint32_t count = index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION);690count += index_fence_count(AC_PolyFenceType::CIRCLE_EXCLUSION_INT)691Debug("Fence: Allocating %u bytes for circ. exc. fences",692(unsigned)(count * sizeof(ExclusionCircle)));693_loaded_circle_exclusion_boundary = NEW_NOTHROW ExclusionCircle[count];694if (_loaded_circle_exclusion_boundary == nullptr) {695unload();696get_loaded_fence_semaphore().give();697return false;698}699}700701Vector2f *next_storage_point = _loaded_offsets_from_origin;702Vector2l *next_storage_point_lla = _loaded_points_lla;703704// use index to load fences from eeprom705bool storage_valid = true;706for (uint8_t i=0; i<_eeprom_fence_count; i++) {707if (!storage_valid) {708break;709}710const FenceIndex &index = _index[i];711uint16_t storage_offset = index.storage_offset;712storage_offset += 1; // skip type713switch (index.type) {714case AC_PolyFenceType::END_OF_STORAGE:715#if CONFIG_HAL_BOARD == HAL_BOARD_SITL716AP_HAL::panic("indexed end of storage found");717#endif718storage_valid = false;719break;720case AC_PolyFenceType::POLYGON_INCLUSION: {721// FIXME: consider factoring this with the EXCLUSION case722InclusionBoundary &boundary = _loaded_inclusion_boundary[_num_loaded_inclusion_boundaries];723boundary.points = next_storage_point;724boundary.points_lla = next_storage_point_lla;725boundary.count = index.count;726if (index.count < 3) {727GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: invalid polygon vertex count %u", index.count);728storage_valid = false;729break;730}731storage_offset += 1; // skip vertex count732if (!read_polygon_from_storage(ekf_origin, storage_offset, index.count, next_storage_point, next_storage_point_lla)) {733GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: polygon read failed");734storage_valid = false;735break;736}737_num_loaded_inclusion_boundaries++;738break;739}740case AC_PolyFenceType::POLYGON_EXCLUSION: {741ExclusionBoundary &boundary = _loaded_exclusion_boundary[_num_loaded_exclusion_boundaries];742boundary.points = next_storage_point;743boundary.points_lla = next_storage_point_lla;744boundary.count = index.count;745if (index.count < 3) {746GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: invalid polygon vertex count %u", index.count);747storage_valid = false;748break;749}750storage_offset += 1; // skip vertex count751if (!read_polygon_from_storage(ekf_origin, storage_offset, index.count, next_storage_point, next_storage_point_lla)) {752GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: polygon read failed");753storage_valid = false;754break;755}756_num_loaded_exclusion_boundaries++;757break;758}759case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:760case AC_PolyFenceType::CIRCLE_EXCLUSION: {761ExclusionCircle &circle = _loaded_circle_exclusion_boundary[_num_loaded_circle_exclusion_boundaries];762if (!read_latlon_from_storage(storage_offset, circle.point)) {763GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");764storage_valid = false;765break;766}767if (!scale_latlon_from_origin(ekf_origin, circle.point, circle.pos_cm)) {768GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");769storage_valid = false;770break;771}772// now read the radius773if (index.type == AC_PolyFenceType::CIRCLE_EXCLUSION_INT) {774circle.radius = fence_storage.read_uint32(storage_offset);775} else {776circle.radius = fence_storage.read_float(storage_offset);777}778if (!is_positive(circle.radius)) {779GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: non-positive circle radius");780storage_valid = false;781break;782}783_num_loaded_circle_exclusion_boundaries++;784break;785}786case AC_PolyFenceType::CIRCLE_INCLUSION_INT:787case AC_PolyFenceType::CIRCLE_INCLUSION: {788InclusionCircle &circle = _loaded_circle_inclusion_boundary[_num_loaded_circle_inclusion_boundaries];789if (!read_latlon_from_storage(storage_offset, circle.point)) {790GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");791storage_valid = false;792break;793}794if (!scale_latlon_from_origin(ekf_origin, circle.point, circle.pos_cm)){795GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: latlon read failed");796storage_valid = false;797break;798}799// now read the radius800if (index.type == AC_PolyFenceType::CIRCLE_INCLUSION_INT) {801circle.radius = fence_storage.read_uint32(storage_offset);802} else {803circle.radius = fence_storage.read_float(storage_offset);804}805if (!is_positive(circle.radius)) {806GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AC_Fence: non-positive circle radius");807storage_valid = false;808break;809}810_num_loaded_circle_inclusion_boundaries++;811break;812}813case AC_PolyFenceType::RETURN_POINT:814if (_loaded_return_point != nullptr) {815GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: Multiple return points found");816storage_valid = false;817break;818}819_loaded_return_point = next_storage_point;820if (_loaded_return_point_lla != nullptr) {821GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: Multiple return points found");822storage_valid = false;823break;824}825_loaded_return_point_lla = next_storage_point_lla;826// Read the point from storage827if (!read_latlon_from_storage(storage_offset, *next_storage_point_lla)) {828storage_valid = false;829GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: latlon read failed");830break;831}832if (!scale_latlon_from_origin(ekf_origin, *next_storage_point_lla, *next_storage_point)) {833storage_valid = false;834GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "PolyFence: latlon read failed");835break;836}837next_storage_point++;838next_storage_point_lla++;839break;840}841}842843if (!storage_valid) {844unload();845get_loaded_fence_semaphore().give();846return false;847}848849_load_time_ms = AP_HAL::millis();850851get_loaded_fence_semaphore().give();852return true;853}854855/// returns pointer to array of exclusion polygon points and num_points is filled in with the number of points in the polygon856/// points are offsets in cm from EKF origin in NE frame857Vector2f* AC_PolyFence_loader::get_exclusion_polygon(uint16_t index, uint16_t &num_points) const858{859if (index >= _num_loaded_exclusion_boundaries) {860num_points = 0;861return nullptr;862}863const ExclusionBoundary &boundary = _loaded_exclusion_boundary[index];864num_points = boundary.count;865866return boundary.points;867}868869/// returns pointer to array of inclusion polygon points and num_points is filled in with the number of points in the polygon870/// points are offsets in cm from EKF origin in NE frame871Vector2f* AC_PolyFence_loader::get_inclusion_polygon(uint16_t index, uint16_t &num_points) const872{873if (index >= _num_loaded_inclusion_boundaries) {874num_points = 0;875return nullptr;876}877const InclusionBoundary &boundary = _loaded_inclusion_boundary[index];878num_points = boundary.count;879880return boundary.points;881}882883/// returns the specified exclusion circle884/// circle center offsets in cm from EKF origin in NE frame, radius is in meters885bool AC_PolyFence_loader::get_exclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const886{887if (index >= _num_loaded_circle_exclusion_boundaries) {888return false;889}890center_pos_cm = _loaded_circle_exclusion_boundary[index].pos_cm;891radius = _loaded_circle_exclusion_boundary[index].radius;892return true;893}894895/// returns the specified inclusion circle896/// circle centre offsets in cm from EKF origin in NE frame, radius is in meters897bool AC_PolyFence_loader::get_inclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const898{899if (index >= _num_loaded_circle_inclusion_boundaries) {900return false;901}902center_pos_cm = _loaded_circle_inclusion_boundary[index].pos_cm;903radius = _loaded_circle_inclusion_boundary[index].radius;904return true;905}906907bool AC_PolyFence_loader::check_inclusion_circle_margin(float margin) const908{909// check circular includes910for (uint8_t i=0; i<_num_loaded_circle_inclusion_boundaries; i++) {911const InclusionCircle &circle = _loaded_circle_inclusion_boundary[i];912if (circle.radius < margin) {913// circle radius should never be less than margin914return false;915}916}917return true;918}919920bool AC_PolyFence_loader::validate_fence(const AC_PolyFenceItem *new_items, uint16_t count) const921{922// validate the fence items...923AC_PolyFenceType expecting_type = AC_PolyFenceType::END_OF_STORAGE;924uint16_t expected_type_count = 0;925uint16_t orig_expected_type_count = 0;926bool seen_return_point = false;927928for (uint16_t i=0; i<count; i++) {929bool validate_latlon = false;930931switch (new_items[i].type) {932case AC_PolyFenceType::END_OF_STORAGE:933#if CONFIG_HAL_BOARD == HAL_BOARD_SITL934AP_HAL::panic("passed in an END_OF_STORAGE");935#endif936return false;937938case AC_PolyFenceType::POLYGON_INCLUSION:939case AC_PolyFenceType::POLYGON_EXCLUSION:940if (new_items[i].vertex_count < 3) {941GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Invalid vertex count (%u)", new_items[i].vertex_count);942return false;943}944if (expected_type_count == 0) {945expected_type_count = new_items[i].vertex_count;946orig_expected_type_count = expected_type_count;947expecting_type = new_items[i].type;948} else {949if (new_items[i].type != expecting_type) {950GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Received incorrect vertex type (want=%u got=%u)", (unsigned)expecting_type, (unsigned)new_items[i].type);951return false;952} else if (new_items[i].vertex_count != orig_expected_type_count) {953GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Unexpected vertex count want=%u got=%u\n", orig_expected_type_count, new_items[i].vertex_count);954return false;955}956}957expected_type_count--;958validate_latlon = true;959break;960961case AC_PolyFenceType::CIRCLE_INCLUSION_INT:962case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:963// should never have AC_PolyFenceItems of these types964INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);965return false;966case AC_PolyFenceType::CIRCLE_INCLUSION:967case AC_PolyFenceType::CIRCLE_EXCLUSION:968if (expected_type_count) {969GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Received incorrect type (want=%u got=%u)", (unsigned)expecting_type, (unsigned)new_items[i].type);970return false;971}972if (!is_positive(new_items[i].radius)) {973GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Non-positive circle radius");974return false;975}976validate_latlon = true;977break;978979case AC_PolyFenceType::RETURN_POINT:980if (expected_type_count) {981GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Received incorrect type (want=%u got=%u)", (unsigned)expecting_type, (unsigned)new_items[i].type);982return false;983}984985// spec says only one return point allowed986if (seen_return_point) {987GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Multiple return points");988return false;989}990seen_return_point = true;991validate_latlon = true;992// TODO: ensure return point is within all fences and993// outside all exclusion zones994break;995}996997if (validate_latlon) {998if (!check_latlng(new_items[i].loc[0], new_items[i].loc[1])) {999GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Bad lat or lon");1000return false;1001}1002}1003}10041005if (expected_type_count) {1006GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Incorrect item count");1007return false;1008}10091010return true;1011}10121013uint16_t AC_PolyFence_loader::fence_storage_space_required(const AC_PolyFenceItem *new_items, uint16_t count)1014{1015uint16_t ret = 4; // for the format header1016uint16_t i = 0;1017while (i < count) {1018ret += 1; // one byte for type1019switch (new_items[i].type) {1020case AC_PolyFenceType::POLYGON_INCLUSION:1021case AC_PolyFenceType::POLYGON_EXCLUSION:1022ret += 1 + 8 * new_items[i].vertex_count; // 1 count, 4 lat, 4 lon for each point1023i += new_items[i].vertex_count - 1; // i is incremented down below1024break;1025case AC_PolyFenceType::END_OF_STORAGE:1026INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);1027break;1028case AC_PolyFenceType::CIRCLE_INCLUSION_INT:1029case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:1030// should never have AC_PolyFenceItems of these types1031INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);1032break;1033case AC_PolyFenceType::CIRCLE_INCLUSION:1034case AC_PolyFenceType::CIRCLE_EXCLUSION:1035ret += 12; // 4 radius, 4 lat, 4 lon1036break;1037case AC_PolyFenceType::RETURN_POINT:1038ret += 8; // 4 lat, 4 lon1039break;1040}1041i++;1042}1043return ret;1044}10451046bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_t count)1047{1048if (!validate_fence(new_items, count)) {1049GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Fence validation failed");1050return false;1051}10521053if (fence_storage_space_required(new_items, count) > fence_storage.size()) {1054GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Fence exceeds storage size");1055return false;1056}10571058if (!format()) {1059return false;1060}10611062uint16_t total_vertex_count = 0;1063uint16_t offset = 4; // skipping magic1064uint8_t vertex_count = 0;1065for (uint16_t i=0; i<count; i++) {1066const AC_PolyFenceItem new_item = new_items[i];1067switch (new_item.type) {1068case AC_PolyFenceType::POLYGON_INCLUSION:1069case AC_PolyFenceType::POLYGON_EXCLUSION:1070if (vertex_count == 0) {1071// write out new polygon count1072vertex_count = new_item.vertex_count;1073total_vertex_count += vertex_count;1074if (!write_type_to_storage(offset, new_item.type)) {1075return false;1076}1077fence_storage.write_uint8(offset, vertex_count);1078offset++;1079}1080vertex_count--;1081if (!write_latlon_to_storage(offset, new_item.loc)) {1082return false;1083}1084break;1085case AC_PolyFenceType::END_OF_STORAGE:1086#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1087AP_HAL::panic("asked to store end-of-storage marker");1088#endif1089return false;1090case AC_PolyFenceType::CIRCLE_INCLUSION_INT:1091case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:1092// should never have AC_PolyFenceItems of these types1093INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);1094return false;1095case AC_PolyFenceType::CIRCLE_INCLUSION:1096case AC_PolyFenceType::CIRCLE_EXCLUSION: {1097total_vertex_count++; // useful to make number of lines in QGC file match FENCE_TOTAL1098const bool store_as_int = (new_item.radius - int(new_item.radius) < 0.001);1099AC_PolyFenceType store_type = new_item.type;1100if (store_as_int) {1101if (new_item.type == AC_PolyFenceType::CIRCLE_INCLUSION) {1102store_type = AC_PolyFenceType::CIRCLE_INCLUSION_INT;1103} else {1104store_type = AC_PolyFenceType::CIRCLE_EXCLUSION_INT;1105}1106}11071108if (!write_type_to_storage(offset, store_type)) {1109return false;1110}1111if (!write_latlon_to_storage(offset, new_item.loc)) {1112return false;1113}1114// store the radius. If the radius is very close to an1115// integer then we store it as an integer so users moving1116// from 4.1 back to 4.0 might be less-disrupted.1117if (store_as_int) {1118fence_storage.write_uint32(offset, new_item.radius);1119} else {1120fence_storage.write_float(offset, new_item.radius);1121}1122offset += 4;1123break;1124}1125case AC_PolyFenceType::RETURN_POINT:1126if (!write_type_to_storage(offset, new_item.type)) {1127return false;1128}1129if (!write_latlon_to_storage(offset, new_item.loc)) {1130return false;1131}1132break;1133}1134}1135if (!write_eos_to_storage(offset)) {1136return false;1137}11381139#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1140// sanity-check the EEPROM in SITL to make sure we can read what1141// we've just written.1142if (!index_eeprom()) {1143AP_HAL::panic("Failed to index eeprom");1144}1145GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Fence Indexed OK");1146#endif11471148#if HAL_LOGGING_ENABLED1149// start logger logging new fence1150AP::logger().Write_Fence();1151#endif11521153void_index();11541155// this may be completely bogus total. If we are storing an1156// advanced fence then the old protocol which relies on this value1157// will error off if the GCS tries to fetch points. This number1158// should be correct for a "compatible" fence, however.1159uint16_t new_total = 0;1160if (total_vertex_count < 3) {1161new_total = 0;1162} else {1163new_total = total_vertex_count+2;1164}1165_total.set_and_save(new_total);11661167return true;1168}116911701171bool AC_PolyFence_loader::get_return_point(Vector2l &ret)1172{1173if (!check_indexed()) {1174return false;1175}11761177const FenceIndex *rp = find_first_fence(AC_PolyFenceType::RETURN_POINT);1178if (rp != nullptr) {1179uint16_t read_offset = rp->storage_offset + 1;1180return read_latlon_from_storage(read_offset, ret);1181}11821183const FenceIndex *inc = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);1184if (inc == nullptr) {1185return false;1186}11871188// we found an inclusion fence but not a return point. Calculate1189// and return the centroid. Note that this may not actually be1190// inside all inclusion fences...1191uint16_t offset = inc->storage_offset;1192if ((AC_PolyFenceType)fence_storage.read_uint8(offset) != AC_PolyFenceType::POLYGON_INCLUSION) {1193#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1194AP_HAL::panic("wrong type at offset");1195#endif1196return false;1197}1198offset++;1199const uint8_t count = fence_storage.read_uint8(offset);1200if (count < 3) {1201#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1202AP_HAL::panic("invalid count found");1203#endif1204return false;1205}1206offset++;1207Vector2l min_loc;1208if (!read_latlon_from_storage(offset, min_loc)) {1209return false;1210}1211if (min_loc.is_zero()) {1212return false;1213}1214Vector2l max_loc = min_loc;1215for (uint8_t i=1; i<count; i++) {1216Vector2l new_loc;1217if (!read_latlon_from_storage(offset, new_loc)) {1218return false;1219}1220if (new_loc.is_zero()) {1221return false;1222}1223if (new_loc.x < min_loc.x) {1224min_loc.x = new_loc.x;1225}1226if (new_loc.y < min_loc.y) {1227min_loc.y = new_loc.y;1228}1229if (new_loc.x > max_loc.x) {1230max_loc.x = new_loc.x;1231}1232if (new_loc.y > max_loc.y) {1233max_loc.y = new_loc.y;1234}1235}12361237// Potential for int32_t overflow when longitudes are beyond [-107, 107].1238// As a result, the calculated return point's longitude is calculated using overflowed figure.1239// Dividing first before adding avoids the potential overflow.1240ret.x = (min_loc.x / 2) + (max_loc.x / 2);1241ret.y = (min_loc.y / 2) + (max_loc.y / 2);12421243return true;1244}12451246AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::find_first_fence(const AC_PolyFenceType type) const1247{1248if (_index == nullptr) {1249return nullptr;1250}1251for (uint8_t i=0; i<_num_fences; i++) {1252if (_index[i].type == type) {1253return &_index[i];1254}1255}1256return nullptr;1257}12581259#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT1260void AC_PolyFence_loader::handle_msg_fetch_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg)1261{1262if (!check_indexed()) {1263return;1264}1265if (!contains_compatible_fence()) {1266link.send_text(MAV_SEVERITY_WARNING, "Vehicle contains advanced fences");1267return;1268}12691270if (_total != 0 && _total < 5) {1271link.send_text(MAV_SEVERITY_WARNING, "Invalid FENCE_TOTAL");1272return;1273}12741275mavlink_fence_fetch_point_t packet;1276mavlink_msg_fence_fetch_point_decode(&msg, &packet);12771278if (packet.idx >= _total) {1279link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, index past total(%u >= %u)", packet.idx, _total.get());1280return;1281}12821283mavlink_fence_point_t ret_packet{};1284ret_packet.target_system = msg.sysid;1285ret_packet.target_component = msg.compid;1286ret_packet.idx = packet.idx;1287ret_packet.count = _total;12881289if (packet.idx == 0) {1290// return point1291Vector2l ret;1292if (get_return_point(ret)) {1293ret_packet.lat = ret.x * 1.0e-7f;1294ret_packet.lng = ret.y * 1.0e-7f;1295} else {1296link.send_text(MAV_SEVERITY_WARNING, "Failed to get return point");1297}1298} else {1299// find the inclusion fence:1300const FenceIndex *inclusion_fence = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);1301if (inclusion_fence == nullptr) {1302// nothing stored yet; just send back zeroes1303ret_packet.lat = 0;1304ret_packet.lng = 0;1305} else {1306uint8_t fencepoint_offset; // 1st idx is return point1307if (packet.idx == _total-1) {1308// the is the loop closure point - send the first point again1309fencepoint_offset = 0;1310} else {1311fencepoint_offset = packet.idx - 1;1312}1313if (fencepoint_offset >= inclusion_fence->count) {1314// we haven't been given a value for this item yet; we will return zeroes1315} else {1316uint16_t storage_offset = inclusion_fence->storage_offset;1317storage_offset++; // skip over type1318storage_offset++; // skip over count1319storage_offset += 8*fencepoint_offset; // move to point we're interested in1320Vector2l bob;1321if (!read_latlon_from_storage(storage_offset, bob)) {1322link.send_text(MAV_SEVERITY_WARNING, "Fence read failed");1323#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1324AP_HAL::panic("read failure");1325#endif1326return;1327}1328ret_packet.lat = bob[0] * 1.0e-7f;1329ret_packet.lng = bob[1] * 1.0e-7f;1330}1331}1332}13331334link.send_message(MAVLINK_MSG_ID_FENCE_POINT, (const char*)&ret_packet);1335}13361337AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::get_or_create_return_point()1338{1339if (!check_indexed()) {1340return nullptr;1341}1342FenceIndex *return_point = find_first_fence(AC_PolyFenceType::RETURN_POINT);1343if (return_point != nullptr) {1344return return_point;1345}13461347// if the inclusion fence exists we will move it in storage to1348// avoid having to continually shift the return point forward as1349// we receive fence points1350uint16_t offset;1351const FenceIndex *inclusion_fence = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);1352if (inclusion_fence != nullptr) {1353offset = inclusion_fence->storage_offset;1354// the "9"s below represent the size of a return point in storage1355for (uint8_t i=0; i<inclusion_fence->count; i++) {1356// we are shifting the last fence point first - so 'i=0'1357// means the last point stored.1358const uint16_t point_storage_offset = offset + 2 + (inclusion_fence->count-1-i) * 8;1359Vector2l latlon;1360uint16_t tmp_read_offs = point_storage_offset;1361if (!read_latlon_from_storage(tmp_read_offs, latlon)) {1362return nullptr;1363}1364uint16_t write_offset = point_storage_offset + 9;1365if (!write_latlon_to_storage(write_offset, latlon)) {1366return nullptr;1367}1368}1369// read/write the count:1370const uint8_t count = fence_storage.read_uint8(inclusion_fence->storage_offset+1);1371fence_storage.write_uint8(inclusion_fence->storage_offset + 1 + 9, count);1372// read/write the type:1373const uint8_t t = fence_storage.read_uint8(inclusion_fence->storage_offset);1374fence_storage.write_uint8(inclusion_fence->storage_offset + 9, t);13751376uint16_t write_offset = offset + 2 + 8*inclusion_fence->count + 9;1377if (!write_eos_to_storage(write_offset)) {1378return nullptr;1379}1380} else {1381if (fence_storage.read_uint8(_eos_offset) != (uint8_t)AC_PolyFenceType::END_OF_STORAGE) {1382#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1383AP_HAL::panic("Expected end-of-storage marker at offset=%u",1384_eos_offset);1385#endif1386return nullptr;1387}1388offset = _eos_offset;1389}13901391if (!write_type_to_storage(offset, AC_PolyFenceType::RETURN_POINT)) {1392return nullptr;1393}1394if (!write_latlon_to_storage(offset, Vector2l{0, 0})) {1395return nullptr;1396}1397if (inclusion_fence == nullptr) {1398if (!write_eos_to_storage(offset)) {1399return nullptr;1400}1401}14021403if (!index_eeprom()) {1404#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1405AP_HAL::panic("Failed to index eeprom after moving inclusion fence for return point");1406#endif1407return nullptr;1408}14091410return_point = find_first_fence(AC_PolyFenceType::RETURN_POINT);1411if (return_point == nullptr) {1412#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1413AP_HAL::panic("Failed to get return point after indexing");1414#endif1415}1416return return_point;1417}14181419AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::get_or_create_include_fence()1420{1421if (!check_indexed()) {1422return nullptr;1423}1424FenceIndex *inclusion = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);1425if (inclusion != nullptr) {1426return inclusion;1427}1428if (_total < 5) {1429return nullptr;1430}1431if (!write_type_to_storage(_eos_offset, AC_PolyFenceType::POLYGON_INCLUSION)) {1432return nullptr;1433}1434fence_storage.write_uint8(_eos_offset, 0);1435_eos_offset++;1436if (!write_eos_to_storage(_eos_offset)) {1437return nullptr;1438}14391440if (!index_eeprom()) {1441#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1442AP_HAL::panic("Failed to index eeprom after creating fence");1443#endif1444return nullptr;1445}1446AC_PolyFence_loader::FenceIndex *ret = find_first_fence(AC_PolyFenceType::POLYGON_INCLUSION);1447#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1448if (ret == nullptr) {1449AP_HAL::panic("Failed to index eeprom after creating fence");1450}1451#endif1452return ret;1453}14541455void AC_PolyFence_loader::handle_msg_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg)1456{1457if (!check_indexed()) {1458return;1459}14601461mavlink_fence_point_t packet;1462mavlink_msg_fence_point_decode(&msg, &packet);14631464if (_total != 0 && _total < 5) {1465link.send_text(MAV_SEVERITY_WARNING, "Invalid FENCE_TOTAL");1466return;1467}14681469if (packet.count != _total) {1470link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, bad count (%u vs %u)", packet.count, _total.get());1471return;1472}14731474if (packet.idx >= _total) {1475// this is a protocol failure1476link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, index past total (%u >= %u)", packet.idx, _total.get());1477return;1478}14791480if (!check_latlng(packet.lat, packet.lng)) {1481link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, bad lat or lng");1482return;1483}14841485if (!contains_compatible_fence()) {1486// the GCS has started to upload using the old protocol;1487// ensure we can accept it. We must be able to index the1488// fence, so it must be valid (minimum number of points)1489if (!format()) {1490return;1491}1492}14931494const Vector2l point{1495(int32_t)(packet.lat*1.0e7f),1496(int32_t)(packet.lng*1.0e7f)1497};14981499if (packet.idx == 0) {1500// this is the return point; if we have a return point then1501// update it, otherwise create a return point fence thingy1502const FenceIndex *return_point = get_or_create_return_point();1503if (return_point == nullptr) {1504#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1505AP_HAL::panic("Didn't get return point");1506#endif1507return;1508}1509uint16_t offset = return_point->storage_offset;1510offset++; // don't overwrite the type!1511if (!write_latlon_to_storage(offset, point)) {1512link.send_text(MAV_SEVERITY_WARNING, "PolyFence: storage write failed");1513return;1514}1515} else if (packet.idx == _total-1) {1516/* this is the fence closing point. We use this to set the vertex1517count of the inclusion fence1518*/1519const FenceIndex *inclusion_fence = get_or_create_include_fence();1520if (inclusion_fence == nullptr) {1521return;1522}1523// write type and length1524fence_storage.write_uint8(inclusion_fence->storage_offset, uint8_t(AC_PolyFenceType::POLYGON_INCLUSION));1525fence_storage.write_uint8(inclusion_fence->storage_offset+1, packet.idx-1);1526// and write end of storage marker1527fence_storage.write_uint8(inclusion_fence->storage_offset+2+(packet.idx-1)*8, uint8_t(AC_PolyFenceType::END_OF_STORAGE));1528void_index();1529} else {1530const FenceIndex *inclusion_fence = get_or_create_include_fence();1531if (inclusion_fence == nullptr) {1532#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1533AP_HAL::panic("no inclusion fences found");1534#endif1535return;1536}1537uint16_t offset = inclusion_fence->storage_offset;1538offset++; // skip type1539if (packet.idx > inclusion_fence->count) {1540// expand the storage space1541fence_storage.write_uint8(offset, packet.idx); // remembering that idx[0] is the return point....1542}1543offset++; // move past number of points1544offset += (packet.idx-1)*8;1545if (!write_latlon_to_storage(offset, point)) {1546link.send_text(MAV_SEVERITY_WARNING, "PolyFence: storage write failed");1547return;1548}1549if (_eos_offset < offset) {1550if (!write_eos_to_storage(offset)) {1551return;1552}1553}1554void_index();1555}1556}15571558bool AC_PolyFence_loader::contains_compatible_fence() const1559{1560// must contain a single inclusion fence with an optional return point1561if (_index == nullptr) {1562// this indicates no boundary points present1563return true;1564}1565bool seen_return_point = false;1566bool seen_poly_inclusion = false;1567for (uint16_t i=0; i<_num_fences; i++) {1568switch (_index[i].type) {1569case AC_PolyFenceType::END_OF_STORAGE:1570#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1571AP_HAL::panic("end-of-storage marker found in loaded list");1572#endif1573return false;1574case AC_PolyFenceType::POLYGON_INCLUSION:1575if (seen_poly_inclusion) {1576return false;1577}1578seen_poly_inclusion = true;1579break;1580case AC_PolyFenceType::CIRCLE_INCLUSION_INT:1581case AC_PolyFenceType::CIRCLE_EXCLUSION_INT:1582case AC_PolyFenceType::POLYGON_EXCLUSION:1583case AC_PolyFenceType::CIRCLE_INCLUSION:1584case AC_PolyFenceType::CIRCLE_EXCLUSION:1585return false;1586case AC_PolyFenceType::RETURN_POINT:1587if (seen_return_point) {1588return false;1589}1590seen_return_point = true;1591break;1592}1593}1594return true;1595}15961597#endif // AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT15981599bool AC_PolyFence_loader::write_eos_to_storage(uint16_t &offset)1600{1601if (!write_type_to_storage(offset, AC_PolyFenceType::END_OF_STORAGE)) {1602return false;1603}1604_eos_offset = offset - 1; // should point to the marker1605return true;1606}16071608/// handler for polygon fence messages with GCS1609void AC_PolyFence_loader::handle_msg(GCS_MAVLINK &link, const mavlink_message_t& msg)1610{1611switch (msg.msgid) {1612#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT1613case MAVLINK_MSG_ID_FENCE_POINT:1614handle_msg_fence_point(link, msg);1615break;1616case MAVLINK_MSG_ID_FENCE_FETCH_POINT:1617handle_msg_fetch_fence_point(link, msg);1618break;1619#endif1620default:1621break;1622}1623}16241625void AC_PolyFence_loader::update()1626{1627#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT1628// if an older GCS sets the fence point count to zero then clear the fence1629if (_old_total != _total) {1630_old_total = _total;1631if (_total == 0 && _eeprom_fence_count) {1632if (!format()) {1633// we are in all sorts of trouble1634return;1635}1636}1637}1638#endif1639if (!load_from_eeprom()) {1640return;1641}1642}16431644#else // build type is not appropriate; provide a dummy implementation:16451646void AC_PolyFence_loader::init() {};16471648bool AC_PolyFence_loader::get_item(const uint16_t seq, AC_PolyFenceItem &item) { return false; }16491650Vector2f* AC_PolyFence_loader::get_exclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; }1651Vector2f* AC_PolyFence_loader::get_inclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; }16521653bool AC_PolyFence_loader::get_exclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const { return false; }1654bool AC_PolyFence_loader::get_inclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const { return false; }16551656void AC_PolyFence_loader::handle_msg(GCS_MAVLINK &link, const mavlink_message_t& msg) {};16571658bool AC_PolyFence_loader::breached() const { return false; }1659bool AC_PolyFence_loader::breached(const Location& loc) const { return false; }16601661uint16_t AC_PolyFence_loader::max_items() const { return 0; }16621663bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_t count) { return false; }16641665void AC_PolyFence_loader::update() {};16661667#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT1668bool AC_PolyFence_loader::get_return_point(Vector2l &ret) { return false; }1669#endif16701671#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED1672#endif // AP_FENCE_ENABLED167316741675