13 #define AC_FENCE_TYPE_ALT_MAX 1 // high alt fence which usually initiates an RTL 14 #define AC_FENCE_TYPE_CIRCLE 2 // circular horizontal fence (usually initiates an RTL) 15 #define AC_FENCE_TYPE_POLYGON 4 // polygon horizontal fence 18 #define AC_FENCE_ACTION_REPORT_ONLY 0 // report to GCS that boundary has been breached but take no further action 19 #define AC_FENCE_ACTION_RTL_AND_LAND 1 // return to launch and, if that fails, land 22 #define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m 23 #define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters 24 #define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m 25 #define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up 26 #define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further out 27 #define AC_FENCE_MARGIN_DEFAULT 2.0f // default distance in meters that autopilot's should maintain from the fence to avoid a breach 30 #define AC_FENCE_GIVE_UP_DISTANCE 100.0f // distance outside the fence at which we should give up and just land. Note: this is not used by library directly but is intended to be used by the main code 31 #define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control bool check_fence_polygon()
check_fence_polygon - true if polygon fence has been newly breached
bool boundary_breached(const Vector2f &location, uint16_t num_points, const Vector2f *points) const
returns true if we've breached the polygon boundary. simple passthrough to underlying _poly_loader ob...
void record_breach(uint8_t fence_type)
record_breach - update breach bitmask, time and count
AC_Fence & operator=(const AC_Fence &)=delete
bool check_destination_within_fence(const Location_Class &loc)
bool pre_arm_check_circle(const char *&fail_msg) const
bool pre_arm_check(const char *&fail_msg) const
pre_arm_check - returns true if all pre-takeoff checks have completed successfully ...
MAVLink transport control class.
static const struct AP_Param::GroupInfo var_info[]
bool sys_status_failed() const
bool sys_status_present() const
void handle_msg(GCS_MAVLINK &link, mavlink_message_t *msg)
handler for polygon fence messages with GCS
uint8_t get_breaches() const
get_breaches - returns bit mask of the fence types that have been breached
bool pre_arm_check_polygon(const char *&fail_msg) const
AC_PolyFence_loader _poly_loader
bool pre_arm_check_alt(const char *&fail_msg) const
uint8_t check()
check - returns the fence type that has been breached (if any)
const AP_AHRS_NavEKF & _ahrs
float get_breach_distance(uint8_t fence_type) const
get_breach_distance - returns distance in meters outside of the given fence
void clear_breach(uint8_t fence_type)
clear_breach - update breach bitmask, time and count
uint16_t get_breach_count() const
get_breach_count - returns number of times we have breached the fence
A system for managing and storing variables that are of general interest to the system.
bool check_fence_alt_max()
check_fence_alt_max - true if alt fence has been newly breached
float _circle_breach_distance
void manual_recovery_start()
bool sys_status_enabled() const
uint8_t get_action() const
get_action - getter for user requested action on limit breach
bool check_fence_circle()
check_fence_circle - true if circle fence has been newly breached
float get_radius() const
get_radius - returns the fence radius in meters
uint32_t _manual_recovery_start_ms
bool _boundary_create_attempted
float _alt_max_breach_distance
Vector2f * get_polygon_points(uint16_t &num_points) const
returns pointer to array of polygon points and num_points is filled in with the total number ...
uint8_t _boundary_num_points
float _circle_radius_backup
uint8_t get_enabled_fences() const
get_enabled_fences - returns bitmask of enabled fences
float get_margin() const
get_margin - returns the fence margin in meters
float get_safe_alt_max() const
get_safe_alt - returns maximum safe altitude (i.e. alt_max - margin)
Common definitions and utility routines for the ArduPilot libraries.
AC_Fence(const AP_AHRS_NavEKF &ahrs)
Default constructor.
float get_safe_alt_min() const
get_safe_alt_min - returns the minimum safe altitude (i.e. alt_min - margin)
void enable(bool value)
enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value ...
uint32_t get_breach_time() const
get_breach_time - returns time the fence was breached
bool enabled() const
enabled - returns true if fence is enabled
bool load_polygon_from_eeprom(bool force_reload=false)
load polygon points stored in eeprom into boundary array and perform validation. returns true if load...