Skip to content

Commit 73dfa16

Browse files
committed
Use GLOBAL_POSITION_INT to set altitude and speeds in ArduPilot
1 parent d985bcc commit 73dfa16

File tree

2 files changed

+21
-28
lines changed

2 files changed

+21
-28
lines changed

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/drone/autopilot/apm/ArduPilot.java

+21-2
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
import com.MAVLink.ardupilotmega.msg_mount_configure;
1414
import com.MAVLink.ardupilotmega.msg_mount_status;
1515
import com.MAVLink.ardupilotmega.msg_radio;
16+
import com.MAVLink.common.msg_global_position_int;
1617
import com.MAVLink.common.msg_named_value_int;
1718
import com.MAVLink.common.msg_raw_imu;
1819
import com.MAVLink.common.msg_rc_channels_raw;
@@ -512,10 +513,28 @@ private void checkControlSensorsHealth(msg_sys_status sysStatus) {
512513
}
513514

514515
protected void processVfrHud(msg_vfr_hud vfrHud) {
515-
if (vfrHud == null)
516+
//Nothing to do. Copter 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)
516526
return;
517527

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);
519538
}
520539

521540
protected void processMountStatus(msg_mount_status mountStatus) {

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/drone/autopilot/apm/ArduPlane.java

-26
Original file line numberDiff line numberDiff line change
@@ -41,32 +41,6 @@ public FirmwareType getFirmwareType() {
4141
return FirmwareType.ARDU_PLANE;
4242
}
4343

44-
@Override
45-
protected void processVfrHud(msg_vfr_hud vfrHud){
46-
//Nothing to do. Plane used GLOBAL_POSITION_INT to set altitude and speeds unlike copter
47-
}
48-
49-
/**
50-
* Used to update the vehicle location, and altitude.
51-
* @param gpi
52-
*/
53-
@Override
54-
protected void processGlobalPositionInt(msg_global_position_int gpi){
55-
if(gpi == null)
56-
return;
57-
58-
super.processGlobalPositionInt(gpi);
59-
60-
final double relativeAlt = gpi.relative_alt / 1000.0;
61-
62-
final double groundSpeedX = gpi.vx / 100.0;
63-
final double groundSpeedY = gpi.vy / 100.0;
64-
final double groundSpeed = Math.sqrt(Math.pow(groundSpeedX, 2) + Math.pow(groundSpeedY, 2));
65-
66-
final double climbRate = gpi.vz / 100.0;
67-
setAltitudeGroundAndAirSpeeds(relativeAlt, groundSpeed, groundSpeed, climbRate);
68-
}
69-
7044
@Override
7145
protected boolean isFeatureSupported(String featureId){
7246
switch(featureId){

0 commit comments

Comments
 (0)