From bf03b8cb18ff6404911ea172e673428efac329b9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 24 Jan 2016 11:13:09 +0100 Subject: [PATCH] Yaw rate limit: use a lower limit for less twitching --- src/modules/mc_att_control/mc_att_control_params.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c index 011a6755ad..fc296ccf74 100644 --- a/src/modules/mc_att_control/mc_att_control_params.c +++ b/src/modules/mc_att_control/mc_att_control_params.c @@ -254,13 +254,14 @@ PARAM_DEFINE_FLOAT(MC_PITCHRATE_MAX, 220.0f); * Limit for yaw rate, has effect for large rotations in autonomous mode, * to avoid large control output and mixer saturation. A value of significantly * over 60 degrees per second can already lead to mixer saturation. + * A value of 30 degrees / second is recommended to avoid very audible twitches. * * @unit deg/s * @min 0.0 * @max 360.0 * @group Multicopter Attitude Control */ -PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 60.0f); +PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 30.0f); /** * Max acro roll rate