mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Plane: Introducing FENCE_RETALT parameter.
This commit is contained in:
parent
87c60ee293
commit
c87d72353f
@ -103,6 +103,9 @@ public:
|
||||
// 100: Arming parameters
|
||||
k_param_arming = 100,
|
||||
|
||||
// 105: Extra parameters
|
||||
k_param_fence_retalt = 105,
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
k_param_gcs0 = 110, // stream rates for uartA
|
||||
@ -328,6 +331,7 @@ public:
|
||||
AP_Int8 fence_channel;
|
||||
AP_Int16 fence_minalt; // meters
|
||||
AP_Int16 fence_maxalt; // meters
|
||||
AP_Int16 fence_retalt; // meters
|
||||
#endif
|
||||
|
||||
AP_Int8 rally_total;
|
||||
|
@ -267,6 +267,15 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(fence_maxalt, "FENCE_MAXALT", 0),
|
||||
|
||||
// @Param: FENCE_RETALT
|
||||
// @DisplayName: Fence Return Altitude
|
||||
// @Description: Altitude the aircraft will transit to when a fence breach occurs. If FENCE_RETALT is <= 0 then the midpoint between FENCE_MAXALT and FENCE_MINALT is used, unless FENCE_MAXALT < FENCE_MINALT. If FENCE_MAXALT < FENCE_MINALT AND FENCE_RETALT is <= 0 then ALT_HOLD_RTL is the altitude used on a fence breach.
|
||||
// @Units: meters
|
||||
// @Range: 0 32767
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(fence_retalt, "FENCE_RETALT", 0),
|
||||
#endif
|
||||
|
||||
// @Param: RALLY_TOTAL
|
||||
|
@ -266,12 +266,15 @@ static void geofence_check(bool altitude_check_only)
|
||||
|
||||
case FENCE_ACTION_GUIDED:
|
||||
case FENCE_ACTION_GUIDED_THR_PASS:
|
||||
// fly to the return point, with an altitude half way between
|
||||
// min and max
|
||||
if (g.fence_minalt >= g.fence_maxalt) {
|
||||
if (g.fence_retalt > 0) {
|
||||
//fly to the return point using fence_retalt
|
||||
guided_WP.alt = home.alt + 100.0*g.fence_retalt;
|
||||
} else if (g.fence_minalt >= g.fence_maxalt) {
|
||||
// invalid min/max, use RTL_altitude
|
||||
guided_WP.alt = home.alt + g.RTL_altitude_cm;
|
||||
} else {
|
||||
// fly to the return point, with an altitude half way between
|
||||
// min and max
|
||||
guided_WP.alt = home.alt + 100.0*(g.fence_minalt + g.fence_maxalt)/2;
|
||||
}
|
||||
guided_WP.id = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user