attitude_estimator_q: Max gyro bias limiting

This commit is contained in:
Anton Babushkin 2015-04-13 16:21:53 +02:00
parent 3b89a2533f
commit cc99e6dc1f
1 changed files with 1 additions and 0 deletions

View File

@ -46,3 +46,4 @@ PARAM_DEFINE_FLOAT(ATT_W_MAG, 0.1f);
PARAM_DEFINE_FLOAT(ATT_W_GYRO_BIAS, 0.1f);
PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f); ///< magnetic declination, in degrees
PARAM_DEFINE_INT32(ATT_ACC_COMP, 2); ///< acceleration compensation
PARAM_DEFINE_FLOAT(ATT_BIAS_MAX, 0.05f); ///< gyro bias limit, rad/s