diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 20c2043c25..e30ea70b75 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -409,7 +409,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan) (float)airspeed / 100.0, (float)g_gps->ground_speed / 100.0, (dcm.yaw_sensor / 100) % 360, - (int)g.channel_throttle.servo_out, + (uint16_t)(100 * g.channel_throttle.norm_output()), current_loc.alt / 100.0, 0); }