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

WP mission sealevel altitude datum #6662

Merged
merged 10 commits into from May 3, 2021

Conversation

breadoven
Copy link
Collaborator

Addresses #6641

Adds the ability to set the altitude datum used for a WP mission to sea level. It uses the WP Mission .P3 field to flag the datum to be used for each geospatial WP in the mission, 0 for Takeoff (as it is now) or 1 for Sea Level, e.g.

wp 0 1 473917087 32023003 3000 0 0 0 0
wp 1 1 473931622 32005274 25000 0 0 1 0
wp 2 1 473948775 32036602 26000 0 0 1 0
wp 3 1 473941049 32071578 2000 0 0 0 0
wp 4 6 0 0 0 1 1 0 0
wp 5 1 473915090 32050643 31000 0 0 1 0
wp 6 1 473911456 32034282 30500 0 0 1 0
wp 7 1 473913158 32005274 3000 0 0 0 0
wp 8 4 0 0 0 0 0 0 165

Simplifies setting up Missions flying close to terrain because WPs using the sea level datum maintain the set true altitude regardless of take off altitude. No easy way to set this up at the moment other than to edit the CLI WP output after a mission has been loaded but at least the option is there if required.

Works as expected when tested on a fixed wing. The logged activeWaypoint.pos.z values calculated during the above Mission were:

wp 0 activeWaypoint.pos.z = 3000
wp 1 activeWaypoint.pos.z = -1985
wp 2 activeWaypoint.pos.z = -985
wp 3 activeWaypoint.pos.z = 2000
wp 4 activeWaypoint.pos.z = N/A
wp 5 activeWaypoint.pos.z = 4015
etc

Take off altitude was 269m when armed according to the OSD (Above activeWaypoint.pos.z values equate to a posControl.gpsOrigin alt of 269.85m)

HUD WP altitude correction
Changed to using WP P3 for altitude datum flag now set individually for each geospatial WP in mission.
@stronnag
Copy link
Collaborator

stronnag commented Mar 2, 2021

P3 is alrady used by the navigation engine as:

Does this PR preserve this extant functionality ? As #6429 is yours, I guess so

@breadoven
Copy link
Collaborator Author

I changed #6429 to use a dedicated array so it doesn't use P3 any more. Wasn't sure it was the best use of P3 anyway since it's an OSD display issue rather than something specific to controlling a mission.

This change only affects the geospatial WPs since they are the only ones with an altitude setting, so Jumps won't be affected. I tested with a Jump WP just to confirm although I wasn't expecting any issues given how this PR works and how Jumps work in the code,

@stronnag
Copy link
Collaborator

stronnag commented Mar 2, 2021

I tested with a Jump WP just to confirm although I wasn't expecting any issues given how this PR works and how Jumps work in the code,

Thanks for testing!

@stronnag
Copy link
Collaborator

stronnag commented May 3, 2021

mwp will support this, including relative / absolute conversion via manual reference input (or online service if connected). I'll merge this once CI has completed, looks very useful.

@breadoven
Copy link
Collaborator Author

breadoven commented May 3, 2021

mwp will support this, including relative / absolute conversion via manual reference input (or online service if connected). I'll merge this once CI has completed, looks very useful.

OK but be aware that a change is required to #6822 if this option is available to allow the landing elevation to be entered as an absolute value (more sensible in fact than using relative).

This is very useful if you fly anywhere other than flat fields or sports grounds.

@stronnag
Copy link
Collaborator

stronnag commented May 3, 2021

OK but be aware that a change is required to #6822 if this option is available to allow the landing elevation to be entered as an absolute value (more sensible in fact than using relative).

I did wonder about that. I've also implemented that in mwp, including automagic setting from mwp's terrain analysis function.

In that case, I'll wait until #6822 is done, and I'll merge them both at the same time to avoid confusion / mismatched stuff.

Nice work on both ...

@stronnag stronnag added this to the 3.0 milestone May 3, 2021
@stronnag stronnag added the Release Notes Add this when a PR needs to be mentioned in the release notes label May 3, 2021
@breadoven
Copy link
Collaborator Author

OK but be aware that a change is required to #6822 if this option is available to allow the landing elevation to be entered as an absolute value (more sensible in fact than using relative).

I did wonder about that. I've also implemented that in mwp, including automagic setting from mwp's terrain analysis function.

In that case, I'll wait until #6822 is done, and I'll merge them both at the same time to avoid confusion / mismatched stuff.

Nice work on both ...

The change to #6822 to allow use of absolute elevations uses part of this PR though so perhaps better to merge this first then I can update #6822 to be merged after otherwise #6822 will fail checks. Or does that not matter, I'll resolve itself when both merged ?

@stronnag stronnag merged commit f4b92bc into iNavFlight:master May 3, 2021
@stronnag
Copy link
Collaborator

stronnag commented May 3, 2021

Done!

breadoven added a commit to breadoven/inav that referenced this pull request May 3, 2021
Add correction if absolute SL landing elevation used (related PR iNavFlight#6662)
stronnag pushed a commit that referenced this pull request May 3, 2021
* Initial build

* Fix p1 error + change cm to meters

* Update navigation.c

Add correction if absolute SL landing elevation used (related PR #6662)
@breadoven breadoven deleted the abo_WP_mission_MSL_datum branch May 3, 2021 16:22
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Release Notes Add this when a PR needs to be mentioned in the release notes
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants