mirror of https://github.com/ArduPilot/ardupilot
AC_AttitudeControl: remove unused get_tilt_limit_rad
This commit is contained in:
parent
c08203de17
commit
6315e6eb45
|
@ -303,9 +303,6 @@ protected:
|
|||
// Return the yaw slew rate limit in radians/s
|
||||
float get_slew_yaw_rads() { return radians(_slew_yaw*0.01f); }
|
||||
|
||||
// Return the tilt angle limit in radians
|
||||
float get_tilt_limit_rad() { return radians(_aparm.angle_max*0.01f); }
|
||||
|
||||
// Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
|
||||
AP_Float _slew_yaw;
|
||||
|
||||
|
|
Loading…
Reference in New Issue