mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
ekf2: organize gyro_bias/accel_bias param yaml
This commit is contained in:
@@ -262,6 +262,8 @@ px4_add_module(
|
||||
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
params_gyro_bias.yaml
|
||||
params_accel_bias.yaml
|
||||
params_multi.yaml
|
||||
params_volatile.yaml
|
||||
params_selector.yaml
|
||||
|
||||
+82
-179
@@ -7,6 +7,11 @@ parameters:
|
||||
short: EKF2 enable
|
||||
type: boolean
|
||||
default: 1
|
||||
EKF2_LOG_VERBOSE:
|
||||
description:
|
||||
short: Verbose logging
|
||||
type: boolean
|
||||
default: 1
|
||||
EKF2_PREDICT_US:
|
||||
description:
|
||||
short: EKF prediction period
|
||||
@@ -18,17 +23,6 @@ parameters:
|
||||
min: 1000
|
||||
max: 20000
|
||||
unit: us
|
||||
EKF2_IMU_CTRL:
|
||||
description:
|
||||
short: IMU control
|
||||
type: bitmask
|
||||
bit:
|
||||
0: Gyro Bias
|
||||
1: Accel Bias
|
||||
2: Gravity vector fusion
|
||||
default: 7
|
||||
min: 0
|
||||
max: 7
|
||||
EKF2_DELAY_MAX:
|
||||
description:
|
||||
short: Maximum delay of all the aiding sensors
|
||||
@@ -41,6 +35,82 @@ parameters:
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_ANGERR_INIT:
|
||||
description:
|
||||
short: 1-sigma tilt angle uncertainty after gravity vector alignment
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.0
|
||||
max: 0.5
|
||||
unit: rad
|
||||
reboot_required: true
|
||||
decimal: 3
|
||||
EKF2_HDG_GATE:
|
||||
description:
|
||||
short: Gate size for heading fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 2.6
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_HEAD_NOISE:
|
||||
description:
|
||||
short: Measurement noise for magnetic heading fusion
|
||||
type: float
|
||||
default: 0.3
|
||||
min: 0.01
|
||||
max: 1.0
|
||||
unit: rad
|
||||
decimal: 2
|
||||
EKF2_NOAID_NOISE:
|
||||
description:
|
||||
short: Measurement noise for non-aiding position hold
|
||||
type: float
|
||||
default: 10.0
|
||||
min: 0.5
|
||||
max: 50.0
|
||||
unit: m
|
||||
decimal: 1
|
||||
EKF2_NOAID_TOUT:
|
||||
description:
|
||||
short: Maximum inertial dead-reckoning time
|
||||
long: Maximum lapsed time from last fusion of measurements that constrain
|
||||
velocity drift before the EKF will report the horizontal nav solution as
|
||||
invalid
|
||||
type: int32
|
||||
default: 5000000
|
||||
min: 500000
|
||||
max: 10000000
|
||||
unit: us
|
||||
EKF2_HGT_REF:
|
||||
description:
|
||||
short: Determines the reference source of height data used by the EKF
|
||||
long: When multiple height sources are enabled at the same time, the height
|
||||
estimate will always converge towards the reference height source selected
|
||||
by this parameter. The range sensor and vision options should only be used
|
||||
when for operation over a flat surface as the local NED origin will move
|
||||
up and down with ground level.
|
||||
type: enum
|
||||
values:
|
||||
0: Barometric pressure
|
||||
1: GPS
|
||||
2: Range sensor
|
||||
3: Vision
|
||||
default: 1
|
||||
reboot_required: true
|
||||
EKF2_IMU_CTRL:
|
||||
description:
|
||||
short: IMU control
|
||||
type: bitmask
|
||||
bit:
|
||||
0: Gyro Bias
|
||||
1: Accel Bias
|
||||
2: Gravity vector fusion
|
||||
default: 7
|
||||
min: 0
|
||||
max: 7
|
||||
EKF2_GYR_NOISE:
|
||||
description:
|
||||
short: Rate gyro noise for covariance prediction
|
||||
@@ -59,79 +129,6 @@ parameters:
|
||||
max: 1.0
|
||||
unit: m/s^2
|
||||
decimal: 2
|
||||
EKF2_GYR_B_NOISE:
|
||||
description:
|
||||
short: Process noise for IMU rate gyro bias prediction
|
||||
type: float
|
||||
default: 0.001
|
||||
min: 0.0
|
||||
max: 0.01
|
||||
unit: rad/s^2
|
||||
decimal: 6
|
||||
EKF2_ACC_B_NOISE:
|
||||
description:
|
||||
short: Process noise for IMU accelerometer bias prediction
|
||||
type: float
|
||||
default: 0.003
|
||||
min: 0.0
|
||||
max: 0.01
|
||||
unit: m/s^3
|
||||
decimal: 6
|
||||
EKF2_NOAID_NOISE:
|
||||
description:
|
||||
short: Measurement noise for non-aiding position hold
|
||||
type: float
|
||||
default: 10.0
|
||||
min: 0.5
|
||||
max: 50.0
|
||||
unit: m
|
||||
decimal: 1
|
||||
EKF2_HEAD_NOISE:
|
||||
description:
|
||||
short: Measurement noise for magnetic heading fusion
|
||||
type: float
|
||||
default: 0.3
|
||||
min: 0.01
|
||||
max: 1.0
|
||||
unit: rad
|
||||
decimal: 2
|
||||
EKF2_HDG_GATE:
|
||||
description:
|
||||
short: Gate size for heading fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 2.6
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_HGT_REF:
|
||||
description:
|
||||
short: Determines the reference source of height data used by the EKF
|
||||
long: When multiple height sources are enabled at the same time, the height
|
||||
estimate will always converge towards the reference height source selected
|
||||
by this parameter. The range sensor and vision options should only be used
|
||||
when for operation over a flat surface as the local NED origin will move
|
||||
up and down with ground level.
|
||||
type: enum
|
||||
values:
|
||||
0: Barometric pressure
|
||||
1: GPS
|
||||
2: Range sensor
|
||||
3: Vision
|
||||
default: 1
|
||||
reboot_required: true
|
||||
EKF2_NOAID_TOUT:
|
||||
description:
|
||||
short: Maximum inertial dead-reckoning time
|
||||
long: Maximum lapsed time from last fusion of measurements that constrain
|
||||
velocity drift before the EKF will report the horizontal nav solution as
|
||||
invalid
|
||||
type: int32
|
||||
default: 5000000
|
||||
min: 500000
|
||||
max: 10000000
|
||||
unit: us
|
||||
EKF2_IMU_POS_X:
|
||||
description:
|
||||
short: X position of IMU in body frame
|
||||
@@ -156,6 +153,7 @@ parameters:
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
|
||||
EKF2_TAU_VEL:
|
||||
description:
|
||||
short: Time constant of the velocity output prediction and smoothing filter
|
||||
@@ -174,98 +172,3 @@ parameters:
|
||||
max: 1.0
|
||||
unit: s
|
||||
decimal: 2
|
||||
EKF2_GBIAS_INIT:
|
||||
description:
|
||||
short: 1-sigma IMU gyro switch-on bias
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.0
|
||||
max: 0.2
|
||||
unit: rad/s
|
||||
reboot_required: true
|
||||
decimal: 2
|
||||
EKF2_ABIAS_INIT:
|
||||
description:
|
||||
short: 1-sigma IMU accelerometer switch-on bias
|
||||
type: float
|
||||
default: 0.2
|
||||
min: 0.0
|
||||
max: 0.5
|
||||
unit: m/s^2
|
||||
reboot_required: true
|
||||
decimal: 2
|
||||
EKF2_ANGERR_INIT:
|
||||
description:
|
||||
short: 1-sigma tilt angle uncertainty after gravity vector alignment
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.0
|
||||
max: 0.5
|
||||
unit: rad
|
||||
reboot_required: true
|
||||
decimal: 3
|
||||
EKF2_ABL_LIM:
|
||||
description:
|
||||
short: Accelerometer bias learning limit
|
||||
long: The ekf accel bias states will be limited to within a range equivalent
|
||||
to +- of this value.
|
||||
type: float
|
||||
default: 0.4
|
||||
min: 0.0
|
||||
max: 0.8
|
||||
unit: m/s^2
|
||||
decimal: 2
|
||||
EKF2_ABL_ACCLIM:
|
||||
description:
|
||||
short: Maximum IMU accel magnitude that allows IMU bias learning
|
||||
long: If the magnitude of the IMU accelerometer vector exceeds this value,
|
||||
the EKF accel bias state estimation will be inhibited. This reduces the
|
||||
adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale
|
||||
factor errors on the accel bias estimates.
|
||||
type: float
|
||||
default: 25.0
|
||||
min: 20.0
|
||||
max: 200.0
|
||||
unit: m/s^2
|
||||
decimal: 1
|
||||
EKF2_ABL_GYRLIM:
|
||||
description:
|
||||
short: Maximum IMU gyro angular rate magnitude that allows IMU bias learning
|
||||
long: If the magnitude of the IMU angular rate vector exceeds this value,
|
||||
the EKF accel bias state estimation will be inhibited. This reduces the
|
||||
adverse effect of rapid rotation rates and associated errors on the accel
|
||||
bias estimates.
|
||||
type: float
|
||||
default: 3.0
|
||||
min: 2.0
|
||||
max: 20.0
|
||||
unit: rad/s
|
||||
decimal: 1
|
||||
EKF2_ABL_TAU:
|
||||
description:
|
||||
short: Accel bias learning inhibit time constant
|
||||
long: The vector magnitude of angular rate and acceleration used to check
|
||||
if learning should be inhibited has a peak hold filter applied to it with
|
||||
an exponential decay. This parameter controls the time constant of the decay.
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.1
|
||||
max: 1.0
|
||||
unit: s
|
||||
decimal: 2
|
||||
EKF2_GYR_B_LIM:
|
||||
description:
|
||||
short: Gyro bias learning limit
|
||||
long: The ekf gyro bias states will be limited to within a range equivalent
|
||||
to +- of this value.
|
||||
type: float
|
||||
default: 0.15
|
||||
min: 0.0
|
||||
max: 0.4
|
||||
unit: rad/s
|
||||
decimal: 3
|
||||
EKF2_LOG_VERBOSE:
|
||||
description:
|
||||
short: Verbose logging
|
||||
type: boolean
|
||||
default: 1
|
||||
|
||||
@@ -0,0 +1,72 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_ABIAS_INIT:
|
||||
description:
|
||||
short: 1-sigma IMU accelerometer switch-on bias
|
||||
type: float
|
||||
default: 0.2
|
||||
min: 0.0
|
||||
max: 0.5
|
||||
unit: m/s^2
|
||||
reboot_required: true
|
||||
decimal: 2
|
||||
EKF2_ACC_B_NOISE:
|
||||
description:
|
||||
short: Process noise for IMU accelerometer bias prediction
|
||||
type: float
|
||||
default: 0.003
|
||||
min: 0.0
|
||||
max: 0.01
|
||||
unit: m/s^3
|
||||
decimal: 6
|
||||
EKF2_ABL_LIM:
|
||||
description:
|
||||
short: Accelerometer bias learning limit
|
||||
long: The ekf accel bias states will be limited to within a range equivalent
|
||||
to +- of this value.
|
||||
type: float
|
||||
default: 0.4
|
||||
min: 0.0
|
||||
max: 0.8
|
||||
unit: m/s^2
|
||||
decimal: 2
|
||||
EKF2_ABL_ACCLIM:
|
||||
description:
|
||||
short: Maximum IMU accel magnitude that allows IMU bias learning
|
||||
long: If the magnitude of the IMU accelerometer vector exceeds this value,
|
||||
the EKF accel bias state estimation will be inhibited. This reduces the
|
||||
adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale
|
||||
factor errors on the accel bias estimates.
|
||||
type: float
|
||||
default: 25.0
|
||||
min: 20.0
|
||||
max: 200.0
|
||||
unit: m/s^2
|
||||
decimal: 1
|
||||
EKF2_ABL_GYRLIM:
|
||||
description:
|
||||
short: Maximum IMU gyro angular rate magnitude that allows IMU bias learning
|
||||
long: If the magnitude of the IMU angular rate vector exceeds this value,
|
||||
the EKF accel bias state estimation will be inhibited. This reduces the
|
||||
adverse effect of rapid rotation rates and associated errors on the accel
|
||||
bias estimates.
|
||||
type: float
|
||||
default: 3.0
|
||||
min: 2.0
|
||||
max: 20.0
|
||||
unit: rad/s
|
||||
decimal: 1
|
||||
EKF2_ABL_TAU:
|
||||
description:
|
||||
short: Accel bias learning inhibit time constant
|
||||
long: The vector magnitude of angular rate and acceleration used to check
|
||||
if learning should be inhibited has a peak hold filter applied to it with
|
||||
an exponential decay. This parameter controls the time constant of the decay.
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.1
|
||||
max: 1.0
|
||||
unit: s
|
||||
decimal: 2
|
||||
@@ -0,0 +1,34 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_GBIAS_INIT:
|
||||
description:
|
||||
short: 1-sigma IMU gyro switch-on bias
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.0
|
||||
max: 0.2
|
||||
unit: rad/s
|
||||
reboot_required: true
|
||||
decimal: 2
|
||||
EKF2_GYR_B_NOISE:
|
||||
description:
|
||||
short: Process noise for IMU rate gyro bias prediction
|
||||
type: float
|
||||
default: 0.001
|
||||
min: 0.0
|
||||
max: 0.01
|
||||
unit: rad/s^2
|
||||
decimal: 6
|
||||
EKF2_GYR_B_LIM:
|
||||
description:
|
||||
short: Gyro bias learning limit
|
||||
long: The ekf gyro bias states will be limited to within a range equivalent
|
||||
to +- of this value.
|
||||
type: float
|
||||
default: 0.15
|
||||
min: 0.0
|
||||
max: 0.4
|
||||
unit: rad/s
|
||||
decimal: 3
|
||||
Reference in New Issue
Block a user