mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: limit rotational rate to 2000dps
This commit is contained in:
parent
4d01cb1716
commit
73a2c99d56
@ -332,6 +332,10 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
|
||||
// update rotational rates in body frame
|
||||
gyro += rot_accel * delta_time;
|
||||
|
||||
gyro.x = constrain_float(gyro.x, -radians(2000), radians(2000));
|
||||
gyro.y = constrain_float(gyro.y, -radians(2000), radians(2000));
|
||||
gyro.z = constrain_float(gyro.z, -radians(2000), radians(2000));
|
||||
|
||||
// update attitude
|
||||
dcm.rotate(gyro * delta_time);
|
||||
dcm.normalize();
|
||||
|
Loading…
Reference in New Issue
Block a user