mirror of https://github.com/ArduPilot/ardupilot
Copter: ignore pilot yaw during takeoff with option
This commit is contained in:
parent
94c771ee74
commit
6d7ef8f436
|
@ -108,7 +108,7 @@ void Mode::auto_takeoff_run()
|
|||
|
||||
// process pilot's yaw input
|
||||
float target_yaw_rate = 0;
|
||||
if (!copter.failsafe.radio) {
|
||||
if (!copter.failsafe.radio && copter.flightmode->use_pilot_yaw()) {
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue