PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <parameters/param.h>
Go to the source code of this file.
Functions | |
PARAM_DEFINE_FLOAT (LPE_FLW_OFF_Z, 0.0f) | |
Optical flow z offset from center. More... | |
PARAM_DEFINE_FLOAT (LPE_FLW_SCALE, 1.3f) | |
Optical flow scale. More... | |
PARAM_DEFINE_FLOAT (LPE_FLW_R, 7.0f) | |
Optical flow rotation (roll/pitch) noise gain. More... | |
PARAM_DEFINE_FLOAT (LPE_FLW_RR, 7.0f) | |
Optical flow angular velocity noise gain. More... | |
PARAM_DEFINE_INT32 (LPE_FLW_QMIN, 150) | |
Optical flow minimum quality threshold. More... | |
PARAM_DEFINE_FLOAT (LPE_SNR_Z, 0.05f) | |
Sonar z standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_SNR_OFF_Z, 0.00f) | |
Sonar z offset from center of vehicle +down. More... | |
PARAM_DEFINE_FLOAT (LPE_LDR_Z, 0.03f) | |
Lidar z standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_LDR_OFF_Z, 0.00f) | |
Lidar z offset from center of vehicle +down. More... | |
PARAM_DEFINE_FLOAT (LPE_ACC_XY, 0.012f) | |
Accelerometer xy noise density. More... | |
PARAM_DEFINE_FLOAT (LPE_ACC_Z, 0.02f) | |
Accelerometer z noise density. More... | |
PARAM_DEFINE_FLOAT (LPE_BAR_Z, 3.0f) | |
Barometric presssure altitude z standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_GPS_DELAY, 0.29f) | |
GPS delay compensaton. More... | |
PARAM_DEFINE_FLOAT (LPE_GPS_XY, 1.0f) | |
Minimum GPS xy standard deviation, uses reported EPH if greater. More... | |
PARAM_DEFINE_FLOAT (LPE_GPS_Z, 3.0f) | |
Minimum GPS z standard deviation, uses reported EPV if greater. More... | |
PARAM_DEFINE_FLOAT (LPE_GPS_VXY, 0.25f) | |
GPS xy velocity standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_GPS_VZ, 0.25f) | |
GPS z velocity standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_EPH_MAX, 3.0f) | |
Max EPH allowed for GPS initialization. More... | |
PARAM_DEFINE_FLOAT (LPE_EPV_MAX, 5.0f) | |
Max EPV allowed for GPS initialization. More... | |
PARAM_DEFINE_FLOAT (LPE_VIS_DELAY, 0.1f) | |
Vision delay compensaton. More... | |
PARAM_DEFINE_FLOAT (LPE_VIS_XY, 0.1f) | |
Vision xy standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_VIS_Z, 0.5f) | |
Vision z standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_VIC_P, 0.001f) | |
Vicon position standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_PN_P, 0.1f) | |
Position propagation noise density. More... | |
PARAM_DEFINE_FLOAT (LPE_PN_V, 0.1f) | |
Velocity propagation noise density. More... | |
PARAM_DEFINE_FLOAT (LPE_PN_B, 1e-3f) | |
Accel bias propagation noise density. More... | |
PARAM_DEFINE_FLOAT (LPE_PN_T, 0.001f) | |
Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) More... | |
PARAM_DEFINE_FLOAT (LPE_T_MAX_GRADE, 1.0f) | |
Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) Used to calculate increased terrain random walk nosie due to movement. More... | |
PARAM_DEFINE_FLOAT (LPE_FGYRO_HP, 0.001f) | |
Flow gyro high pass filter cut off frequency. More... | |
PARAM_DEFINE_INT32 (LPE_FAKE_ORIGIN, 0) | |
Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable. More... | |
PARAM_DEFINE_FLOAT (LPE_LAT, 47.397742f) | |
Local origin latitude for nav w/o GPS. More... | |
PARAM_DEFINE_FLOAT (LPE_LON, 8.545594) | |
Local origin longitude for nav w/o GPS. More... | |
PARAM_DEFINE_FLOAT (LPE_X_LP, 5.0f) | |
Cut frequency for state publication. More... | |
PARAM_DEFINE_FLOAT (LPE_VXY_PUB, 0.3f) | |
Required velocity xy standard deviation to publish position. More... | |
PARAM_DEFINE_FLOAT (LPE_Z_PUB, 1.0f) | |
Required z standard deviation to publish altitude/ terrain. More... | |
PARAM_DEFINE_FLOAT (LPE_LAND_Z, 0.03f) | |
Land detector z standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_LAND_VXY, 0.05f) | |
Land detector xy velocity standard deviation. More... | |
PARAM_DEFINE_FLOAT (LPE_LT_COV, 0.0001f) | |
Minimum landing target standard covariance, uses reported covariance if greater. More... | |
PARAM_DEFINE_INT32 (LPE_FUSION, 145) | |
Integer bitmask controlling data fusion. More... | |
PARAM_DEFINE_FLOAT | ( | LPE_FLW_OFF_Z | , |
0. | 0f | ||
) |
Optical flow z offset from center.
Local Position Estimator m -1 1 3
PARAM_DEFINE_FLOAT | ( | LPE_FLW_SCALE | , |
1. | 3f | ||
) |
Optical flow scale.
Local Position Estimator m 0.1 10.0 3
PARAM_DEFINE_FLOAT | ( | LPE_FLW_R | , |
7. | 0f | ||
) |
Optical flow rotation (roll/pitch) noise gain.
Local Position Estimator m/s / (rad) 0.1 10.0 3
PARAM_DEFINE_FLOAT | ( | LPE_FLW_RR | , |
7. | 0f | ||
) |
Optical flow angular velocity noise gain.
Local Position Estimator m/s / (rad/s) 0.0 10.0 3
PARAM_DEFINE_FLOAT | ( | LPE_SNR_Z | , |
0. | 05f | ||
) |
Sonar z standard deviation.
Local Position Estimator m 0.01 1 3
PARAM_DEFINE_FLOAT | ( | LPE_SNR_OFF_Z | , |
0. | 00f | ||
) |
Sonar z offset from center of vehicle +down.
Local Position Estimator m -1 1 3
PARAM_DEFINE_FLOAT | ( | LPE_LDR_Z | , |
0. | 03f | ||
) |
Lidar z standard deviation.
Local Position Estimator m 0.01 1 3
PARAM_DEFINE_FLOAT | ( | LPE_LDR_OFF_Z | , |
0. | 00f | ||
) |
Lidar z offset from center of vehicle +down.
Local Position Estimator m -1 1 3
PARAM_DEFINE_FLOAT | ( | LPE_ACC_XY | , |
0. | 012f | ||
) |
Accelerometer xy noise density.
Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)
Larger than data sheet to account for tilt error.
Local Position Estimator m/s^2/sqrt(Hz) 0.00001 2 4
PARAM_DEFINE_FLOAT | ( | LPE_ACC_Z | , |
0. | 02f | ||
) |
Accelerometer z noise density.
Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)
Local Position Estimator m/s^2/sqrt(Hz) 0.00001 2 4
PARAM_DEFINE_FLOAT | ( | LPE_BAR_Z | , |
3. | 0f | ||
) |
Barometric presssure altitude z standard deviation.
Local Position Estimator m 0.01 100 2
PARAM_DEFINE_FLOAT | ( | LPE_GPS_DELAY | , |
0. | 29f | ||
) |
GPS delay compensaton.
Local Position Estimator sec 0 0.4 2
PARAM_DEFINE_FLOAT | ( | LPE_GPS_XY | , |
1. | 0f | ||
) |
Minimum GPS xy standard deviation, uses reported EPH if greater.
Local Position Estimator m 0.01 5 2
PARAM_DEFINE_FLOAT | ( | LPE_GPS_Z | , |
3. | 0f | ||
) |
Minimum GPS z standard deviation, uses reported EPV if greater.
Local Position Estimator m 0.01 200 2
PARAM_DEFINE_FLOAT | ( | LPE_GPS_VXY | , |
0. | 25f | ||
) |
GPS xy velocity standard deviation.
EPV used if greater than this value.
Local Position Estimator m/s 0.01 2 3
PARAM_DEFINE_FLOAT | ( | LPE_GPS_VZ | , |
0. | 25f | ||
) |
GPS z velocity standard deviation.
Local Position Estimator m/s 0.01 2 3
PARAM_DEFINE_FLOAT | ( | LPE_EPH_MAX | , |
3. | 0f | ||
) |
Max EPH allowed for GPS initialization.
Local Position Estimator m 1.0 5.0 3
PARAM_DEFINE_FLOAT | ( | LPE_EPV_MAX | , |
5. | 0f | ||
) |
Max EPV allowed for GPS initialization.
Local Position Estimator m 1.0 5.0 3
PARAM_DEFINE_FLOAT | ( | LPE_VIS_DELAY | , |
0. | 1f | ||
) |
Vision delay compensaton.
Set to zero to enable automatic compensation from measurement timestamps
Local Position Estimator sec 0 0.1 2
PARAM_DEFINE_FLOAT | ( | LPE_VIS_XY | , |
0. | 1f | ||
) |
Vision xy standard deviation.
Local Position Estimator m 0.01 1 3
PARAM_DEFINE_FLOAT | ( | LPE_VIS_Z | , |
0. | 5f | ||
) |
Vision z standard deviation.
Local Position Estimator m 0.01 100 3
PARAM_DEFINE_FLOAT | ( | LPE_VIC_P | , |
0. | 001f | ||
) |
Vicon position standard deviation.
Local Position Estimator m 0.0001 1 4
PARAM_DEFINE_FLOAT | ( | LPE_PN_P | , |
0. | 1f | ||
) |
Position propagation noise density.
Increase to trust measurements more. Decrease to trust model more.
Local Position Estimator m/s/sqrt(Hz) 0 1 8
PARAM_DEFINE_FLOAT | ( | LPE_PN_V | , |
0. | 1f | ||
) |
Velocity propagation noise density.
Increase to trust measurements more. Decrease to trust model more.
Local Position Estimator (m/s)/s/sqrt(Hz) 0 1 8
PARAM_DEFINE_FLOAT | ( | LPE_PN_B | , |
1e- | 3f | ||
) |
Accel bias propagation noise density.
Local Position Estimator (m/s^2)/s/sqrt(Hz) 0 1 8
PARAM_DEFINE_FLOAT | ( | LPE_PN_T | , |
0. | 001f | ||
) |
Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)
Local Position Estimator (m/s)/(sqrt(hz)) 0 1 3
PARAM_DEFINE_FLOAT | ( | LPE_T_MAX_GRADE | , |
1. | 0f | ||
) |
Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) Used to calculate increased terrain random walk nosie due to movement.
Local Position Estimator % 0 100 3
PARAM_DEFINE_FLOAT | ( | LPE_FGYRO_HP | , |
0. | 001f | ||
) |
Flow gyro high pass filter cut off frequency.
Local Position Estimator Hz 0 2 3
PARAM_DEFINE_FLOAT | ( | LPE_LAT | , |
47. | 397742f | ||
) |
Local origin latitude for nav w/o GPS.
Local Position Estimator deg -90 90 8
PARAM_DEFINE_FLOAT | ( | LPE_LON | , |
8. | 545594 | ||
) |
Local origin longitude for nav w/o GPS.
Local Position Estimator deg -180 180 8
PARAM_DEFINE_FLOAT | ( | LPE_X_LP | , |
5. | 0f | ||
) |
Cut frequency for state publication.
Local Position Estimator Hz 5 1000 0
PARAM_DEFINE_FLOAT | ( | LPE_VXY_PUB | , |
0. | 3f | ||
) |
Required velocity xy standard deviation to publish position.
Local Position Estimator m/s 0.01 1.0 3
PARAM_DEFINE_FLOAT | ( | LPE_Z_PUB | , |
1. | 0f | ||
) |
Required z standard deviation to publish altitude/ terrain.
Local Position Estimator m 0.3 5.0 1
PARAM_DEFINE_FLOAT | ( | LPE_LAND_Z | , |
0. | 03f | ||
) |
Land detector z standard deviation.
Local Position Estimator m 0.001 10.0 3
PARAM_DEFINE_FLOAT | ( | LPE_LAND_VXY | , |
0. | 05f | ||
) |
Land detector xy velocity standard deviation.
Local Position Estimator m/s 0.01 10.0 3
PARAM_DEFINE_FLOAT | ( | LPE_LT_COV | , |
0. | 0001f | ||
) |
Minimum landing target standard covariance, uses reported covariance if greater.
Local Position Estimator m^2 0.0 10 2
PARAM_DEFINE_INT32 | ( | LPE_FLW_QMIN | , |
150 | |||
) |
Optical flow minimum quality threshold.
Local Position Estimator 0 255 0
PARAM_DEFINE_INT32 | ( | LPE_FAKE_ORIGIN | , |
0 | |||
) |
Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable.
Local Position Estimator 0 1
PARAM_DEFINE_INT32 | ( | LPE_FUSION | , |
145 | |||
) |
Integer bitmask controlling data fusion.
Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion
default (145 - GPS, baro, land detector)
Local Position Estimator 0 255 0 fuse GPS, requires GPS for alt. init 1 fuse optical flow 2 fuse vision position 3 fuse landing target 4 fuse land detector 5 pub agl as lpos down 6 flow gyro compensation 7 fuse baro