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_Fence.cpp
Views: 1798
#include "AC_Fence.h"12#if AP_FENCE_ENABLED34#include <AP_Vehicle/AP_Vehicle_Type.h>56#ifndef AC_FENCE_DUMMY_METHODS_ENABLED7#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)))8#endif910#if !AC_FENCE_DUMMY_METHODS_ENABLED1112#include <AP_AHRS/AP_AHRS.h>13#include <AP_HAL/AP_HAL.h>14#include <AP_Logger/AP_Logger.h>15#include <GCS_MAVLink/GCS.h>1617extern const AP_HAL::HAL& hal;1819#if APM_BUILD_TYPE(APM_BUILD_Rover)20#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON21#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)22#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_POLYGON23#else24#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON25#endif2627// default boundaries28#define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m29#define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters30#define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m31#define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up32#define AC_FENCE_ALT_MIN_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further down33#define AC_FENCE_MARGIN_DEFAULT 2.0f // default distance in meters that autopilot's should maintain from the fence to avoid a breach34#define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control3536#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)37#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 100m further out38#define AC_FENCE_OPTIONS_DEFAULT OPTIONS::DISABLE_MODE_CHANGE39#else40#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0 // after fence is broken we recreate the fence 20m further out41#define AC_FENCE_OPTIONS_DEFAULT 042#endif4344//#define AC_FENCE_DEBUG4546const AP_Param::GroupInfo AC_Fence::var_info[] = {4748// @Param: ENABLE49// @DisplayName: Fence enable/disable50// @Description: Allows you to enable (1) or disable (0) the fence functionality. Fences can still be enabled and disabled via mavlink or an RC option, but these changes are not persisted.51// @Values: 0:Disabled,1:Enabled52// @User: Standard53AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),5455// @Param: TYPE56// @DisplayName: Fence Type57// @Description: Configured fence types held as bitmask. Max altitide, Circle and Polygon fences will be immediately enabled if configured. Min altitude fence will only be enabled once the minimum altitude is reached.58// @Bitmask{Rover}: 1:Circle Centered on Home,2:Inclusion/Exclusion Circles+Polygons59// @Bitmask{Copter, Plane, Sub}: 0:Max altitude,1:Circle Centered on Home,2:Inclusion/Exclusion Circles+Polygons,3:Min altitude60// @User: Standard61AP_GROUPINFO("TYPE", 1, AC_Fence, _configured_fences, AC_FENCE_TYPE_DEFAULT),6263// @Param: ACTION64// @DisplayName: Fence Action65// @Description: What action should be taken when fence is breached66// @Values{Copter}: 0:Report Only,1:RTL or Land,2:Always Land,3:SmartRTL or RTL or Land,4:Brake or Land,5:SmartRTL or Land67// @Values{Rover}: 0:Report Only,1:RTL or Hold,2:Hold,3:SmartRTL or RTL or Hold,4:SmartRTL or Hold68// @Values{Plane}: 0:Report Only,1:RTL,6:Guided,7:GuidedThrottlePass69// @Values: 0:Report Only,1:RTL or Land70// @User: Standard71AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND),7273// @Param{Copter, Plane, Sub}: ALT_MAX74// @DisplayName: Fence Maximum Altitude75// @Description: Maximum altitude allowed before geofence triggers76// @Units: m77// @Range: 10 100078// @Increment: 179// @User: Standard80AP_GROUPINFO_FRAME("ALT_MAX", 3, AC_Fence, _alt_max, AC_FENCE_ALT_MAX_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_SUB | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_PLANE),8182// @Param: RADIUS83// @DisplayName: Circular Fence Radius84// @Description: Circle fence radius which when breached will cause an RTL85// @Units: m86// @Range: 30 1000087// @User: Standard88AP_GROUPINFO("RADIUS", 4, AC_Fence, _circle_radius, AC_FENCE_CIRCLE_RADIUS_DEFAULT),8990// @Param: MARGIN91// @DisplayName: Fence Margin92// @Description: Distance that autopilot's should maintain from the fence to avoid a breach93// @Units: m94// @Range: 1 1095// @User: Standard96AP_GROUPINFO("MARGIN", 5, AC_Fence, _margin, AC_FENCE_MARGIN_DEFAULT),9798// @Param: TOTAL99// @DisplayName: Fence polygon point total100// @Description: Number of polygon points saved in eeprom (do not update manually)101// @Range: 1 20102// @User: Standard103AP_GROUPINFO("TOTAL", 6, AC_Fence, _total, 0),104105// @Param{Copter, Plane, Sub}: ALT_MIN106// @DisplayName: Fence Minimum Altitude107// @Description: Minimum altitude allowed before geofence triggers108// @Units: m109// @Range: -100 100110// @Increment: 1111// @User: Standard112AP_GROUPINFO_FRAME("ALT_MIN", 7, AC_Fence, _alt_min, AC_FENCE_ALT_MIN_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_SUB | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_PLANE),113114// @Param{Plane}: RET_RALLY115// @DisplayName: Fence Return to Rally116// @Description: Should the vehicle return to fence return point or rally point117// @Values: 0:Fence Return Point,1:Nearest Rally Point118// @Range: 0 1119// @Increment: 1120// @User: Standard121AP_GROUPINFO_FRAME("RET_RALLY", 8, AC_Fence, _ret_rally, 0, AP_PARAM_FRAME_PLANE),122123// @Param{Plane}: RET_ALT124// @DisplayName: Fence Return Altitude125// @Description: Altitude the vehicle will transit to when a fence breach occurs126// @Units: m127// @Range: 0 32767128// @Increment: 1129// @User: Standard130AP_GROUPINFO_FRAME("RET_ALT", 9, AC_Fence, _ret_altitude, 0.0f, AP_PARAM_FRAME_PLANE),131132// @Param{Plane, Copter}: AUTOENABLE133// @DisplayName: Fence Auto-Enable134// @Description: Auto-enable of fences. AutoEnableOnTakeoff enables all configured fences, except the minimum altitude fence (which is enabled when the minimum altitude is reached), after autotakeoffs reach altitude. During autolandings the fences will be disabled. AutoEnableDisableFloorOnLanding enables all configured fences, except the minimum altitude fence (which is enabled when the minimum altitude is reached), after autotakeoffs reach altitude. During autolandings only the Minimum Altitude fence will be disabled. AutoEnableOnlyWhenArmed enables all configured fences on arming, except the minimum altitude fence (which is enabled when the minimum altitude is reached), but no fences are disabled during autolandings. However, fence breaches are ignored while executing prior breach recovery actions which may include autolandings.135// @Values{Plane, Copter}: 0:AutoEnableOff,1:AutoEnableOnTakeoff,2:AutoEnableDisableFloorOnLanding,3:AutoEnableOnlyWhenArmed136// @Range: 0 3137// @Increment: 1138// @User: Standard139AP_GROUPINFO_FRAME("AUTOENABLE", 10, AC_Fence, _auto_enabled, static_cast<uint8_t>(AutoEnable::ALWAYS_DISABLED), AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),140141// @Param{Plane, Copter}: OPTIONS142// @DisplayName: Fence options143// @Description: When bit 0 is set sisable mode change following fence action until fence breach is cleared. When bit 1 is set the allowable flight areas is the union of all polygon and circle fence areas instead of the intersection, which means a fence breach occurs only if you are outside all of the fence areas.144// @Bitmask: 0:Disable mode change following fence action until fence breach is cleared, 1:Allow union of inclusion areas145// @User: Standard146AP_GROUPINFO_FRAME("OPTIONS", 11, AC_Fence, _options, static_cast<uint16_t>(AC_FENCE_OPTIONS_DEFAULT), AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),147148AP_GROUPEND149};150151/// Default constructor.152AC_Fence::AC_Fence()153{154#if CONFIG_HAL_BOARD == HAL_BOARD_SITL155if (_singleton != nullptr) {156AP_HAL::panic("Fence must be singleton");157}158#endif159_singleton = this;160AP_Param::setup_object_defaults(this, var_info);161if (_enabled) {162_enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN;163}164}165166// get a user-friendly list of fences167void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg)168{169if (!fences) {170return;171}172static const char* FENCE_NAMES[] = {173"Max Alt",174"Circle",175"Polygon",176"Min Alt",177};178uint8_t i = 0;179uint8_t nfences = 0;180while (fences !=0) {181if (fences & 0x1) {182if (nfences > 0) {183if (!(fences & ~1U)) {184msg.printf(" and ");185} else {186msg.printf(", ");187}188}189msg.printf("%s", FENCE_NAMES[i]);190nfences++;191}192fences >>= 1;193i++;194}195msg.printf(" fence");196if (nfences>1) {197msg.printf("s");198}199}200201// print a message about the passed in fences202void AC_Fence::print_fence_message(const char* message, uint8_t fences) const203{204if (!fences) {205return;206}207208char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];209ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);210AC_Fence::get_fence_names(fences, e);211GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "%s %s", e.get_writeable_string(), message);212}213214// should be called @10Hz to handle loading from eeprom215void AC_Fence::update()216{217_poly_loader.update();218// if someone changes the parameter we want to enable or disable everything219if (_enabled != _last_enabled || _auto_enabled != _last_auto_enabled) {220// reset the auto mask since we just reconfigured all of fencing221_last_enabled = _enabled;222_last_auto_enabled = _auto_enabled;223if (_enabled) {224_enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN;225} else {226_enabled_fences = 0;227}228}229#ifdef AC_FENCE_DEBUG230static uint32_t last_msg_count = 0;231if (get_enabled_fences() && last_msg_count++ % 10 == 0) {232print_fence_message("active", get_enabled_fences());233print_fence_message("breached", get_breaches());234}235#endif236}237238// enable or disable configured fences present in fence_types239// also updates the _min_alt_state enum if update_auto_enable is true240// returns a bitmask of fences that were changed241uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable)242{243uint8_t fences = _configured_fences.get() & fence_types;244uint8_t enabled_fences = _enabled_fences;245if (value) {246enabled_fences |= fences;247} else {248enabled_fences &= ~fences;249}250251if (update_auto_enable && (fences & AC_FENCE_TYPE_ALT_MIN) != 0) {252// remember that min-alt fence was manually enabled/disabled253_min_alt_state = value ? MinAltState::MANUALLY_ENABLED : MinAltState::MANUALLY_DISABLED;254}255256uint8_t fences_to_change = _enabled_fences ^ enabled_fences;257258if (!fences_to_change) {259return 0;260}261262#if HAL_LOGGING_ENABLED263AP::logger().Write_Event(value ? LogEvent::FENCE_ENABLE : LogEvent::FENCE_DISABLE);264if (fences_to_change & AC_FENCE_TYPE_ALT_MAX) {265AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MAX_ENABLE : LogEvent::FENCE_ALT_MAX_DISABLE);266}267if (fences_to_change & AC_FENCE_TYPE_CIRCLE) {268AP::logger().Write_Event(value ? LogEvent::FENCE_CIRCLE_ENABLE : LogEvent::FENCE_CIRCLE_DISABLE);269}270if (fences_to_change & AC_FENCE_TYPE_ALT_MIN) {271AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MIN_ENABLE : LogEvent::FENCE_ALT_MIN_DISABLE);272}273if (fences_to_change & AC_FENCE_TYPE_POLYGON) {274AP::logger().Write_Event(value ? LogEvent::FENCE_POLYGON_ENABLE : LogEvent::FENCE_POLYGON_DISABLE);275}276#endif277278_enabled_fences = enabled_fences;279280if (!value) {281clear_breach(fences_to_change);282}283284return fences_to_change;285}286287/// enable/disable fence floor only288void AC_Fence::enable_floor()289{290enable(true, AC_FENCE_TYPE_ALT_MIN);291}292293void AC_Fence::disable_floor()294{295enable(false, AC_FENCE_TYPE_ALT_MIN);296}297298/*299called on arming300*/301void AC_Fence::auto_enable_fence_on_arming(void)302{303if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {304return;305}306307// reset min alt state, after an auto-enable the min alt fence can be auto-enabled on308// reaching altitude309_min_alt_state = MinAltState::DEFAULT;310311const uint8_t fences = enable(true, AC_FENCE_ARMING_FENCES, false);312print_fence_message("auto-enabled", fences);313}314315/*316called on disarming317*/318void AC_Fence::auto_disable_fence_on_disarming(void)319{320if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {321return;322}323324const uint8_t fences = enable(false, AC_FENCE_ALL_FENCES, false);325print_fence_message("auto-disabled", fences);326}327328/*329called when an auto-takeoff is complete330*/331void AC_Fence::auto_enable_fence_after_takeoff(void)332{333if (auto_enabled() != AutoEnable::ENABLE_ON_AUTO_TAKEOFF &&334auto_enabled() != AutoEnable::ENABLE_DISABLE_FLOOR_ONLY) {335return;336}337338// reset min-alt state339_min_alt_state = MinAltState::DEFAULT;340341const uint8_t fences = enable(true, AC_FENCE_ALL_FENCES, false);342print_fence_message("auto-enabled", fences);343}344345// return fences that should be auto-disabled when requested346uint8_t AC_Fence::get_auto_disable_fences(void) const347{348uint8_t auto_disable = 0;349switch (auto_enabled()) {350case AC_Fence::AutoEnable::ENABLE_ON_AUTO_TAKEOFF:351auto_disable = AC_FENCE_ALL_FENCES;352break;353case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:354case AC_Fence::AutoEnable::ONLY_WHEN_ARMED:355default: // when auto disable is not set we still need to disable the altmin fence on landing356auto_disable = AC_FENCE_TYPE_ALT_MIN;357break;358}359if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {360// don't auto-disable min alt fence if manually enabled361auto_disable &= ~AC_FENCE_TYPE_ALT_MIN;362}363return auto_disable;364}365366uint8_t AC_Fence::present() const367{368uint8_t mask = AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX;369if (_poly_loader.total_fence_count() > 0) {370mask |= AC_FENCE_TYPE_POLYGON;371}372373return _configured_fences.get() & mask;374}375376/// get_enabled_fences - returns bitmask of enabled fences377uint8_t AC_Fence::get_enabled_fences() const378{379return _enabled_fences & present();380}381382// additional checks for the polygon fence:383bool AC_Fence::pre_arm_check_polygon(char *failure_msg, const uint8_t failure_msg_len) const384{385if (!(_configured_fences & AC_FENCE_TYPE_POLYGON)) {386// not enabled; all good387return true;388}389390if (! _poly_loader.loaded()) {391hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence(s) invalid");392return false;393}394395if (!_poly_loader.check_inclusion_circle_margin(_margin)) {396hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence margin is less than inclusion circle radius");397return false;398}399400return true;401}402403// additional checks for the circle fence:404bool AC_Fence::pre_arm_check_circle(char *failure_msg, const uint8_t failure_msg_len) const405{406if (_circle_radius < 0) {407hal.util->snprintf(failure_msg, failure_msg_len, "Invalid Circle FENCE_RADIUS value");408return false;409}410if (_circle_radius < _margin) {411hal.util->snprintf(failure_msg, failure_msg_len, "Circle FENCE_MARGIN is less than FENCE_RADIUS");412return false;413}414415return true;416}417418// additional checks for the alt fence:419bool AC_Fence::pre_arm_check_alt(char *failure_msg, const uint8_t failure_msg_len) const420{421if (_alt_max < 0.0f) {422hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MAX value");423return false;424}425426if (_alt_min < -100.0f) {427hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MIN value");428return false;429}430return true;431}432433434/// pre_arm_check - returns true if all pre-takeoff checks have completed successfully435bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const436{437// if fences are enabled but none selected fail pre-arm check438if (_enabled && !present()) {439hal.util->snprintf(failure_msg, failure_msg_len, "Fences enabled, but none selected");440return false;441}442443// if AUTOENABLE = 1 or 2 warn now, but fail in a later release444// PARAMETER_CONVERSION - Added: Jul-2024 for ArduPilot-4.6445if (_auto_enabled == 1 || _auto_enabled == 2) {446static uint32_t last_autoenable_warn_ms;447const uint32_t now_ms = AP_HAL::millis();448if (now_ms - last_autoenable_warn_ms > 60000) {449GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "FENCE_AUTOENABLE is %u, will be removed in 4.7, use 3", unsigned(_auto_enabled));450last_autoenable_warn_ms = now_ms;451}452}453454// if not enabled or not fence set-up always return true455if ((!enabled() && !_auto_enabled) || !_configured_fences) {456return true;457}458459// if we have horizontal limits enabled, check we can get a460// relative position from the AHRS461if ((_configured_fences & AC_FENCE_TYPE_CIRCLE) ||462(_configured_fences & AC_FENCE_TYPE_POLYGON)) {463Vector2f position;464if (!AP::ahrs().get_relative_position_NE_home(position)) {465hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");466return false;467}468}469470if (!pre_arm_check_polygon(failure_msg, failure_msg_len)) {471return false;472}473474if (!pre_arm_check_circle(failure_msg, failure_msg_len)) {475return false;476}477478if (!pre_arm_check_alt(failure_msg, failure_msg_len)) {479return false;480}481482auto breached_fences = _breached_fences;483if (auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {484Location loc;485if (!AP::ahrs().get_location(loc)) {486hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");487return false;488}489if (_poly_loader.breached(loc)) {490breached_fences |= AC_FENCE_TYPE_POLYGON;491}492}493494// check no limits are currently breached495if (breached_fences) {496char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];497ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);498AC_Fence::get_fence_names(_breached_fences, e);499hal.util->snprintf(failure_msg, failure_msg_len, "Vehicle breaching %s", e.get_writeable_string());500return false;501}502503// validate FENCE_MARGIN parameter range504if (_margin < 0.0f) {505hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_MARGIN value");506return false;507}508509if (_alt_max < _alt_min) {510hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_ALT_MAX < FENCE_ALT_MIN");511return false;512}513514if (_alt_max - _alt_min <= 2.0f * _margin) {515hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_MARGIN too big");516return false;517}518519// if we got this far everything must be ok520return true;521}522523/// returns true if we have freshly breached the maximum altitude524/// fence; also may set up a fallback fence which, if breached, will525/// cause the altitude fence to be freshly breached526bool AC_Fence::check_fence_alt_max()527{528// altitude fence check529if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {530// not enabled; no breach531return false;532}533534float alt;535AP::ahrs().get_relative_position_D_home(alt);536const float _curr_alt = -alt; // translate Down to Up537538// check if we are over the altitude fence539if (_curr_alt >= _alt_max) {540541// record distance above breach542_alt_max_breach_distance = _curr_alt - _alt_max;543544// check for a new breach or a breach of the backup fence545if (!(_breached_fences & AC_FENCE_TYPE_ALT_MAX) ||546(!is_zero(_alt_max_backup) && _curr_alt >= _alt_max_backup)) {547548// new breach549record_breach(AC_FENCE_TYPE_ALT_MAX);550551// create a backup fence 20m higher up552_alt_max_backup = _curr_alt + AC_FENCE_ALT_MAX_BACKUP_DISTANCE;553// new breach554return true;555}556// old breach557return false;558}559560// not breached561562// clear max alt breach if present563if ((_breached_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {564clear_breach(AC_FENCE_TYPE_ALT_MAX);565_alt_max_backup = 0.0f;566_alt_max_breach_distance = 0.0f;567}568569return false;570}571572/// returns true if we have freshly breached the minimum altitude573/// fence; also may set up a fallback fence which, if breached, will574/// cause the altitude fence to be freshly breached575bool AC_Fence::check_fence_alt_min()576{577// altitude fence check578if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)) {579// not enabled; no breach580return false;581}582583float alt;584AP::ahrs().get_relative_position_D_home(alt);585const float _curr_alt = -alt; // translate Down to Up586587// check if we are under the altitude fence588if (_curr_alt <= _alt_min) {589590// record distance below breach591_alt_min_breach_distance = _alt_min - _curr_alt;592593// check for a new breach or a breach of the backup fence594if (!(_breached_fences & AC_FENCE_TYPE_ALT_MIN) ||595(!is_zero(_alt_min_backup) && _curr_alt <= _alt_min_backup)) {596597// new breach598record_breach(AC_FENCE_TYPE_ALT_MIN);599600// create a backup fence 20m lower down601_alt_min_backup = _curr_alt - AC_FENCE_ALT_MIN_BACKUP_DISTANCE;602// new breach603return true;604}605// old breach606return false;607}608609// not breached610611// clear min alt breach if present612if ((_breached_fences & AC_FENCE_TYPE_ALT_MIN) != 0) {613clear_breach(AC_FENCE_TYPE_ALT_MIN);614_alt_min_backup = 0.0f;615_alt_min_breach_distance = 0.0f;616}617618return false;619}620621622/// auto enable fence floor623bool AC_Fence::auto_enable_fence_floor()624{625// altitude fence check626if (!(_configured_fences & AC_FENCE_TYPE_ALT_MIN) // not configured627|| (get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) // already enabled628|| _min_alt_state == MinAltState::MANUALLY_DISABLED // user has manually disabled the fence629|| (!_enabled && (auto_enabled() == AC_Fence::AutoEnable::ALWAYS_DISABLED630|| auto_enabled() == AutoEnable::ENABLE_ON_AUTO_TAKEOFF))) {631// not enabled632return false;633}634635float alt;636AP::ahrs().get_relative_position_D_home(alt);637const float _curr_alt = -alt; // translate Down to Up638639// check if we are over the altitude fence640if (!floor_enabled() && _curr_alt >= _alt_min + _margin) {641enable(true, AC_FENCE_TYPE_ALT_MIN, false);642GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Min Alt fence enabled (auto enable)");643return true;644}645646return false;647}648649// check_fence_polygon - returns true if the poly fence is freshly650// breached. That includes being inside exclusion zones and outside651// inclusions zones652bool AC_Fence::check_fence_polygon()653{654if (!(get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {655// not enabled; no breach656clear_breach(AC_FENCE_TYPE_POLYGON);657return false;658}659660const bool was_breached = _breached_fences & AC_FENCE_TYPE_POLYGON;661if (_poly_loader.breached()) {662if (!was_breached) {663record_breach(AC_FENCE_TYPE_POLYGON);664return true;665}666return false;667}668if (was_breached) {669clear_breach(AC_FENCE_TYPE_POLYGON);670}671return false;672}673674/// check_fence_circle - returns true if the circle fence (defined via675/// parameters) has been freshly breached. May also set up a backup676/// fence outside the fence and return a fresh breach if that backup677/// fence is breached.678bool AC_Fence::check_fence_circle()679{680if (!(get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {681// not enabled; no breach682return false;683}684685Vector2f home;686if (AP::ahrs().get_relative_position_NE_home(home)) {687// we (may) remain breached if we can't update home688_home_distance = home.length();689}690691// check if we are outside the fence692if (_home_distance >= _circle_radius) {693694// record distance outside the fence695_circle_breach_distance = _home_distance - _circle_radius;696697// check for a new breach or a breach of the backup fence698if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) ||699(!is_zero(_circle_radius_backup) && _home_distance >= _circle_radius_backup)) {700// new breach701// create a backup fence 20m or 100m further out702record_breach(AC_FENCE_TYPE_CIRCLE);703_circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE;704return true;705}706return false;707}708709// not currently breached710711// clear circle breach if present712if (_breached_fences & AC_FENCE_TYPE_CIRCLE) {713clear_breach(AC_FENCE_TYPE_CIRCLE);714_circle_radius_backup = 0.0f;715_circle_breach_distance = 0.0f;716}717718return false;719}720721722/// check - returns bitmask of fence types breached (if any)723uint8_t AC_Fence::check(bool disable_auto_fences)724{725uint8_t ret = 0;726uint8_t disabled_fences = disable_auto_fences ? get_auto_disable_fences() : 0;727uint8_t fences_to_disable = disabled_fences & _enabled_fences;728729// clear any breach from a non-enabled fence730clear_breach(~_configured_fences);731// clear any breach from disabled fences732clear_breach(fences_to_disable);733734if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {735// if user has manually enabled the min-alt fence then don't auto-disable736fences_to_disable &= ~AC_FENCE_TYPE_ALT_MIN;737}738739// report on any fences that were auto-disabled740if (fences_to_disable) {741print_fence_message("auto-disabled", fences_to_disable);742}743744#if 0745/*746this debug log message is very useful both when developing tests747and doing manual SITL fence testing748*/749{750float alt;751AP::ahrs().get_relative_position_D_home(alt);752753AP::logger().WriteStreaming("FENC", "TimeUS,EN,AE,CF,EF,DF,Alt", "QIIIIIf",754AP_HAL::micros64(),755enabled(),756_auto_enabled,757_configured_fences,758get_enabled_fences(),759disabled_fences,760alt*-1);761}762#endif763764// return immediately if disabled765if ((!enabled() && !_auto_enabled && !(_configured_fences & AC_FENCE_TYPE_ALT_MIN)) || !_configured_fences) {766return 0;767}768769// disable the (temporarily) disabled fences770enable(false, disabled_fences, false);771772// maximum altitude fence check773if (!(disabled_fences & AC_FENCE_TYPE_ALT_MAX) && check_fence_alt_max()) {774ret |= AC_FENCE_TYPE_ALT_MAX;775}776777// minimum altitude fence check, do this before auto-disabling (e.g. because falling)778// so that any action can be taken779if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN) && check_fence_alt_min()) {780ret |= AC_FENCE_TYPE_ALT_MIN;781}782783// auto enable floor unless auto enable on auto takeoff has been set (which means other behaviour is required)784if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN)) {785auto_enable_fence_floor();786}787788// circle fence check789if (!(disabled_fences & AC_FENCE_TYPE_CIRCLE) && check_fence_circle()) {790ret |= AC_FENCE_TYPE_CIRCLE;791}792793// polygon fence check794if (!(disabled_fences & AC_FENCE_TYPE_POLYGON) && check_fence_polygon()) {795ret |= AC_FENCE_TYPE_POLYGON;796}797798// check if pilot is attempting to recover manually799// this is done last so that _breached_fences is correct800if (_manual_recovery_start_ms != 0) {801// we ignore any fence breaches during the manual recovery period which is about 10 seconds802if ((AP_HAL::millis() - _manual_recovery_start_ms) < AC_FENCE_MANUAL_RECOVERY_TIME_MIN) {803return 0;804}805// recovery period has passed so reset manual recovery time806// and continue with fence breach checks807_manual_recovery_start_ms = 0;808}809810// return any new breaches that have occurred811return ret;812}813814// returns true if the destination is within fence (used to reject waypoints outside the fence)815bool AC_Fence::check_destination_within_fence(const Location& loc)816{817// Altitude fence check - Fence Ceiling818if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {819int32_t alt_above_home_cm;820if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {821if ((alt_above_home_cm * 0.01f) > _alt_max) {822return false;823}824}825}826827// Altitude fence check - Fence Floor828if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)) {829int32_t alt_above_home_cm;830if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {831if ((alt_above_home_cm * 0.01f) < _alt_min) {832return false;833}834}835}836837// Circular fence check838if ((get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {839if (AP::ahrs().get_home().get_distance(loc) > _circle_radius) {840return false;841}842}843844// polygon fence check845if ((get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {846if (_poly_loader.breached(loc)) {847return false;848}849}850851return true;852}853854/// record_breach - update breach bitmask, time and count855void AC_Fence::record_breach(uint8_t fence_type)856{857// if we haven't already breached a limit, update the breach time858if (!_breached_fences) {859const uint32_t now = AP_HAL::millis();860_breach_time = now;861862// emit a message indicated we're newly-breached, but not too often863if (now - _last_breach_notify_sent_ms > 1000) {864_last_breach_notify_sent_ms = now;865GCS_SEND_MESSAGE(MSG_FENCE_STATUS);866}867}868869// update breach count870if (_breach_count < 65500) {871_breach_count++;872}873874// update bitmask875_breached_fences |= fence_type;876}877878/// clear_breach - update breach bitmask, time and count879void AC_Fence::clear_breach(uint8_t fence_type)880{881_breached_fences &= ~fence_type;882}883884/// get_breach_distance - returns maximum distance in meters outside885/// of the given fences. fence_type is a bitmask here.886float AC_Fence::get_breach_distance(uint8_t fence_type) const887{888float max = 0.0f;889890if (fence_type & AC_FENCE_TYPE_ALT_MAX) {891max = MAX(_alt_max_breach_distance, max);892}893if (fence_type & AC_FENCE_TYPE_ALT_MIN) {894max = MAX(_alt_min_breach_distance, max);895}896if (fence_type & AC_FENCE_TYPE_CIRCLE) {897max = MAX(_circle_breach_distance, max);898}899return max;900}901902/// manual_recovery_start - caller indicates that pilot is re-taking manual control so fence should be disabled for 10 seconds903/// has no effect if no breaches have occurred904void AC_Fence::manual_recovery_start()905{906// return immediate if we haven't breached a fence907if (!_breached_fences) {908return;909}910911// record time pilot began manual recovery912_manual_recovery_start_ms = AP_HAL::millis();913914GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Manual recovery started");915}916917// methods for mavlink SYS_STATUS message (send_sys_status)918bool AC_Fence::sys_status_present() const919{920return present();921}922923bool AC_Fence::sys_status_enabled() const924{925if (!sys_status_present()) {926return false;927}928if (_action == AC_FENCE_ACTION_REPORT_ONLY) {929return false;930}931// Fence is only enabled when the flag is enabled932return enabled();933}934935bool AC_Fence::sys_status_failed() const936{937if (!sys_status_present()) {938// not failed if not present; can fail if present but not enabled939return false;940}941if (get_breaches() != 0) {942return true;943}944return false;945}946947AC_PolyFence_loader &AC_Fence::polyfence()948{949return _poly_loader;950}951const AC_PolyFence_loader &AC_Fence::polyfence() const952{953return _poly_loader;954}955956957#else // build type is not appropriate; provide a dummy implementation:958const AP_Param::GroupInfo AC_Fence::var_info[] = { AP_GROUPEND };959960AC_Fence::AC_Fence() {};961962uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable) { return 0; }963964void AC_Fence::enable_floor() {}965void AC_Fence::disable_floor() {}966void AC_Fence::update() {}967968void AC_Fence::auto_enable_fence_after_takeoff() {}969void AC_Fence::auto_enable_fence_on_arming() {}970void AC_Fence::auto_disable_fence_on_disarming() {}971972uint8_t AC_Fence::present() const { return 0; }973974uint8_t AC_Fence::get_enabled_fences() const { return 0; }975976bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const { return true; }977978uint8_t AC_Fence::check(bool disable_auto_fences) { return 0; }979bool AC_Fence::check_destination_within_fence(const Location& loc) { return true; }980float AC_Fence::get_breach_distance(uint8_t fence_type) const { return 0.0; }981void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg) { }982void AC_Fence::print_fence_message(const char* msg, uint8_t fences) const {}983984void AC_Fence::manual_recovery_start() {}985986bool AC_Fence::sys_status_present() const { return false; }987bool AC_Fence::sys_status_enabled() const { return false; }988bool AC_Fence::sys_status_failed() const { return false; }989990AC_PolyFence_loader &AC_Fence::polyfence()991{992return _poly_loader;993}994const AC_PolyFence_loader &AC_Fence::polyfence() const995{996return _poly_loader;997}998999#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED10001001// singleton instance1002AC_Fence *AC_Fence::_singleton;10031004namespace AP1005{10061007AC_Fence *fence()1008{1009return AC_Fence::get_singleton();1010}10111012}10131014#endif // AP_FENCE_ENABLED101510161017