Plane: Introducing FENCE_RETALT parameter.

This commit is contained in:
Michael Day 2013-12-30 14:33:02 -08:00 committed by Andrew Tridgell
parent 87c60ee293
commit c87d72353f
3 changed files with 19 additions and 3 deletions

View File

@ -103,6 +103,9 @@ public:
// 100: Arming parameters // 100: Arming parameters
k_param_arming = 100, k_param_arming = 100,
// 105: Extra parameters
k_param_fence_retalt = 105,
// 110: Telemetry control // 110: Telemetry control
// //
k_param_gcs0 = 110, // stream rates for uartA k_param_gcs0 = 110, // stream rates for uartA
@ -328,6 +331,7 @@ public:
AP_Int8 fence_channel; AP_Int8 fence_channel;
AP_Int16 fence_minalt; // meters AP_Int16 fence_minalt; // meters
AP_Int16 fence_maxalt; // meters AP_Int16 fence_maxalt; // meters
AP_Int16 fence_retalt; // meters
#endif #endif
AP_Int8 rally_total; AP_Int8 rally_total;

View File

@ -267,6 +267,15 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
GSCALAR(fence_maxalt, "FENCE_MAXALT", 0), 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 #endif
// @Param: RALLY_TOTAL // @Param: RALLY_TOTAL

View File

@ -266,12 +266,15 @@ static void geofence_check(bool altitude_check_only)
case FENCE_ACTION_GUIDED: case FENCE_ACTION_GUIDED:
case FENCE_ACTION_GUIDED_THR_PASS: case FENCE_ACTION_GUIDED_THR_PASS:
// fly to the return point, with an altitude half way between if (g.fence_retalt > 0) {
// min and max //fly to the return point using fence_retalt
if (g.fence_minalt >= g.fence_maxalt) { guided_WP.alt = home.alt + 100.0*g.fence_retalt;
} else if (g.fence_minalt >= g.fence_maxalt) {
// invalid min/max, use RTL_altitude // invalid min/max, use RTL_altitude
guided_WP.alt = home.alt + g.RTL_altitude_cm; guided_WP.alt = home.alt + g.RTL_altitude_cm;
} else { } 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.alt = home.alt + 100.0*(g.fence_minalt + g.fence_maxalt)/2;
} }
guided_WP.id = 0; guided_WP.id = 0;