From 0385932afbeafc55f0098f79e91004b4d5a26075 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 5 Jul 2012 11:11:07 +1000 Subject: [PATCH] MAVLink: added climb rate reporting --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 1c3a5cb5b9..71539f050a 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -349,7 +349,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan) (ahrs.yaw_sensor / 100) % 360, (uint16_t)(100 * (g.channel_throttle.norm_output() / 2.0 + 0.5)), // scale -1,1 to 0-100 current_loc.alt / 100.0, - 0); + barometer.get_climb_rate()); } #if HIL_MODE != HIL_MODE_ATTITUDE