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

improve and document mission interface #984

Open
2 of 4 tasks
flixr opened this issue Nov 25, 2014 · 6 comments
Open
2 of 4 tasks

improve and document mission interface #984

flixr opened this issue Nov 25, 2014 · 6 comments
Labels

Comments

@flixr
Copy link
Member

flixr commented Nov 25, 2014

We have a basic mission interface with the mission modules:
mission_fw.xml
mission_rotorcraft.xml
https://wiki.paparazziuav.org/wiki/Mission

While it now has support for global LLA coordinates, lat/lon are sent as float which should never be done because it has really bad precision/resolution.
Also how about using a variable length array for PATH instead of fixed 5 waypoints?

Todo:

  • don't send lat/lon as floats as that has bad precision (use int32 with 1e7deg instead)
  • don't convert LLA to float again in the fixedwing version (we seem to miss functions to convert LLA to UTM in int or double...)
  • add one fixedwing and one rotorcraft example airframe to conf_tests.xml
  • improve documentation (also description in module.xml)

Want to back this issue? Post a bounty on it! We accept bounties via Bountysource.

@flixr flixr added the Module label Nov 25, 2014
@gautierhattenberger
Copy link
Member

Concerning the 5 WP in Path, I did it like that because:

  • I'm not sure sending a variable length array uplink really work (possible data alignment issue ?)
  • it prevents people from sending too many WP
  • since the mission element is a union, I didn't want the path element to be to big
  • it was a fair trade-off I think (if you need 2 segments, send 2 segment elements, if you need 3 or 4 segments, send a path element)

@flixr
Copy link
Member Author

flixr commented Nov 25, 2014

Hm... I can understand the point about the union and ease of implementation.

Still think that it would be nicer to use variable length array in the end, that would also save bytes in the messages if your path is shorter.
It would also make the MISSION_SEGMENT superfluous, as it is simply a PATH with two entries...

On the other hand, do we really want to have the same alt for the whole path (instead of a separate alt for each point in the path)?

@agressiva
Copy link
Contributor

about mission module, i think it a good idea to make a polysurvey (osam like).
I think about that some time ago but i am not a master in c programming.

what you suggest on how pass waypoints to MISSION_SURVEY ?
it need to be dinamic because some poligon use 10 point and others may use 20 ... 25 ...

its very usefull for pro grade photogrammetry jobs.

@benlaurie
Copy link
Contributor

Did I get my sums wrong? 1e7deg is up to 1.5 meters of error, isn't it?

On Tue Nov 25 2014 at 7:58:57 PM Eduardo Reginato lavratti <
notifications@github.com> wrote:

about mission module, i think it a good idea to make a polysurvey (osam
like).
I think about that some time ago but i am not a master in c programming.

what you suggest on how pass waypoints to MISSION_SURVEY ?
it need to be dinamic because some poligon use 10 point and others may use
20 ... 25 ...

its very usefull for pro grade photogrammetry jobs.


Reply to this email directly or view it on GitHub
#984 (comment).

@gautierhattenberger
Copy link
Member

if you consider the earth radius at around 6371km, it gives a resolution of 6371000_1e^-7_pi/180 = 0.011 m. So 1cm resolution for 1e7deg with integer. Not sure what you can expect from float.

@flixr
Copy link
Member Author

flixr commented Nov 26, 2014

A 32bit float has 23bits for the mantissa, which is a bit more than 7 digits. Since you already use 3 digits to represent the part to the left of the decimal point, that leaves about 4 digits for the rest..
So in the worst case of 180deg you have a precision of only ~3m!
http://en.wikipedia.org/wiki/Decimal_degrees

flixr added a commit that referenced this issue Nov 26, 2014
A 32bit float has 23bits for the mantissa, which is a bit more than 7 digits.
Since you already use 3 digits to represent the part to the left of the decimal point, that leaves about 4 digits for the rest..
So in the worst case of 180deg you have a resolution of only ~3m!

With 1e7deg 32bit int you get ~1cm resolution.

Rotorcraft part: Also removed the removed the altitude conversion from geoid alt to ellipsoid alt,
requiring the alt in the message to already have ellipsoid alt.

addresses first part of #984
flixr added a commit that referenced this issue Nov 26, 2014
A 32bit float has 23bits for the mantissa, which is a bit more than 7 digits.
Since you already use 3 digits to represent the part to the left of the decimal point, that leaves about 4 digits for the rest..
So in the worst case of 180deg you have a resolution of only ~3m!

With 1e7deg 32bit int you get ~1cm resolution.

addresses first part of #984 (at least for the rotorcraft version, fixedwing version still converts to LLA float in between...)
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

4 participants