Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

CurrenState :Use VFR_HUD for climbrate IF it is received. #3267

Merged
merged 1 commit into from
Jan 12, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 11 additions & 13 deletions ExtLibs/ArduPilot/CurrentState.cs
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,9 @@ public bool prearmstatus
/// </summary>
private double Wn_fgo;

//It is true when we got a VFR_HUD message, so it can be used to get climbrate, instead of calculating it from time and alt change.
private bool gotVFR = false;

static CurrentState()
{
// set default telemrates
Expand Down Expand Up @@ -313,7 +316,11 @@ public float alt

if ((datetime - lastalt).TotalSeconds >= 0.2 && oldalt != alt || lastalt > datetime)
{
climbrate = (alt - oldalt) / (float)(datetime - lastalt).TotalSeconds;
//Don't update climbrate if we got a VFR_HUD message, because it is more accurate
if (!gotVFR)
{
climbrate = (alt - oldalt) / (float)(datetime - lastalt).TotalSeconds;
}
verticalspeed = (alt - oldalt) / (float)(datetime - lastalt).TotalSeconds;
if (float.IsInfinity(_verticalspeed))
_verticalspeed = 0;
Expand Down Expand Up @@ -3498,25 +3505,16 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
var vfr = mavLinkMessage.ToStructure<MAVLink.mavlink_vfr_hud_t>();

groundspeed = vfr.groundspeed;

airspeed = vfr.airspeed;

//alt = vfr.alt; // this might include baro

ch3percent = vfr.throttle;

if (sensors_present.revthrottle && sensors_enabled.revthrottle && sensors_health.revthrottle)
if (ch3percent > 0)
ch3percent *= -1;

//Console.WriteLine(alt);

//climbrate = vfr.climb;

// heading = vfr.heading;


//MAVLink.packets[(byte)MAVLink.MSG_NAMES.VFR_HUD);
//This comes from the EKF, so it supposed to be correct
climbrate = vfr.climb;
gotVFR = true; // we have a vfr packet
}

break;
Expand Down
Loading