Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_GPS: Backport correct satellite count for SBF DNU NrSv value #27799

Conversation

chiara-septentrio
Copy link
Contributor

Backport to Copter 4.5 of PR 26628 : it sets the satellite count to 0 rather than ignoring it

@@ -453,8 +453,10 @@ AP_GPS_SBF::process_message(void)
set_alt_amsl_cm(state, ((float)temp.Height - temp.Undulation) * 1e2f);
}

if (temp.NrSV != 255) {
state.num_sats = temp.NrSV;
state.num_sats = temp.NrSV;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

correct indentation

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The indentation has been corrected, thank you for catching that

@rmackay9 rmackay9 merged commit 62fe90b into ArduPilot:Copter-4.5 Sep 25, 2024
91 of 92 checks passed
@rmackay9
Copy link
Contributor

This has been included in Copter-4.5.7-beta1

@rmackay9
Copy link
Contributor

rmackay9 commented Oct 6, 2024

We have a report here on the forums that suggests this has negatively impacted the [EKF] failsafe: https://discuss.ardupilot.org/t/coper-4-5-7-beta1-available-for-testing/124355

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
Status: 4.5.7-beta1
Development

Successfully merging this pull request may close these issues.

3 participants