mirror of https://github.com/ArduPilot/ardupilot
removed airspeed
This commit is contained in:
parent
d0af95f0e3
commit
b8c0bdb66f
|
@ -367,7 +367,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_vfr_hud_send(
|
mavlink_msg_vfr_hud_send(
|
||||||
chan,
|
chan,
|
||||||
(float)airspeed / 100.0,
|
(float)g_gps->ground_speed / 100.0,
|
||||||
(float)g_gps->ground_speed / 100.0,
|
(float)g_gps->ground_speed / 100.0,
|
||||||
(dcm.yaw_sensor / 100) % 360,
|
(dcm.yaw_sensor / 100) % 360,
|
||||||
g.rc_3.servo_out / 10,
|
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);
|
mavlink_msg_vfr_hud_decode(msg, &packet);
|
||||||
|
|
||||||
// set airspeed
|
// set airspeed
|
||||||
airspeed = 100 * packet.airspeed;
|
//airspeed = 100 * packet.airspeed;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#ifdef MAVLINK10
|
#ifdef MAVLINK10
|
||||||
|
|
Loading…
Reference in New Issue