forked from Archive/PX4-Autopilot
VFR_HUD should be indicated airspeed
This commit is contained in:
parent
7fcf2d9733
commit
c0070a19a8
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue