AP_NavEKF2: update and correct GSF parameter documentation

This commit is contained in:
Henry Wurzburg 2022-02-14 07:32:57 -06:00 committed by Andrew Tridgell
parent 77f9d4fdba
commit 5e6447e893
2 changed files with 4 additions and 4 deletions

View File

@ -574,7 +574,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Param: GSF_RUN_MASK
// @DisplayName: Bitmask of which EKF-GSF yaw estimators run
// @Description: 1 byte bitmap of which EKF2 instances run an independant EKF-GSF yaw estimator to provide a backup yaw estimate that doesn't rely on magnetometer data. This estimator uses IMU, GPS and, if available, airspeed data. EKF-GSF yaw estimator data for the primary EKF2 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK2_GSF_USE, EK2_GSF_DELAY and EK2_GSF_MAXCOUNT parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK2_GSF_USE to 0.
// @Description: A bitmask of which EKF2 instances run an independant EKF-GSF yaw estimator to provide a backup yaw estimate that doesn't rely on magnetometer data. This estimator uses IMU, GPS and, if available, airspeed data. EKF-GSF yaw estimator data for the primary EKF2 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK2_GSF_USE_MASK and EK2_GSF_RST_MAX parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK2_GSF_USE_MASK to 0.
// @Bitmask: 0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
// @User: Advanced
// @RebootRequired: True
@ -582,7 +582,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Param: GSF_USE_MASK
// @DisplayName: Bitmask of which EKF-GSF yaw estimators are used
// @Description: 1 byte bitmap of which EKF2 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK2_GSF_RUN parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF2 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF2 instance. Additionally the EKF2 will initiate a reset internally if navigation is lost for more than EK2_GSF_DELAY milli seconds.
// @Description: 1 byte bitmap of which EKF2 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK2_GSF_RUN_MASK parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF2 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF2 instance.
// @Bitmask: 0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
// @User: Advanced
// @RebootRequired: True
@ -592,7 +592,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @Param: GSF_RST_MAX
// @DisplayName: Maximum number of resets to the EKF-GSF yaw estimate allowed
// @Description: Sets the maximum number of times the EKF2 will be allowed to reset it's yaw to the estimate from the EKF-GSF yaw estimator. No resets will be allowed unless the use of the EKF-GSF yaw estimate is enabled via the EK2_GSF_USE parameter.
// @Description: Sets the maximum number of times the EKF2 will be allowed to reset its yaw to the estimate from the EKF-GSF yaw estimator. No resets will be allowed unless the use of the EKF-GSF yaw estimate is enabled via the EK2_GSF_USE_MASK parameter.
// @Range: 1 10
// @Increment: 1
// @User: Advanced

View File

@ -1161,7 +1161,7 @@ void NavEKF2_core::recordMagReset()
// Reset states using yaw from EKF-GSF and velocity and position from GPS
bool NavEKF2_core::EKFGSF_resetMainFilterYaw()
{
// Don't do a reset unless permitted by the EK2_GSF_USE_MASK and EKF@_GSF_RUN_MASK parameter masks
// Don't do a reset unless permitted by the EK2_GSF_USE_MASK and EKF2_GSF_RUN_MASK parameter masks
if ((yawEstimator == nullptr)
|| !(frontend->_gsfUseMask & (1U<<core_index))
|| EKFGSF_yaw_reset_count >= frontend->_gsfResetMaxCount) {