Plane: Rename set_yaw_target_to_current_heading

This commit is contained in:
Leonard Hall 2021-05-24 23:12:30 +09:30 committed by Randy Mackay
parent 3b0a870504
commit e275ec9e63

View File

@ -1914,7 +1914,7 @@ void QuadPlane::update_transition(void)
// using vectored yaw for tilt-rotors as the yaw control
// is needed to maintain good control in forward
// transitions
attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_yaw_target_and_rate();
attitude_control->rate_bf_yaw_target(ahrs.get_gyro().z);
}
@ -1966,7 +1966,7 @@ void QuadPlane::update_transition(void)
// We disable this for vectored yaw tilt rotors as they do need active
// yaw control throughout the transition
if (!tilt.is_vectored) {
attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_yaw_target_and_rate();
attitude_control->rate_bf_yaw_target(ahrs.get_gyro().z);
}
break;