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.h
Views: 1798
#pragma once12#include "AC_Fence_config.h"3#include <AP_Math/AP_Math.h>45// CIRCLE_INCLUSION_INT stores the radius an a 32-bit integer in6// metres. This was a bug, and CIRCLE_INCLUSION was created to store7// as a 32-bit float instead. We save as _INT in the case that the8// radius looks like an integer as a backwards-compatibility measure.9// For 4.2 we might consider only loading _INT and always saving as10// float, and in 4.3 considering _INT invalid11enum class AC_PolyFenceType : uint8_t {12END_OF_STORAGE = 99,13POLYGON_INCLUSION = 98,14POLYGON_EXCLUSION = 97,15CIRCLE_EXCLUSION_INT = 96,16RETURN_POINT = 95,17CIRCLE_INCLUSION_INT = 94,18CIRCLE_EXCLUSION = 93,19CIRCLE_INCLUSION = 92,20};2122// a FenceItem is just a means of passing data about an item into23// and out of the polyfence loader. It uses a AC_PolyFenceType to24// indicate the item type, assuming each fence type is made up of25// only one sort of item.26// TODO: make this a union (or use subclasses) to save memory27class AC_PolyFenceItem {28public:29AC_PolyFenceType type;30Vector2l loc;31uint8_t vertex_count;32float radius;33};3435#if AP_FENCE_ENABLED3637#include <AP_Common/AP_Common.h>38#include <AP_Common/Location.h>39#include <GCS_MAVLink/GCS_MAVLink.h>4041class AC_PolyFence_loader42{4344public:4546AC_PolyFence_loader(AP_Int8 &total, const AP_Int16 &options) :47_total(total),48_options(options) {}4950/* Do not allow copies */51CLASS_NO_COPY(AC_PolyFence_loader);5253void init();5455// methods primarily for MissionItemProtocol_Fence to use:56// return the total number of points stored57uint16_t num_stored_items() const { return _eeprom_item_count; }58bool get_item(const uint16_t seq, AC_PolyFenceItem &item) WARN_IF_UNUSED;5960///61/// exclusion polygons62///63/// returns number of polygon exclusion zones defined64uint8_t get_exclusion_polygon_count() const {65return _num_loaded_exclusion_boundaries;66}6768/// returns pointer to array of exclusion polygon points and num_points is filled in with the number of points in the polygon69/// points are offsets in cm from EKF origin in NE frame70Vector2f* get_exclusion_polygon(uint16_t index, uint16_t &num_points) const;7172/// return system time of last update to the exclusion polygon points73uint32_t get_exclusion_polygon_update_ms() const {74return _load_time_ms;75}7677///78/// inclusion polygons79///80/// returns number of polygon inclusion zones defined81uint8_t get_inclusion_polygon_count() const {82return _num_loaded_inclusion_boundaries;83}8485/// returns pointer to array of inclusion polygon points and num_points is filled in with the number of points in the polygon86/// points are offsets in cm from EKF origin in NE frame87Vector2f* get_inclusion_polygon(uint16_t index, uint16_t &num_points) const;8889/// return system time of last update to the inclusion polygon points90uint32_t get_inclusion_polygon_update_ms() const {91return _load_time_ms;92}9394///95/// exclusion circles96///97/// returns number of exclusion circles defined98uint8_t get_exclusion_circle_count() const {99return _num_loaded_circle_exclusion_boundaries;100}101102/// returns the specified exclusion circle103/// center is offsets in cm from EKF origin in NE frame, radius is in meters104bool get_exclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const;105106/// return system time of last update to the exclusion circles107uint32_t get_exclusion_circle_update_ms() const {108return _load_time_ms;109}110111///112/// inclusion circles113///114/// returns number of inclusion circles defined115uint8_t get_inclusion_circle_count() const {116return _num_loaded_circle_inclusion_boundaries;117}118119/// returns the specified inclusion circle120/// center is offsets in cm from EKF origin in NE frame, radius is in meters121bool get_inclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const;122123// false if margin < fence radius124bool check_inclusion_circle_margin(float margin) const;125126///127/// mavlink128///129/// handler for polygon fence messages with GCS130void handle_msg(class GCS_MAVLINK &link, const mavlink_message_t& msg);131132// breached() - returns true if the vehicle has breached any fence133bool breached() const WARN_IF_UNUSED;134// breached(Location&) - returns true if location is outside the boundary135bool breached(const Location& loc) const WARN_IF_UNUSED;136137// returns true if a polygonal include fence could be returned138bool inclusion_boundary_available() const WARN_IF_UNUSED {139return _num_loaded_inclusion_boundaries != 0;140}141142// loaded - returns true if the fences have been loaded from143// storage and are available for use144bool loaded() const WARN_IF_UNUSED {145return _load_time_ms != 0;146};147148// maximum number of fence points we can store in eeprom149uint16_t max_items() const;150151// write_fence - validate and write count new_items to permanent storage152bool write_fence(const AC_PolyFenceItem *new_items, uint16_t count) WARN_IF_UNUSED;153154/*155* Loaded Fence functionality156*157* methods and members to do with fences stored in memory. The158* locations are translated into offset-from-origin-in-metres159*/160161// load polygon points stored in eeprom into162// _loaded_offsets_from_origin and perform validation. returns163// true if load successfully completed164bool load_from_eeprom() WARN_IF_UNUSED;165166// allow threads to lock against AHRS update167HAL_Semaphore &get_loaded_fence_semaphore(void) {168return _loaded_fence_sem;169}170171// call @10Hz to check for fence load being valid172void update();173174// get_return_point - returns latitude/longitude of return point.175// This works with storage - the returned vector is absolute176// lat/lon.177bool get_return_point(Vector2l &ret) WARN_IF_UNUSED;178179// return total number of fences - polygons and circles180uint16_t total_fence_count() const {181return (get_exclusion_polygon_count() +182get_inclusion_polygon_count() +183get_exclusion_circle_count() +184get_inclusion_circle_count());185}186187188#if AP_SDCARD_STORAGE_ENABLED189bool failed_sdcard_storage(void) const {190return _failed_sdcard_storage;191}192#endif193194private:195// multi-thread access support196HAL_Semaphore _loaded_fence_sem;197198/*199* Fence storage Index related functions200*/201// FenceIndex - a class used to store information about a fence in202// fence storage.203class FenceIndex {204public:205AC_PolyFenceType type;206uint16_t count;207uint16_t storage_offset;208};209// index_fence_count - returns the number of fences of type210// currently in the index211uint16_t index_fence_count(const AC_PolyFenceType type);212213// void_index - free resources for the index, forcing a reindex214// (typically via check_indexed)215void void_index() {216delete[] _index;217_index = nullptr;218_index_attempted = false;219_indexed = false;220}221222// check_indexed - read eeprom and create index if the index does223// not already exist224bool check_indexed() WARN_IF_UNUSED;225226// find_first_fence - return first fence in index of specific type227FenceIndex *find_first_fence(const AC_PolyFenceType type) const;228229// find_index_for_seq - returns true if seq is contained within a230// fence. If it is, entry will be the relevant FenceIndex. i231// will be the offset within _loaded_offsets_from_origin where the232// first point in the fence is found233bool find_index_for_seq(const uint16_t seq, const FenceIndex *&entry, uint16_t &i) const WARN_IF_UNUSED;234// find_storage_offset_for_seq - uses the index to return an235// offset into storage for an item236bool find_storage_offset_for_seq(const uint16_t seq, uint16_t &offset, AC_PolyFenceType &type, uint16_t &vertex_count_offset) const WARN_IF_UNUSED;237238uint16_t sum_of_polygon_point_counts_and_returnpoint();239240/*241* storage-related methods - dealing with fence_storage242*/243244// new_fence_storage_magic - magic number indicating fence storage245// has been formatted for use by polygon fence storage code.246// FIXME: ensure this is out-of-band for old lat/lon point storage247static const uint8_t new_fence_storage_magic = 235;248249// validate_fence - returns true if new_items look completely valid250bool validate_fence(const AC_PolyFenceItem *new_items, uint16_t count) const WARN_IF_UNUSED;251252// _eos_offset - stores the offset in storage of the253// end-of-storage marker. Used by low-level manipulation code to254// extend storage255uint16_t _eos_offset;256257// formatted - returns true if the fence storage space seems to be258// formatted for new-style fence storage259bool formatted() const WARN_IF_UNUSED;260// format - format the storage space for use by261// the new polyfence code262bool format() WARN_IF_UNUSED;263264265/*266* Loaded Fence functionality267*268* methods and members to do with fences stored in memory. The269* locations are translated into offset-from-origin-in-metres270*/271272// remove resources dedicated to the transformed fences - for273// example, in _loaded_offsets_from_origin274void unload();275276// pointer into _loaded_offsets_from_origin where the return point277// can be found:278Vector2f *_loaded_return_point;279280// pointer into _loaded_points_lla where the return point281// can be found:282Vector2l *_loaded_return_point_lla;283284class InclusionBoundary {285public:286Vector2f *points; // pointer into the _loaded_offsets_from_origin array287Vector2l *points_lla; // pointer into the _loaded_points_lla array288uint8_t count; // count of points in the boundary289};290InclusionBoundary *_loaded_inclusion_boundary;291292uint8_t _num_loaded_inclusion_boundaries;293294class ExclusionBoundary {295public:296Vector2f *points; // pointer into the _loaded_offsets_from_origin array297Vector2l *points_lla; // pointer into the _loaded_points_lla_lla array298uint8_t count; // count of points in the boundary299};300ExclusionBoundary *_loaded_exclusion_boundary;301302uint8_t _num_loaded_exclusion_boundaries;303304// _loaded_offsets_from_origin - stores x/y offset-from-origin305// coordinate pairs. Various items store their locations in this306// allocation - the polygon boundaries and the return point, for307// example.308Vector2f *_loaded_offsets_from_origin;309Vector2l *_loaded_points_lla;310311class ExclusionCircle {312public:313Vector2f pos_cm; // vector offset from home in cm314Vector2l point; // lat/lng of zone315float radius;316};317ExclusionCircle *_loaded_circle_exclusion_boundary;318319uint8_t _num_loaded_circle_exclusion_boundaries;320321class InclusionCircle {322public:323Vector2f pos_cm; // vector offset from home in cm324Vector2l point; // lat/lng of zone325float radius;326};327InclusionCircle *_loaded_circle_inclusion_boundary;328329uint8_t _num_loaded_circle_inclusion_boundaries;330331// _load_attempted - true if we have attempted to load the fences332// from storage into _loaded_circle_exclusion_boundary,333// _loaded_offsets_from_origin etc etc334bool _load_attempted;335336// _load_time_ms - from millis(), system time when fence load last337// succeeded. Will be zero if fences are not loaded338uint32_t _load_time_ms;339340// scale_latlon_from_origin - given a latitude/longitude341// transforms the point to an offset-from-origin and deposits342// the result into pos_cm.343bool scale_latlon_from_origin(const Location &origin,344const Vector2l &point,345Vector2f &pos_cm) WARN_IF_UNUSED;346347// read_polygon_from_storage - reads vertex_count348// latitude/longitude points from offset in permanent storage,349// transforms them into an offset-from-origin and deposits the350// results into next_storage_point.351bool read_polygon_from_storage(const Location &origin,352uint16_t &read_offset,353const uint8_t vertex_count,354Vector2f *&next_storage_point,355Vector2l *&next_storage_point_lla) WARN_IF_UNUSED;356357#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT358/*359* FENCE_POINT protocol compatibility360*/361void handle_msg_fetch_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg);362void handle_msg_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg);363// contains_compatible_fence - returns true if the permanent fence364// storage contains fences that are compatible with the old365// FENCE_POINT protocol.366bool contains_compatible_fence() const WARN_IF_UNUSED;367368// get_or_create_include_fence - returns a point to an include369// fence to be used for the FENCE_POINT-supplied polygon. May370// format the storage appropriately.371FenceIndex *get_or_create_include_fence();372// get_or_create_include_fence - returns a point to a return point373// to be used for the FENCE_POINT-supplied return point. May374// format the storage appropriately.375FenceIndex *get_or_create_return_point();376#endif377378// primitives to write parts of fencepoints out:379bool write_type_to_storage(uint16_t &offset, AC_PolyFenceType type) WARN_IF_UNUSED;380bool write_latlon_to_storage(uint16_t &offset, const Vector2l &latlon) WARN_IF_UNUSED;381bool read_latlon_from_storage(uint16_t &read_offset, Vector2l &latlon) const WARN_IF_UNUSED;382383// methods to write specific types of fencepoint out:384bool write_eos_to_storage(uint16_t &offset);385386// _total - reference to FENCE_TOTAL parameter. This is used387// solely for compatibility with the FENCE_POINT protocol388AP_Int8 &_total;389const AP_Int16 &_options;390uint8_t _old_total;391392393// scan_eeprom - a method that traverses the fence storage area,394// calling the supplied callback for each fence found. If the395// scan fails (for example, the storage is corrupt), then this396// method will return false.397FUNCTOR_TYPEDEF(scan_fn_t, void, const AC_PolyFenceType, uint16_t);398bool scan_eeprom(scan_fn_t scan_fn) WARN_IF_UNUSED;399// scan_eeprom_count_fences - a static function designed to be400// massed to scan_eeprom which counts the number of fences and401// fence items present. The results of this counting appear in _eeprom_fence_count and _eeprom_item_count402void scan_eeprom_count_fences(const AC_PolyFenceType type, uint16_t read_offset);403uint16_t _eeprom_fence_count;404uint16_t _eeprom_item_count;405406// scan_eeprom_index_fences - a static function designed to be407// passed to scan_eeprom. _index must be a pointer to408// memory sufficient to hold information about all fences present409// in storage - so it is expected that scan_eeprom_count_fences410// has been used to count those fences and the allocation already411// made. After this method has been called _index will412// be filled with information about the fences in the fence413// storage - type, item counts and storage offset.414void scan_eeprom_index_fences(const AC_PolyFenceType type, uint16_t read_offset);415// array specifying type of each fence in storage (and a count of416// items in that fence)417FenceIndex *_index;418bool _indexed; // true if indexing successful419bool _index_attempted; // true if we attempted to index the eeprom420// _num_fences - count of the number of fences in _index. This421// should be equal to _eeprom_fence_count422uint16_t _num_fences;423424// count_eeprom_fences - refresh the count of fences in permanent storage425bool count_eeprom_fences() WARN_IF_UNUSED;426// index_eeprom - (re)allocate and fill in _index427bool index_eeprom() WARN_IF_UNUSED;428429uint16_t fence_storage_space_required(const AC_PolyFenceItem *new_items, uint16_t count);430431#if AP_SDCARD_STORAGE_ENABLED432// true if we failed to load SDCard storage on init433bool _failed_sdcard_storage;434#endif435};436437#endif // AP_FENCE_ENABLED438439440