mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AC_Fence: add SmartRTL and Brake actions
This commit is contained in:
parent
8350943e78
commit
e7f87f767a
@ -30,7 +30,8 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = {
|
||||
// @Param: ACTION
|
||||
// @DisplayName: Fence Action
|
||||
// @Description: What action should be taken when fence is breached
|
||||
// @Values: 0:Report Only,1:RTL or Land, 2:Always land
|
||||
// @Values{Copter}: 0:Report Only,1:RTL or Land,2:Always Land,3:SmartRTL or RTL or Land,4:Brake or Land
|
||||
// @Values: 0:Report Only,1:RTL or Land
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND),
|
||||
|
||||
|
@ -18,6 +18,9 @@
|
||||
#define AC_FENCE_ACTION_REPORT_ONLY 0 // report to GCS that boundary has been breached but take no further action
|
||||
#define AC_FENCE_ACTION_RTL_AND_LAND 1 // return to launch and, if that fails, land
|
||||
#define AC_FENCE_ACTION_ALWAYS_LAND 2 // always land
|
||||
#define AC_FENCE_ACTION_SMART_RTL 3 // smartRTL, if that fails, RTL, it that still fails, land
|
||||
#define AC_FENCE_ACTION_BRAKE 4 // brake, if that fails, land
|
||||
|
||||
// default boundaries
|
||||
#define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m
|
||||
#define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters
|
||||
|
Loading…
Reference in New Issue
Block a user