mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AC_AttitudeControl: minor comment fix
This commit is contained in:
parent
05418d3d29
commit
b3de52dc59
@ -399,7 +399,7 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, fl
|
||||
_attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z);
|
||||
|
||||
if (_rate_bf_ff_enabled) {
|
||||
// Compute acceleration-limited euler rates
|
||||
// Compute acceleration-limited body frame rates
|
||||
// When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing
|
||||
// the output rate towards the input rate.
|
||||
_attitude_target_ang_vel.x = input_shaping_ang_vel(_attitude_target_ang_vel.x, roll_rate_rads, get_accel_roll_max_radss(), _dt);
|
||||
|
Loading…
Reference in New Issue
Block a user