Browse Source

AP_GPS_MAV: fix hdop conversion

mission-4.1.18
Randy Mackay 8 years ago
parent
commit
e6e6e36da7
  1. 4
      libraries/AP_GPS/AP_GPS_MAV.cpp

4
libraries/AP_GPS/AP_GPS_MAV.cpp

@ -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;
if (have_hdop) {
state.hdop = packet.hdop * 10; //In centimeters
state.hdop = packet.hdop * 100; // convert to centimeters
}
if (have_vdop) {
state.vdop = packet.vdop * 10; //In centimeters
state.vdop = packet.vdop * 100; // convert to centimeters
}
if (have_vel_h) {

Loading…
Cancel
Save