mirror of https://github.com/ArduPilot/ardupilot
Plane: don't use ground steering until flare in landing
we need to be able to guide the plane fully in the landing approach
This commit is contained in:
parent
cf98cc29b5
commit
b94bc0c243
|
@ -214,6 +214,10 @@ static void stabilize_yaw(float speed_scaler)
|
||||||
// are below the GROUND_STEER_ALT
|
// are below the GROUND_STEER_ALT
|
||||||
steering_control.ground_steering = (channel_roll->control_in == 0 &&
|
steering_control.ground_steering = (channel_roll->control_in == 0 &&
|
||||||
fabsf(relative_altitude()) < g.ground_steer_alt);
|
fabsf(relative_altitude()) < g.ground_steer_alt);
|
||||||
|
if (control_mode == AUTO && flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
||||||
|
// don't use ground steering on landing approach
|
||||||
|
steering_control.ground_steering = false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue