Skip to content

Commit

Permalink
Plane: remove AUTO_FBW_STEER
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and magicrub committed Sep 13, 2021
1 parent 66e1baa commit b18da48
Show file tree
Hide file tree
Showing 5 changed files with 4 additions and 24 deletions.
9 changes: 2 additions & 7 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,12 +419,7 @@ void Plane::update_GPS_10Hz(void)
*/
void Plane::update_control_mode(void)
{
Mode *effective_mode = control_mode;
if (control_mode == &mode_auto && g.auto_fbw_steer == 42) {
effective_mode = &mode_fbwa;
}

if (effective_mode != &mode_auto) {
if (control_mode != &mode_auto) {
// hold_course is only used in takeoff and landing
steer_state.hold_course_cd = -1;
}
Expand All @@ -444,7 +439,7 @@ void Plane::update_control_mode(void)
ahrs.set_fly_forward(true);
}

effective_mode->update();
control_mode->update();
}

/*
Expand Down
3 changes: 1 addition & 2 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,8 +226,7 @@ void Plane::stabilize_stick_mixing_fbw()
control_mode == &mode_qrtl ||
control_mode == &mode_qacro ||
control_mode == &mode_training ||
control_mode == &mode_qautotune ||
(control_mode == &mode_auto && g.auto_fbw_steer == 42)) {
control_mode == &mode_qautotune) {
return;
}
// do FBW style stick mixing. We don't treat it linearly
Expand Down
7 changes: 0 additions & 7 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,13 +110,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(stick_mixing, "STICK_MIXING", STICK_MIXING_FBW),

// @Param: AUTO_FBW_STEER
// @DisplayName: Use FBWA steering in AUTO
// @Description: When enabled this option gives FBWA navigation and steering in AUTO mode. This can be used to allow manual stabilised piloting with waypoint logic for triggering payloads. With this enabled the pilot has the same control over the plane as in FBWA mode, and the normal AUTO navigation is completely disabled. THIS OPTION IS NOT RECOMMENDED FOR NORMAL USE.
// @Values: 0:Disabled,42:Enabled
// @User: Advanced
GSCALAR(auto_fbw_steer, "AUTO_FBW_STEER", 0),

// @Param: TKOFF_THR_MINSPD
// @DisplayName: Takeoff throttle min speed
// @Description: Minimum GPS ground speed in m/s used by the speed check that un-suppresses throttle in auto-takeoff. This can be be used for catapult launches where you want the motor to engage only after the plane leaves the catapult, but it is preferable to use the TKOFF_THR_MINACC and TKOFF_THR_DELAY parameters for catapult launches due to the errors associated with GPS measurements. For hand launches with a pusher prop it is strongly advised that this parameter be set to a value no less than 4 m/s to provide additional protection against premature motor start. Note that the GPS velocity will lag the real velocity by about 0.5 seconds. The ground speed check is delayed by the TKOFF_THR_DELAY parameter.
Expand Down
4 changes: 1 addition & 3 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ class Parameters {
k_param_relay,
k_param_takeoff_throttle_delay,
k_param_mode_takeoff, // was skip_gyro_cal
k_param_auto_fbw_steer,
k_param_auto_fbw_steer, // unused
k_param_waypoint_max_radius,
k_param_ground_steer_alt,
k_param_ground_steer_dps,
Expand Down Expand Up @@ -377,8 +377,6 @@ class Parameters {
// speed used for speed scaling
AP_Float scaling_speed;

AP_Int8 auto_fbw_steer;

// Waypoints
//
AP_Int16 waypoint_radius;
Expand Down
5 changes: 0 additions & 5 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,11 +80,6 @@ bool Plane::suppress_throttle(void)
return false;
}

if (control_mode == &mode_auto && g.auto_fbw_steer == 42) {
// user has throttle control
return false;
}

bool gps_movement = (gps.status() >= AP_GPS::GPS_OK_FIX_2D && gps.ground_speed() >= 5);

if ((control_mode == &mode_auto &&
Expand Down

0 comments on commit b18da48

Please sign in to comment.