VFR_HUD should be indicated airspeed

This commit is contained in:
Daniel Agar 2015-12-10 10:27:46 -05:00 committed by Lorenz Meier
parent 7fcf2d9733
commit c0070a19a8
1 changed files with 1 additions and 1 deletions

View File

@ -920,7 +920,7 @@ protected:
if (updated) {
mavlink_vfr_hud_t msg;
msg.airspeed = airspeed.true_airspeed_m_s;
msg.airspeed = airspeed.indicated_airspeed_m_s;
msg.groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e);
msg.heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F;
msg.throttle = armed.armed ? act.control[3] * 100.0f : 0.0f;