AC_Fence: add AUTOLAND as FENCE_ACTION

This commit is contained in:
Henry Wurzburg 2025-02-12 08:38:28 -06:00 committed by Andrew Tridgell
parent 6b7445fd39
commit bdd84b974a
2 changed files with 2 additions and 1 deletions

View File

@ -66,7 +66,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = {
// @Description: What action should be taken when fence is breached
// @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 Land
// @Values{Rover}: 0:Report Only,1:RTL or Hold,2:Hold,3:SmartRTL or RTL or Hold,4:SmartRTL or Hold
// @Values{Plane}: 0:Report Only,1:RTL,6:Guided,7:GuidedThrottlePass
// @Values{Plane}: 0:Report Only,1:RTL,6:Guided,7:GuidedThrottlePass,8:AUTOLAND if possible else RTL
// @Values: 0:Report Only,1:RTL or Land
// @User: Standard
AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND),

View File

@ -28,6 +28,7 @@
#define AC_FENCE_ACTION_SMART_RTL_OR_LAND 5 // SmartRTL, if that fails, Land
#define AC_FENCE_ACTION_GUIDED 6 // guided mode, with target waypoint as fence return point
#define AC_FENCE_ACTION_GUIDED_THROTTLE_PASS 7 // guided mode, but pilot retains manual throttle control
#define AC_FENCE_ACTION_AUTOLAND_OR_RTL 8 // fixed wing autoland,if enabled, or RTL
// give up distance
#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