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 GPS2_RAW mavlink message #6534

Merged

Conversation

amilcarlucas
Copy link
Contributor

@amilcarlucas amilcarlucas commented Jul 3, 2017

implement missing "RTK number of satellites" and "RTK correction age" information in the GPS2_RAW MAVLink message for Nova and sbf GPS types

I splitted the #6424 into three ardupilot PRs to make it easier to review. This one should go in first to avoid conflicts.
I also expect this one to be less controversial.

This is the first one to go in. This is just a small part of it (been working and testing this since May 9th) , the rest of the related work is at #6424 #6541 ArduPilot/mavlink#48 ArduPilot/mavlink#49 ArduPilot/pymavlink#88 https://github.com/emlid/reach-docs/pull/26 emlid/RTKLIB#21 emlid/RTKLIB#28

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.

I strongly appreciate the effort to improve the documentation on what we expect units to be, however I'm not sure if RMS is actually correct. I can't find strong indicators either way for u-blox and a couple of other ones.

With that being said maybe that's fine and we request that RMS is what we are looking at for accuracies and move towards that.

@@ -135,13 +135,17 @@ class AP_GPS
uint8_t num_sats; ///< Number of visible satellites
Vector3f velocity; ///< 3D velocity in m/s, in NED format
float speed_accuracy; ///< 3D velocity accuracy estimate in m/s
float horizontal_accuracy; ///< horizontal accuracy estimate in m
float vertical_accuracy; ///< vertical accuracy estimate in m
float horizontal_accuracy; ///< horizontal accuracy estimate in m RMS
Copy link
Contributor

Choose a reason for hiding this comment

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

I'm not sure this is actually true for all the instances. U-blox doesn't note it formally either way in their protocol data sheet (that I can find), but they cite the accuracies as CEP when stating the performance of the unit, which I suspect means they might stick with that reporting for real time reasons as well since it would correspond with the data sheet better.

@@ -289,6 +289,7 @@ AP_GPS_SBP::_attempt_state_update()

last_full_update_tow = last_vel_ned.tow;
last_full_update_cpu_ms = now;
state.rtk_age_cs = (last_full_update_cpu_ms - last_injected_data_ms) / 10;
Copy link
Contributor

Choose a reason for hiding this comment

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

I don't think this is really a fair metric. It might be sorta correct, but provides no guarantees that the needed data was injected, or that the data you have scheduled for injection has been injected yet (or processed).

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Better than nothing I think.

float latsdev;
float lngsdev;
float hgtsdev;
uint32_t solstat; //!< Solution status
Copy link
Contributor

Choose a reason for hiding this comment

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

I have to ask whats the meaning you use in comments? I see things that are // ///< and //!< and it just looks really inconsistent.

Copy link
Contributor Author

@amilcarlucas amilcarlucas Jul 3, 2017

Choose a reason for hiding this comment

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

///< and //!< are both accepted doxygen markups.

@@ -398,7 +418,7 @@ class AP_GPS

private:
// returns the desired gps update rate in milliseconds
// this does not provide any gurantee that the GPS is updating at the requested
// this does not provide any guarantee that the GPS is updating at the requested
Copy link
Contributor

Choose a reason for hiding this comment

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

My ongoing bad spelling continues!

@@ -202,10 +202,12 @@ AP_GPS_NOVA::process_message(void)

state.num_sats = bestposu.svsused;

state.horizontal_accuracy = (float) ((bestposu.latsdev + bestposu.lngsdev)/2);
state.vertical_accuracy = (float) bestposu.hgtsdev;
state.horizontal_accuracy = (float) ((bestposu.latsdev + bestposu.lngsdev)/2); // RMS
Copy link
Contributor

Choose a reason for hiding this comment

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

I'm a bit confused, you have already labeled the horizontal_accuracy storage location RMS in it's comments, you updated all the comments for the messages to say the accuracy in millimeters, but omitted the RMS tag there, but then applied it here. This should really just be documented in the header, rather then in line in the code randomly like this, and particularly in the structs that are used to decode the messages.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

