mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: Add Smart RTL or LAND to the fence action
This commit is contained in:
parent
17f285b68f
commit
3824277d11
|
@ -31,7 +31,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = {
|
|||
// @Param: ACTION
|
||||
// @DisplayName: Fence Action
|
||||
// @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
|
||||
// @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,2:Hold,3:SmartRTL,4:SmartRTL or Hold
|
||||
// @Values: 0:Report Only,1:RTL or Land
|
||||
// @User: Standard
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
#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
|
||||
#define AC_FENCE_ACTION_SMART_RTL_OR_LAND 5 // SmartRTL, if that fails, Land
|
||||
|
||||
// default boundaries
|
||||
#define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m
|
||||
|
|
Loading…
Reference in New Issue