Browse Source

Update AP_ADSB.cpp

AP_ADSB: fixed GPS.alt reporting  cm to mm conversion bug

Issue 5424
master
Tom Pittenger 8 years ago committed by GitHub
parent
commit
372837b959
  1. 2
      libraries/AP_ADSB/AP_ADSB.cpp

2
libraries/AP_ADSB/AP_ADSB.cpp

@ -469,7 +469,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan) @@ -469,7 +469,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
int32_t latitude = _my_loc.lat;
int32_t longitude = _my_loc.lng;
int32_t altGNSS = _my_loc.alt*0.1f; // convert cm to mm
int32_t altGNSS = _my_loc.alt * 10; // convert cm to mm
int16_t velVert = gps_velocity.z * 1E2; // convert m/s to cm/s
int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s
int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s

Loading…
Cancel
Save