Path: blob/master/libraries/AC_Fence/AC_PolyFence_loader.h
9700 views
#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 invalid1112// CODE_REMOVAL13// ArduPilot 4.7 no longer stores circle radiuses that look like14// integers as integer item types, so any time a fence is saved the15// use of the deprecated types is fixed.16// ArduPilot 4.8 warns if it loads an integer item, warns user to re-upload the fence17// ArduPilot 4.9 warns if it loads an integer item, warns user to re-upload the fence18// ArduPilot 4.10 removes support for them1920enum class AC_PolyFenceType : uint8_t {21END_OF_STORAGE = 99,22POLYGON_INCLUSION = 98,23POLYGON_EXCLUSION = 97,24#if AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED25CIRCLE_EXCLUSION_INT = 96,26#endif // AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED27RETURN_POINT = 95,28#if AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED29CIRCLE_INCLUSION_INT = 94,30#endif // #if AC_POLYFENCE_CIRCLE_INT_SUPPORT_ENABLED31CIRCLE_EXCLUSION = 93,32CIRCLE_INCLUSION = 92,33};3435// a FenceItem is just a means of passing data about an item into36// and out of the polyfence loader. It uses a AC_PolyFenceType to37// indicate the item type, assuming each fence type is made up of38// only one sort of item.39// TODO: make this a union (or use subclasses) to save memory40class AC_PolyFenceItem {41public:42AC_PolyFenceType type;43Vector2l loc;44uint8_t vertex_count;45float radius;46};4748#if AP_FENCE_ENABLED4950#include <AP_Common/AP_Common.h>51#include <AP_Common/Location.h>52#include <GCS_MAVLink/GCS_MAVLink.h>5354class AC_PolyFence_loader55{5657public:5859AC_PolyFence_loader(AP_Int8 &total, const AP_Int16 &options) :60_total(total),61_options(options) {}6263/* Do not allow copies */64CLASS_NO_COPY(AC_PolyFence_loader);6566void init();6768// methods primarily for MissionItemProtocol_Fence to use:69// return the total number of points stored70uint16_t num_stored_items() const { return _eeprom_item_count; }71bool get_item(const uint16_t seq, AC_PolyFenceItem &item) WARN_IF_UNUSED;7273///74/// exclusion polygons75///76/// returns number of polygon exclusion zones defined77uint8_t get_exclusion_polygon_count() const {78return _num_loaded_exclusion_boundaries;79}8081/// returns pointer to array of exclusion polygon points and num_points is filled in with the number of points in the polygon82/// points are offsets in cm from EKF origin in NE frame83Vector2f* get_exclusion_polygon(uint16_t index, uint16_t &num_points) const;8485/// return system time of last update to the exclusion polygon points86uint32_t get_exclusion_polygon_update_ms() const {87return _load_time_ms;88}8990///91/// inclusion polygons92///93/// returns number of polygon inclusion zones defined94uint8_t get_inclusion_polygon_count() const {95return _num_loaded_inclusion_boundaries;96}9798/// returns pointer to array of inclusion polygon points and num_points is filled in with the number of points in the polygon99/// points are offsets in cm from EKF origin in NE frame100Vector2f* get_inclusion_polygon(uint16_t index, uint16_t &num_points) const;101102/// return system time of last update to the inclusion polygon points103uint32_t get_inclusion_polygon_update_ms() const {104return _load_time_ms;105}106107///108/// exclusion circles109///110/// returns number of exclusion circles defined111uint8_t get_exclusion_circle_count() const {112return _num_loaded_circle_exclusion_boundaries;113}114115/// returns the specified exclusion circle116/// center is offsets in cm from EKF origin in NE frame, radius is in meters117bool get_exclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const;118119/// return system time of last update to the exclusion circles120uint32_t get_exclusion_circle_update_ms() const {121return _load_time_ms;122}123124///125/// inclusion circles126///127/// returns number of inclusion circles defined128uint8_t get_inclusion_circle_count() const {129return _num_loaded_circle_inclusion_boundaries;130}131132/// returns the specified inclusion circle133/// center is offsets in cm from EKF origin in NE frame, radius is in meters134bool get_inclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const;135136// false if margin < fence radius137bool check_inclusion_circle_margin(float margin) const;138139///140/// mavlink141///142/// handler for polygon fence messages with GCS143void handle_msg(class GCS_MAVLINK &link, const mavlink_message_t& msg);144145// breached() - returns true if the vehicle has breached any fence146bool breached() const WARN_IF_UNUSED;147// returns true if location is outside the boundary also returns the minimum distance to the fence148bool breached(const Location& loc, float& distance_outside_fence, Vector2f& fence_direction) const WARN_IF_UNUSED;149// breached(Location&) - returns true if location is outside the boundary150bool breached(const Location& loc) const WARN_IF_UNUSED151{152float distance_outside_fence;153Vector2f breach_direction;154return breached(loc, distance_outside_fence, breach_direction);155}156157// returns true if a polygonal include fence could be returned158bool inclusion_boundary_available() const WARN_IF_UNUSED {159return _num_loaded_inclusion_boundaries != 0;160}161162// loaded - returns true if the fences have been loaded from163// storage and are available for use164bool loaded() const WARN_IF_UNUSED {165return _load_time_ms != 0;166};167168// maximum number of fence points we can store in eeprom169uint16_t max_items() const;170171// write_fence - validate and write count new_items to permanent storage172bool write_fence(const AC_PolyFenceItem *new_items, uint16_t count) WARN_IF_UNUSED;173174/*175* Loaded Fence functionality176*177* methods and members to do with fences stored in memory. The178* locations are translated into offset-from-origin-in-metres179*/180181// load polygon points stored in eeprom into182// _loaded_offsets_from_origin and perform validation. returns183// true if load successfully completed184bool load_from_storage() WARN_IF_UNUSED;185186// allow threads to lock against AHRS update187HAL_Semaphore &get_loaded_fence_semaphore(void) {188return _loaded_fence_sem;189}190191// call @10Hz to check for fence load being valid192void update();193194// get_return_point - returns latitude/longitude of return point.195// This works with storage - the returned vector is absolute196// lat/lon.197bool get_return_point(Vector2l &ret) WARN_IF_UNUSED;198199// return total number of fences - polygons and circles200uint16_t total_fence_count() const {201return (get_exclusion_polygon_count() +202get_inclusion_polygon_count() +203get_exclusion_circle_count() +204get_inclusion_circle_count());205}206207208#if AP_SDCARD_STORAGE_ENABLED209bool failed_sdcard_storage(void) const {210return _failed_sdcard_storage;211}212#endif213214private:215// multi-thread access support216HAL_Semaphore _loaded_fence_sem;217218/*219* Fence storage Index related functions220*/221// FenceIndex - a class used to store information about a fence in222// fence storage.223class FenceIndex {224public:225AC_PolyFenceType type;226uint16_t count;227uint16_t storage_offset;228};229// index_fence_count - returns the number of fences of type230// currently in the index231uint16_t index_fence_count(const AC_PolyFenceType type);232233// void_index - free resources for the index, forcing a reindex234// (typically via check_indexed)235void void_index() {236delete[] _index;237_index = nullptr;238_index_attempted = false;239_indexed = false;240}241242// check_indexed - read eeprom and create index if the index does243// not already exist244bool check_indexed() WARN_IF_UNUSED;245246// find_first_fence - return first fence in index of specific type247FenceIndex *find_first_fence(const AC_PolyFenceType type) const;248249// find_index_for_seq - returns true if seq is contained within a250// fence. If it is, entry will be the relevant FenceIndex. i251// will be the offset within _loaded_offsets_from_origin where the252// first point in the fence is found253bool find_index_for_seq(const uint16_t seq, const FenceIndex *&entry, uint16_t &i) const WARN_IF_UNUSED;254// find_storage_offset_for_seq - uses the index to return an255// offset into storage for an item256bool find_storage_offset_for_seq(const uint16_t seq, uint16_t &offset, AC_PolyFenceType &type, uint16_t &vertex_count_offset) const WARN_IF_UNUSED;257258uint16_t sum_of_polygon_point_counts_and_returnpoint();259260/*261* storage-related methods - dealing with fence_storage262*/263264// new_fence_storage_magic - magic number indicating fence storage265// has been formatted for use by polygon fence storage code.266// FIXME: ensure this is out-of-band for old lat/lon point storage267static const uint8_t new_fence_storage_magic = 235;268269// validate_fence - returns true if new_items look completely valid270bool validate_fence(const AC_PolyFenceItem *new_items, uint16_t count) const WARN_IF_UNUSED;271272// _eos_offset - stores the offset in storage of the273// end-of-storage marker. Used by low-level manipulation code to274// extend storage275uint16_t _eos_offset;276277// formatted - returns true if the fence storage space seems to be278// formatted for new-style fence storage279bool formatted() const WARN_IF_UNUSED;280// format - format the storage space for use by281// the new polyfence code282bool format() WARN_IF_UNUSED;283284285/*286* Loaded Fence functionality287*288* methods and members to do with fences stored in memory. The289* locations are translated into offset-from-origin-in-metres290*/291292// remove resources dedicated to the transformed fences - for293// example, in _loaded_offsets_from_origin294void unload();295296// pointer into _loaded_offsets_from_origin where the return point297// can be found:298Vector2f *_loaded_return_point;299300// pointer into _loaded_points_lla where the return point301// can be found:302Vector2l *_loaded_return_point_lla;303304class InclusionBoundary {305public:306Vector2f *points; // pointer into the _loaded_offsets_from_origin array307Vector2l *points_lla; // pointer into the _loaded_points_lla array308uint8_t count; // count of points in the boundary309};310InclusionBoundary *_loaded_inclusion_boundary;311312uint8_t _num_loaded_inclusion_boundaries;313314class ExclusionBoundary {315public:316Vector2f *points; // pointer into the _loaded_offsets_from_origin array317Vector2l *points_lla; // pointer into the _loaded_points_lla_lla array318uint8_t count; // count of points in the boundary319};320ExclusionBoundary *_loaded_exclusion_boundary;321322uint8_t _num_loaded_exclusion_boundaries;323324// _loaded_offsets_from_origin - stores x/y offset-from-origin325// coordinate pairs. Various items store their locations in this326// allocation - the polygon boundaries and the return point, for327// example.328Vector2f *_loaded_offsets_from_origin;329Vector2l *_loaded_points_lla;330Location loaded_origin; // origin at the time the boundary was loaded331332class ExclusionCircle {333public:334Vector2f pos_cm; // vector offset from home in cm335Vector2l point; // lat/lng of zone336float radius;337};338ExclusionCircle *_loaded_circle_exclusion_boundary;339340uint8_t _num_loaded_circle_exclusion_boundaries;341342class InclusionCircle {343public:344Vector2f pos_cm; // vector offset from home in cm345Vector2l point; // lat/lng of zone346float radius;347};348InclusionCircle *_loaded_circle_inclusion_boundary;349350uint8_t _num_loaded_circle_inclusion_boundaries;351352// _load_attempted - true if we have attempted to load the fences353// from storage into _loaded_circle_exclusion_boundary,354// _loaded_offsets_from_origin etc etc355bool _load_attempted;356357// _load_time_ms - from millis(), system time when fence load last358// succeeded. Will be zero if fences are not loaded359uint32_t _load_time_ms;360361// scale_latlon_from_origin - given a latitude/longitude362// transforms the point to an offset-from-origin and deposits363// the result into pos_cm.364bool scale_latlon_from_origin(const Location &origin,365const Vector2l &point,366Vector2f &pos_cm) const WARN_IF_UNUSED;367368// read_polygon_from_storage - reads vertex_count369// latitude/longitude points from offset in permanent storage,370// transforms them into an offset-from-origin and deposits the371// results into next_storage_point.372bool read_polygon_from_storage(const Location &origin,373uint16_t &read_offset,374const uint8_t vertex_count,375Vector2f *&next_storage_point,376Vector2l *&next_storage_point_lla) WARN_IF_UNUSED;377378#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT379/*380* FENCE_POINT protocol compatibility381*/382void handle_msg_fetch_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg);383void handle_msg_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg);384// contains_compatible_fence - returns true if the permanent fence385// storage contains fences that are compatible with the old386// FENCE_POINT protocol.387bool contains_compatible_fence() const WARN_IF_UNUSED;388389// get_or_create_include_fence - returns a point to an include390// fence to be used for the FENCE_POINT-supplied polygon. May391// format the storage appropriately.392FenceIndex *get_or_create_include_fence();393// get_or_create_include_fence - returns a point to a return point394// to be used for the FENCE_POINT-supplied return point. May395// format the storage appropriately.396FenceIndex *get_or_create_return_point();397#endif398399// primitives to write parts of fencepoints out:400bool write_type_to_storage(uint16_t &offset, AC_PolyFenceType type) WARN_IF_UNUSED;401bool write_latlon_to_storage(uint16_t &offset, const Vector2l &latlon) WARN_IF_UNUSED;402bool read_latlon_from_storage(uint16_t &read_offset, Vector2l &latlon) const WARN_IF_UNUSED;403404// methods to write specific types of fencepoint out:405bool write_eos_to_storage(uint16_t &offset);406407// _total - reference to FENCE_TOTAL parameter. This is used408// solely for compatibility with the FENCE_POINT protocol409AP_Int8 &_total;410const AP_Int16 &_options;411uint8_t _old_total;412413414// scan_eeprom - a method that traverses the fence storage area,415// calling the supplied callback for each fence found. If the416// scan fails (for example, the storage is corrupt), then this417// method will return false.418FUNCTOR_TYPEDEF(scan_fn_t, void, const AC_PolyFenceType, uint16_t);419bool scan_eeprom(scan_fn_t scan_fn) WARN_IF_UNUSED;420// scan_eeprom_count_fences - a static function designed to be421// massed to scan_eeprom which counts the number of fences and422// fence items present. The results of this counting appear in _eeprom_fence_count and _eeprom_item_count423void scan_eeprom_count_fences(const AC_PolyFenceType type, uint16_t read_offset);424uint16_t _eeprom_fence_count;425uint16_t _eeprom_item_count;426427// scan_eeprom_index_fences - a static function designed to be428// passed to scan_eeprom. _index must be a pointer to429// memory sufficient to hold information about all fences present430// in storage - so it is expected that scan_eeprom_count_fences431// has been used to count those fences and the allocation already432// made. After this method has been called _index will433// be filled with information about the fences in the fence434// storage - type, item counts and storage offset.435void scan_eeprom_index_fences(const AC_PolyFenceType type, uint16_t read_offset);436// array specifying type of each fence in storage (and a count of437// items in that fence)438FenceIndex *_index;439bool _indexed; // true if indexing successful440bool _index_attempted; // true if we attempted to index the eeprom441// _num_fences - count of the number of fences in _index. This442// should be equal to _eeprom_fence_count443uint16_t _num_fences;444445// count_eeprom_fences - refresh the count of fences in permanent storage446bool count_eeprom_fences() WARN_IF_UNUSED;447// index_eeprom - (re)allocate and fill in _index448bool index_eeprom() WARN_IF_UNUSED;449450uint16_t fence_storage_space_required(const AC_PolyFenceItem *new_items, uint16_t count);451452#if AP_SDCARD_STORAGE_ENABLED453// true if we failed to load SDCard storage on init454bool _failed_sdcard_storage;455#endif456};457458#endif // AP_FENCE_ENABLED459460461