Skip to content
Snippets Groups Projects
Commit e6e6e36d authored by Randy Mackay's avatar Randy Mackay
Browse files

AP_GPS_MAV: fix hdop conversion

parent 227bd3d1
No related branches found
No related tags found
No related merge requests found
...@@ -69,11 +69,11 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg) ...@@ -69,11 +69,11 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
state.location.options = 0; state.location.options = 0;
if (have_hdop) { if (have_hdop) {
state.hdop = packet.hdop * 10; //In centimeters state.hdop = packet.hdop * 100; // convert to centimeters
} }
if (have_vdop) { if (have_vdop) {
state.vdop = packet.vdop * 10; //In centimeters state.vdop = packet.vdop * 100; // convert to centimeters
} }
if (have_vel_h) { if (have_vel_h) {
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment