Skip to content

Commit

Permalink
position_estimator_inav param @Unit
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar authored and LorenzMeier committed Mar 14, 2016
1 parent db06e7e commit cfac0b0
Showing 1 changed file with 21 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
*
* Weight (cutoff frequency) for barometer altitude measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -57,6 +58,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f);
*
* Weight (cutoff frequency) for GPS altitude measurements. GPS altitude data is very noisy and should be used only as slow correction for baro offset.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -68,6 +70,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f);
*
* Weight (cutoff frequency) for GPS altitude velocity measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -79,6 +82,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_V, 0.0f);
*
* Weight (cutoff frequency) for vision altitude measurements. vision altitude data is very noisy and should be used only as slow correction for baro offset.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -90,6 +94,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_VIS_P, 5.0f);
*
* Weight (cutoff frequency) for lidar measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -101,6 +106,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_LIDAR, 3.0f);
*
* Weight (cutoff frequency) for GPS position measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -112,6 +118,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
*
* Weight (cutoff frequency) for GPS velocity measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -123,6 +130,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
*
* Weight (cutoff frequency) for vision position measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -134,6 +142,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_P, 7.0f);
*
* Weight (cutoff frequency) for vision velocity measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -145,6 +154,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_V, 0.0f);
*
* Weight (cutoff frequency) for mocap position measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -157,6 +167,7 @@ PARAM_DEFINE_FLOAT(INAV_W_MOC_P, 10.0f);
*
* Weight (cutoff frequency) for optical flow (velocity) measurements.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -168,6 +179,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 0.8f);
*
* When velocity sources lost slowly decrease estimated horizontal velocity with this weight.
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -179,6 +191,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.5f);
*
* When optical flow data available, multiply GPS weights (for position and velocity) by this factor.
*
* @unit
* @min 0.0
* @max 1.0
* @group Position Estimator INAV
Expand All @@ -190,6 +203,7 @@ PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f);
*
* Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable.
*
* @unit
* @min 0.0
* @max 0.1
* @group Position Estimator INAV
Expand All @@ -201,6 +215,7 @@ PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f);
*
* Factor to scale optical flow
*
* @unit
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
Expand All @@ -212,6 +227,7 @@ PARAM_DEFINE_FLOAT(INAV_FLOW_K, 1.35f);
*
* 0 - lowest quality, 1 - best quality.
*
* @unit
* @min 0.0
* @max 1.0
* @group Position Estimator INAV
Expand Down Expand Up @@ -259,6 +275,7 @@ PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
*
* Value should be lower than minimal hovering thrust. Half of it is good choice.
*
* @unit
* @min 0.0
* @max 1.0
* @group Position Estimator INAV
Expand Down Expand Up @@ -306,8 +323,7 @@ PARAM_DEFINE_FLOAT(INAV_FLOW_DIST_Y, 0.0f);
*
* Disable mocap
*
* @min 0
* @max 1
* @unit boolean
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0);
Expand All @@ -317,8 +333,7 @@ PARAM_DEFINE_FLOAT(INAV_DISAB_MOCAP, 0);
*
* Enable LIDAR for altitude estimation
*
* @min 0
* @max 1
* @unit boolean
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_LIDAR_EST, 0);
Expand All @@ -340,8 +355,8 @@ PARAM_DEFINE_FLOAT(INAV_LIDAR_OFF, 0.0f);
*
* Set to the appropriate key (328754) to disable vision input.
*
* @unit
* @min 0
* @max 1
* @group Position Estimator INAV
*/
PARAM_DEFINE_INT32(CBRK_NO_VISION, 0);
Expand All @@ -353,8 +368,7 @@ PARAM_DEFINE_INT32(CBRK_NO_VISION, 0);
* Else the system uses the combined attitude / position
* filter framework.
*
* @min 0
* @max 1
* @unit boolean
* @group Position Estimator INAV
*/
PARAM_DEFINE_INT32(INAV_ENABLED, 1);
Expand Down

0 comments on commit cfac0b0

Please sign in to comment.