mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: respect yaw orientation on LAND
This commit is contained in:
parent
1c04a91efb
commit
99e04e5861
|
@ -486,6 +486,9 @@ void Copter::Mode::land_run_horizontal_control()
|
|||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
|
||||
if (!is_zero(target_yaw_rate)) {
|
||||
auto_yaw.set_mode(AUTO_YAW_HOLD);
|
||||
}
|
||||
}
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
|
@ -537,9 +540,14 @@ void Copter::Mode::land_run_horizontal_control()
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
// call attitude controller
|
||||
if (auto_yaw.mode() == AUTO_YAW_HOLD) {
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(nav_roll, nav_pitch, target_yaw_rate);
|
||||
} else {
|
||||
// roll, pitch from waypoint controller, yaw heading from auto_heading()
|
||||
attitude_control->input_euler_angle_roll_pitch_yaw(nav_roll, nav_pitch, auto_yaw.yaw(), true);
|
||||
}
|
||||
}
|
||||
|
||||
// pass-through functions to reduce code churn on conversion;
|
||||
|
|
Loading…
Reference in New Issue