GCS_Common: allow fallback vert rate in VFR_HUD

This commit is contained in:
Bob Long 2023-10-30 20:46:38 -04:00 committed by Andrew Tridgell
parent 6eed40dec1
commit 467e62b967

View File

@ -3111,10 +3111,11 @@ float GCS_MAVLINK::vfr_hud_airspeed() const
float GCS_MAVLINK::vfr_hud_climbrate() const
{
Vector3f velned;
if (!AP::ahrs().get_velocity_NED(velned)) {
velned.zero();
if (AP::ahrs().get_velocity_NED(velned) ||
AP::ahrs().get_vert_pos_rate_D(velned.z)) {
return -velned.z;
}
return -velned.z;
return 0;
}
float GCS_MAVLINK::vfr_hud_alt() const