Plane: FENCE_RET_RALLY param. Plane returns to rally point on breach.

This commit is contained in:
Michael Day 2014-02-20 09:10:57 -08:00 committed by Andrew Tridgell
parent 25f23cf16c
commit f921d4fbac
3 changed files with 10 additions and 6 deletions

View File

@ -111,6 +111,7 @@ public:
// 105: Extra parameters
k_param_fence_retalt = 105,
k_param_fence_autoenable,
k_param_fence_ret_rally,
// 110: Telemetry control
//
@ -341,6 +342,7 @@ public:
AP_Int16 fence_maxalt; // meters
AP_Int16 fence_retalt; // meters
AP_Int8 fence_autoenable;
AP_Int8 fence_ret_rally;
#endif
AP_Int8 rally_total;

View File

@ -277,7 +277,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Description: When set to 1, gefence automatically enables after an auto takeoff and automatically disables at the beginning of an auto landing. When on the ground before takeoff the fence is disabled.
// @Range: 0 1
// @User: Standard
GSCALAR(fence_autoenable, "FENCE_AUTOENABLE", 0),
GSCALAR(fence_autoenable, "FENCE_AUTOENABLE", 0),
// @Param: FENCE_RET_RALLY
// @DisplayName: Fence Return to Rally
// @Description: When set to 1: on fence breach the plane will return to the nearest rally point rather than the fence return point. If no rally points have been defined the plane will return to the home point.
// @Range: 0 1
// @User: Standard
GSCALAR(fence_ret_rally, "FENCE_RET_RALLY", 0),
#endif
// @Param: RALLY_TOTAL

View File

@ -334,15 +334,10 @@ static void geofence_check(bool altitude_check_only)
// min and max
guided_WP_loc.alt = home.alt + 100.0*(g.fence_minalt + g.fence_maxalt)/2;
}
//guided_WP_loc.id = 0;
//guided_WP_loc.p1 = 0;
guided_WP_loc.options = 0;
guided_WP_loc.lat = geofence_state->boundary[0].x;
guided_WP_loc.lng = geofence_state->boundary[0].y;
}
guided_WP_loc.options = 0;
guided_WP_loc.lat = geofence_state->boundary[0].x;
guided_WP_loc.lng = geofence_state->boundary[0].y;
geofence_state->old_switch_position = oldSwitchPosition;