Browse Source

Plane: send ahrs groundspeed estimate instead of GPS groundspeed in VFR_HUD message

master
floaledm 8 years ago committed by Andrew Tridgell
parent
commit
b2a6b93d30
  1. 2
      ArduPlane/GCS_Mavlink.cpp

2
ArduPlane/GCS_Mavlink.cpp

@ -238,7 +238,7 @@ void Plane::send_vfr_hud(mavlink_channel_t chan) @@ -238,7 +238,7 @@ void Plane::send_vfr_hud(mavlink_channel_t chan)
mavlink_msg_vfr_hud_send(
chan,
aspeed,
gps.ground_speed(),
ahrs.groundspeed(),
(ahrs.yaw_sensor / 100) % 360,
abs(throttle_percentage()),
current_loc.alt / 100.0f,

Loading…
Cancel
Save