|
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;
|
@@ -416,10 +417,6 @@ public void onMavLinkMessageReceived(MAVLinkMessage message) {
|
416 | 417 | processStatusText(msg_statustext);
|
417 | 418 | break;
|
418 | 419 |
|
419 |
| - case msg_vfr_hud.MAVLINK_MSG_ID_VFR_HUD: |
420 |
| - processVfrHud((msg_vfr_hud) message); |
421 |
| - break; |
422 |
| - |
423 | 420 | case msg_raw_imu.MAVLINK_MSG_ID_RAW_IMU:
|
424 | 421 | msg_raw_imu msg_imu = (msg_raw_imu) message;
|
425 | 422 | mag.newData(msg_imu);
|
@@ -511,11 +508,25 @@ private void checkControlSensorsHealth(msg_sys_status sysStatus) {
|
511 | 508 | }
|
512 | 509 | }
|
513 | 510 |
|
514 |
| - protected void processVfrHud(msg_vfr_hud vfrHud) { |
515 |
| - if (vfrHud == null) |
| 511 | + /** |
| 512 | + * Used to update the vehicle location, and altitude. |
| 513 | + * @param gpi |
| 514 | + */ |
| 515 | + @Override |
| 516 | + protected void processGlobalPositionInt(msg_global_position_int gpi) { |
| 517 | + if(gpi == null) |
516 | 518 | return;
|
517 | 519 |
|
518 |
| - setAltitudeGroundAndAirSpeeds(vfrHud.alt, vfrHud.groundspeed, vfrHud.airspeed, vfrHud.climb); |
| 520 | + super.processGlobalPositionInt(gpi); |
| 521 | + |
| 522 | + final double relativeAlt = gpi.relative_alt / 1000.0; |
| 523 | + |
| 524 | + final double groundSpeedX = gpi.vx / 100.0; |
| 525 | + final double groundSpeedY = gpi.vy / 100.0; |
| 526 | + final double groundSpeed = Math.sqrt(Math.pow(groundSpeedX, 2) + Math.pow(groundSpeedY, 2)); |
| 527 | + |
| 528 | + final double climbRate = gpi.vz / 100.0; |
| 529 | + setAltitudeGroundAndAirSpeeds(relativeAlt, groundSpeed, groundSpeed, climbRate); |
519 | 530 | }
|
520 | 531 |
|
521 | 532 | protected void processMountStatus(msg_mount_status mountStatus) {
|
|
0 commit comments