mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_AttitudeControl: added get_ang_vel_yaw_max_rads()
This commit is contained in:
parent
7ebf45616d
commit
53f1fc1295
@ -113,6 +113,9 @@ public:
|
||||
// get the pitch angular velocity limit in radians/s
|
||||
float get_ang_vel_pitch_max_rads() const { return radians(_ang_vel_pitch_max); }
|
||||
|
||||
// get the yaw angular velocity limit in radians/s
|
||||
float get_ang_vel_yaw_max_rads() const { return radians(_ang_vel_yaw_max); }
|
||||
|
||||
// get the yaw slew limit
|
||||
float get_slew_yaw_cds() const { return _slew_yaw; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user