mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_NavEKF3: fix some parameter descriptions
This commit is contained in:
parent
8032ed295d
commit
195e32c2fc
@ -194,9 +194,9 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
|
||||
// Height measurement parameters
|
||||
|
||||
// @Param: ALT_SOURCE
|
||||
// @DisplayName: Primary altitude sensor source
|
||||
// @Description: This parameter controls the primary height sensor used by the EKF. If the selected option cannot be used, it will default to Baro as the primary height source. Setting 0 will use the baro altitude at all times. Setting 1 uses the range finder and is only available in combination with optical flow navigation (EK2_GPS_TYPE = 3). Setting 2 uses GPS. Setting 3 uses the range beacon data. NOTE - the EK2_RNG_USE_HGT parameter can be used to switch to range-finder when close to the ground.
|
||||
// @Values: 0:Use Baro, 1:Use Range Finder, 2:Use GPS, 3:Use Range Beacon
|
||||
// @Values: 0:Use Baro, 1:Use Range Finder, 2:Use GPS
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ALT_SOURCE", 9, NavEKF3, _altSource, 0),
|
||||
|
||||
@ -429,7 +429,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
|
||||
// @Range: 0.05 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
// @Units: gauss
|
||||
// @Units: rad
|
||||
AP_GROUPINFO("YAW_M_NSE", 37, NavEKF3, _yawNoise, 0.5f),
|
||||
|
||||
// @Param: YAW_I_GATE
|
||||
@ -446,6 +446,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
|
||||
// @Range: 10 50
|
||||
// @Increment: 5
|
||||
// @User: Advanced
|
||||
// @Units: cs
|
||||
AP_GROUPINFO("TAU_OUTPUT", 39, NavEKF3, _tauVelPosOutput, 25),
|
||||
|
||||
// @Param: MAGE_P_NSE
|
||||
|
Loading…
Reference in New Issue
Block a user