mavlink_messages: send EAS instead of IAS (#14858)

Send equivalent_airspeed_m_s instead of indicated_airspeed_m_s for HUD on groundstation.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer 2020-05-18 10:34:39 +02:00 committed by GitHub
parent e670d5f1e2
commit b5cc3c4ef5
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

View File

@ -1540,7 +1540,7 @@ protected:
_airspeed_validated_sub.copy(&airspeed_validated);
mavlink_vfr_hud_t msg{};
msg.airspeed = airspeed_validated.indicated_airspeed_m_s;
msg.airspeed = airspeed_validated.equivalent_airspeed_m_s;
msg.groundspeed = sqrtf(lpos.vx * lpos.vx + lpos.vy * lpos.vy);
msg.heading = math::degrees(wrap_2pi(lpos.yaw));