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/ArduPlane/fence.cpp
Views: 1798
#include "Plane.h"12// Code to integrate AC_Fence library with main ArduPlane code34#if AP_FENCE_ENABLED56// fence_check - ask fence library to check for breaches and initiate the response7void Plane::fence_check()8{9const uint8_t orig_breaches = fence.get_breaches();10const bool armed = arming.is_armed();1112uint16_t mission_id = plane.mission.get_current_nav_cmd().id;13bool landing_or_landed = plane.flight_stage == AP_FixedWing::FlightStage::LAND14|| !armed15#if HAL_QUADPLANE_ENABLED16|| control_mode->mode_number() == Mode::Number::QLAND17|| quadplane.in_vtol_land_descent()18#endif19|| (plane.is_land_command(mission_id) && plane.mission.state() == AP_Mission::MISSION_RUNNING);2021// check for new breaches; new_breaches is bitmask of fence types breached22const uint8_t new_breaches = fence.check(landing_or_landed);2324/*25if we are either disarmed or we are currently not in breach and26we are not flying then clear the state associated with the27previous mode breach handling. This allows the fence state28machine to reset at the end of a fence breach action such as an29RTL and autoland30*/31if (plane.previous_mode_reason == ModeReason::FENCE_BREACHED) {32if (!armed || ((new_breaches == 0 && orig_breaches == 0) && !plane.is_flying())) {33plane.previous_mode_reason = ModeReason::UNKNOWN;34}35}3637if (!fence.enabled()) {38// Switch back to the chosen control mode if still in39// GUIDED to the return point40switch(fence.get_action()) {41case AC_FENCE_ACTION_GUIDED:42case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:43case AC_FENCE_ACTION_RTL_AND_LAND:44if (plane.control_mode_reason == ModeReason::FENCE_BREACHED &&45control_mode->is_guided_mode()) {46set_mode(*previous_mode, ModeReason::FENCE_RETURN_PREVIOUS_MODE);47}48break;49default:50// No returning to a previous mode, unless our action allows it51break;52}53return;54}5556// we still don't do anything when disarmed, but we do check for fence breaches.57// fence pre-arm check actually checks if any fence has been breached58// that's not ever going to be true if we don't call check on AP_Fence while disarmed59if (!armed) {60return;61}6263// Never trigger a fence breach in the final stage of landing64if (landing.is_expecting_impact()) {65return;66}6768if (in_fence_recovery()) {69// we have already triggered, don't trigger again until the70// user disables/re-enables using the fence channel switch71return;72}7374if (new_breaches) {75fence.print_fence_message("breached", new_breaches);7677// if the user wants some kind of response and motors are armed78const uint8_t fence_act = fence.get_action();79switch (fence_act) {80case AC_FENCE_ACTION_REPORT_ONLY:81break;82case AC_FENCE_ACTION_GUIDED:83case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:84case AC_FENCE_ACTION_RTL_AND_LAND:85if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {86if (control_mode == &mode_auto &&87mission.get_in_landing_sequence_flag() &&88(g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START ||89g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START)) {90// already landing91return;92}93set_mode(mode_rtl, ModeReason::FENCE_BREACHED);94} else {95set_mode(mode_guided, ModeReason::FENCE_BREACHED);96}9798Location loc;99if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {100loc = calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm());101} else {102//return to fence return point, not a rally point103if (fence.get_return_altitude() > 0) {104// fly to the return point using _retalt105loc.alt = home.alt + 100.0f * fence.get_return_altitude();106} else if (fence.get_safe_alt_min() >= fence.get_safe_alt_max()) {107// invalid min/max, use RTL_altitude108loc.alt = home.alt + g.RTL_altitude*100;109} else {110// fly to the return point, with an altitude half way between111// min and max112loc.alt = home.alt + 100.0f * (fence.get_safe_alt_min() + fence.get_safe_alt_max()) / 2;113}114115Vector2l return_point;116if(fence.polyfence().get_return_point(return_point)) {117loc.lat = return_point[0];118loc.lng = return_point[1];119} else {120// When no fence return point is found (ie. no inclusion fence uploaded, but exclusion is)121// we fail to obtain a valid fence return point. In this case, home is considered a safe122// return point.123loc.lat = home.lat;124loc.lng = home.lng;125}126}127128if (fence.get_action() != AC_FENCE_ACTION_RTL_AND_LAND) {129setup_terrain_target_alt(loc);130set_guided_WP(loc);131}132133if (fence.get_action() == AC_FENCE_ACTION_GUIDED_THROTTLE_PASS) {134guided_throttle_passthru = true;135}136break;137}138139LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));140} else if (orig_breaches && fence.get_breaches() == 0) {141GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared");142// record clearing of breach143LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);144}145}146147bool Plane::fence_stickmixing(void) const148{149if (fence.enabled() &&150fence.get_breaches() &&151in_fence_recovery())152{153// don't mix in user input154return false;155}156// normal mixing rules157return true;158}159160bool Plane::in_fence_recovery() const161{162const bool current_mode_breach = plane.control_mode_reason == ModeReason::FENCE_BREACHED;163const bool previous_mode_breach = plane.previous_mode_reason == ModeReason::FENCE_BREACHED;164const bool previous_mode_complete = (plane.control_mode_reason == ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL) ||165(plane.control_mode_reason == ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND) ||166(plane.control_mode_reason == ModeReason::QRTL_INSTEAD_OF_RTL) ||167(plane.control_mode_reason == ModeReason::QLAND_INSTEAD_OF_RTL);168169return current_mode_breach || (previous_mode_breach && previous_mode_complete);170}171172#endif173174175