AP_GPS_MAV: fix hdop conversion

This commit is contained in:
Randy Mackay 2016-10-18 20:24:33 +09:00
parent 227bd3d13c
commit e6e6e36da7
1 changed files with 2 additions and 2 deletions

View File

@ -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) {