mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
ekf2: organize aid source parameters
This commit is contained in:
parent
ee022a70c1
commit
ebbd2c1825
@ -111,6 +111,7 @@ if(EKF2_SYMFORCE_GEN AND (${PYTHON_SYMFORCE_EXIT_CODE} EQUAL 0))
|
||||
)
|
||||
endif()
|
||||
|
||||
set(EKF_MODULE_PARAMS)
|
||||
set(EKF_LIBS)
|
||||
set(EKF_SRCS)
|
||||
list(APPEND EKF_SRCS
|
||||
@ -135,24 +136,27 @@ list(APPEND EKF_SRCS
|
||||
|
||||
if(CONFIG_EKF2_AIRSPEED)
|
||||
list(APPEND EKF_SRCS EKF/aid_sources/airspeed/airspeed_fusion.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_airspeed.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_AUX_GLOBAL_POSITION)
|
||||
list(APPEND EKF_SRCS EKF/aid_sources/aux_global_position/aux_global_position.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_aux_global_position.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_AUXVEL)
|
||||
list(APPEND EKF_SRCS EKF/aid_sources/auxvel/auxvel_fusion.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_aux_velocity.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_BAROMETER)
|
||||
list(APPEND EKF_SRCS
|
||||
EKF/aid_sources/barometer/baro_height_control.cpp
|
||||
)
|
||||
list(APPEND EKF_SRCS EKF/aid_sources/barometer/baro_height_control.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_barometer.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_DRAG_FUSION)
|
||||
list(APPEND EKF_SRCS EKF/aid_sources/drag/drag_fusion.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_drag.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_EXTERNAL_VISION)
|
||||
@ -163,6 +167,7 @@ if(CONFIG_EKF2_EXTERNAL_VISION)
|
||||
EKF/aid_sources/external_vision/ev_vel_control.cpp
|
||||
EKF/aid_sources/external_vision/ev_yaw_control.cpp
|
||||
)
|
||||
list(APPEND EKF_MODULE_PARAMS params_external_vision.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_GNSS)
|
||||
@ -177,10 +182,13 @@ if(CONFIG_EKF2_GNSS)
|
||||
endif()
|
||||
|
||||
list(APPEND EKF_LIBS yaw_estimator)
|
||||
|
||||
list(APPEND EKF_MODULE_PARAMS params_gnss.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_GRAVITY_FUSION)
|
||||
list(APPEND EKF_SRCS EKF/aid_sources/gravity/gravity_fusion.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_gravity.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_MAGNETOMETER)
|
||||
@ -188,6 +196,7 @@ if(CONFIG_EKF2_MAGNETOMETER)
|
||||
EKF/aid_sources/magnetometer/mag_control.cpp
|
||||
EKF/aid_sources/magnetometer/mag_fusion.cpp
|
||||
)
|
||||
list(APPEND EKF_MODULE_PARAMS params_magnetometer.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_OPTICAL_FLOW)
|
||||
@ -195,6 +204,7 @@ if(CONFIG_EKF2_OPTICAL_FLOW)
|
||||
EKF/aid_sources/optical_flow/optical_flow_control.cpp
|
||||
EKF/aid_sources/optical_flow/optical_flow_fusion.cpp
|
||||
)
|
||||
list(APPEND EKF_MODULE_PARAMS params_optical_flow.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_RANGE_FINDER)
|
||||
@ -204,18 +214,22 @@ if(CONFIG_EKF2_RANGE_FINDER)
|
||||
EKF/aid_sources/range_finder/range_height_fusion.cpp
|
||||
EKF/aid_sources/range_finder/sensor_range_finder.cpp
|
||||
)
|
||||
list(APPEND EKF_MODULE_PARAMS params_range_finder.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_SIDESLIP)
|
||||
list(APPEND EKF_SRCS EKF/aid_sources/sideslip/sideslip_fusion.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_sideslip.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_TERRAIN)
|
||||
list(APPEND EKF_SRCS EKF/terrain_control.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_terrain.yaml)
|
||||
endif()
|
||||
|
||||
if(CONFIG_EKF2_WIND)
|
||||
list(APPEND EKF_SRCS EKF/wind.cpp)
|
||||
list(APPEND EKF_MODULE_PARAMS params_wind.yaml)
|
||||
endif ()
|
||||
|
||||
add_subdirectory(EKF)
|
||||
@ -251,6 +265,7 @@ px4_add_module(
|
||||
params_multi.yaml
|
||||
params_volatile.yaml
|
||||
params_selector.yaml
|
||||
${EKF_MODULE_PARAMS}
|
||||
|
||||
DEPENDS
|
||||
geo
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
45
src/modules/ekf2/params_airspeed.yaml
Normal file
45
src/modules/ekf2/params_airspeed.yaml
Normal file
@ -0,0 +1,45 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_ARSP_THR:
|
||||
description:
|
||||
short: Airspeed fusion threshold
|
||||
long: Airspeed data is fused for wind estimation if above this threshold.
|
||||
Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip
|
||||
(see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies
|
||||
to fixed-wing vehicles (or VTOLs in fixed-wing mode).
|
||||
type: float
|
||||
default: 0.0
|
||||
min: 0.0
|
||||
unit: m/s
|
||||
decimal: 1
|
||||
EKF2_ASP_DELAY:
|
||||
description:
|
||||
short: Airspeed measurement delay relative to IMU measurements
|
||||
type: float
|
||||
default: 100
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_TAS_GATE:
|
||||
description:
|
||||
short: Gate size for TAS fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_EAS_NOISE:
|
||||
description:
|
||||
short: Measurement noise for airspeed fusion
|
||||
type: float
|
||||
default: 1.4
|
||||
min: 0.5
|
||||
max: 5.0
|
||||
unit: m/s
|
||||
decimal: 1
|
||||
45
src/modules/ekf2/params_aux_global_position.yaml
Normal file
45
src/modules/ekf2/params_aux_global_position.yaml
Normal file
@ -0,0 +1,45 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_AGP_CTRL:
|
||||
description:
|
||||
short: Aux global position (AGP) sensor aiding
|
||||
long: 'Set bits in the following positions to enable: 0 : Horizontal position
|
||||
fusion 1 : Vertical position fusion'
|
||||
type: bitmask
|
||||
bit:
|
||||
0: Horizontal position
|
||||
1: Vertical position
|
||||
default: 0
|
||||
min: 0
|
||||
max: 3
|
||||
EKF2_AGP_DELAY:
|
||||
description:
|
||||
short: Aux global position estimator delay relative to IMU measurements
|
||||
type: float
|
||||
default: 0
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_AGP_NOISE:
|
||||
description:
|
||||
short: Measurement noise for aux global position measurements
|
||||
long: Used to lower bound or replace the uncertainty included in the message
|
||||
type: float
|
||||
default: 0.9
|
||||
min: 0.01
|
||||
unit: m
|
||||
decimal: 2
|
||||
EKF2_AGP_GATE:
|
||||
description:
|
||||
short: Gate size for aux global position fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 3.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
14
src/modules/ekf2/params_aux_velocity.yaml
Normal file
14
src/modules/ekf2/params_aux_velocity.yaml
Normal file
@ -0,0 +1,14 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_AVEL_DELAY:
|
||||
description:
|
||||
short: Auxiliary Velocity Estimate delay relative to IMU measurements
|
||||
type: float
|
||||
default: 5
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
130
src/modules/ekf2/params_barometer.yaml
Normal file
130
src/modules/ekf2/params_barometer.yaml
Normal file
@ -0,0 +1,130 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_BARO_CTRL:
|
||||
description:
|
||||
short: Barometric sensor height aiding
|
||||
long: If this parameter is enabled then the estimator will make use of the
|
||||
barometric height measurements to estimate its height in addition to other
|
||||
height sources (if activated).
|
||||
type: boolean
|
||||
default: 1
|
||||
EKF2_BARO_DELAY:
|
||||
description:
|
||||
short: Barometer measurement delay relative to IMU measurements
|
||||
type: float
|
||||
default: 0
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_BARO_GATE:
|
||||
description:
|
||||
short: Gate size for barometric and GPS height fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_BARO_NOISE:
|
||||
description:
|
||||
short: Measurement noise for barometric altitude
|
||||
type: float
|
||||
default: 3.5
|
||||
min: 0.01
|
||||
max: 15.0
|
||||
unit: m
|
||||
decimal: 2
|
||||
EKF2_GND_EFF_DZ:
|
||||
description:
|
||||
short: Baro deadzone range for height fusion
|
||||
long: Sets the value of deadzone applied to negative baro innovations. Deadzone
|
||||
is enabled when EKF2_GND_EFF_DZ > 0.
|
||||
type: float
|
||||
default: 4.0
|
||||
min: 0.0
|
||||
max: 10.0
|
||||
unit: m
|
||||
decimal: 1
|
||||
EKF2_GND_MAX_HGT:
|
||||
description:
|
||||
short: Height above ground level for ground effect zone
|
||||
long: Sets the maximum distance to the ground level where negative baro innovations
|
||||
are expected.
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.0
|
||||
max: 5.0
|
||||
unit: m
|
||||
decimal: 1
|
||||
EKF2_PCOEF_XP:
|
||||
description:
|
||||
short: Static pressure position error coefficient for the positive X axis
|
||||
long: This is the ratio of static pressure error to dynamic pressure generated
|
||||
by a positive wind relative velocity along the X body axis. If the baro
|
||||
height estimate rises during forward flight, then this will be a negative
|
||||
number.
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -0.5
|
||||
max: 0.5
|
||||
decimal: 2
|
||||
EKF2_PCOEF_XN:
|
||||
description:
|
||||
short: Static pressure position error coefficient for the negative X axis
|
||||
long: This is the ratio of static pressure error to dynamic pressure generated
|
||||
by a negative wind relative velocity along the X body axis. If the baro
|
||||
height estimate rises during backwards flight, then this will be a negative
|
||||
number.
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -0.5
|
||||
max: 0.5
|
||||
decimal: 2
|
||||
EKF2_PCOEF_YP:
|
||||
description:
|
||||
short: Pressure position error coefficient for the positive Y axis
|
||||
long: This is the ratio of static pressure error to dynamic pressure generated
|
||||
by a wind relative velocity along the positive Y (RH) body axis. If the
|
||||
baro height estimate rises during sideways flight to the right, then this
|
||||
will be a negative number.
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -0.5
|
||||
max: 0.5
|
||||
decimal: 2
|
||||
EKF2_PCOEF_YN:
|
||||
description:
|
||||
short: Pressure position error coefficient for the negative Y axis
|
||||
long: This is the ratio of static pressure error to dynamic pressure generated
|
||||
by a wind relative velocity along the negative Y (LH) body axis. If the
|
||||
baro height estimate rises during sideways flight to the left, then this
|
||||
will be a negative number.
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -0.5
|
||||
max: 0.5
|
||||
decimal: 2
|
||||
EKF2_PCOEF_Z:
|
||||
description:
|
||||
short: Static pressure position error coefficient for the Z axis
|
||||
long: This is the ratio of static pressure error to dynamic pressure generated
|
||||
by a wind relative velocity along the Z body axis.
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -0.5
|
||||
max: 0.5
|
||||
decimal: 2
|
||||
EKF2_ASPD_MAX:
|
||||
description:
|
||||
short: Maximum airspeed used for baro static pressure compensation
|
||||
type: float
|
||||
default: 20.0
|
||||
min: 5.0
|
||||
max: 50.0
|
||||
unit: m/s
|
||||
decimal: 1
|
||||
75
src/modules/ekf2/params_drag.yaml
Normal file
75
src/modules/ekf2/params_drag.yaml
Normal file
@ -0,0 +1,75 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_DRAG_CTRL:
|
||||
description:
|
||||
short: Multirotor wind estimation selection
|
||||
long: Activate wind speed estimation using specific-force measurements and
|
||||
a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles
|
||||
that have their thrust aligned with the Z axis and no thrust in the XY plane.
|
||||
type: boolean
|
||||
default: 0
|
||||
EKF2_DRAG_NOISE:
|
||||
description:
|
||||
short: Specific drag force observation noise variance
|
||||
long: Used by the multi-rotor specific drag force model.
|
||||
Increasing this makes the multi-rotor wind estimates adjust more slowly.
|
||||
type: float
|
||||
default: 2.5
|
||||
min: 0.5
|
||||
max: 10.0
|
||||
unit: (m/s^2)^2
|
||||
decimal: 2
|
||||
EKF2_BCOEF_X:
|
||||
description:
|
||||
short: X-axis ballistic coefficient used for multi-rotor wind estimation
|
||||
long: This parameter controls the prediction of drag produced by bluff body
|
||||
drag along the forward/reverse axis when flying a multi-copter which enables
|
||||
estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The
|
||||
drag produced by this effect scales with speed squared. The predicted drag
|
||||
from the rotors is specified separately by the EKF2_MCOEF parameter. Set
|
||||
this parameter to zero to turn off the bluff body drag model for this axis.
|
||||
type: float
|
||||
default: 100.0
|
||||
min: 0.0
|
||||
max: 200.0
|
||||
unit: kg/m^2
|
||||
decimal: 1
|
||||
EKF2_BCOEF_Y:
|
||||
description:
|
||||
short: Y-axis ballistic coefficient used for multi-rotor wind estimation
|
||||
long: This parameter controls the prediction of drag produced by bluff body
|
||||
drag along the right/left axis when flying a multi-copter, which enables
|
||||
estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The
|
||||
drag produced by this effect scales with speed squared. The predicted drag
|
||||
from the rotors is specified separately by the EKF2_MCOEF parameter. Set
|
||||
this parameter to zero to turn off the bluff body drag model for this axis.
|
||||
type: float
|
||||
default: 100.0
|
||||
min: 0.0
|
||||
max: 200.0
|
||||
unit: kg/m^2
|
||||
decimal: 1
|
||||
EKF2_MCOEF:
|
||||
description:
|
||||
short: Propeller momentum drag coefficient for multi-rotor wind estimation
|
||||
long: This parameter controls the prediction of drag produced by the propellers
|
||||
when flying a multi-copter, which enables estimation of wind drift when
|
||||
enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect
|
||||
scales with speed not speed squared and is produced because some of the
|
||||
air velocity normal to the propeller axis of rotation is lost when passing
|
||||
through the rotor disc. This changes the momentum of the flow which creates
|
||||
a drag reaction force. When comparing un-ducted propellers of the same diameter,
|
||||
the effect is roughly proportional to the area of the propeller blades when
|
||||
viewed side on and changes with propeller selection. Momentum drag is significantly
|
||||
higher for ducted rotors. To account for the drag produced by the body which
|
||||
scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y
|
||||
parameters. Set this parameter to zero to turn off the momentum drag model
|
||||
for both axis.
|
||||
type: float
|
||||
default: 0.15
|
||||
min: 0
|
||||
max: 1.0
|
||||
unit: 1/s
|
||||
decimal: 2
|
||||
121
src/modules/ekf2/params_external_vision.yaml
Normal file
121
src/modules/ekf2/params_external_vision.yaml
Normal file
@ -0,0 +1,121 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_EV_CTRL:
|
||||
description:
|
||||
short: External vision (EV) sensor aiding
|
||||
long: 'Set bits in the following positions to enable: 0 : Horizontal position
|
||||
fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw'
|
||||
type: bitmask
|
||||
bit:
|
||||
0: Horizontal position
|
||||
1: Vertical position
|
||||
2: 3D velocity
|
||||
3: Yaw
|
||||
default: 0
|
||||
min: 0
|
||||
max: 15
|
||||
EKF2_EV_DELAY:
|
||||
description:
|
||||
short: Vision Position Estimator delay relative to IMU measurements
|
||||
type: float
|
||||
default: 0
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_EV_NOISE_MD:
|
||||
description:
|
||||
short: External vision (EV) noise mode
|
||||
long: If set to 0 (default) the measurement noise is taken from the vision
|
||||
message and the EV noise parameters are used as a lower bound. If set to
|
||||
1 the observation noise is set from the parameters directly,
|
||||
type: enum
|
||||
values:
|
||||
0: EV reported variance (parameter lower bound)
|
||||
1: EV noise parameters
|
||||
default: 0
|
||||
EKF2_EV_QMIN:
|
||||
description:
|
||||
short: External vision (EV) minimum quality (optional)
|
||||
long: External vision will only be started and fused if the quality metric
|
||||
is above this threshold. The quality metric is a completely optional field
|
||||
provided by some VIO systems.
|
||||
type: int32
|
||||
default: 0
|
||||
min: 0
|
||||
max: 100
|
||||
decimal: 1
|
||||
EKF2_EVA_NOISE:
|
||||
description:
|
||||
short: Measurement noise for vision angle measurements
|
||||
long: Used to lower bound or replace the uncertainty included in the message
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.05
|
||||
unit: rad
|
||||
decimal: 2
|
||||
EKF2_EVP_GATE:
|
||||
description:
|
||||
short: Gate size for vision position fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_EVP_NOISE:
|
||||
description:
|
||||
short: Measurement noise for vision position measurements
|
||||
long: Used to lower bound or replace the uncertainty included in the message
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.01
|
||||
unit: m
|
||||
decimal: 2
|
||||
EKF2_EVV_GATE:
|
||||
description:
|
||||
short: Gate size for vision velocity estimate fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 3.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_EVV_NOISE:
|
||||
description:
|
||||
short: Measurement noise for vision velocity measurements
|
||||
long: Used to lower bound or replace the uncertainty included in the message
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.01
|
||||
unit: m/s
|
||||
decimal: 2
|
||||
EKF2_EV_POS_X:
|
||||
description:
|
||||
short: X position of VI sensor focal point in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_EV_POS_Y:
|
||||
description:
|
||||
short: Y position of VI sensor focal point in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_EV_POS_Z:
|
||||
description:
|
||||
short: Z position of VI sensor focal point in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
196
src/modules/ekf2/params_gnss.yaml
Normal file
196
src/modules/ekf2/params_gnss.yaml
Normal file
@ -0,0 +1,196 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_GPS_CTRL:
|
||||
description:
|
||||
short: GNSS sensor aiding
|
||||
long: 'Set bits in the following positions to enable: 0 : Longitude and latitude
|
||||
fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading
|
||||
fusion'
|
||||
type: bitmask
|
||||
bit:
|
||||
0: Lon/lat
|
||||
1: Altitude
|
||||
2: 3D velocity
|
||||
3: Dual antenna heading
|
||||
default: 7
|
||||
min: 0
|
||||
max: 15
|
||||
EKF2_GPS_DELAY:
|
||||
description:
|
||||
short: GPS measurement delay relative to IMU measurements
|
||||
type: float
|
||||
default: 110
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_GPS_P_NOISE:
|
||||
description:
|
||||
short: Measurement noise for GNSS position
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.01
|
||||
max: 10.0
|
||||
unit: m
|
||||
decimal: 2
|
||||
EKF2_GPS_P_GATE:
|
||||
description:
|
||||
short: Gate size for GNSS position fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_GPS_V_GATE:
|
||||
description:
|
||||
short: Gate size for GNSS velocity fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_GPS_V_NOISE:
|
||||
description:
|
||||
short: Measurement noise for GNSS velocity
|
||||
type: float
|
||||
default: 0.3
|
||||
min: 0.01
|
||||
max: 5.0
|
||||
unit: m/s
|
||||
decimal: 2
|
||||
EKF2_GPS_POS_X:
|
||||
description:
|
||||
short: X position of GPS antenna in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_GPS_POS_Y:
|
||||
description:
|
||||
short: Y position of GPS antenna in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_GPS_POS_Z:
|
||||
description:
|
||||
short: Z position of GPS antenna in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_GPS_CHECK:
|
||||
description:
|
||||
short: Integer bitmask controlling GPS checks
|
||||
long: 'Each threshold value is defined by the parameter indicated next to the check.
|
||||
Drift and offset checks only run when the vehicle is on ground and stationary.'
|
||||
type: bitmask
|
||||
bit:
|
||||
0: Sat count (EKF2_REQ_NSATS)
|
||||
1: PDOP (EKF2_REQ_PDOP)
|
||||
2: EPH (EKF2_REQ_EPH)
|
||||
3: EPV (EKF2_REQ_EPV)
|
||||
4: Speed accuracy (EKF2_REQ_SACC)
|
||||
5: Horizontal position drift (EKF2_REQ_HDRIFT)
|
||||
6: Vertical position drift (EKF2_REQ_VDRIFT)
|
||||
7: Horizontal speed offset (EKF2_REQ_HDRIFT)
|
||||
8: Vertical speed offset (EKF2_REQ_VDRIFT)
|
||||
9: Spoofing
|
||||
default: 1023
|
||||
min: 0
|
||||
max: 1023
|
||||
EKF2_REQ_EPH:
|
||||
description:
|
||||
short: Required EPH to use GPS
|
||||
type: float
|
||||
default: 3.0
|
||||
min: 2
|
||||
max: 100
|
||||
unit: m
|
||||
decimal: 1
|
||||
EKF2_REQ_EPV:
|
||||
description:
|
||||
short: Required EPV to use GPS
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 2
|
||||
max: 100
|
||||
unit: m
|
||||
decimal: 1
|
||||
EKF2_REQ_SACC:
|
||||
description:
|
||||
short: Required speed accuracy to use GPS
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.5
|
||||
max: 5.0
|
||||
unit: m/s
|
||||
decimal: 2
|
||||
EKF2_REQ_NSATS:
|
||||
description:
|
||||
short: Required satellite count to use GPS
|
||||
type: int32
|
||||
default: 6
|
||||
min: 4
|
||||
max: 12
|
||||
EKF2_REQ_PDOP:
|
||||
description:
|
||||
short: Maximum PDOP to use GPS
|
||||
type: float
|
||||
default: 2.5
|
||||
min: 1.5
|
||||
max: 5.0
|
||||
decimal: 1
|
||||
EKF2_REQ_HDRIFT:
|
||||
description:
|
||||
short: Maximum horizontal drift speed to use GPS
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.1
|
||||
max: 1.0
|
||||
unit: m/s
|
||||
decimal: 2
|
||||
EKF2_REQ_VDRIFT:
|
||||
description:
|
||||
short: Maximum vertical drift speed to use GPS
|
||||
type: float
|
||||
default: 0.2
|
||||
min: 0.1
|
||||
max: 1.5
|
||||
decimal: 2
|
||||
unit: m/s
|
||||
EKF2_REQ_GPS_H:
|
||||
description:
|
||||
short: Required GPS health time on startup
|
||||
long: Minimum continuous period without GPS failure required to mark a healthy
|
||||
GPS status. It can be reduced to speed up initialization, but it's recommended
|
||||
to keep this unchanged for a vehicle.
|
||||
type: float
|
||||
default: 10.0
|
||||
min: 0.1
|
||||
decimal: 1
|
||||
unit: s
|
||||
reboot_required: true
|
||||
EKF2_GSF_TAS:
|
||||
description:
|
||||
short: Default value of true airspeed used in EKF-GSF AHRS calculation
|
||||
long: If no airspeed measurements are available, the EKF-GSF AHRS calculation
|
||||
will assume this value of true airspeed when compensating for centripetal
|
||||
acceleration during turns. Set to zero to disable centripetal acceleration
|
||||
compensation during fixed wing flight modes.
|
||||
type: float
|
||||
default: 15.0
|
||||
min: 0.0
|
||||
unit: m/s
|
||||
max: 100.0
|
||||
decimal: 1
|
||||
13
src/modules/ekf2/params_gravity.yaml
Normal file
13
src/modules/ekf2/params_gravity.yaml
Normal file
@ -0,0 +1,13 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_GRAV_NOISE:
|
||||
description:
|
||||
short: Accelerometer measurement noise for gravity based observations
|
||||
type: float
|
||||
default: 1.0
|
||||
min: 0.1
|
||||
max: 10.0
|
||||
unit: g0
|
||||
decimal: 2
|
||||
153
src/modules/ekf2/params_magnetometer.yaml
Normal file
153
src/modules/ekf2/params_magnetometer.yaml
Normal file
@ -0,0 +1,153 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_MAG_TYPE:
|
||||
description:
|
||||
short: Type of magnetometer fusion
|
||||
long: Integer controlling the type of magnetometer fusion used - magnetic
|
||||
heading or 3-component vector. The fusion of magnetometer data as a three
|
||||
component vector enables vehicle body fixed hard iron errors to be learned,
|
||||
but requires a stable earth field. If set to 'Automatic' magnetic heading
|
||||
fusion is used when on-ground and 3-axis magnetic field fusion in-flight.
|
||||
If set to 'Magnetic heading' magnetic heading fusion is used at all times.
|
||||
If set to 'None' the magnetometer will not be used under any circumstance.
|
||||
If no external source of yaw is available, it is possible to use post-takeoff
|
||||
horizontal movement combined with GNSS velocity measurements to align the yaw angle.
|
||||
If set to 'Init' the magnetometer is only used to initalize the heading.
|
||||
type: enum
|
||||
values:
|
||||
0: Automatic
|
||||
1: Magnetic heading
|
||||
5: None
|
||||
6: Init
|
||||
default: 0
|
||||
reboot_required: true
|
||||
EKF2_MAG_DELAY:
|
||||
description:
|
||||
short: Magnetometer measurement delay relative to IMU measurements
|
||||
type: float
|
||||
default: 0
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_MAG_GATE:
|
||||
description:
|
||||
short: Gate size for magnetometer XYZ component fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 3.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_MAG_NOISE:
|
||||
description:
|
||||
short: Measurement noise for magnetometer 3-axis fusion
|
||||
type: float
|
||||
default: 0.05
|
||||
min: 0.001
|
||||
max: 1.0
|
||||
unit: gauss
|
||||
decimal: 3
|
||||
EKF2_MAG_B_NOISE:
|
||||
description:
|
||||
short: Process noise for body magnetic field prediction
|
||||
type: float
|
||||
default: 0.0001
|
||||
min: 0.0
|
||||
max: 0.1
|
||||
unit: gauss/s
|
||||
decimal: 6
|
||||
EKF2_MAG_E_NOISE:
|
||||
description:
|
||||
short: Process noise for earth magnetic field prediction
|
||||
type: float
|
||||
default: 0.001
|
||||
min: 0.0
|
||||
max: 0.1
|
||||
unit: gauss/s
|
||||
decimal: 6
|
||||
EKF2_DECL_TYPE:
|
||||
description:
|
||||
short: Integer bitmask controlling handling of magnetic declination
|
||||
long: 'Set bits in the following positions to enable functions. 0 : Set to
|
||||
true to use the declination from the geo_lookup library when the GPS position
|
||||
becomes available, set to false to always use the EKF2_MAG_DECL value. 1
|
||||
: Set to true to save the EKF2_MAG_DECL parameter to the value returned
|
||||
by the EKF when the vehicle disarms.'
|
||||
type: bitmask
|
||||
bit:
|
||||
0: use geo_lookup declination
|
||||
1: save EKF2_MAG_DECL on disarm
|
||||
default: 3
|
||||
min: 0
|
||||
max: 3
|
||||
reboot_required: true
|
||||
EKF2_MAG_ACCLIM:
|
||||
description:
|
||||
short: Horizontal acceleration threshold used for heading observability check
|
||||
long: The heading is assumed to be observable when the body acceleration is
|
||||
greater than this parameter when a global position/velocity aiding source
|
||||
is active.
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.0
|
||||
max: 5.0
|
||||
unit: m/s^2
|
||||
decimal: 2
|
||||
EKF2_MAG_CHECK:
|
||||
description:
|
||||
short: Magnetic field strength test selection
|
||||
long: 'Bitmask to set which check is used to decide whether the magnetometer
|
||||
data is valid. If GNSS data is received, the magnetic field is compared
|
||||
to a World Magnetic Model (WMM), otherwise an average value is used. This
|
||||
check is useful to reject occasional hard iron disturbance. Set bits to
|
||||
1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic
|
||||
field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field
|
||||
inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find
|
||||
the theoretical strength and inclination using the WMM'
|
||||
type: bitmask
|
||||
bit:
|
||||
0: Strength (EKF2_MAG_CHK_STR)
|
||||
1: Inclination (EKF2_MAG_CHK_INC)
|
||||
2: Wait for WMM
|
||||
default: 1
|
||||
min: 0
|
||||
max: 7
|
||||
EKF2_MAG_CHK_STR:
|
||||
description:
|
||||
short: Magnetic field strength check tolerance
|
||||
long: Maximum allowed deviation from the expected magnetic field strength
|
||||
to pass the check.
|
||||
type: float
|
||||
default: 0.2
|
||||
min: 0.0
|
||||
max: 1.0
|
||||
unit: gauss
|
||||
decimal: 2
|
||||
EKF2_MAG_CHK_INC:
|
||||
description:
|
||||
short: Magnetic field inclination check tolerance
|
||||
long: Maximum allowed deviation from the expected magnetic field inclination
|
||||
to pass the check.
|
||||
type: float
|
||||
default: 20.0
|
||||
min: 0.0
|
||||
max: 90.0
|
||||
unit: deg
|
||||
decimal: 1
|
||||
EKF2_SYNT_MAG_Z:
|
||||
description:
|
||||
short: Enable synthetic magnetometer Z component measurement
|
||||
long: Use for vehicles where the measured body Z magnetic field is subject
|
||||
to strong magnetic interference. For magnetic heading fusion the magnetometer
|
||||
Z measurement will be replaced by a synthetic value calculated using the
|
||||
knowledge of the 3D magnetic field vector at the location of the drone.
|
||||
Therefore, this parameter will only have an effect if the global position
|
||||
of the drone is known. For 3D mag fusion the magnetometer Z measurement
|
||||
will simply be ignored instead of fusing the synthetic value.
|
||||
type: boolean
|
||||
default: 0
|
||||
103
src/modules/ekf2/params_optical_flow.yaml
Normal file
103
src/modules/ekf2/params_optical_flow.yaml
Normal file
@ -0,0 +1,103 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_OF_CTRL:
|
||||
description:
|
||||
short: Optical flow aiding
|
||||
long: Enable optical flow fusion.
|
||||
type: boolean
|
||||
default: 1
|
||||
EKF2_OF_DELAY:
|
||||
description:
|
||||
short: Optical flow measurement delay relative to IMU measurements
|
||||
long: Assumes measurement is timestamped at trailing edge of integration period
|
||||
type: float
|
||||
default: 20
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_OF_GATE:
|
||||
description:
|
||||
short: Gate size for optical flow fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 3.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_OF_N_MIN:
|
||||
description:
|
||||
short: Optical flow minimum noise
|
||||
long: Measurement noise for the optical flow sensor when it's reported quality
|
||||
metric is at the maximum
|
||||
type: float
|
||||
default: 0.15
|
||||
min: 0.05
|
||||
unit: rad/s
|
||||
decimal: 2
|
||||
EKF2_OF_N_MAX:
|
||||
description:
|
||||
short: Optical flow maximum noise
|
||||
long: Measurement noise for the optical flow sensor when it's reported quality
|
||||
metric is at the minimum
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.05
|
||||
unit: rad/s
|
||||
decimal: 2
|
||||
EKF2_OF_QMIN:
|
||||
description:
|
||||
short: In air optical flow minimum quality
|
||||
long: Optical Flow data will only be used in air if the sensor reports a
|
||||
quality metric >= EKF2_OF_QMIN
|
||||
type: int32
|
||||
default: 1
|
||||
min: 0
|
||||
max: 255
|
||||
EKF2_OF_QMIN_GND:
|
||||
description:
|
||||
short: On ground optical flow minimum quality
|
||||
long: Optical Flow data will only be used on the ground if the sensor reports
|
||||
a quality metric >= EKF2_OF_QMIN_GND
|
||||
type: int32
|
||||
default: 0
|
||||
min: 0
|
||||
max: 255
|
||||
EKF2_OF_GYR_SRC:
|
||||
description:
|
||||
short: Optical flow angular rate compensation source
|
||||
long: 'Auto: use gyro from optical flow message if available, internal gyro otherwise.
|
||||
Internal: always use internal gyro'
|
||||
type: enum
|
||||
values:
|
||||
0: Auto
|
||||
1: Internal
|
||||
default: 0
|
||||
EKF2_OF_POS_X:
|
||||
description:
|
||||
short: X position of optical flow focal point in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_OF_POS_Y:
|
||||
description:
|
||||
short: Y position of optical flow focal point in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_OF_POS_Z:
|
||||
description:
|
||||
short: Z position of optical flow focal point in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
152
src/modules/ekf2/params_range_finder.yaml
Normal file
152
src/modules/ekf2/params_range_finder.yaml
Normal file
@ -0,0 +1,152 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_RNG_CTRL:
|
||||
description:
|
||||
short: Range sensor height aiding
|
||||
long: 'WARNING: Range finder measurements are less reliable and can experience
|
||||
unexpected errors. For these reasons, if accurate control of height relative
|
||||
to ground is required, it is recommended to use the MPC_ALT_MODE parameter
|
||||
instead, unless baro errors are severe enough to cause problems with landing
|
||||
and takeoff. If this parameter is enabled then the estimator
|
||||
will make use of the range finder measurements to estimate its height in
|
||||
addition to other height sources (if activated). Range sensor aiding can
|
||||
be enabled (i.e.: always use) or set in "conditional" mode. Conditional
|
||||
mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX)
|
||||
and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing,
|
||||
where baro interference from rotor wash is excessive and can corrupt EKF
|
||||
state estimates. It is intended to be used where a vertical takeoff and
|
||||
landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.'
|
||||
type: enum
|
||||
values:
|
||||
0: Disable range fusion
|
||||
1: Enabled (conditional mode)
|
||||
2: Enabled
|
||||
default: 1
|
||||
EKF2_RNG_DELAY:
|
||||
description:
|
||||
short: Range finder measurement delay relative to IMU measurements
|
||||
type: float
|
||||
default: 5
|
||||
min: 0
|
||||
max: 300
|
||||
unit: ms
|
||||
reboot_required: true
|
||||
decimal: 1
|
||||
EKF2_RNG_GATE:
|
||||
description:
|
||||
short: Gate size for range finder fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_RNG_NOISE:
|
||||
description:
|
||||
short: Measurement noise for range finder fusion
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.01
|
||||
unit: m
|
||||
decimal: 2
|
||||
EKF2_RNG_PITCH:
|
||||
description:
|
||||
short: Range sensor pitch offset
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -0.75
|
||||
max: 0.75
|
||||
unit: rad
|
||||
decimal: 3
|
||||
EKF2_RNG_A_VMAX:
|
||||
description:
|
||||
short: Maximum horizontal velocity allowed for conditional range aid mode
|
||||
long: If the vehicle horizontal speed exceeds this value then the estimator
|
||||
will not fuse range measurements to estimate its height. This only applies
|
||||
when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).
|
||||
type: float
|
||||
default: 1.0
|
||||
min: 0.1
|
||||
max: 2
|
||||
unit: m/s
|
||||
EKF2_RNG_A_HMAX:
|
||||
description:
|
||||
short: Maximum height above ground allowed for conditional range aid mode
|
||||
long: If the vehicle absolute altitude exceeds this value then the estimator
|
||||
will not fuse range measurements to estimate its height. This only applies
|
||||
when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
max: 10.0
|
||||
unit: m
|
||||
EKF2_RNG_A_IGATE:
|
||||
description:
|
||||
short: Gate size used for innovation consistency checks for range aid fusion
|
||||
long: A lower value means HAGL needs to be more stable in order to use range
|
||||
finder for height estimation in range aid mode
|
||||
type: float
|
||||
default: 1.0
|
||||
unit: SD
|
||||
min: 0.1
|
||||
max: 5.0
|
||||
EKF2_RNG_QLTY_T:
|
||||
description:
|
||||
short: Minumum range validity period
|
||||
long: Minimum duration during which the reported range finder signal quality
|
||||
needs to be non-zero in order to be declared valid (s)
|
||||
type: float
|
||||
default: 1.0
|
||||
unit: s
|
||||
min: 0.1
|
||||
max: 5
|
||||
EKF2_RNG_K_GATE:
|
||||
description:
|
||||
short: Gate size used for range finder kinematic consistency check
|
||||
long: 'To be used, the time derivative of the distance sensor measurements
|
||||
projected on the vertical axis needs to be statistically consistent with
|
||||
the estimated vertical velocity of the drone. Decrease this value to make
|
||||
the filter more robust against range finder faulty data (stuck, reflections,
|
||||
...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE)
|
||||
before tuning this gate.'
|
||||
type: float
|
||||
default: 1.0
|
||||
unit: SD
|
||||
min: 0.1
|
||||
max: 5.0
|
||||
EKF2_RNG_SFE:
|
||||
description:
|
||||
short: Range finder range dependent noise scaler
|
||||
long: Specifies the increase in range finder noise with range.
|
||||
type: float
|
||||
default: 0.05
|
||||
min: 0.0
|
||||
max: 0.2
|
||||
unit: m/m
|
||||
EKF2_RNG_POS_X:
|
||||
description:
|
||||
short: X position of range finder origin in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_RNG_POS_Y:
|
||||
description:
|
||||
short: Y position of range finder origin in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
EKF2_RNG_POS_Z:
|
||||
description:
|
||||
short: Z position of range finder origin in body frame
|
||||
long: Forward axis with origin relative to vehicle centre of gravity
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: m
|
||||
decimal: 3
|
||||
32
src/modules/ekf2/params_sideslip.yaml
Normal file
32
src/modules/ekf2/params_sideslip.yaml
Normal file
@ -0,0 +1,32 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_FUSE_BETA:
|
||||
description:
|
||||
short: Enable synthetic sideslip fusion
|
||||
long: 'For reliable wind estimation both sideslip and airspeed fusion (see
|
||||
EKF2_ARSP_THR) should be enabled. Only applies to fixed-wing vehicles (or
|
||||
VTOLs in fixed-wing mode). Note: side slip fusion is currently not supported
|
||||
for tailsitters.'
|
||||
type: boolean
|
||||
default: 0
|
||||
EKF2_BETA_GATE:
|
||||
description:
|
||||
short: Gate size for synthetic sideslip fusion
|
||||
long: Sets the number of standard deviations used by the innovation consistency
|
||||
test.
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 1.0
|
||||
unit: SD
|
||||
decimal: 1
|
||||
EKF2_BETA_NOISE:
|
||||
description:
|
||||
short: Noise for synthetic sideslip fusion
|
||||
type: float
|
||||
default: 0.3
|
||||
min: 0.1
|
||||
max: 1.0
|
||||
unit: m/s
|
||||
decimal: 2
|
||||
34
src/modules/ekf2/params_terrain.yaml
Normal file
34
src/modules/ekf2/params_terrain.yaml
Normal file
@ -0,0 +1,34 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_TERR_NOISE:
|
||||
description:
|
||||
short: Terrain altitude process noise
|
||||
type: float
|
||||
default: 5.0
|
||||
min: 0.5
|
||||
unit: m/s
|
||||
decimal: 1
|
||||
EKF2_TERR_GRAD:
|
||||
description:
|
||||
short: Magnitude of terrain gradient
|
||||
type: float
|
||||
default: 0.5
|
||||
min: 0.0
|
||||
unit: m/m
|
||||
decimal: 2
|
||||
EKF2_MIN_RNG:
|
||||
description:
|
||||
short: Expected range finder reading when on ground
|
||||
long: If the vehicle is on ground, is not moving as determined by the motion
|
||||
test and the range finder is returning invalid or no data, then an assumed
|
||||
range value of EKF2_MIN_RNG will be used by the terrain estimator so that
|
||||
a terrain height estimate is available at the start of flight in situations
|
||||
where the range finder may be inside its minimum measurements distance when
|
||||
on ground.
|
||||
type: float
|
||||
default: 0.1
|
||||
min: 0.01
|
||||
unit: m
|
||||
decimal: 2
|
||||
15
src/modules/ekf2/params_wind.yaml
Normal file
15
src/modules/ekf2/params_wind.yaml
Normal file
@ -0,0 +1,15 @@
|
||||
module_name: ekf2
|
||||
parameters:
|
||||
- group: EKF2
|
||||
definitions:
|
||||
EKF2_WIND_NSD:
|
||||
description:
|
||||
short: Process noise spectral density for wind velocity prediction
|
||||
long: When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases
|
||||
by this amount every second.
|
||||
type: float
|
||||
default: 0.05
|
||||
min: 0.0
|
||||
max: 1.0
|
||||
unit: m/s^2/sqrt(Hz)
|
||||
decimal: 3
|
||||
Loading…
x
Reference in New Issue
Block a user