mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AC_AttitudeControl: Fix Angle Vel units on function
This commit is contained in:
parent
c4cf4d6a8c
commit
0ee9dbc059
@ -106,10 +106,10 @@ public:
|
|||||||
void save_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max.set_and_save(accel_yaw_max); }
|
void save_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max.set_and_save(accel_yaw_max); }
|
||||||
|
|
||||||
// get the roll angular velocity limit in radians/s
|
// get the roll angular velocity limit in radians/s
|
||||||
float get_ang_vel_roll_max_radss() const { return _ang_vel_roll_max; }
|
float get_ang_vel_roll_max_rads() const { return _ang_vel_roll_max; }
|
||||||
|
|
||||||
// get the pitch angular velocity limit in radians/s
|
// get the pitch angular velocity limit in radians/s
|
||||||
float get_ang_vel_pitch_max_radss() const { return _ang_vel_pitch_max; }
|
float get_ang_vel_pitch_max_rads() const { return _ang_vel_pitch_max; }
|
||||||
|
|
||||||
// get the yaw slew limit
|
// get the yaw slew limit
|
||||||
float get_slew_yaw_cds() const { return _slew_yaw; }
|
float get_slew_yaw_cds() const { return _slew_yaw; }
|
||||||
|
Loading…
Reference in New Issue
Block a user