Browse Source

ekf_att_pos_estimator param @unit

sbg
Daniel Agar 9 years ago committed by Lorenz Meier
parent
commit
676713d0c2
  1. 23
      src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c

23
src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c

@ -49,6 +49,7 @@ @@ -49,6 +49,7 @@
*
* The delay in milliseconds of the velocity estimate from GPS.
*
* @unit ms
* @min 0
* @max 1000
* @group Position Estimator
@ -60,6 +61,7 @@ PARAM_DEFINE_INT32(PE_VEL_DELAY_MS, 230); @@ -60,6 +61,7 @@ PARAM_DEFINE_INT32(PE_VEL_DELAY_MS, 230);
*
* The delay in milliseconds of the position estimate from GPS.
*
* @unit ms
* @min 0
* @max 1000
* @group Position Estimator
@ -71,6 +73,7 @@ PARAM_DEFINE_INT32(PE_POS_DELAY_MS, 210); @@ -71,6 +73,7 @@ PARAM_DEFINE_INT32(PE_POS_DELAY_MS, 210);
*
* The delay in milliseconds of the height estimate from the barometer.
*
* @unit ms
* @min 0
* @max 1000
* @group Position Estimator
@ -83,6 +86,7 @@ PARAM_DEFINE_INT32(PE_HGT_DELAY_MS, 350); @@ -83,6 +86,7 @@ PARAM_DEFINE_INT32(PE_HGT_DELAY_MS, 350);
* The delay in milliseconds of the magnetic field estimate from
* the magnetometer.
*
* @unit ms
* @min 0
* @max 1000
* @group Position Estimator
@ -94,6 +98,7 @@ PARAM_DEFINE_INT32(PE_MAG_DELAY_MS, 30); @@ -94,6 +98,7 @@ PARAM_DEFINE_INT32(PE_MAG_DELAY_MS, 30);
*
* The delay in milliseconds of the airspeed estimate.
*
* @unit ms
* @min 0
* @max 1000
* @group Position Estimator
@ -104,7 +109,7 @@ PARAM_DEFINE_INT32(PE_TAS_DELAY_MS, 210); @@ -104,7 +109,7 @@ PARAM_DEFINE_INT32(PE_TAS_DELAY_MS, 210);
* GPS vs. barometric altitude update weight
*
* RE-CHECK this.
*
* @unit
* @min 0.0
* @max 1.0
* @group Position Estimator
@ -117,6 +122,7 @@ PARAM_DEFINE_FLOAT(PE_GPS_ALT_WGT, 0.9f); @@ -117,6 +122,7 @@ PARAM_DEFINE_FLOAT(PE_GPS_ALT_WGT, 0.9f);
* Increasing this value will make the filter trust this sensor
* less and trust other sensors more.
*
* @unit
* @min 0.5
* @max 5.0
* @group Position Estimator
@ -128,6 +134,7 @@ PARAM_DEFINE_FLOAT(PE_EAS_NOISE, 1.4f); @@ -128,6 +134,7 @@ PARAM_DEFINE_FLOAT(PE_EAS_NOISE, 1.4f);
*
* Generic default: 0.3, multicopters: 0.5, ground vehicles: 0.5
*
* @unit
* @min 0.05
* @max 5.0
* @group Position Estimator
@ -139,6 +146,7 @@ PARAM_DEFINE_FLOAT(PE_VELNE_NOISE, 0.3f); @@ -139,6 +146,7 @@ PARAM_DEFINE_FLOAT(PE_VELNE_NOISE, 0.3f);
*
* Generic default: 0.3, multicopters: 0.4, ground vehicles: 0.7
*
* @unit
* @min 0.2
* @max 3.0
* @group Position Estimator
@ -150,6 +158,7 @@ PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.3f); @@ -150,6 +158,7 @@ PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.3f);
*
* Generic defaults: 0.5, multicopters: 0.5, ground vehicles: 0.5
*
* @unit
* @min 0.1
* @max 10.0
* @group Position Estimator
@ -161,6 +170,7 @@ PARAM_DEFINE_FLOAT(PE_POSNE_NOISE, 0.5f); @@ -161,6 +170,7 @@ PARAM_DEFINE_FLOAT(PE_POSNE_NOISE, 0.5f);
*
* Generic defaults: 1.25, multicopters: 1.0, ground vehicles: 1.0
*
* @unit
* @min 0.5
* @max 3.0
* @group Position Estimator
@ -172,6 +182,7 @@ PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 1.25f); @@ -172,6 +182,7 @@ PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 1.25f);
*
* Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05
*
* @unit
* @min 0.01
* @max 1.0
* @group Position Estimator
@ -185,6 +196,7 @@ PARAM_DEFINE_FLOAT(PE_MAG_NOISE, 0.05f); @@ -185,6 +196,7 @@ PARAM_DEFINE_FLOAT(PE_MAG_NOISE, 0.05f);
* This noise controls how much the filter trusts the gyro measurements.
* Increasing it makes the filter trust the gyro less and other sensors more.
*
* @unit
* @min 0.001
* @max 0.05
* @group Position Estimator
@ -198,6 +210,7 @@ PARAM_DEFINE_FLOAT(PE_GYRO_PNOISE, 0.015f); @@ -198,6 +210,7 @@ PARAM_DEFINE_FLOAT(PE_GYRO_PNOISE, 0.015f);
* Increasing this value makes the filter trust the accelerometer less
* and other sensors more.
*
* @unit
* @min 0.05
* @max 1.0
* @group Position Estimator
@ -210,6 +223,7 @@ PARAM_DEFINE_FLOAT(PE_ACC_PNOISE, 0.125f); @@ -210,6 +223,7 @@ PARAM_DEFINE_FLOAT(PE_ACC_PNOISE, 0.125f);
* Generic defaults: 1e-07f, multicopters: 1e-07f, ground vehicles: 1e-07f.
* Increasing this value will make the gyro bias converge faster but noisier.
*
* @unit
* @min 0.00000005
* @max 0.00001
* @group Position Estimator
@ -222,6 +236,7 @@ PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-07f); @@ -222,6 +236,7 @@ PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-07f);
* Generic defaults: 0.00001f, multicopters: 0.00001f, ground vehicles: 0.00001f.
* Increasing this value makes the bias estimation faster and noisier.
*
* @unit
* @min 0.00001
* @max 0.001
* @group Position Estimator
@ -235,6 +250,7 @@ PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 1e-05f); @@ -235,6 +250,7 @@ PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 1e-05f);
* Increasing this value makes the magnetometer earth bias estimate converge
* faster but also noisier.
*
* @unit
* @min 0.0001
* @max 0.01
* @group Position Estimator
@ -248,6 +264,7 @@ PARAM_DEFINE_FLOAT(PE_MAGE_PNOISE, 0.0003f); @@ -248,6 +264,7 @@ PARAM_DEFINE_FLOAT(PE_MAGE_PNOISE, 0.0003f);
* Increasing this value makes the magnetometer body bias estimate converge faster
* but also noisier.
*
* @unit
* @min 0.0001
* @max 0.01
* @group Position Estimator
@ -260,6 +277,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_PNOISE, 0.0003f); @@ -260,6 +277,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_PNOISE, 0.0003f);
* The magnetometer bias. This bias is learnt by the filter over time and
* persists between boots.
*
* @unit
* @min -0.6
* @max 0.6
* @group Position Estimator
@ -272,6 +290,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_X, 0.0f); @@ -272,6 +290,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_X, 0.0f);
* The magnetometer bias. This bias is learnt by the filter over time and
* persists between boots.
*
* @unit
* @min -0.6
* @max 0.6
* @group Position Estimator
@ -284,6 +303,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_Y, 0.0f); @@ -284,6 +303,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_Y, 0.0f);
* The magnetometer bias. This bias is learnt by the filter over time and
* persists between boots.
*
* @unit
* @min -0.6
* @max 0.6
* @group Position Estimator
@ -296,6 +316,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_Z, 0.0f); @@ -296,6 +316,7 @@ PARAM_DEFINE_FLOAT(PE_MAGB_Z, 0.0f);
* If the standard deviation of the GPS position estimate is below this threshold
* in meters, the filter will initialize.
*
* @unit
* @min 0.3
* @max 10.0
* @group Position Estimator

Loading…
Cancel
Save