Plane: added FENCE_ACTION=3 behaviour
this makes it safer to enable the geofence as a receiver failsafe mode. It retains manual throttle control, so if it triggers on the ground due to the receiver losing signal from the transmitter then the throttle can be kept low, preventing an unexpected takeoff.
This commit is contained in:
parent
7328369b91
commit
f6688582a6
@ -268,6 +268,9 @@ SITL sitl;
|
||||
static bool training_manual_roll; // user has manual roll control
|
||||
static bool training_manual_pitch; // user has manual pitch control
|
||||
|
||||
// should throttle be pass-thru in guided?
|
||||
static bool guided_throttle_passthru;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// GCS selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -743,6 +743,10 @@ static void set_servos(void)
|
||||
// manual pass through of throttle while in FBWA or
|
||||
// STABILIZE mode with THR_PASS_STAB set
|
||||
channel_throttle->radio_out = channel_throttle->radio_in;
|
||||
} else if (control_mode == GUIDED &&
|
||||
guided_throttle_passthru) {
|
||||
// manual pass through of throttle while in GUIDED
|
||||
channel_throttle->radio_out = channel_throttle->radio_in;
|
||||
} else {
|
||||
// normal throttle calculation based on servo_out
|
||||
channel_throttle->calc_pwm();
|
||||
|
@ -207,8 +207,8 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
// @Param: FENCE_ACTION
|
||||
// @DisplayName: Action on geofence breach
|
||||
// @Description: What to do on fence breach
|
||||
// @Values: 0:None,1:GuidedMode,2:ReportOnly
|
||||
// @Description: What to do on fence breach. If this is set to 0 then no action is taken, and geofencing is disabled. If this is set to 1 then the plane will enter GUIDED mode, with the target waypoint as the fence return point. If this is set to 2 then the fence breach is reported to the ground station, but no other action is taken. If set to 3 then the plane enters guided mode but the pilot retains manual throttle control.
|
||||
// @Values: 0:None,1:GuidedMode,2:ReportOnly,3:GuidedModeThrPass
|
||||
// @User: Standard
|
||||
GSCALAR(fence_action, "FENCE_ACTION", 0),
|
||||
|
||||
|
@ -180,7 +180,7 @@ static void geofence_check(bool altitude_check_only)
|
||||
// switch back to the chosen control mode if still in
|
||||
// GUIDED to the return point
|
||||
if (geofence_state != NULL &&
|
||||
g.fence_action == FENCE_ACTION_GUIDED &&
|
||||
(g.fence_action == FENCE_ACTION_GUIDED || g.fence_action == FENCE_ACTION_GUIDED_THR_PASS) &&
|
||||
g.fence_channel != 0 &&
|
||||
control_mode == GUIDED &&
|
||||
g.fence_total >= 5 &&
|
||||
@ -264,6 +264,7 @@ static void geofence_check(bool altitude_check_only)
|
||||
break;
|
||||
|
||||
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) {
|
||||
@ -286,6 +287,9 @@ static void geofence_check(bool altitude_check_only)
|
||||
}
|
||||
|
||||
set_mode(GUIDED);
|
||||
if (g.fence_action == FENCE_ACTION_GUIDED_THR_PASS) {
|
||||
guided_throttle_passthru = true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -343,6 +343,7 @@ static void set_mode(enum FlightMode mode)
|
||||
break;
|
||||
|
||||
case GUIDED:
|
||||
guided_throttle_passthru = false;
|
||||
set_guided_WP();
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user