forked from Archive/PX4-Autopilot
Add filter parameters and multicopter defaults to parametrize Pauls estimator correctly when running for multicopters. Estimator itself not updated yet, will be next step.
This commit is contained in:
parent
12eae1777d
commit
edd16afead
|
@ -35,6 +35,12 @@ then
|
|||
param set MPC_TILT_MAX 1.0
|
||||
param set MPC_LAND_SPEED 1.0
|
||||
param set MPC_LAND_TILT 0.3
|
||||
|
||||
param set PE_VELNE_NOISE 0.5
|
||||
param set PE_VELNE_NOISE 0.7
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
param set PE_POSD_NOISE 1.0
|
||||
|
||||
fi
|
||||
|
||||
set PWM_RATE 400
|
||||
|
|
|
@ -199,6 +199,17 @@ private:
|
|||
int32_t height_delay_ms;
|
||||
int32_t mag_delay_ms;
|
||||
int32_t tas_delay_ms;
|
||||
float velne_noise;
|
||||
float veld_noise;
|
||||
float posne_noise;
|
||||
float posd_noise;
|
||||
float mag_noise;
|
||||
float gyro_pnoise;
|
||||
float acc_pnoise;
|
||||
float gbias_pnoise;
|
||||
float abias_pnoise;
|
||||
float mage_pnoise;
|
||||
float magb_pnoise;
|
||||
} _parameters; /**< local copies of interesting parameters */
|
||||
|
||||
struct {
|
||||
|
@ -207,6 +218,17 @@ private:
|
|||
param_t height_delay_ms;
|
||||
param_t mag_delay_ms;
|
||||
param_t tas_delay_ms;
|
||||
param_t velne_noise;
|
||||
param_t veld_noise;
|
||||
param_t posne_noise;
|
||||
param_t posd_noise;
|
||||
param_t mag_noise;
|
||||
param_t gyro_pnoise;
|
||||
param_t acc_pnoise;
|
||||
param_t gbias_pnoise;
|
||||
param_t abias_pnoise;
|
||||
param_t mage_pnoise;
|
||||
param_t magb_pnoise;
|
||||
} _parameter_handles; /**< handles for interesting parameters */
|
||||
|
||||
AttPosEKF *_ekf;
|
||||
|
@ -302,6 +324,17 @@ FixedwingEstimator::FixedwingEstimator() :
|
|||
_parameter_handles.height_delay_ms = param_find("PE_HGT_DELAY_MS");
|
||||
_parameter_handles.mag_delay_ms = param_find("PE_MAG_DELAY_MS");
|
||||
_parameter_handles.tas_delay_ms = param_find("PE_TAS_DELAY_MS");
|
||||
_parameter_handles.velne_noise = param_find("PE_VELNE_NOISE");
|
||||
_parameter_handles.veld_noise = param_find("PE_VELD_NOISE");
|
||||
_parameter_handles.posne_noise = param_find("PE_POSNE_NOISE");
|
||||
_parameter_handles.posd_noise = param_find("PE_POSD_NOISE");
|
||||
_parameter_handles.mag_noise = param_find("PE_MAG_NOISE");
|
||||
_parameter_handles.gyro_pnoise = param_find("PE_GYRO_PNOISE");
|
||||
_parameter_handles.acc_pnoise = param_find("PE_ACC_PNOISE");
|
||||
_parameter_handles.gbias_pnoise = param_find("PE_GBIAS_PNOISE");
|
||||
_parameter_handles.abias_pnoise = param_find("PE_ABIAS_PNOISE");
|
||||
_parameter_handles.mage_pnoise = param_find("PE_MAGE_PNOISE");
|
||||
_parameter_handles.magb_pnoise = param_find("PE_MAGB_PNOISE");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
|
@ -366,6 +399,17 @@ FixedwingEstimator::parameters_update()
|
|||
param_get(_parameter_handles.height_delay_ms, &(_parameters.height_delay_ms));
|
||||
param_get(_parameter_handles.mag_delay_ms, &(_parameters.mag_delay_ms));
|
||||
param_get(_parameter_handles.tas_delay_ms, &(_parameters.tas_delay_ms));
|
||||
param_get(_parameter_handles.velne_noise, &(_parameters.velne_noise));
|
||||
param_get(_parameter_handles.veld_noise, &(_parameters.veld_noise));
|
||||
param_get(_parameter_handles.posne_noise, &(_parameters.posne_noise));
|
||||
param_get(_parameter_handles.posd_noise, &(_parameters.posd_noise));
|
||||
param_get(_parameter_handles.mag_noise, &(_parameters.mag_noise));
|
||||
param_get(_parameter_handles.gyro_pnoise, &(_parameters.gyro_pnoise));
|
||||
param_get(_parameter_handles.acc_pnoise, &(_parameters.acc_pnoise));
|
||||
param_get(_parameter_handles.gbias_pnoise, &(_parameters.gbias_pnoise));
|
||||
param_get(_parameter_handles.abias_pnoise, &(_parameters.abias_pnoise));
|
||||
param_get(_parameter_handles.mage_pnoise, &(_parameters.mage_pnoise));
|
||||
param_get(_parameter_handles.magb_pnoise, &(_parameters.magb_pnoise));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -115,3 +115,134 @@ PARAM_DEFINE_INT32(PE_TAS_DELAY_MS, 210);
|
|||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_GPS_ALT_WGT, 0.9f);
|
||||
|
||||
/**
|
||||
* Velocity noise in north-east (horizontal) direction.
|
||||
*
|
||||
* Generic default: 0.3, multicopters: 0.5, ground vehicles: 0.5
|
||||
*
|
||||
* @min 0.05
|
||||
* @max 5.0
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_VELNE_NOISE, 0.3f);
|
||||
|
||||
/**
|
||||
* Velocity noise in down (vertical) direction
|
||||
*
|
||||
* Generic default: 0.5, multicopters: 0.7, ground vehicles: 0.7
|
||||
*
|
||||
* @min 0.05
|
||||
* @max 5.0
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.5f);
|
||||
|
||||
/**
|
||||
* Position noise in north-east (horizontal) direction
|
||||
*
|
||||
* Generic defaults: 0.5, multicopters: 0.5, ground vehicles: 0.5
|
||||
*
|
||||
* @min 0.1
|
||||
* @max 10.0
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_POSNE_NOISE, 0.5f);
|
||||
|
||||
/**
|
||||
* Position noise in down (vertical) direction
|
||||
*
|
||||
* Generic defaults: 0.5, multicopters: 1.0, ground vehicles: 1.0
|
||||
*
|
||||
* @min 0.1
|
||||
* @max 10.0
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 0.5f);
|
||||
|
||||
/**
|
||||
* Magnetometer measurement noise
|
||||
*
|
||||
* Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05
|
||||
*
|
||||
* @min 0.1
|
||||
* @max 10.0
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_MAG_NOISE, 0.05f);
|
||||
|
||||
/**
|
||||
* Gyro process noise
|
||||
*
|
||||
* Generic defaults: 0.015, multicopters: 0.015, ground vehicles: 0.015.
|
||||
* This noise controls how much the filter trusts the gyro measurements.
|
||||
* Increasing it makes the filter trust the gyro less and other sensors more.
|
||||
*
|
||||
* @min 0.001
|
||||
* @max 0.05
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_GYRO_PNOISE, 0.015f);
|
||||
|
||||
/**
|
||||
* Accelerometer process noise
|
||||
*
|
||||
* Generic defaults: 0.25, multicopters: 0.25, ground vehicles: 0.25.
|
||||
* Increasing this value makes the filter trust the accelerometer less
|
||||
* and other sensors more.
|
||||
*
|
||||
* @min 0.05
|
||||
* @max 1.0
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_ACC_PNOISE, 0.25f);
|
||||
|
||||
/**
|
||||
* Gyro bias estimate process noise
|
||||
*
|
||||
* Generic defaults: 1e-07f, multicopters: 1e-07f, ground vehicles: 1e-07f.
|
||||
* Increasing this value will make the gyro bias converge faster but noisier.
|
||||
*
|
||||
* @min 0.0000001
|
||||
* @max 0.00001
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-07f);
|
||||
|
||||
/**
|
||||
* Accelerometer bias estimate process noise
|
||||
*
|
||||
* Generic defaults: 0.0001f, multicopters: 0.0001f, ground vehicles: 0.0001f.
|
||||
* Increasing this value makes the bias estimation faster and noisier.
|
||||
*
|
||||
* @min 0.0001
|
||||
* @max 0.001
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 0.0001f);
|
||||
|
||||
/**
|
||||
* Magnetometer earth frame offsets process noise
|
||||
*
|
||||
* Generic defaults: 0.0001, multicopters: 0.0001, ground vehicles: 0.0001.
|
||||
* Increasing this value makes the magnetometer earth bias estimate converge
|
||||
* faster but also noisier.
|
||||
*
|
||||
* @min 0.0001
|
||||
* @max 0.01
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_MAGE_PNOISE, 0.0003f);
|
||||
|
||||
/**
|
||||
* Magnetometer body frame offsets process noise
|
||||
*
|
||||
* Generic defaults: 0.0003, multicopters: 0.0003, ground vehicles: 0.0003.
|
||||
* Increasing this value makes the magnetometer body bias estimate converge faster
|
||||
* but also noisier.
|
||||
*
|
||||
* @min 0.0001
|
||||
* @max 0.01
|
||||
* @group Position Estimator
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PE_MAGB_PNOISE, 0.0003f);
|
||||
|
||||
|
|
Loading…
Reference in New Issue