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/ArduCopter/fence.cpp
Views: 1798
#include "Copter.h"12// Code to integrate AC_Fence library with main ArduCopter code34#if AP_FENCE_ENABLED56// fence_check - ask fence library to check for breaches and initiate the response7// called at 1hz8void Copter::fence_check()9{10const uint8_t orig_breaches = fence.get_breaches();1112bool is_landing_or_landed = flightmode->is_landing() || ap.land_complete || !motors->armed();1314// check for new breaches; new_breaches is bitmask of fence types breached15const uint8_t new_breaches = fence.check(is_landing_or_landed);1617// we still don't do anything when disarmed, but we do check for fence breaches.18// fence pre-arm check actually checks if any fence has been breached19// that's not ever going to be true if we don't call check on AP_Fence while disarmed.20if (!motors->armed()) {21return;22}2324// if there is a new breach take action25if (new_breaches) {2627if (!copter.ap.land_complete) {28fence.print_fence_message("breached", new_breaches);29}3031// if the user wants some kind of response and motors are armed32uint8_t fence_act = fence.get_action();33if (fence_act != AC_FENCE_ACTION_REPORT_ONLY ) {3435// disarm immediately if we think we are on the ground or in a manual flight mode with zero throttle36// don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down37if (ap.land_complete || (flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){38arming.disarm(AP_Arming::Method::FENCEBREACH);3940} else {4142// if more than 100m outside the fence just force a land43if (fence.get_breach_distance(new_breaches) > AC_FENCE_GIVE_UP_DISTANCE) {44set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);45} else {46switch (fence_act) {47case AC_FENCE_ACTION_RTL_AND_LAND:48default:49// switch to RTL, if that fails then Land50if (!set_mode(Mode::Number::RTL, ModeReason::FENCE_BREACHED)) {51set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);52}53break;54case AC_FENCE_ACTION_ALWAYS_LAND:55// if always land option mode is specified, land56set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);57break;58case AC_FENCE_ACTION_SMART_RTL:59// Try SmartRTL, if that fails, RTL, if that fails Land60if (!set_mode(Mode::Number::SMART_RTL, ModeReason::FENCE_BREACHED)) {61if (!set_mode(Mode::Number::RTL, ModeReason::FENCE_BREACHED)) {62set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);63}64}65break;66case AC_FENCE_ACTION_BRAKE:67// Try Brake, if that fails Land68if (!set_mode(Mode::Number::BRAKE, ModeReason::FENCE_BREACHED)) {69set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);70}71break;72case AC_FENCE_ACTION_SMART_RTL_OR_LAND:73// Try SmartRTL, if that fails, Land74if (!set_mode(Mode::Number::SMART_RTL, ModeReason::FENCE_BREACHED)) {75set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);76}77break;78}79}80}81}8283LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));8485} else if (orig_breaches && fence.get_breaches() == 0) {86if (!copter.ap.land_complete) {87GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared");88}89// record clearing of breach90LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);91}92}9394#endif959697