diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 856f48b9df..c040e7f365 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -876,7 +876,7 @@ Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const } // Sets yaw target to vehicle heading and sets yaw rate to zero -void AC_AttitudeControl::set_yaw_target_to_current_heading() +void AC_AttitudeControl::reset_yaw_target_and_rate() { // move attitude target to current heading float yaw_shift = _ahrs.yaw - _euler_angle_target.z; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index bfbeb50d2c..325a916af0 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -133,7 +133,7 @@ public: void set_attitude_target_to_current_attitude() { _ahrs.get_quat_body_to_ned(_attitude_target); } // Sets yaw target to vehicle heading and sets yaw rate to zero - void set_yaw_target_to_current_heading(); + void reset_yaw_target_and_rate(); // handle reset of attitude from EKF since the last iteration void inertial_frame_reset();