mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
GCS_Common: allow fallback vert rate in VFR_HUD
This commit is contained in:
parent
6eed40dec1
commit
467e62b967
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user