GPS: MAV driver fix for GPS_INPUT altitude

This commit is contained in:
Randy Mackay 2016-12-08 09:36:41 +09:00
parent 4efbc29490
commit 8118222946
1 changed files with 1 additions and 1 deletions

View File

@ -65,7 +65,7 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
loc.lat = packet.lat;
loc.lng = packet.lon;
if (have_alt) {
loc.alt = packet.alt;
loc.alt = packet.alt * 100; // convert to centimeters
}
state.location = loc;
state.location.options = 0;