forked from Archive/PX4-Autopilot
position_estimator_inav: parameters descriptions added
This commit is contained in:
parent
8688cad8e6
commit
e7d8d9c91f
|
@ -40,22 +40,196 @@
|
|||
|
||||
#include "position_estimator_inav_params.h"
|
||||
|
||||
/**
|
||||
* Z axis weight for barometer
|
||||
*
|
||||
* Weight (cutoff frequency) for barometer altitude measurements.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f);
|
||||
|
||||
/**
|
||||
* Z axis weight for GPS
|
||||
*
|
||||
* Weight (cutoff frequency) for GPS altitude measurements. GPS altitude data is very noisy and should be used only as slow correction for baro offset.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f);
|
||||
|
||||
/**
|
||||
* Z axis weight for sonar
|
||||
*
|
||||
* Weight (cutoff frequency) for sonar measurements.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f);
|
||||
|
||||
/**
|
||||
* XY axis weight for GPS position
|
||||
*
|
||||
* Weight (cutoff frequency) for GPS position measurements.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
|
||||
|
||||
/**
|
||||
* XY axis weight for GPS velocity
|
||||
*
|
||||
* Weight (cutoff frequency) for GPS velocity measurements.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
|
||||
|
||||
/**
|
||||
* XY axis weight for optical flow
|
||||
*
|
||||
* Weight (cutoff frequency) for optical flow (velocity) measurements.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f);
|
||||
|
||||
/**
|
||||
* XY axis weight for resetting velocity
|
||||
*
|
||||
* When velocity sources lost slowly decrease estimated horizontal velocity with this weight.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.5f);
|
||||
|
||||
/**
|
||||
* XY axis weight factor for GPS when optical flow available
|
||||
*
|
||||
* When optical flow data available, multiply GPS weights (for position and velocity) by this factor.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f);
|
||||
|
||||
/**
|
||||
* Accelerometer bias estimation weight
|
||||
*
|
||||
* Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 0.1
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f);
|
||||
|
||||
/**
|
||||
* Optical flow scale factor
|
||||
*
|
||||
* Factor to convert raw optical flow (in pixels) to radians [rad/px].
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @unit rad/px
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f);
|
||||
|
||||
/**
|
||||
* Minimal acceptable optical flow quality
|
||||
*
|
||||
* 0 - lowest quality, 1 - best quality.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_FLOW_Q_MIN, 0.5f);
|
||||
|
||||
/**
|
||||
* Weight for sonar filter
|
||||
*
|
||||
* Sonar filter detects spikes on sonar measurements and used to detect new surface level.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_SONAR_FILT, 0.05f);
|
||||
|
||||
/**
|
||||
* Sonar maximal error for new surface
|
||||
*
|
||||
* If sonar measurement error is larger than this value it skiped (spike) or accepted as new surface level (if offset is stable).
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @unit m
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
|
||||
|
||||
/**
|
||||
* Land detector time
|
||||
*
|
||||
* Vehicle assumed landed if no altitude changes happened during this time on low throttle.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @unit s
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
|
||||
|
||||
/**
|
||||
* Land detector altitude dispersion threshold
|
||||
*
|
||||
* Dispersion threshold for triggering land detector.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 10.0
|
||||
* @unit m
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
|
||||
|
||||
/**
|
||||
* Land detector throttle threshold
|
||||
*
|
||||
* Value should be lower than minimal hovering thrust. Half of it is good choice.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f);
|
||||
|
||||
/**
|
||||
* GPS delay
|
||||
*
|
||||
* GPS delay compensation
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @unit s
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_DELAY_GPS, 0.2f);
|
||||
|
||||
int parameters_init(struct position_estimator_inav_param_handles *h)
|
||||
|
|
Loading…
Reference in New Issue