mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AC_AttitudeControl: Rename set_attitude_target_to_current_attitude
This commit is contained in:
parent
fb83f98b77
commit
359cf8ed0e
@ -876,7 +876,7 @@ Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Sets attitude target to vehicle attitude and sets all rates to zero
|
// Sets attitude target to vehicle attitude and sets all rates to zero
|
||||||
void AC_AttitudeControl::set_attitude_target_to_current_attitude()
|
void AC_AttitudeControl::reset_target_and_rate()
|
||||||
{
|
{
|
||||||
// move attitude target to current attitude
|
// move attitude target to current attitude
|
||||||
_ahrs.get_quat_body_to_ned(_attitude_target);
|
_ahrs.get_quat_body_to_ned(_attitude_target);
|
||||||
|
@ -130,7 +130,7 @@ public:
|
|||||||
void reset_rate_controller_I_terms_smoothly();
|
void reset_rate_controller_I_terms_smoothly();
|
||||||
|
|
||||||
// Sets attitude target to vehicle attitude and sets all rates to zero
|
// Sets attitude target to vehicle attitude and sets all rates to zero
|
||||||
void set_attitude_target_to_current_attitude();
|
void reset_target_and_rate();
|
||||||
|
|
||||||
// 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 reset_yaw_target_and_rate();
|
void reset_yaw_target_and_rate();
|
||||||
|
Loading…
Reference in New Issue
Block a user