removed airspeed

This commit is contained in:
Jason Short 2012-01-03 10:28:46 -08:00
parent d0af95f0e3
commit b8c0bdb66f
1 changed files with 2 additions and 2 deletions

View File

@ -367,7 +367,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
{
mavlink_msg_vfr_hud_send(
chan,
(float)airspeed / 100.0,
(float)g_gps->ground_speed / 100.0,
(float)g_gps->ground_speed / 100.0,
(dcm.yaw_sensor / 100) % 360,
g.rc_3.servo_out / 10,
@ -1766,7 +1766,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_msg_vfr_hud_decode(msg, &packet);
// set airspeed
airspeed = 100 * packet.airspeed;
//airspeed = 100 * packet.airspeed;
break;
}
#ifdef MAVLINK10