Att control: Allow higher yaw rate by default

This commit is contained in:
Lorenz Meier 2016-02-27 11:23:24 +01:00
parent e9d778fd24
commit 44e885f3c3
1 changed files with 1 additions and 1 deletions

View File

@ -278,7 +278,7 @@ PARAM_DEFINE_FLOAT(MC_PITCHRATE_MAX, 220.0f);
* @decimal 1
* @group Multicopter Attitude Control
*/
PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 120.0f);
PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 200.0f);
/**
* Max yaw rate in auto mode