AP_NavEKF2: Change default value of EK2_OGN_HGT_MASK

Turn off by default.
Update parameter description
This commit is contained in:
priseborough 2017-05-31 12:40:01 +10:00 committed by Francisco Ferreira
parent 49ec2b4032
commit b42fb31d7d
1 changed files with 15 additions and 4 deletions

View File

@ -194,6 +194,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Increment: 10
// @User: Advanced
// @Units: ms
// @RebootRequired: True
AP_GROUPINFO("GPS_DELAY", 8, NavEKF2, _gpsDelay_ms, 220),
// Height measurement parameters
@ -229,6 +230,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Increment: 10
// @User: Advanced
// @Units: ms
// @RebootRequired: True
AP_GROUPINFO("HGT_DELAY", 12, NavEKF2, _hgtDelay_ms, 60),
// Magnetometer measurement parameters
@ -330,6 +332,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Increment: 10
// @User: Advanced
// @Units: ms
// @RebootRequired: True
AP_GROUPINFO("FLOW_DELAY", 23, NavEKF2, _flowDelay_ms, FLOW_MEAS_DELAY),
// State and Covariance Predition Parameters
@ -407,6 +410,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Description: 1 byte bitmap of IMUs to use in EKF2. A separate instance of EKF2 will be started for each IMU selected. Set to 1 to use the first IMU only (default), set to 2 to use the second IMU only, set to 3 to use the first and second IMU. Additional IMU's can be used up to a maximum of 6 if memory and processing resources permit. There may be insufficient memory and processing resources to run multiple instances. If this occurs EKF2 will fail to start.
// @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("IMU_MASK", 33, NavEKF2, _imuMask, 3),
// @Param: CHECK_SCALE
@ -430,6 +434,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Description: This sets the IMU mask of sensors to do full logging for
// @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("LOG_MASK", 36, NavEKF2, _logging_mask, 1),
// control of magentic yaw angle fusion
@ -517,6 +522,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Increment: 10
// @User: Advanced
// @Units: ms
// @RebootRequired: True
AP_GROUPINFO("BCN_DELAY", 46, NavEKF2, _rngBcnDelay_ms, 50),
// @Param: RNG_USE_SPD
@ -533,14 +539,19 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Description: 1 byte bitmap of EKF cores that will disable magnetic field states and use simple magnetic heading fusion at all times. This parameter enables specified cores to be used as a backup for flight into an environment with high levels of external magnetic interference which may degrade the EKF attitude estimate when using 3-axis magnetometer fusion. NOTE : Use of a different magnetometer fusion algorithm on different cores makes unwanted EKF core switches due to magnetometer errors more likely.
// @Bitmask: 0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("MAG_MASK", 48, NavEKF2, _magMask, 0),
// @Param: OGN_HGT_MASK
// @DisplayName: Bitmask control of EKF origin height adjustment
// @Description: When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference. If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be adjusted so that the height returned by the getLLH() function is corrected for primary height sensor drift and change in datum over time. This parameter controls when the WGS-84 reference height used by the EKF to convert GPS height to local height will be adjusted. Adjustment is performed using a Bayes filter and only operates when GPS quality permits. The parameter also controls whether the adjustments to the GPS reference datum also update the reported height of the EKF origin.
// @Bitmask: 0:When using Baro hgt,1:When using range height,2:Update Origin
// @DisplayName: Bitmask control of EKF reference height correction
// @Description: When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference.
// If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be corrected so that the height returned by the getLLH() function is compensated for primary height sensor drift and change in datum over time.
// The first two bit positions control when the height datum will be corrected. Correction is performed using a Bayes filter and only operates when GPS quality permits.
// The third bit position controls where the corrections to the GPS reference datum are applied. Corrections can be applied to the local vertical position (default) or to the reported EKF origin height.
// @Bitmask: 0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to origin height
// @User: Advanced
AP_GROUPINFO("OGN_HGT_MASK", 49, NavEKF2, _originHgtMode, 7),
// @RebootRequired: True
AP_GROUPINFO("OGN_HGT_MASK", 49, NavEKF2, _originHgtMode, 0),
AP_GROUPEND
};