mirror of https://github.com/ArduPilot/ardupilot
Plane: Support unlocking cruise heading with rudder
This commit is contained in:
parent
dc85e538e1
commit
ec86a30a4d
|
@ -715,8 +715,7 @@ void Plane::update_flight_mode(void)
|
|||
roll when heading is locked. Heading becomes unlocked on
|
||||
any aileron or rudder input
|
||||
*/
|
||||
if ((channel_roll->get_control_in() != 0 ||
|
||||
rudder_input != 0)) {
|
||||
if (channel_roll->get_control_in() != 0 || channel_rudder->get_control_in() != 0) {
|
||||
cruise_state.locked_heading = false;
|
||||
cruise_state.lock_timer_ms = 0;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue