Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import com.MAVLink.common.msg_heartbeat;
import com.MAVLink.common.msg_mission_current;
import com.MAVLink.common.msg_mission_item;
import com.MAVLink.common.msg_named_value_int;
import com.MAVLink.common.msg_nav_controller_output;
import com.MAVLink.common.msg_radio_status;
import com.MAVLink.common.msg_raw_imu;
Expand All @@ -26,6 +27,7 @@
import com.MAVLink.common.msg_sys_status;
import com.MAVLink.common.msg_vfr_hud;
import com.MAVLink.enums.MAV_MODE_FLAG;
import com.MAVLink.enums.MAV_SEVERITY;
import com.MAVLink.enums.MAV_STATE;
import com.MAVLink.enums.MAV_SYS_STATUS_SENSOR;

Expand All @@ -37,9 +39,6 @@
*/
public class MavLinkMsgHandler {

private static final byte SEVERITY_HIGH = 3;
private static final byte SEVERITY_CRITICAL = 4;

private Drone drone;

public MavLinkMsgHandler(Drone drone) {
Expand Down Expand Up @@ -147,6 +146,10 @@ public void receiveData(MAVLinkMessage msg) {
drone.getCamera().updateMountOrientation(((msg_mount_status) msg));
break;

case msg_named_value_int.MAVLINK_MSG_ID_NAMED_VALUE_INT:
processNamedValueInt((msg_named_value_int) msg);
break;

//*************** GoPro messages handling **************//
case msg_gopro_heartbeat.MAVLINK_MSG_ID_GOPRO_HEARTBEAT:
drone.getGoProImpl().onHeartBeat((msg_gopro_heartbeat) msg);
Expand Down Expand Up @@ -183,6 +186,24 @@ public void receiveData(MAVLinkMessage msg) {
}
}

private void processNamedValueInt(msg_named_value_int message){
if(message == null)
return;

switch (message.getName()) {
case "ARMMASK":
//Give information about the vehicle's ability to arm successfully.
final ApmModes vehicleMode = drone.getState().getMode();
if (ApmModes.isCopter(vehicleMode.getType())) {
final int value = message.value;
final boolean isReadyToArm = (value & (1 << vehicleMode.getNumber())) != 0;
final String armReadinessMsg = isReadyToArm ? "READY TO ARM" : "UNREADY FOR ARMING";
drone.logMessage(MAV_SEVERITY.MAV_SEVERITY_NOTICE, armReadinessMsg);
}
break;
}
}

private void checkIfFlying(msg_heartbeat msg_heart) {
final byte systemStatus = msg_heart.system_status;
final boolean wasFlying = drone.getState().isFlying();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,9 @@ private void initialize() {
}

private void disable() {
if(state == GuidedStates.UNINITIALIZED)
return;

state = GuidedStates.UNINITIALIZED;
myDrone.notifyDroneEvent(DroneEventsType.GUIDEDPOINT);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
import com.MAVLink.enums.EKF_STATUS_FLAGS;

public class State extends DroneVariable {
private static final long ERROR_ON_SCREEN_TIMEOUT = 5000;
private static final long ERROR_TIMEOUT = 5000l;

private final AutopilotWarningParser warningParser;

Expand Down Expand Up @@ -85,7 +85,7 @@ public boolean parseAutopilotError(String errorMsg){
}

watchdog.removeCallbacks(watchdogCallback);
this.watchdog.postDelayed(watchdogCallback, ERROR_ON_SCREEN_TIMEOUT);
this.watchdog.postDelayed(watchdogCallback, ERROR_TIMEOUT);
return true;
}

Expand All @@ -94,7 +94,7 @@ public void repeatWarning(){
return;

watchdog.removeCallbacks(watchdogCallback);
this.watchdog.postDelayed(watchdogCallback, ERROR_ON_SCREEN_TIMEOUT);
this.watchdog.postDelayed(watchdogCallback, ERROR_TIMEOUT);
}

public void setArmed(boolean newState) {
Expand Down