OK

@@ -159,8 +159,8 @@ AP_GPS_ERB::_parse_gps(void)
state.location.alt = (int32_t)(_buffer.pos.altitude_msl * 100);
state.status = next_fix;
_new_position = true;
state.horizontal_accuracy = _buffer.pos.horizontal_accuracy * 1.0e-3f;
state.vertical_accuracy = _buffer.pos.vertical_accuracy * 1.0e-3f;
state.horizontal_accuracy = _buffer.pos.horizontal_accuracy * 1.0e-3f; // RMS
Copy link
Contributor

Choose a reason for hiding this comment

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

I thought I had seen an e-mail about this, but now I can't find the comment anywhere, but I don't see anything in the ERB sheet that indicates characterizing this as RMS is correct. (And I admit I hesitated before peaking at RTKlib :) a quick google search filed to yield an anwser)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I looked at the RTKLIB code and even patched it. It's RMS

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Take a look at emlid/RTKLIB#28

@amilcarlucas amilcarlucas force-pushed the pr-improve-GPS2_RAW-mavlink-message branch from b4e5556 to 7c7cfed Compare July 3, 2017 20:13
@amilcarlucas
Copy link
Contributor Author

I think I have addressed your comments.

@amilcarlucas amilcarlucas force-pushed the pr-improve-GPS2_RAW-mavlink-message branch from 7c7cfed to 93538d8 Compare July 3, 2017 20:27
@amilcarlucas
Copy link
Contributor Author

I think I have addressed all your comments, can this one go in ?

@amilcarlucas amilcarlucas force-pushed the pr-improve-GPS2_RAW-mavlink-message branch from 0e6fcd4 to fe82c2e Compare July 5, 2017 16:20
@amilcarlucas
Copy link
Contributor Author

I cleaned this one up, even more.

@amilcarlucas
Copy link
Contributor Author

@rrr6399 This is the first one that needs to go in. And it is IMHO the one that is less controversial.

@amilcarlucas amilcarlucas force-pushed the pr-improve-GPS2_RAW-mavlink-message branch from fe82c2e to 7af8de1 Compare July 11, 2017 19:42
@rrr6399
Copy link
Contributor

rrr6399 commented Jul 17, 2017

@WickedShell , I just wanted to say that @amilcarlucas improvements for RTK support are very important. There is currently no way of retrieving the calculated offsets from the rover to base without the GPS_RTK message (especially for the moving base problem). This message is important not only for better diagnostics but also for more accurate "follow me" mode navigation. Please merge these changes soon since the master branch is going through many large changes right now.

@@ -289,6 +289,7 @@ AP_GPS_SBP::_attempt_state_update()

last_full_update_tow = last_vel_ned.tow;
last_full_update_cpu_ms = now;
state.rtk_age_ms = last_full_update_cpu_ms - last_injected_data_ms;
Copy link
Contributor

Choose a reason for hiding this comment

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

Pending dropping this I'm fine with this.

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

@@ -289,6 +289,7 @@ AP_GPS_SBP::_attempt_state_update()

last_full_update_tow = last_vel_ned.tow;
last_full_update_cpu_ms = now;
state.rtk_age_ms = last_full_update_cpu_ms - last_injected_data_ms;
Copy link
Contributor Author

Choose a reason for hiding this comment

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

…es, and the age of the RTK correction messages
@amilcarlucas amilcarlucas force-pushed the pr-improve-GPS2_RAW-mavlink-message branch from 7af8de1 to c69dc1a Compare July 18, 2017 01:36
@rmackay9 rmackay9 merged commit b791fef into ArduPilot:master Jul 19, 2017
@amilcarlucas amilcarlucas deleted the pr-improve-GPS2_RAW-mavlink-message branch July 19, 2017 11:48
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants