108         fail_msg = 
"Polygon boundary invalid";
   119         fail_msg = 
"Invalid FENCE_RADIUS value";
   129         fail_msg = 
"Invalid FENCE_ALT_MAX value";
   148         fail_msg =  
"vehicle outside fence";
   158             fail_msg = 
"fence requires position";
   251     position = position * 100.0f;  
   360         int32_t alt_above_home_cm;
   362             if ((alt_above_home_cm * 0.01
f) > 
_alt_max) {
   421     switch (fence_type) {
   466     if (msg == 
nullptr) {
   470     switch (msg->msgid) {
   472         case MAVLINK_MSG_ID_FENCE_POINT: {
   473             mavlink_fence_point_t packet;
   474             mavlink_msg_fence_point_decode(msg, &packet);
   476                 link.
send_text(MAV_SEVERITY_WARNING, 
"Invalid fence point, lat or lng too large");
   479                 point.
x = packet.lat*1.0e7f;
   480                 point.
y = packet.lng*1.0e7f;
   482                     link.
send_text(MAV_SEVERITY_WARNING, 
"Failed to save polygon point, too many points?");
   492         case MAVLINK_MSG_ID_FENCE_FETCH_POINT: {
   493             mavlink_fence_fetch_point_t packet;
   494             mavlink_msg_fence_fetch_point_decode(msg, &packet);
   498                 mavlink_msg_fence_point_send_buf(msg, link.
get_chan(), msg->sysid, msg->compid, packet.idx, 
_total, point.
x*1.0e-7
f, point.
y*1.0e-7
f);
   500                 link.
send_text(MAV_SEVERITY_WARNING, 
"Bad fence point");
   543     for (uint16_t index=0; index<
_total; index++) {
   547         temp_loc.
lat = temp_latlon.x;
   548         temp_loc.
lng = temp_latlon.y;
 bool check_fence_polygon()
check_fence_polygon - true if polygon fence has been newly breached 
 
void get_relative_position_D_home(float &posD) const override
 
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 
 
bool check_destination_within_fence(const Location_Class &loc)
 
#define AC_FENCE_ALT_MIN_DEFAULT
 
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
 
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. 
 
#define AC_FENCE_ALT_MAX_DEFAULT
 
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 
 
#define AC_FENCE_ACTION_REPORT_ONLY
 
Interface definition for the various Ground Control System. 
 
#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE
 
#define AC_FENCE_TYPE_CIRCLE
 
#define AC_FENCE_MANUAL_RECOVERY_TIME_MIN
 
const struct Location & get_home(void) const
 
#define AP_GROUPINFO(name, idx, clazz, element, def)
 
uint8_t get_breaches() const
get_breaches - returns bit mask of the fence types that have been breached 
 
bool get_location(struct Location &loc) const
 
bool pre_arm_check_polygon(const char *&fail_msg) const
 
bool load_point_from_eeprom(uint16_t i, Vector2l &point)
 
AC_PolyFence_loader _poly_loader
 
bool pre_arm_check_alt(const char *&fail_msg) const
 
#define AC_FENCE_MARGIN_DEFAULT
 
uint8_t check()
check - returns the fence type that has been breached (if any) 
 
mavlink_channel_t get_chan() const
 
const AP_AHRS_NavEKF & _ahrs
 
int32_t lat
param 3 - Latitude * 10**7 
 
float get_breach_distance(uint8_t fence_type) const
get_breach_distance - returns distance in meters outside of the given fence 
 
uint32_t get_distance_cm(const struct Location &loc1, const struct Location &loc2)
 
bool boundary_valid(uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
 
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
 
#define AC_FENCE_CIRCLE_RADIUS_DEFAULT
 
bool get_origin(Location &ret) const override
 
void clear_breach(uint8_t fence_type)
clear_breach - update breach bitmask, time and count 
 
uint8_t max_points() const
 
bool check_fence_alt_max()
check_fence_alt_max - true if alt fence has been newly breached 
 
float _circle_breach_distance
 
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
 
#define AC_FENCE_ALT_MAX_BACKUP_DISTANCE
 
void manual_recovery_start()
 
bool is_zero(const T fVal1)
 
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
get altitude in desired frame 
 
bool sys_status_enabled() const
 
bool check_fence_circle()
check_fence_circle - true if circle fence has been newly breached 
 
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
 
bool check_latlng(float lat, float lng)
 
float _circle_radius_backup
 
bool get_relative_position_NE_origin(Vector2f &posNE) const override
 
void send_text(MAV_SEVERITY severity, const char *fmt,...)
 
bool save_point_to_eeprom(uint16_t i, const Vector2l &point)
 
uint8_t get_enabled_fences() const
get_enabled_fences - returns bitmask of enabled fences 
 
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
 
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
 
int32_t lng
param 4 - Longitude * 10**7 
 
AC_Fence(const AP_AHRS_NavEKF &ahrs)
Default constructor. 
 
#define AP_PARAM_FRAME_COPTER
 
#define AC_FENCE_TYPE_POLYGON
 
void * create_point_array(uint8_t element_size)
 
void enable(bool value)
enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value ...
 
#define AC_FENCE_ACTION_RTL_AND_LAND
 
bool boundary_breached(const Vector2< T > &location, uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
 
#define AP_PARAM_FRAME_SUB
 
bool get_relative_position_NE_home(Vector2f &posNE) const override
 
#define AP_PARAM_FRAME_TRICOPTER
 
#define AC_FENCE_TYPE_ALT_MAX
 
#define AP_PARAM_FRAME_HELI
 
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...
 
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)