Skip to content

Commit 522290c

Browse files
committed
Merge pull request #172 from squilter/add_emergency_disarm
add magic number for emergency disarm
2 parents ffe53b1 + 5507d0d commit 522290c

File tree

7 files changed

+26
-5
lines changed

7 files changed

+26
-5
lines changed

ClientLib/libs/Mavlink.jar

0 Bytes
Binary file not shown.

ClientLib/src/main/java/com/o3dr/android/client/apis/drone/DroneStateApi.java

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import static com.o3dr.services.android.lib.drone.action.StateActions.ACTION_ARM;
1010
import static com.o3dr.services.android.lib.drone.action.StateActions.ACTION_SET_VEHICLE_MODE;
1111
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_ARM;
12+
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_EMERGENCY_DISARM;
1213
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_VEHICLE_MODE;
1314

1415
/**
@@ -22,8 +23,20 @@ public class DroneStateApi {
2223
* @param arm true to arm, false to disarm.
2324
*/
2425
public static void arm(Drone drone, boolean arm) {
26+
arm(drone, arm, false);
27+
}
28+
29+
/**
30+
* Arm or disarm the connected drone.
31+
*
32+
* @param arm true to arm, false to disarm.
33+
* @param emergencyDisarm true to skip landing check and disarm immediately,
34+
* false to disarm only if it is safe to do so.
35+
*/
36+
public static void arm(Drone drone, boolean arm, boolean emergencyDisarm) {
2537
Bundle params = new Bundle();
2638
params.putBoolean(EXTRA_ARM, arm);
39+
params.putBoolean(EXTRA_EMERGENCY_DISARM, emergencyDisarm);
2740
drone.performAsyncAction(new Action(ACTION_ARM, params));
2841
}
2942

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/action/StateActions.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ public class StateActions {
99

1010
public static final String ACTION_ARM = Utils.PACKAGE_NAME + ".action.ARM";
1111
public static final String EXTRA_ARM = "extra_arm";
12+
public static final String EXTRA_EMERGENCY_DISARM = "extra_emergency_disarm";
1213

1314
public static final String ACTION_SET_VEHICLE_MODE = Utils.PACKAGE_NAME + ".action.SET_VEHICLE_MODE";
1415
public static final String EXTRA_VEHICLE_MODE = "extra_vehicle_mode";

ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -403,7 +403,8 @@ public void performAction(Action action) throws RemoteException {
403403
//DRONE STATE ACTIONS
404404
case StateActions.ACTION_ARM:
405405
boolean doArm = data.getBoolean(StateActions.EXTRA_ARM);
406-
DroneApiUtils.arm(getDrone(), doArm);
406+
boolean emergencyDisarm = data.getBoolean(StateActions.EXTRA_EMERGENCY_DISARM);
407+
DroneApiUtils.arm(getDrone(), doArm, emergencyDisarm);
407408
break;
408409

409410
case StateActions.ACTION_SET_VEHICLE_MODE:

ServiceApp/src/org/droidplanner/services/android/api/DroneApiUtils.java

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -671,9 +671,13 @@ static float generateDronie(Drone drone) {
671671
}
672672

673673
static void arm(Drone drone, boolean arm) {
674+
arm(drone, arm, false);
675+
}
676+
677+
static void arm(Drone drone, boolean arm, boolean emergencyDisarm) {
674678
if (drone == null)
675679
return;
676-
MavLinkArm.sendArmMessage(drone, arm);
680+
MavLinkArm.sendArmMessage(drone, arm, emergencyDisarm);
677681
}
678682

679683
static void startMagnetometerCalibration(Drone drone, boolean retryOnFailure, boolean saveAutomatically, int

ServiceApp/test/java/org/droidplanner/services/android/BasicTest.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,7 @@ public void testPreconditions() {
119119
*/
120120
@Test
121121
public void testArm() {
122-
MavLinkArm.sendArmMessage(drone, true);
122+
MavLinkArm.sendArmMessage(drone, true, false);
123123
MAVLinkPacket data = mavlinkApi.getData();
124124
Assert.assertTrue(data != null);
125125

dependencyLibs/Core/src/org/droidplanner/core/MAVLink/MavLinkArm.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,14 +7,16 @@
77

88
public class MavLinkArm {
99

10-
public static void sendArmMessage(Drone drone, boolean arm) {
10+
public static final int EMERGENCY_DISARM_MAGIC_NUMBER = 21196;
11+
12+
public static void sendArmMessage(Drone drone, boolean arm, boolean emergencyDisarm) {
1113
msg_command_long msg = new msg_command_long();
1214
msg.target_system = drone.getSysid();
1315
msg.target_component = drone.getCompid();
1416

1517
msg.command = MAV_CMD.MAV_CMD_COMPONENT_ARM_DISARM;
1618
msg.param1 = arm ? 1 : 0;
17-
msg.param2 = 0;
19+
msg.param2 = emergencyDisarm ? EMERGENCY_DISARM_MAGIC_NUMBER : 0;
1820
msg.param3 = 0;
1921
msg.param4 = 0;
2022
msg.param5 = 0;

0 commit comments

Comments
 (0)