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

Disable gps heading for UBX driver in RTK float fix type #104

Merged
merged 5 commits into from
Apr 19, 2022
Merged
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 12 additions & 0 deletions src/ubx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2036,8 +2036,15 @@ GPSDriverUBX::payloadRxDone()
float rel_length_acc = _buf.payload_rx_nav_relposned.accLength * 1e-2f;
bool heading_valid = _buf.payload_rx_nav_relposned.flags & (1 << 8);
bool rel_pos_valid = _buf.payload_rx_nav_relposned.flags & (1 << 2);
bool carrier_solution_fixed = _buf.payload_rx_nav_relposned.flags & (1 << 4);
(void)rel_length_acc;

// RTK float fix type is not accurate enough
Copy link
Member

Choose a reason for hiding this comment

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

Instead of depending on the fix_type being set I would directly check the carrier_solution_floating flag in NAV-RELPOSNED here.

See the carrier_solution_floating and carrier_solution_fixed handling below.

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've updated the code, please let me know if this is what you meant @dagar

Copy link
Member

Choose a reason for hiding this comment

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

I would roll carrier_solution_fixed right into the conditional below, but otherwise this looks good.

if (!carrier_solution_fixed)
{
heading_valid = false;
}

if (heading_valid && rel_pos_valid && rel_length < 1000.f) { // validity & sanity checks
heading *= M_PI_F / 180.0f; // deg to rad, now in range [0, 2pi]
heading -= _heading_offset; // range: [-pi, 3pi]
Expand Down Expand Up @@ -2097,6 +2104,11 @@ GPSDriverUBX::payloadRxDone()
gps_rel.heading_valid = _buf.payload_rx_nav_relposned.flags & (1 << 8);
gps_rel.relative_position_normalized = _buf.payload_rx_nav_relposned.flags & (1 << 9);

if (!gps_rel.carrier_solution_fixed)
Copy link
Member

Choose a reason for hiding this comment

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

I would drop this for now, at the moment we're just passing on the "heading_valid" flag as reported in NAV-RELPOSNED. For the heading field in sensor_gps we can have a higher standard.

{
gps_rel.heading_valid = false;
}

gotRelativePositionMessage(gps_rel);
}

Expand Down