mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AC_AttitudeControl: Rename set_yaw_target_to_current_heading
This commit is contained in:
parent
b489dd5fe1
commit
34e342f658
@ -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
|
// 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
|
// move attitude target to current heading
|
||||||
float yaw_shift = _ahrs.yaw - _euler_angle_target.z;
|
float yaw_shift = _ahrs.yaw - _euler_angle_target.z;
|
||||||
|
@ -133,7 +133,7 @@ public:
|
|||||||
void set_attitude_target_to_current_attitude() { _ahrs.get_quat_body_to_ned(_attitude_target); }
|
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
|
// 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
|
// handle reset of attitude from EKF since the last iteration
|
||||||
void inertial_frame_reset();
|
void inertial_frame_reset();
|
||||||
|
Loading…
Reference in New Issue
Block a user