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

Copter: correct current_loc.alt to be above home instead of above ekf origin #13444

Merged
merged 1 commit into from
Feb 5, 2020

Conversation

rmackay9
Copy link
Contributor

@rmackay9 rmackay9 commented Feb 1, 2020

This fixes this issue #13441 which was caused by Copter's current_loc.alt being an altitude above EKF origin instead of an altitude above home. The issue becomes especially obvious when we force the EKF origin and Home altitude to be different by changing the GND_ALT_OFFSET parameter before arming the vehicle.

Below are screen shots of the vehicle's altitude and we can see in the 2nd image (After) that the vehicle does not decend after being switched to RTL.

rtl-alt-bug-before

rtl-alt-bug-after

This fix should be fine but we need to carefully review everywhere else we use current_loc.alt before merging.

ArduCopter/inertia.cpp Outdated Show resolved Hide resolved
Comment on lines 27 to 25
// if home has not been set yet we treat alt-above-origin as alt-above-home
// current_loc's altitude frame is always ABOVE_HOME
current_loc.set_alt_cm(alt_above_origin_cm, Location::AltFrame::ABOVE_HOME);
Copy link
Member

Choose a reason for hiding this comment

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

Do we really need this part? I can't see why this is needed. AFAIK, we are still using current_loc.alt directly and not really caring about the alt frame, so it doesn't actually matter if we do this (with or without other code parts should behave the same) - but I'd rather have code that makes sense here.

The real issue was that we were using an altitude above origin and setting it as above home, which is fixed above.

Copy link
Contributor Author

@rmackay9 rmackay9 Feb 3, 2020

Choose a reason for hiding this comment

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

thanks for the review. I'm not sure I totally understand the question but the underlying issue is that we were setting current_loc.alt's frame to be ABOVE_ORIGIN. It's frame must always be ABOVE_HOME.

I think maybe you're asking why we both using the "loc" variable. I did this to make it atomic .. it perhaps doesn't matter but with the growing number of threads in AP I worried that current_loc.alt's frame momentarily being ABOVE_ORIGIN might cause some odd issues somewhere.

Copy link
Member

Choose a reason for hiding this comment

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

I'm not sure I totally understand the question but the underlying issue is that we were setting current_loc.alt's frame to be ABOVE_ORIGIN. It's frame must always be ABOVE_HOME.

@rmackay9 That's not the real issue. The actual issue was that, when home was set, we got the altitude from InertialNav (which is above origin) and set it in current_loc saying it was above home (no conversion from AO to AH happened). This is actually important to understand because we use the Location class everywhere now - if I'm not explaining myself properly let me know and we'll have a call to discuss it.

What I was saying above is that this code shouldn't matter because we are using current_loc.alt and not caring about the (relative, terrain, etc.) flags - which is the only thing that using ABOVE_HOME or ABOVE_ORIGIN changes. We should change this (so that every caller knows exactly what reference the altitude they are using has), but that's another topic.
Anyway, it doesn't really hurt either.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@OXINARF, thanks for the feedback. In my testing I found that when home was set, the altitude was coming from Inertial Nav (as you say) but it's frame was set to above-ekf-origin (which does not match what you say).

By the way, before home is set, it's ok for the current_loc.alt to be the altitude above the ekf origin (but with the frame actually specified as alt-above-home). This is done on purpose actually to handle the situation where the user is flying without a GPS. We need current_loc.alt to update at least for reporting purposes to the GCS.

Copy link
Member

Choose a reason for hiding this comment

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

@OXINARF, thanks for the feedback. In my testing I found that when home was set, the altitude was coming from Inertial Nav (as you say) but it's frame was set to above-ekf-origin (which does not match what you say).

@rmackay9 Was the frame set to above-ekf-origin or (from the log) you could tell the altitude value was above-ekf-origin? These are different things: the frame is told by the flags in Location, but the altitude value in Location is agnostic to what it relates to - we can usually infer it, but code doesn't infer, it just does what it's told 🙂
I think we are saying the same with different names, but I'd like to be sure.

By the way, before home is set, it's ok for the current_loc.alt to be the altitude above the ekf origin (but with the frame actually specified as alt-above-home). This is done on purpose actually to handle the situation where the user is flying without a GPS. We need current_loc.alt to update at least for reporting purposes to the GCS.

What I am saying is that we don't actually need the bold part, it doesn't make any difference - it just hides away what the true altitude frame is.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@OXINARF, the frame was actually being set to above-ekf-origin. I added debug and could see this.

You may be right that before home is set, it doesn't matter if we set the frame to alt-above-home or alt-above-ekf origin because we will never use the current_loc.alt for anything important.

It's unrelated to our discussion and I'm probably repeating myself but the horrible thing about this PR was that the current_loc's frame was always alt-above-ekf origin. This was a terribly insidious mistake that caused bad behaviour in about 10 different parts of the code. This bug was in the top 3 worst bugs in the Copter-4.0 release. The other two being the crash-o-matic FrSky send-text bug and the RCOutput timing bug (actually present since Copter-3.6.10 as well).

@rmackay9 rmackay9 merged commit bd8bcd5 into ArduPilot:master Feb 5, 2020
@rmackay9 rmackay9 deleted the copter-current-alt-fix branch February 5, 2020 05:23
@rmackay9 rmackay9 moved this from PRs to 4.0.2-rc4 in Copter 4.0 backports Feb 5, 2020
@rmackay9
Copy link
Contributor Author

rmackay9 commented Feb 5, 2020

this is included in Copter-4.0.2-rc4

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

Successfully merging this pull request may close these issues.

None yet

4 participants