diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 0c5d2b84a9c8f2ba3b8257d31aec235cb31e5948..099b02ca25bbfa7476e9a6fdd402d670b76ea313 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -954,6 +954,7 @@ void Vehicle::_handleVfrHud(mavlink_message_t& message) _airSpeedFact.setRawValue(qIsNaN(vfrHud.airspeed) ? 0 : vfrHud.airspeed); _groundSpeedFact.setRawValue(qIsNaN(vfrHud.groundspeed) ? 0 : vfrHud.groundspeed); _climbRateFact.setRawValue(qIsNaN(vfrHud.climb) ? 0 : vfrHud.climb); + _throttlePctFact.setRawValue(vfrHud.throttle); } void Vehicle::_handleEstimatorStatus(mavlink_message_t& message)