Skip to content

Commit

Permalink
Correct HIGH_LATENCY2 message units
Browse files Browse the repository at this point in the history
  • Loading branch information
stephendade authored and meee1 committed Mar 2, 2025
1 parent a4c5a09 commit 84941d7
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions ExtLibs/ArduPilot/CurrentState.cs
Original file line number Diff line number Diff line change
Expand Up @@ -2441,7 +2441,7 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
alt = altasl - (float)HomeAlt;
alt_error = highlatency.target_altitude - alt;
targetalt = highlatency.target_altitude;
wp_dist = highlatency.target_distance;
wp_dist = highlatency.target_distance * 10;
wpno = highlatency.wp_num;

if (highlatency.failure_flags != 0)
Expand Down Expand Up @@ -2471,15 +2471,15 @@ private void Parent_OnPacketReceived(object sender, MAVLink.MAVLinkMessage mavLi
yaw = highlatency.heading * 2;
target_bearing = highlatency.target_heading * 2;
ch3percent = highlatency.throttle;
airspeed = highlatency.airspeed;
targetairspeed = highlatency.airspeed_sp;
groundspeed = highlatency.groundspeed;
airspeed = highlatency.airspeed / 5.0f;
targetairspeed = highlatency.airspeed_sp / 5.0f;
groundspeed = highlatency.groundspeed / 5.0f;
wind_vel = highlatency.windspeed / 5.0f;
wind_dir = highlatency.wind_heading * 2;
gpshdop = highlatency.eph;
// epv
airspeed1_temp = highlatency.temperature_air;
climbrate = highlatency.climb_rate;
climbrate = highlatency.climb_rate * 10;
battery_remaining = highlatency.battery;

}
Expand Down

0 comments on commit 84941d7

Please sign in to comment.