AC_Attitude_Control: add get_attitude_target_ang_vel
This commit is contained in:
parent
f3cac9e1aa
commit
4b51dc73b5
@ -210,6 +210,9 @@ public:
|
||||
// Return the body-to-NED target attitude used by the quadplane-specific attitude control input methods
|
||||
Quaternion get_attitude_target_quat() const { return _attitude_target; }
|
||||
|
||||
// Return the angular velocity of the target (setpoint) [rad/s] in the target attitude frame
|
||||
const Vector3f& get_attitude_target_ang_vel() const { return _ang_vel_target;}
|
||||
|
||||
// Return the angle between the target thrust vector and the current thrust vector.
|
||||
float get_att_error_angle_deg() const { return degrees(_thrust_error_angle); }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user