diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index f81c1efe4e..6b03a94f3e 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -905,7 +905,7 @@ static void update_current_flight_mode(void) nav_roll = g.channel_roll.norm_input() * g.roll_limit; altitude_error = g.channel_pitch.norm_input() * g.pitch_limit_min; - if ((current_loc.alt>=home.alt+g.FBWB_min_altitude) || (g.FBWB_min_altitude == -1)) { + if ((current_loc.alt>=home.alt+g.FBWB_min_altitude) || (g.FBWB_min_altitude == 0)) { altitude_error = g.channel_pitch.norm_input() * g.pitch_limit_min; } else { if (g.channel_pitch.norm_input()<0) diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index cdb3ea1217..9277351bf9 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -85,7 +85,7 @@ public: // k_param_flybywire_airspeed_min = 120, k_param_flybywire_airspeed_max, - k_param_FBWB_min_altitude, // -1=disabled, minimum value for altitude in cm (default 30m) + k_param_FBWB_min_altitude, // 0=disabled, minimum value for altitude in cm (for first time try 30 meters = 3000 cm) // // 130: Sensor parameters