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: fixed antenna offset for blending #13802

Merged
merged 2 commits into from
Mar 17, 2020

Conversation

tridge
Copy link
Contributor

@tridge tridge commented Mar 13, 2020

we were accessing beyond the end of the antenna_offset array. This could cause the EKF position and velocity data to be corrupted when blending
Bug introduced in
261465e AP_GPS: split out update_primary() from update()

@tridge tridge requested a review from rmackay9 March 13, 2020 05:30
@rmackay9
Copy link
Contributor

I agree with this change and can confirm that it resolves the issues I was having with Copter-4.0.4-dev when using GPS blending.

@@ -795,8 +795,10 @@ void AP_GPS::update(void)

#if defined(GPS_BLENDED_INSTANCE)
// copy the primary instance to the blended instance in case it is enabled later
state[GPS_BLENDED_INSTANCE] = state[primary_instance];
_blended_antenna_offset = _antenna_offset[primary_instance];
if (primary_instance != GPS_BLENDED_INSTANCE) {
Copy link
Contributor

Choose a reason for hiding this comment

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

JUST NUKE THIS ALREADY! Sorry to be a bear on it but I've pointed this out in review before: #12844 (comment) It's dead code that doesn't make sense. If we had removed it when first brought up we never would have had the problem...

Copy link
Contributor

Choose a reason for hiding this comment

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

I may have pushed for the minimum change. If we're sure it can just be nuked then I'm OK with that and I'm happy to re-test afterwards..

Copy link
Contributor Author

Choose a reason for hiding this comment

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

done

@@ -1654,14 +1656,6 @@ void AP_GPS::calc_blended_state(void)
_hgt_offset_cm[i] = (float)(state[GPS_BLENDED_INSTANCE].location.alt - state[i].location.alt) * alpha[i] + _hgt_offset_cm[i] * (1.0f - alpha[i]);
}

// Calculate a corrected location for each GPS
Copy link
Contributor

Choose a reason for hiding this comment

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

If we are going to remove this then the calculation of _NE_pos_offset_m and _hgt_off_cm above should also be removed. Also worth observing they should have been locals here, rather then members of the GPS object. (Given that we track _blended_antenna_offset directly I think removing this is fine, but lets remove all the dead bits of code.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

done, note that this ended up removing quite a bit of code

we were accessing beyond the end of the antenna_offset array
@rmackay9
Copy link
Contributor

I guess the next step for this is for me to test fly it right? I'll try and do that tomorrow.

Copy link
Contributor

@WickedShell WickedShell left a comment

Choose a reason for hiding this comment

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

Changes look reasonable, I agree that the old comments make it worrisome though :)

@tridge tridge merged commit f00314a into ArduPilot:master Mar 17, 2020
@rmackay9
Copy link
Contributor

@priseborough, just FYI

@rmackay9
Copy link
Contributor

I flight tested this and it worked great, thanks!

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

Successfully merging this pull request may close these issues.

4 participants