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

GPS accuracy wo approximations #1034

Merged
merged 3 commits into from
May 25, 2018
Merged

Conversation

pavloblindnology
Copy link

GPS accuracy published by mavros is now based on accuracies reported by FCU in GPS_RAW_INT message if using mavlink v2.0. Otherwise they are approximated by HDOP & VDOP values, scaled by GPS User Equivalent Range Error (UERE) measured in meters.
According to #1020.

fix->position_covariance[6 + 2] = std::pow(2 * hdop, 2);
// With FCU protocol v2.0 use accuracies reported by sensor
if (UAS_FCU(m_uas)->get_protocol_version() == mavconn::Protocol::V20 &&
raw_gps.h_acc > 0 && raw_gps.v_acc > 0) {
Copy link
Member

Choose a reason for hiding this comment

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

That is ok, but i think that bit faster: msg->magic == MAVLINK_STX.

  • MAVLINK_STX = 0xfd (v2.0)
  • MAVLINK_STX_MAVLINK1 = 0xfe (v1.0)

Copy link
Member

Choose a reason for hiding this comment

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

Also that check is not depend on link configuration, because it always can receive v1 and v2 msgs.

Copy link
Member

Choose a reason for hiding this comment

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

Hmm, perhaps it is good idea to add is_mavlink_v10 and is_mavlink_v20() inline helpers...
Will add that after merge.

raw_gps.h_acc > 0 && raw_gps.v_acc > 0) {
fix->position_covariance[0 + 0] = fix->position_covariance[3 + 1] = std::pow(raw_gps.h_acc / 1E3, 2);
fix->position_covariance[6 + 2] = std::pow(raw_gps.v_acc / 1E3, 2);
fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
Copy link
Member

Choose a reason for hiding this comment

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

About filling cov matrix, i'd like to see Eigen::Map here (ftf::EigenMapCovariance3d), old code done long before we start to use Eigen.

Copy link
Member

Choose a reason for hiding this comment

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

Pseudocode:

ftf::EigenMapCovariance3d cov(fix->position_covariance.data());

xy = pow(...);
cov.diagonal() << xy, xy, z;

@pavloblindnology
Copy link
Author

Updated according to review.

fix->position_covariance[6 + 2] = std::pow(2 * hdop, 2);
// With FCU protocol v2.0 use accuracies reported by sensor
if (UAS_FCU(m_uas)->get_protocol_version() == mavconn::Protocol::V20 &&
raw_gps.h_acc > 0 && raw_gps.v_acc > 0) {
Copy link
Member

Choose a reason for hiding this comment

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

Hmm, perhaps it is good idea to add is_mavlink_v10 and is_mavlink_v20() inline helpers...
Will add that after merge.

@vooon vooon merged commit 37dc5cb into mavlink:master May 25, 2018
@vooon vooon added this to the Version 0.26 milestone May 25, 2018
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants