Skip to content

Commit

Permalink
AP_NavEKF3: update GSF parms documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Feb 11, 2022
1 parent 4d974c0 commit a7159a6
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_NavEKF3/AP_NavEKF3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -608,15 +608,15 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {

// @Param: GSF_RUN_MASK
// @DisplayName: Bitmask of which EKF-GSF yaw estimators run
// @Description: 1 byte bitmap of which EKF3 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 EKF3 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK3_GSF_USE, EK3_GSF_DELAY and EK3_GSF_MAXCOUNT parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK3_GSF_USE to 0.
// @Description: 1 byte bitmap of which EKF3 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 EKF3 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK3_GSF_USE_MASK and EK3_GSF_RST_MAX parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK3_GSF_USE to 0.
// @Bitmask: 0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("GSF_RUN_MASK", 57, NavEKF3, _gsfRunMask, 3),

// @Param: GSF_USE_MASK
// @DisplayName: Bitmask of which EKF-GSF yaw estimators are used
// @Description: 1 byte bitmap of which EKF3 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK3_GSF_RUN parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF3 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF3 instance. Additionally the EKF3 will initiate a reset internally if navigation is lost for more than EK3_GSF_DELAY milli seconds.
// @Description: 1 byte bitmap of which EKF3 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK3_GSF_RUN_MASK parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF3 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF3 instance.
// @Bitmask: 0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
// @User: Advanced
// @RebootRequired: True
Expand All @@ -626,7 +626,7 @@ const AP_Param::GroupInfo NavEKF3::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 EKF3 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 EK3_GSF_USE parameter.
// @Description: Sets the maximum number of times the EKF3 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 EK3_GSF_USE_MASK parameter.
// @Range: 1 10
// @Increment: 1
// @User: Advanced
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1534,7 +1534,7 @@ bool NavEKF3_core::learnMagBiasFromGPS(void)
// Reset states using yaw from EKF-GSF and velocity and position from GPS
bool NavEKF3_core::EKFGSF_resetMainFilterYaw(bool emergency_reset)
{
// Don't do a reset unless permitted by the EK3_GSF_USE and EK3_GSF_RUN parameter masks
// Don't do a reset unless permitted by the EK3_GSF_USE_MASK and EK3_GSF_RUN_MASK parameter masks
if ((yawEstimator == nullptr)
|| !(frontend->_gsfUseMask & (1U<<core_index))) {
return false;
Expand Down

0 comments on commit a7159a6

Please sign in to comment.