mirror of https://github.com/ArduPilot/ardupilot
GPS: MAV driver fix for GPS_INPUT altitude
This commit is contained in:
parent
4efbc29490
commit
8118222946
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue