|
13 | 13 | import com.MAVLink.ardupilotmega.msg_mount_configure;
|
14 | 14 | import com.MAVLink.ardupilotmega.msg_mount_status;
|
15 | 15 | import com.MAVLink.ardupilotmega.msg_radio;
|
| 16 | +import com.MAVLink.common.msg_global_position_int; |
16 | 17 | import com.MAVLink.common.msg_named_value_int;
|
17 | 18 | import com.MAVLink.common.msg_raw_imu;
|
18 | 19 | import com.MAVLink.common.msg_rc_channels_raw;
|
@@ -512,10 +513,28 @@ private void checkControlSensorsHealth(msg_sys_status sysStatus) {
|
512 | 513 | }
|
513 | 514 |
|
514 | 515 | protected void processVfrHud(msg_vfr_hud vfrHud) {
|
515 |
| - if (vfrHud == null) |
| 516 | + //Nothing to do. ArduPilot now use GLOBAL_POSITION_INT to set altitude and speeds |
| 517 | + } |
| 518 | + |
| 519 | + /** |
| 520 | + * Used to update the vehicle location, and altitude. |
| 521 | + * @param gpi |
| 522 | + */ |
| 523 | + @Override |
| 524 | + protected void processGlobalPositionInt(msg_global_position_int gpi) { |
| 525 | + if(gpi == null) |
516 | 526 | return;
|
517 | 527 |
|
518 |
| - setAltitudeGroundAndAirSpeeds(vfrHud.alt, vfrHud.groundspeed, vfrHud.airspeed, vfrHud.climb); |
| 528 | + super.processGlobalPositionInt(gpi); |
| 529 | + |
| 530 | + final double relativeAlt = gpi.relative_alt / 1000.0; |
| 531 | + |
| 532 | + final double groundSpeedX = gpi.vx / 100.0; |
| 533 | + final double groundSpeedY = gpi.vy / 100.0; |
| 534 | + final double groundSpeed = Math.sqrt(Math.pow(groundSpeedX, 2) + Math.pow(groundSpeedY, 2)); |
| 535 | + |
| 536 | + final double climbRate = gpi.vz / 100.0; |
| 537 | + setAltitudeGroundAndAirSpeeds(relativeAlt, groundSpeed, groundSpeed, climbRate); |
519 | 538 | }
|
520 | 539 |
|
521 | 540 | protected void processMountStatus(msg_mount_status mountStatus) {
|
|
0 commit comments