MAVLink: added climb rate reporting

This commit is contained in:
Andrew Tridgell 2012-07-05 11:11:07 +10:00
parent f03ba86d9d
commit 0385932afb

View File

@ -349,7 +349,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
(ahrs.yaw_sensor / 100) % 360, (ahrs.yaw_sensor / 100) % 360,
(uint16_t)(100 * (g.channel_throttle.norm_output() / 2.0 + 0.5)), // scale -1,1 to 0-100 (uint16_t)(100 * (g.channel_throttle.norm_output() / 2.0 + 0.5)), // scale -1,1 to 0-100
current_loc.alt / 100.0, current_loc.alt / 100.0,
0); barometer.get_climb_rate());
} }
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE