private void updateFlightModeButtons() { resetFlightModeButtons(); final Drone drone = getDrone(); final State droneState = drone.getAttribute(AttributeType.STATE); final VehicleMode flightMode = droneState.getVehicleMode(); if (flightMode != null) { switch (flightMode) { case PLANE_AUTO: autoBtn.setActivated(true); break; case PLANE_GUIDED: final GuidedState guidedState = drone.getAttribute(AttributeType.GUIDED_STATE); final FollowState followState = drone.getAttribute(AttributeType.FOLLOW_STATE); if (guidedState.isInitialized() && !followState.isEnabled()) { pauseBtn.setActivated(true); } break; case PLANE_RTL: homeBtn.setActivated(true); break; } } }
@Override public boolean isSlidingUpPanelEnabled(Drone drone) { final State droneState = drone.getAttribute(AttributeType.STATE); return droneState.isConnected() && droneState.isArmed() && droneState.isFlying(); }
@Override public void onClick(View v) { final Drone drone = getDrone(); HitBuilders.EventBuilder eventBuilder = new HitBuilders.EventBuilder().setCategory(GAUtils.Category.FLIGHT); switch (v.getId()) { case R.id.mc_connectBtn: ((SuperUI) getActivity()).toggleDroneConnection(); break; case R.id.mc_armBtn: getArmingConfirmation(); eventBuilder.setAction(ACTION_FLIGHT_ACTION_BUTTON).setLabel("Arm"); break; case R.id.mc_disarmBtn: getDrone().arm(false); eventBuilder.setAction(ACTION_FLIGHT_ACTION_BUTTON).setLabel("Disarm"); break; case R.id.mc_homeBtn: drone.changeVehicleMode(VehicleMode.PLANE_RTL); eventBuilder .setAction(ACTION_FLIGHT_ACTION_BUTTON) .setLabel(VehicleMode.PLANE_RTL.getLabel()); break; case R.id.mc_pause: { final FollowState followState = drone.getAttribute(AttributeType.FOLLOW_STATE); if (followState.isEnabled()) { drone.disableFollowMe(); } drone.pauseAtCurrentLocation(); eventBuilder.setAction(ACTION_FLIGHT_ACTION_BUTTON).setLabel("Pause"); break; } case R.id.mc_TakeoffInAutoBtn: case R.id.mc_autoBtn: drone.changeVehicleMode(VehicleMode.PLANE_AUTO); eventBuilder .setAction(ACTION_FLIGHT_ACTION_BUTTON) .setLabel(VehicleMode.PLANE_AUTO.getLabel()); break; case R.id.mc_follow: { toggleFollowMe(); break; } default: eventBuilder = null; break; } if (eventBuilder != null) { GAUtils.sendEvent(eventBuilder); } }
/** * Set a Relay pin’s voltage high or low * * @param drone target vehicle * @param relayNumber * @param enabled true for relay to be on, false for relay to be off. */ public static void setRelay(Drone drone, int relayNumber, boolean enabled) { Bundle params = new Bundle(2); params.putInt(EXTRA_RELAY_NUMBER, relayNumber); params.putBoolean(EXTRA_IS_RELAY_ON, enabled); drone.performAsyncAction(new Action(ACTION_SET_RELAY, params)); }
/** * This is an advanced/low-level method to send raw mavlink to the vehicle. * * <p>This method is included as an ‘escape hatch’ to allow developers to make progress if we’ve * somehow missed providing some essentential operation in the rest of this API. Callers do not * need to populate sysId/componentId/crc in the packet, this method will take care of that before * sending. * * <p>If you find yourself needing to use this mathod please contact the drone-platform google * group and we’ll see if we can support the operation you needed in some future revision of the * API. * * @param messageWrapper A MAVLinkMessage wrapper instance. No need to fill in sysId/compId/seqNum * - the API will take care of that. */ public static void sendMavlinkMessage(Drone drone, MavlinkMessageWrapper messageWrapper) { Bundle params = new Bundle(); params.putParcelable(EXTRA_MAVLINK_MESSAGE, messageWrapper); drone.performAsyncAction(new Action(ACTION_SEND_MAVLINK_MESSAGE, params)); }
public static void epmCommand(Drone drone, boolean release) { Bundle params = new Bundle(); params.putBoolean(EXTRA_EPM_RELEASE, release); Action epmAction = new Action(ACTION_EPM_COMMAND, params); drone.performAsyncAction(epmAction); }
public static void triggerCamera(Drone drone) { drone.performAsyncAction(new Action(ACTION_TRIGGER_CAMERA)); }