Browse Source

Rover: Fixing issue 327 - reporting Baro alt instead of GPS

master
Grant Morphett 10 years ago committed by Andrew Tridgell
parent
commit
90b48fe46a
  1. 2
      APMrover2/GCS_Mavlink.cpp

2
APMrover2/GCS_Mavlink.cpp

@ -215,7 +215,7 @@ void Rover::send_location(mavlink_channel_t chan) @@ -215,7 +215,7 @@ void Rover::send_location(mavlink_channel_t chan)
fix_time,
current_loc.lat, // in 1E7 degrees
current_loc.lng, // in 1E7 degrees
gps.location().alt * 10UL, // millimeters above sea level
current_loc.alt * 10UL, // millimeters above sea level
(current_loc.alt - home.alt) * 10, // millimeters above ground
vel.x * 100, // X speed cm/s (+ve North)
vel.y * 100, // Y speed cm/s (+ve East)

Loading…
Cancel
Save