diff --git a/ClientLib/build.gradle b/ClientLib/build.gradle index 21792232eb..29f05a67a3 100644 --- a/ClientLib/build.gradle +++ b/ClientLib/build.gradle @@ -1,15 +1,19 @@ apply plugin: 'com.android.library' ext { + VERSION_MAJOR = 2 + VERSION_MINOR = 5 + VERSION_PATCH = 21 + VERSION_BUILD = 0 + PUBLISH_ARTIFACT_ID = 'dronekit-android' - PUBLISH_VERSION = '2.5.15' + PUBLISH_VERSION = generateVersionName("", VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH) + PUBLISH_VERSION_CODE = computeVersionCode(VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH, VERSION_BUILD) PROJECT_DESCRIPTION = "Android DroneKit client library." PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android', 'DroneKit'] PROJECT_LICENSES = ['Apache-2.0'] } -/* Every time something is changed in the client library the versionCode and - PUBLISH_VERSION must be incremented. - */ + android { compileSdkVersion Integer.parseInt(project.ANDROID_BUILD_SDK_VERSION) buildToolsVersion project.ANDROID_BUILD_TOOLS_VERSION @@ -17,7 +21,7 @@ android { defaultConfig { minSdkVersion Integer.parseInt(project.ANDROID_BUILD_MIN_SDK_VERSION) targetSdkVersion Integer.parseInt(project.ANDROID_BUILD_TARGET_SDK_VERSION) - versionCode 20515 + versionCode PUBLISH_VERSION_CODE versionName PUBLISH_VERSION } diff --git a/ClientLib/src/main/java/com/o3dr/android/client/Drone.java b/ClientLib/src/main/java/com/o3dr/android/client/Drone.java index 0690137a2e..bf3012987c 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/Drone.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/Drone.java @@ -19,6 +19,7 @@ import com.o3dr.services.android.lib.drone.attribute.AttributeEvent; import com.o3dr.services.android.lib.drone.attribute.AttributeType; import com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationStatus; +import com.o3dr.services.android.lib.drone.companion.solo.SoloAttributes; import com.o3dr.services.android.lib.drone.connection.ConnectionParameter; import com.o3dr.services.android.lib.drone.connection.ConnectionResult; import com.o3dr.services.android.lib.drone.mission.Mission; @@ -358,8 +359,8 @@ private T getAttributeDefaultValue(String attributeType) return (T) new MagnetometerCalibrationStatus(); case AttributeType.CAMERA: - case AttributeType.SOLOLINK_STATE: - case AttributeType.SOLOLINK_GOPRO_STATE: + case SoloAttributes.SOLO_STATE: + case SoloAttributes.SOLO_GOPRO_STATE: default: return null; } diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/Api.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/Api.java index 1ab605e02b..f1851abd66 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/Api.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/Api.java @@ -1,12 +1,39 @@ package com.o3dr.android.client.apis; +import com.o3dr.android.client.Drone; + +import java.util.concurrent.ConcurrentHashMap; + /** * Common interface for the drone set of api classes. * Created by Fredia Huya-Kouadio on 7/5/15. */ -interface Api { +public abstract class Api { + + protected interface Builder { + T build(Drone drone); + } + + /** + * Retrieves the api instance bound to the given Drone object. + * @param drone Drone object + * @param apiCache Used to retrieve the api instance if it exists, or store it if it doesn't exist. + * @param apiBuilder Api instance generator. + * @param Specific api instance type. + * @return The matching Api instance. + */ + protected static T getApi(Drone drone, ConcurrentHashMap apiCache, Api.Builder apiBuilder){ + if(drone == null || apiCache == null) + return null; + + T apiInstance = apiCache.get(drone); + if(apiInstance == null && apiBuilder != null){ + apiInstance = apiBuilder.build(drone); + final T previousInstance = apiCache.putIfAbsent(drone, apiInstance); + if(previousInstance != null) + apiInstance = previousInstance; + } - interface Builder { - T build(); + return apiInstance; } } diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/ApiUtils.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/ApiUtils.java deleted file mode 100644 index 6b5f7c008e..0000000000 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/ApiUtils.java +++ /dev/null @@ -1,36 +0,0 @@ -package com.o3dr.android.client.apis; - -import com.o3dr.android.client.Drone; - -import java.util.concurrent.ConcurrentHashMap; - -/** - * Provides utility methods for api access and use. - * Created by Fredia Huya-Kouadio on 7/5/15. - */ -class ApiUtils { - - /** - * Retrieves the api instance bound to the given Drone object. - * @param drone Drone object - * @param apiCache Used to retrieve the api instance if it exists, or store it if it doesn't exist. - * @param apiBuilder Api instance generator. - * @param Specific api instance type. - * @return The matching Api instance. - */ - static T getApi(Drone drone, ConcurrentHashMap apiCache, Api.Builder apiBuilder){ - if(drone == null || apiCache == null) - return null; - - T apiInstance = apiCache.get(drone); - if(apiInstance == null && apiBuilder != null){ - apiInstance = apiBuilder.build(); - final T previousInstance = apiCache.putIfAbsent(drone, apiInstance); - if(previousInstance != null) - apiInstance = previousInstance; - } - - return apiInstance; - } - -} diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/CalibrationApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/CalibrationApi.java index 5a71ad24f9..80dca6618f 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/CalibrationApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/CalibrationApi.java @@ -22,9 +22,15 @@ * Provides access to the calibration specific functionality. * Created by Fredia Huya-Kouadio on 1/19/15. */ -public class CalibrationApi implements Api { +public class CalibrationApi extends Api { private static final ConcurrentHashMap calibrationApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public CalibrationApi build(Drone drone) { + return new CalibrationApi(drone); + } + }; /** * Retrieves a CalibrationApi instance. @@ -33,12 +39,7 @@ public class CalibrationApi implements Api { * @return a CalibrationApi instance. */ public static CalibrationApi getApi(final Drone drone) { - return ApiUtils.getApi(drone, calibrationApiCache, new Api.Builder() { - @Override - public CalibrationApi build() { - return new CalibrationApi(drone); - } - }); + return getApi(drone, calibrationApiCache, apiBuilder); } private final Drone drone; diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/CapabilityApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/CapabilityApi.java index 61e17af182..218886e412 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/CapabilityApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/CapabilityApi.java @@ -16,7 +16,7 @@ * Allows to query the capabilities offered by the vehicle. * Created by Fredia Huya-Kouadio on 7/5/15. */ -public class CapabilityApi implements Api { +public class CapabilityApi extends Api { /** * Feature support check error. The drone is disconnected. @@ -34,6 +34,12 @@ public class CapabilityApi implements Api { public static final int FEATURE_UNSUPPORTED = 1; private static final ConcurrentHashMap capabilityApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public CapabilityApi build(Drone drone) { + return new CapabilityApi(drone); + } + }; /** * Retrieves a capability api instance. @@ -41,12 +47,7 @@ public class CapabilityApi implements Api { * @return a CapabilityApi instance. */ public static CapabilityApi getApi(final Drone drone){ - return ApiUtils.getApi(drone, capabilityApiCache, new Builder() { - @Override - public CapabilityApi build() { - return new CapabilityApi(drone); - } - }); + return getApi(drone, capabilityApiCache, apiBuilder); } private final Drone drone; @@ -84,7 +85,7 @@ public void run() { }); break; - case FeatureIds.SOLOLINK_VIDEO_STREAMING: + case FeatureIds.SOLO_VIDEO_STREAMING: if(Build.VERSION.SDK_INT < Build.VERSION_CODES.JELLY_BEAN_MR2) { drone.post(new Runnable() { @Override @@ -137,7 +138,7 @@ public static final class FeatureIds { /** * Id for the video feature. */ - public static final String SOLOLINK_VIDEO_STREAMING = "feature_sololink_video_streaming"; + public static final String SOLO_VIDEO_STREAMING = "feature_solo_video_streaming"; /** * Id for the compass calibration feature. diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/ExperimentalApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/ExperimentalApi.java index 916a2a6100..2714b118ae 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/ExperimentalApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/ExperimentalApi.java @@ -26,9 +26,15 @@ /** * Contains drone commands with no defined interaction model yet. */ -public class ExperimentalApi implements Api { +public class ExperimentalApi extends Api { private static final ConcurrentHashMap experimentalApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public ExperimentalApi build(Drone drone) { + return new ExperimentalApi(drone); + } + }; /** * Retrieves an ExperimentalApi instance. @@ -37,12 +43,7 @@ public class ExperimentalApi implements Api { * @return a ExperimentalApi instance. */ public static ExperimentalApi getApi(final Drone drone) { - return ApiUtils.getApi(drone, experimentalApiCache, new Builder() { - @Override - public ExperimentalApi build() { - return new ExperimentalApi(drone); - } - }); + return getApi(drone, experimentalApiCache, apiBuilder); } private final Drone drone; diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/FollowApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/FollowApi.java index 68e52a9c14..8513d18fb2 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/FollowApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/FollowApi.java @@ -17,9 +17,15 @@ * Provides access to the Follow me api. * Created by Fredia Huya-Kouadio on 1/19/15. */ -public class FollowApi implements Api { +public class FollowApi extends Api { private static final ConcurrentHashMap followApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public FollowApi build(Drone drone) { + return new FollowApi(drone); + } + }; /** * Retrieves a FollowApi instance. @@ -28,12 +34,7 @@ public class FollowApi implements Api { * @return a FollowApi instance. */ public static FollowApi getApi(final Drone drone) { - return ApiUtils.getApi(drone, followApiCache, new Builder() { - @Override - public FollowApi build() { - return new FollowApi(drone); - } - }); + return getApi(drone, followApiCache, apiBuilder); } private final Drone drone; diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/GimbalApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/GimbalApi.java index 634f4b54e9..392a9beeaf 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/GimbalApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/GimbalApi.java @@ -19,17 +19,18 @@ import static com.o3dr.services.android.lib.drone.action.GimbalActions.*; -public final class GimbalApi implements Api, DroneListener { +public final class GimbalApi extends Api implements DroneListener { private static final ConcurrentHashMap gimbalApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public GimbalApi build(Drone drone) { + return new GimbalApi(drone); + } + }; public static GimbalApi getApi(final Drone drone){ - return ApiUtils.getApi(drone, gimbalApiCache, new Builder() { - @Override - public GimbalApi build() { - return new GimbalApi(drone); - } - }); + return getApi(drone, gimbalApiCache, apiBuilder); } public interface GimbalOrientationListener { diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/MissionApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/MissionApi.java index b7a46003d0..d714e5b5fc 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/MissionApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/MissionApi.java @@ -17,22 +17,23 @@ * Provides access to missions specific functionality. * Created by Fredia Huya-Kouadio on 1/19/15. */ -public class MissionApi implements Api { +public class MissionApi extends Api { private static final ConcurrentHashMap missionApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public MissionApi build(Drone drone) { + return new MissionApi(drone); + } + }; /** * Retrieves a MissionApi instance. * @param drone Target vehicle * @return a MissionApi instance. */ - public static MissionApi getApi(final Drone drone){ - return ApiUtils.getApi(drone, missionApiCache, new Builder() { - @Override - public MissionApi build() { - return new MissionApi(drone); - } - }); + public static MissionApi getApi(final Drone drone) { + return getApi(drone, missionApiCache, apiBuilder); } private final Drone drone; diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/VehicleApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/VehicleApi.java index 99c4a46375..e0f6a5f454 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/VehicleApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/VehicleApi.java @@ -35,22 +35,23 @@ /** * Provides access to the vehicle specific functionality. */ -public class VehicleApi implements Api { +public class VehicleApi extends Api { private static final ConcurrentHashMap vehicleApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public VehicleApi build(Drone drone) { + return new VehicleApi(drone); + } + }; /** * Retrieves a vehicle api instance. * @param drone target vehicle * @return a VehicleApi instance. */ - public static VehicleApi getApi(final Drone drone){ - return ApiUtils.getApi(drone, vehicleApiCache, new Builder() { - @Override - public VehicleApi build() { - return new VehicleApi(drone); - } - }); + public static VehicleApi getApi(final Drone drone) { + return getApi(drone, vehicleApiCache, apiBuilder); } private final Drone drone; diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloApi.java new file mode 100644 index 0000000000..8dd2d0c0ec --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloApi.java @@ -0,0 +1,35 @@ +package com.o3dr.android.client.apis.solo; + +import android.os.Bundle; + +import com.o3dr.android.client.Drone; +import com.o3dr.android.client.apis.Api; +import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket; +import com.o3dr.services.android.lib.model.AbstractCommandListener; +import com.o3dr.services.android.lib.model.action.Action; + +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloActions.ACTION_SEND_MESSAGE; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloActions.EXTRA_MESSAGE_DATA; + +/** + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public abstract class SoloApi extends Api { + + protected final Drone drone; + + protected SoloApi(Drone drone){ + this.drone = drone; + } + + /** + * Sends a message to the solo vehicle. + * @param messagePacket TLV message data. + * @param listener Register a callback to receive update of the command execution status. + */ + protected void sendMessage(TLVPacket messagePacket, AbstractCommandListener listener){ + Bundle params = new Bundle(); + params.putParcelable(EXTRA_MESSAGE_DATA, messagePacket); + drone.performAsyncActionOnDroneThread(new Action(ACTION_SEND_MESSAGE, params), listener); + } +} diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/SoloLinkApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloCameraApi.java similarity index 65% rename from ClientLib/src/main/java/com/o3dr/android/client/apis/SoloLinkApi.java rename to ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloCameraApi.java index ef362aa86f..c3e0a6c54f 100644 --- a/ClientLib/src/main/java/com/o3dr/android/client/apis/SoloLinkApi.java +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloCameraApi.java @@ -1,115 +1,60 @@ -package com.o3dr.android.client.apis; +package com.o3dr.android.client.apis.solo; import android.os.Bundle; import android.view.Surface; import com.o3dr.android.client.Drone; +import com.o3dr.android.client.apis.CapabilityApi; import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError; -import com.o3dr.services.android.lib.drone.companion.solo.SoloControllerMode; -import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloGoproRecord; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloGoproSetRequest; -import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket; import com.o3dr.services.android.lib.model.AbstractCommandListener; import com.o3dr.services.android.lib.model.action.Action; import java.util.concurrent.ConcurrentHashMap; -import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloLinkActions.*; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloCameraActions.ACTION_START_VIDEO_STREAM; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloCameraActions.ACTION_STOP_VIDEO_STREAM; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloCameraActions.EXTRA_VIDEO_DISPLAY; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloCameraActions.EXTRA_VIDEO_TAG; /** - * Provides access to the sololink specific functionality + * Provides access to the solo video specific functionality * Created by Fredia Huya-Kouadio on 7/12/15. */ -public class SoloLinkApi implements Api { +public class SoloCameraApi extends SoloApi { - private static final ConcurrentHashMap soloLinkApiCache = new ConcurrentHashMap<>(); + private static final ConcurrentHashMap soloCameraApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public SoloCameraApi build(Drone drone) { + return new SoloCameraApi(drone); + } + }; /** * Retrieves a sololink api instance. + * * @param drone target vehicle - * @return a SoloLinkApi instance. + * @return a SoloCameraApi instance. */ - public static SoloLinkApi getApi(final Drone drone){ - return ApiUtils.getApi(drone, soloLinkApiCache, new Builder() { - @Override - public SoloLinkApi build() { - return new SoloLinkApi(drone); - } - }); + public static SoloCameraApi getApi(final Drone drone) { + return getApi(drone, soloCameraApiCache, apiBuilder); } - private final Drone drone; private final CapabilityApi capabilityChecker; - private SoloLinkApi(Drone drone){ - this.drone = drone; + private SoloCameraApi(Drone drone) { + super(drone); this.capabilityChecker = CapabilityApi.getApi(drone); } - /** - * Updates the wifi settings for the solo vehicle. - * @param wifiSsid Updated wifi ssid - * @param wifiPassword Updated wifi password - * @param listener Register a callback to receive update of the command execution status. - */ - public void updateWifiSettings(String wifiSsid, String wifiPassword, AbstractCommandListener listener){ - Bundle params = new Bundle(); - params.putString(EXTRA_WIFI_SSID, wifiSsid); - params.putString(EXTRA_WIFI_PASSWORD, wifiPassword); - drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_WIFI_SETTINGS, params), listener); - } - - /** - * Updates the button settings for the solo vehicle. - * @param buttonSettings Updated button settings. - * @param listener Register a callback to receive update of the command execution status. - */ - public void updateButtonSettings(SoloButtonSettingSetter buttonSettings, AbstractCommandListener listener){ - Bundle params = new Bundle(); - params.putParcelable(EXTRA_BUTTON_SETTINGS, buttonSettings); - drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_BUTTON_SETTINGS, params), listener); - } - - /** - * Sends a message to the solo vehicle. - * @param messagePacket TLV message data. - * @param listener Register a callback to receive update of the command execution status. - */ - public void sendMessage(TLVPacket messagePacket, AbstractCommandListener listener){ - Bundle params = new Bundle(); - params.putParcelable(EXTRA_MESSAGE_DATA, messagePacket); - drone.performAsyncActionOnDroneThread(new Action(ACTION_SEND_MESSAGE, params), listener); - } - - /** - * Updates the controller mode (joystick mapping) - * - * @param controllerMode Controller mode. @see {@link SoloControllerMode} - * @param listener Register a callback to receive update of the command execution status. - */ - public void updateControllerMode(@SoloControllerMode.ControllerMode int controllerMode, AbstractCommandListener listener){ - Bundle params = new Bundle(); - params.putInt(EXTRA_CONTROLLER_MODE, controllerMode); - drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_CONTROLLER_MODE, params), listener); - } - - /** - * Updates the EU tx power compliance. - * @param isCompliant true for the controller to be made compliant, false otherwise. - * @param listener Register a callback to receive update of the command execution status. - */ - public void updateEUTxPowerCompliance(boolean isCompliant, AbstractCommandListener listener) { - Bundle params = new Bundle(); - params.putBoolean(EXTRA_EU_TX_POWER_COMPLIANT, isCompliant); - drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_EU_TX_POWER_COMPLIANCE, params), listener); - } - /** * Take a photo with the connected gopro. + * * @param listener Register a callback to receive update of the command execution status. */ - public void takePhoto(final AbstractCommandListener listener){ + public void takePhoto(final AbstractCommandListener listener) { //Set the gopro to photo mode final SoloGoproSetRequest photoModeRequest = new SoloGoproSetRequest(SoloGoproSetRequest.CAPTURE_MODE, SoloGoproSetRequest.CAPTURE_MODE_PHOTO); @@ -140,29 +85,32 @@ public void onTimeout() { /** * Toggle video recording on the connected gopro. + * * @param listener Register a callback to receive update of the command execution status. */ - public void toggleVideoRecording(final AbstractCommandListener listener){ + public void toggleVideoRecording(final AbstractCommandListener listener) { sendVideoRecordingCommand(SoloGoproRecord.TOGGLE_RECORDING, listener); } /** * Starts video recording on the connected gopro. + * * @param listener Register a callback to receive update of the command execution status. */ - public void startVideoRecording(final AbstractCommandListener listener){ + public void startVideoRecording(final AbstractCommandListener listener) { sendVideoRecordingCommand(SoloGoproRecord.START_RECORDING, listener); } /** * Stops video recording on the connected gopro. + * * @param listener Register a callback to receive update of the command execution status. */ - public void stopVideoRecording(final AbstractCommandListener listener){ + public void stopVideoRecording(final AbstractCommandListener listener) { sendVideoRecordingCommand(SoloGoproRecord.STOP_RECORDING, listener); } - private void sendVideoRecordingCommand(@SoloGoproRecord.RecordCommand final int recordCommand, final AbstractCommandListener listener){ + private void sendVideoRecordingCommand(@SoloGoproRecord.RecordCommand final int recordCommand, final AbstractCommandListener listener) { //Set the gopro to video mode final SoloGoproSetRequest videoModeRequest = new SoloGoproSetRequest(SoloGoproSetRequest.CAPTURE_MODE, SoloGoproSetRequest.CAPTURE_MODE_VIDEO); @@ -194,12 +142,13 @@ public void onTimeout() { /** * Attempt to grab ownership and start the video stream from the connected drone. Can fail if * the video stream is already owned by another client. - * @param surface Surface object onto which the video is decoded. - * @param tag Video tag. + * + * @param surface Surface object onto which the video is decoded. + * @param tag Video tag. * @param listener Register a callback to receive update of the command execution status. */ - public void startVideoStream(final Surface surface, final String tag, final AbstractCommandListener listener){ - capabilityChecker.checkFeatureSupport(CapabilityApi.FeatureIds.SOLOLINK_VIDEO_STREAMING, + public void startVideoStream(final Surface surface, final String tag, final AbstractCommandListener listener) { + capabilityChecker.checkFeatureSupport(CapabilityApi.FeatureIds.SOLO_VIDEO_STREAMING, new CapabilityApi.FeatureSupportListener() { @Override public void onFeatureSupportResult(String featureId, int result, Bundle resultInfo) { @@ -232,32 +181,35 @@ public void onFeatureSupportResult(String featureId, int result, Bundle resultIn /** * Attempt to grab ownership and start the video stream from the connected drone. Can fail if * the video stream is already owned by another client. - * @param surface Surface object onto which the video is decoded. + * + * @param surface Surface object onto which the video is decoded. * @param listener Register a callback to receive update of the command execution status. */ - public void startVideoStream(final Surface surface, final AbstractCommandListener listener){ + public void startVideoStream(final Surface surface, final AbstractCommandListener listener) { startVideoStream(surface, "", listener); } /** * Stop the video stream from the connected drone, and release ownership. + * * @param listener Register a callback to receive update of the command execution status. */ - public void stopVideoStream(final AbstractCommandListener listener){ + public void stopVideoStream(final AbstractCommandListener listener) { stopVideoStream("", listener); } /** * Stop the video stream from the connected drone, and release ownership. - * @param tag Video tag. + * + * @param tag Video tag. * @param listener Register a callback to receive update of the command execution status. */ - public void stopVideoStream(final String tag, final AbstractCommandListener listener){ - capabilityChecker.checkFeatureSupport(CapabilityApi.FeatureIds.SOLOLINK_VIDEO_STREAMING, + public void stopVideoStream(final String tag, final AbstractCommandListener listener) { + capabilityChecker.checkFeatureSupport(CapabilityApi.FeatureIds.SOLO_VIDEO_STREAMING, new CapabilityApi.FeatureSupportListener() { @Override public void onFeatureSupportResult(String featureId, int result, Bundle resultInfo) { - switch(result){ + switch (result) { case CapabilityApi.FEATURE_SUPPORTED: final Bundle params = new Bundle(); diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloConfigApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloConfigApi.java new file mode 100644 index 0000000000..fe32857b89 --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloConfigApi.java @@ -0,0 +1,99 @@ +package com.o3dr.android.client.apis.solo; + +import android.os.Bundle; + +import com.o3dr.android.client.Drone; +import com.o3dr.services.android.lib.drone.companion.solo.controller.SoloControllerMode; +import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter; +import com.o3dr.services.android.lib.model.AbstractCommandListener; +import com.o3dr.services.android.lib.model.action.Action; + +import java.util.concurrent.ConcurrentHashMap; + +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.ACTION_UPDATE_BUTTON_SETTINGS; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.ACTION_UPDATE_CONTROLLER_MODE; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.ACTION_UPDATE_EU_TX_POWER_COMPLIANCE; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.ACTION_UPDATE_WIFI_SETTINGS; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.EXTRA_BUTTON_SETTINGS; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.EXTRA_CONTROLLER_MODE; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.EXTRA_EU_TX_POWER_COMPLIANT; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.EXTRA_WIFI_PASSWORD; +import static com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions.EXTRA_WIFI_SSID; + +/** + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloConfigApi extends SoloApi { + + private static final ConcurrentHashMap soloConfigApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public SoloConfigApi build(Drone drone) { + return new SoloConfigApi(drone); + } + }; + + /** + * Retrieves a sololink api instance. + * + * @param drone target vehicle + * @return a SoloLinkApi instance. + */ + public static SoloConfigApi getApi(final Drone drone) { + return getApi(drone, soloConfigApiCache, apiBuilder); + } + + protected SoloConfigApi(Drone drone) { + super(drone); + } + + /** + * Updates the wifi settings for the solo vehicle. + * + * @param wifiSsid Updated wifi ssid + * @param wifiPassword Updated wifi password + * @param listener Register a callback to receive update of the command execution status. + */ + public void updateWifiSettings(String wifiSsid, String wifiPassword, AbstractCommandListener listener) { + Bundle params = new Bundle(); + params.putString(EXTRA_WIFI_SSID, wifiSsid); + params.putString(EXTRA_WIFI_PASSWORD, wifiPassword); + drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_WIFI_SETTINGS, params), listener); + } + + /** + * Updates the button settings for the solo vehicle. + * + * @param buttonSettings Updated button settings. + * @param listener Register a callback to receive update of the command execution status. + */ + public void updateButtonSettings(SoloButtonSettingSetter buttonSettings, AbstractCommandListener listener) { + Bundle params = new Bundle(); + params.putParcelable(EXTRA_BUTTON_SETTINGS, buttonSettings); + drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_BUTTON_SETTINGS, params), listener); + } + + /** + * Updates the controller mode (joystick mapping) + * + * @param controllerMode Controller mode. @see {@link SoloControllerMode} + * @param listener Register a callback to receive update of the command execution status. + */ + public void updateControllerMode(@SoloControllerMode.ControllerMode int controllerMode, AbstractCommandListener listener) { + Bundle params = new Bundle(); + params.putInt(EXTRA_CONTROLLER_MODE, controllerMode); + drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_CONTROLLER_MODE, params), listener); + } + + /** + * Updates the EU tx power compliance. + * + * @param isCompliant true for the controller to be made compliant, false otherwise. + * @param listener Register a callback to receive update of the command execution status. + */ + public void updateEUTxPowerCompliance(boolean isCompliant, AbstractCommandListener listener) { + Bundle params = new Bundle(); + params.putBoolean(EXTRA_EU_TX_POWER_COMPLIANT, isCompliant); + drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_EU_TX_POWER_COMPLIANCE, params), listener); + } +} diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloMessageApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloMessageApi.java new file mode 100644 index 0000000000..c9ad2187b0 --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloMessageApi.java @@ -0,0 +1,34 @@ +package com.o3dr.android.client.apis.solo; + +import com.o3dr.android.client.Drone; +import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket; +import com.o3dr.services.android.lib.model.AbstractCommandListener; + +import java.util.concurrent.ConcurrentHashMap; + +/** + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloMessageApi extends SoloApi { + + private static final ConcurrentHashMap apiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public SoloMessageApi build(Drone drone) { + return new SoloMessageApi(drone); + } + }; + + public static SoloMessageApi getApi(final Drone drone){ + return getApi(drone, apiCache, apiBuilder); + } + + protected SoloMessageApi(Drone drone) { + super(drone); + } + + @Override + public void sendMessage(TLVPacket messagePacket, AbstractCommandListener listener){ + super.sendMessage(messagePacket, listener); + } +} diff --git a/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloShotsApi.java b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloShotsApi.java new file mode 100644 index 0000000000..ea9000a181 --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/android/client/apis/solo/SoloShotsApi.java @@ -0,0 +1,28 @@ +package com.o3dr.android.client.apis.solo; + +import com.o3dr.android.client.Drone; + +import java.util.concurrent.ConcurrentHashMap; + +/** + * //TODO: Complete solo shot api. Made invisible to api users until then. + * Created by Fredia Huya-Kouadio on 7/31/15. + */ + class SoloShotsApi extends SoloApi { + + private static final ConcurrentHashMap soloShotsApiCache = new ConcurrentHashMap<>(); + private static final Builder apiBuilder = new Builder() { + @Override + public SoloShotsApi build(Drone drone) { + return new SoloShotsApi(drone); + } + }; + + public static SoloShotsApi getApi(final Drone drone){ + return getApi(drone, soloShotsApiCache, apiBuilder); + } + + protected SoloShotsApi(Drone drone) { + super(drone); + } +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEvent.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEvent.java index 66d0ff183e..05407304a2 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEvent.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEvent.java @@ -5,6 +5,10 @@ */ public class AttributeEvent { + //Private to prevent instantiation + private AttributeEvent() { + } + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.attribute.event"; /** @@ -14,6 +18,7 @@ public class AttributeEvent { /** * Signals an autopilot error. + * * @see {@link com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra#EXTRA_AUTOPILOT_ERROR_ID} */ public static final String AUTOPILOT_ERROR = PACKAGE_NAME + ".AUTOPILOT_ERROR"; @@ -32,12 +37,14 @@ public class AttributeEvent { /** * Signals completion of the magnetometer calibration. + * * @see {@link AttributeEventExtra#EXTRA_CALIBRATION_MAG_RESULT} */ public static final String CALIBRATION_MAG_COMPLETED = PACKAGE_NAME + ".CALIBRATION_MAG_COMPLETED"; /** * Provides progress updates for the magnetometer calibration. + * * @see {@link AttributeEventExtra#EXTRA_CALIBRATION_MAG_PROGRESS} */ public static final String CALIBRATION_MAG_PROGRESS = PACKAGE_NAME + ".CALIBRATION_MAG_PROGRESS"; @@ -64,8 +71,7 @@ public class AttributeEvent { * Mission attribute events. */ public static final String MISSION_UPDATED = PACKAGE_NAME + ".MISSION_UPDATED"; - public static final String MISSION_DRONIE_CREATED = PACKAGE_NAME + "" + - ".MISSION_DRONIE_CREATED"; + public static final String MISSION_DRONIE_CREATED = PACKAGE_NAME + ".MISSION_DRONIE_CREATED"; public static final String MISSION_SENT = PACKAGE_NAME + ".MISSION_SENT"; public static final String MISSION_RECEIVED = PACKAGE_NAME + ".MISSION_RECEIVED"; public static final String MISSION_ITEM_UPDATED = PACKAGE_NAME + ".MISSION_ITEM_UPDATED"; @@ -77,6 +83,7 @@ public class AttributeEvent { /** * Event to signal the start of parameters refresh from the vehicle. + * * @see {@link com.o3dr.services.android.lib.drone.property.Parameters} * @see {@link com.o3dr.services.android.lib.drone.property.Parameter} */ @@ -84,6 +91,7 @@ public class AttributeEvent { /** * Event to signal the completion of the parameters refresh from the vehicle. + * * @see {@link com.o3dr.services.android.lib.drone.property.Parameters} * @see {@link com.o3dr.services.android.lib.drone.property.Parameter} */ @@ -93,6 +101,7 @@ public class AttributeEvent { * Event to signal receipt of a single parameter from the vehicle. During a parameters refresh, this event will * fire as many times as the count of the set of parameters being refreshed. * Allows listeners to keep track of the parameters refresh progress. + * * @see {@link AttributeEventExtra#EXTRA_PARAMETER_INDEX} * @see {@link AttributeEventExtra#EXTRA_PARAMETERS_COUNT} * @see {@link AttributeEventExtra#EXTRA_PARAMETER_NAME} @@ -174,43 +183,9 @@ public class AttributeEvent { */ public static final String ALTITUDE_UPDATED = PACKAGE_NAME + ".ALTITUDE_UPDATED"; - /** - * Broadcasts updates to the GoPro state. - * @see {@link com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloGoproState} - */ - public static final String SOLOLINK_GOPRO_STATE_UPDATED = PACKAGE_NAME + ".GOPRO_STATE_UPDATED"; - - /** - * Signals update to the sololink wifi settings - * @see {@link com.o3dr.services.android.lib.drone.companion.solo.SoloLinkState} - */ - public static final String SOLOLINK_WIFI_SETTINGS_UPDATED = PACKAGE_NAME + ".SOLOLINK_WIFI_SETTINGS_UPDATED"; - - /** - * Signals update to the sololink button settings - * @see {@link com.o3dr.services.android.lib.drone.companion.solo.SoloLinkState} - */ - public static final String SOLOLINK_BUTTON_SETTINGS_UPDATED = PACKAGE_NAME + ".SOLOLINK_BUTTON_SETTINGS_UPDATED"; - - /** - * Triggers every time a button event occurs. - * @see {@link AttributeEventExtra#EXTRA_SOLOLINK_BUTTON_EVENT} - */ - public static final String SOLOLINK_BUTTON_EVENT = PACKAGE_NAME + ".SOLOLINK_BUTTON_EVENT"; - - /** - * Triggers upon receipt of a sololink message. - * @see {@link AttributeEventExtra#EXTRA_SOLOLINK_MESSAGE_DATA} - */ - public static final String SOLOLINK_MESSAGE_RECEIVED = PACKAGE_NAME + ".SOLOLINK_MESSAGE_RECEIVED"; - - /** - * Triggers upon updates to the EU tx power compliance. - */ - public static final String SOLOLINK_EU_TX_POWER_COMPLIANCE_UPDATED = PACKAGE_NAME + ".SOLOLINK_EU_TX_POWER_COMPLIANCE_UPDATED"; - /** * Signals the gimbal orientation was updated. + * * @see {@link AttributeEventExtra#EXTRA_GIMBAL_ORIENTATION_PITCH} * @see {@link AttributeEventExtra#EXTRA_GIMBAL_ORIENTATION_ROLL} * @see {@link AttributeEventExtra#EXTRA_GIMBAL_ORIENTATION_YAW} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEventExtra.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEventExtra.java index d01cdbaf90..ab6261fafb 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEventExtra.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEventExtra.java @@ -5,10 +5,15 @@ */ public class AttributeEventExtra { + //Private to prevent instantiation + private AttributeEventExtra() { + } + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.attribute.event.extra"; /** * Used to access autopilot error type. + * * @see {@link com.o3dr.services.android.lib.drone.attribute.error.ErrorType} * @see {@link com.o3dr.services.android.lib.drone.attribute.AttributeEvent#AUTOPILOT_ERROR} */ @@ -16,6 +21,7 @@ public class AttributeEventExtra { /** * Used to access autopilot messages. + * * @see {@link com.o3dr.services.android.lib.drone.attribute.AttributeEvent#AUTOPILOT_MESSAGE} */ public static final String EXTRA_AUTOPILOT_MESSAGE = PACKAGE_NAME + ".AUTOPILOT_MESSAGE"; @@ -29,12 +35,14 @@ public class AttributeEventExtra { /** * Used to access the magnetometer calibration progress. + * * @see {@link com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationProgress} */ public static final String EXTRA_CALIBRATION_MAG_PROGRESS = PACKAGE_NAME + ".CALIBRATION_MAG_PROGRESS"; /** * Used to access the result from the magnetometer calibration. + * * @see {@link com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationResult} */ public static final String EXTRA_CALIBRATION_MAG_RESULT = PACKAGE_NAME + ".CALIBRATION_MAG_RESULT"; @@ -51,64 +59,55 @@ public class AttributeEventExtra { public static final String EXTRA_MISSION_LAST_REACHED_WAYPOINT = PACKAGE_NAME + "" + ".MISSION_REACHED_WAYPOINT"; - public static final String EXTRA_MISSION_DRONIE_BEARING = PACKAGE_NAME + "" + - ".MISSION_DRONIE_BEARING"; + public static final String EXTRA_MISSION_DRONIE_BEARING = PACKAGE_NAME + ".MISSION_DRONIE_BEARING"; /** * Used to retrieve the count of the set of parameters being refreshed. + * * @see {@link AttributeEvent#PARAMETER_RECEIVED} */ public static final String EXTRA_PARAMETERS_COUNT = PACKAGE_NAME + ".PARAMETERS_COUNT"; /** * Used to retrieve the index of the received parameter. + * * @see {@link AttributeEvent#PARAMETER_RECEIVED} */ public static final String EXTRA_PARAMETER_INDEX = PACKAGE_NAME + ".PARAMETER_INDEX"; /** * Used to retrieve the name of the received parameter. + * * @see {@link AttributeEvent#PARAMETER_RECEIVED} */ public static final String EXTRA_PARAMETER_NAME = PACKAGE_NAME + ".PARAMETER_NAME"; /** * Used to retrieve the value of the received parameter. + * * @see {@link AttributeEvent#PARAMETER_RECEIVED} */ public static final String EXTRA_PARAMETER_VALUE = PACKAGE_NAME + ".PARAMETER_VALUE"; - /** - * Used to retrieve the {@link com.o3dr.services.android.lib.drone.companion.solo.button.ButtonPacket} object describing the button event. - */ - public static final String EXTRA_SOLOLINK_BUTTON_EVENT = PACKAGE_NAME + ".EXTRA_SOLOLINK_BUTTON_EVENT"; - - /** - * Used to retrieve the received sololink message data in bytes. - */ - public static final String EXTRA_SOLOLINK_MESSAGE_DATA = PACKAGE_NAME + ".EXTRA_SOLOLINK_MESSAGE_DATA"; - /** * Used to retrieve the gimbal pitch angle in degree. + * * @see {@link AttributeEvent#GIMBAL_ORIENTATION_UPDATED} */ public static final String EXTRA_GIMBAL_ORIENTATION_PITCH = PACKAGE_NAME + ".EXTRA_GIMBAL_ORIENTATION_PITCH"; /** * Used to retrieve the gimbal roll angle in degree. + * * @see {@link AttributeEvent#GIMBAL_ORIENTATION_UPDATED} */ public static final String EXTRA_GIMBAL_ORIENTATION_ROLL = PACKAGE_NAME + ".EXTRA_GIMBAL_ORIENTATION_ROLL"; /** * Used to retrieve the gimbal yaw angle in degree. + * * @see {@link AttributeEvent#GIMBAL_ORIENTATION_UPDATED} */ public static final String EXTRA_GIMBAL_ORIENTATION_YAW = PACKAGE_NAME + ".EXTRA_GIMBAL_ORIENTATION_YAW"; - /** - * Used to retrieve the boolean value specifying whether the controller is compliant with the EU tx power levels. - * @see {@link AttributeEvent#SOLOLINK_EU_TX_POWER_COMPLIANCE_UPDATED} - */ - public static final String EXTRA_SOLOLINK_EU_TX_POWER_COMPLIANT = PACKAGE_NAME + ".EXTRA_SOLOLINK_EU_TX_POWER_COMPLIANT"; } diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeType.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeType.java index bd3c809892..35bd297c36 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeType.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeType.java @@ -7,6 +7,9 @@ public class AttributeType { private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.attribute"; + //Private to prevent instantiation + private AttributeType(){} + /** * Used to access the vehicle's altitude state. * @see {@link com.o3dr.services.android.lib.drone.property.Altitude} @@ -98,13 +101,4 @@ public class AttributeType { */ public static final String MAGNETOMETER_CALIBRATION_STATUS = PACKAGE_NAME + ".MAGNETOMETER_CALIBRATION_STATUS"; - /** - * Used to access the sololink state. - */ - public static final String SOLOLINK_STATE = PACKAGE_NAME + ".SOLOLINK_STATE"; - - /** - * Used to access the sololink gopro state. - */ - public static final String SOLOLINK_GOPRO_STATE = PACKAGE_NAME + ".SOLOLINK_GOPRO_STATE"; } diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloAttributes.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloAttributes.java new file mode 100644 index 0000000000..433c342450 --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloAttributes.java @@ -0,0 +1,23 @@ +package com.o3dr.services.android.lib.drone.companion.solo; + +/** + * Stores the set of solo attribute types. + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloAttributes { + + //Private to prevent instantiation + private SoloAttributes(){} + + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.drone.companion.solo.attribute"; + + /** + * Used to access the sololink state. + */ + public static final String SOLO_STATE = PACKAGE_NAME + ".SOLO_STATE"; + + /** + * Used to access the sololink gopro state. + */ + public static final String SOLO_GOPRO_STATE = PACKAGE_NAME + ".SOLO_GOPRO_STATE"; +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloEventExtras.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloEventExtras.java new file mode 100644 index 0000000000..f503a04d86 --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloEventExtras.java @@ -0,0 +1,29 @@ +package com.o3dr.services.android.lib.drone.companion.solo; + +import com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra; + +/** + * Holds handles used to retrieve additional information broadcast along a drone event. + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloEventExtras { + + //Private to prevent instantiation + private SoloEventExtras(){} + + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.drone.companion.solo.event.extra"; + + /** + * Used to retrieve the {@link com.o3dr.services.android.lib.drone.companion.solo.button.ButtonPacket} object describing the button event. + */ + public static final String EXTRA_SOLO_BUTTON_EVENT = PACKAGE_NAME + ".EXTRA_SOLO_BUTTON_EVENT"; + /** + * Used to retrieve the received sololink message data in bytes. + */ + public static final String EXTRA_SOLO_MESSAGE_DATA = PACKAGE_NAME + ".EXTRA_SOLO_MESSAGE_DATA"; + /** + * Used to retrieve the boolean value specifying whether the controller is compliant with the EU tx power levels. + * @see {@link SoloEvents#SOLO_EU_TX_POWER_COMPLIANCE_UPDATED} + */ + public static final String EXTRA_SOLO_EU_TX_POWER_COMPLIANT = PACKAGE_NAME + ".EXTRA_SOLO_EU_TX_POWER_COMPLIANT"; +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloEvents.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloEvents.java new file mode 100644 index 0000000000..c26e9cd6ee --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloEvents.java @@ -0,0 +1,49 @@ +package com.o3dr.services.android.lib.drone.companion.solo; + +/** + * Stores all possible drone events. + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloEvents { + + //Private to prevent instantiation + private SoloEvents() { + } + + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.drone.companion.solo.event"; + + /** + * Broadcasts updates to the GoPro state. + * + * @see {@link com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloGoproState} + */ + public static final String SOLO_GOPRO_STATE_UPDATED = PACKAGE_NAME + ".GOPRO_STATE_UPDATED"; + /** + * Signals update to the sololink wifi settings + * + * @see {@link SoloState} + */ + public static final String SOLO_WIFI_SETTINGS_UPDATED = PACKAGE_NAME + ".SOLO_WIFI_SETTINGS_UPDATED"; + /** + * Signals update to the sololink button settings + * + * @see {@link SoloState} + */ + public static final String SOLO_BUTTON_SETTINGS_UPDATED = PACKAGE_NAME + ".SOLO_BUTTON_SETTINGS_UPDATED"; + /** + * Triggers every time a button event occurs. + * + * @see {@link SoloEventExtras#EXTRA_SOLO_BUTTON_EVENT} + */ + public static final String SOLO_BUTTON_EVENT_RECEIVED = PACKAGE_NAME + ".SOLO_BUTTON_EVENT_RECEIVED"; + /** + * Triggers upon receipt of a sololink message. + * + * @see {@link SoloEventExtras#EXTRA_SOLO_MESSAGE_DATA} + */ + public static final String SOLO_MESSAGE_RECEIVED = PACKAGE_NAME + ".SOLO_MESSAGE_RECEIVED"; + /** + * Triggers upon updates to the EU tx power compliance. + */ + public static final String SOLO_EU_TX_POWER_COMPLIANCE_UPDATED = PACKAGE_NAME + ".SOLO_EU_TX_POWER_COMPLIANCE_UPDATED"; +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloLinkState.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloState.java similarity index 60% rename from ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloLinkState.java rename to ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloState.java index 5c03c326ab..7908c52f64 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloLinkState.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloState.java @@ -1,18 +1,19 @@ package com.o3dr.services.android.lib.drone.companion.solo; import android.os.Parcel; -import android.os.Parcelable; import android.util.SparseArray; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSetting; import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVMessageParser; import com.o3dr.services.android.lib.drone.property.DroneAttribute; +import java.nio.ByteBuffer; + /** * Stores state information for the sololink companion computer. * Created by Fredia Huya-Kouadio on 7/10/15. */ -public class SoloLinkState implements DroneAttribute { +public class SoloState implements DroneAttribute { private String wifiSsid; private String wifiPassword; @@ -27,12 +28,12 @@ public class SoloLinkState implements DroneAttribute { private SparseArray buttonSettings; - public SoloLinkState(){} + public SoloState(){} - public SoloLinkState(String autopilotVersion, String controllerFirmwareVersion, - String controllerVersion, String vehicleVersion, - String wifiPassword, String wifiSsid, boolean isEUTxPowerCompliant, - SparseArray buttonSettings) { + public SoloState(String autopilotVersion, String controllerFirmwareVersion, + String controllerVersion, String vehicleVersion, + String wifiPassword, String wifiSsid, boolean isEUTxPowerCompliant, + SparseArray buttonSettings) { this.autopilotVersion = autopilotVersion; this.controllerFirmwareVersion = controllerFirmwareVersion; this.controllerVersion = controllerVersion; @@ -89,10 +90,24 @@ public void writeToParcel(Parcel dest, int flags) { dest.writeString(this.vehicleVersion); dest.writeString(this.autopilotVersion); dest.writeByte(isEUTxPowerCompliant ? (byte) 1 : (byte) 0); - dest.writeSparseArray((SparseArray) this.buttonSettings); + + final int buttonCount = buttonSettings.size(); + dest.writeInt(buttonCount); + + for(int i = 0; i < buttonCount; i++){ + final SoloButtonSetting buttonSetting = buttonSettings.valueAt(i); + if(buttonSetting == null){ + dest.writeInt(0); + continue; + } + + final byte[] buttonData = buttonSetting.toBytes(); + dest.writeInt(buttonData.length); + dest.writeByteArray(buttonData); + } } - protected SoloLinkState(Parcel in) { + protected SoloState(Parcel in) { this.wifiSsid = in.readString(); this.wifiPassword = in.readString(); this.controllerVersion = in.readString(); @@ -100,16 +115,30 @@ protected SoloLinkState(Parcel in) { this.vehicleVersion = in.readString(); this.autopilotVersion = in.readString(); this.isEUTxPowerCompliant = in.readByte() != 0; - this.buttonSettings = in.readSparseArray(SparseArray.class.getClassLoader()); + + final int buttonCount = in.readInt(); + + this.buttonSettings = new SparseArray<>(buttonCount); + for(int i = 0; i < buttonCount; i++){ + final int dataSize = in.readInt(); + if(dataSize == 0) + continue; + + final ByteBuffer dataBuffer = ByteBuffer.allocate(dataSize); + in.readByteArray(dataBuffer.array()); + + final SoloButtonSetting button = (SoloButtonSetting) TLVMessageParser.parseTLVPacket(dataBuffer); + buttonSettings.put(button.getButton(), button); + } } - public static final Creator CREATOR = new Creator() { - public SoloLinkState createFromParcel(Parcel source) { - return new SoloLinkState(source); + public static final Creator CREATOR = new Creator() { + public SoloState createFromParcel(Parcel source) { + return new SoloState(source); } - public SoloLinkState[] newArray(int size) { - return new SoloLinkState[size]; + public SoloState[] newArray(int size) { + return new SoloState[size]; } }; } diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloActions.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloActions.java new file mode 100644 index 0000000000..c6b436665e --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloActions.java @@ -0,0 +1,25 @@ +package com.o3dr.services.android.lib.drone.companion.solo.action; + +import com.o3dr.services.android.lib.util.Utils; + +/** + * Created by Fredia Huya-Kouadio on 7/10/15. + */ +public class SoloActions { + + //Private to prevent instantiation + private SoloActions() { + } + + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.drone.companion.solo.action"; + + public static final String ACTION_SEND_MESSAGE = PACKAGE_NAME + ".SEND_MESSAGE"; + + /** + * TLV message object to send to the sololink companion computer. + * + * @see {@link com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket} + */ + public static final String EXTRA_MESSAGE_DATA = "extra_message_data"; + +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloCameraActions.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloCameraActions.java new file mode 100644 index 0000000000..e2281dce30 --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloCameraActions.java @@ -0,0 +1,19 @@ +package com.o3dr.services.android.lib.drone.companion.solo.action; + +/** + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloCameraActions { + + //Private to prevent instantiation + private SoloCameraActions() { + } + + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.drone.companion.solo.action.camera"; + + public static final String ACTION_START_VIDEO_STREAM = PACKAGE_NAME + ".START_VIDEO_STREAM"; + public static final String EXTRA_VIDEO_DISPLAY = "extra_video_display"; + public static final String EXTRA_VIDEO_TAG = "extra_video_tag"; + + public static final String ACTION_STOP_VIDEO_STREAM = PACKAGE_NAME + ".STOP_VIDEO_STREAM"; +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloConfigActions.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloConfigActions.java new file mode 100644 index 0000000000..88304cd36a --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloConfigActions.java @@ -0,0 +1,45 @@ +package com.o3dr.services.android.lib.drone.companion.solo.action; + +import com.o3dr.services.android.lib.drone.companion.solo.controller.SoloControllerMode; + +/** + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloConfigActions { + + //Private to prevent instantiation + private SoloConfigActions() { + } + + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.drone.companion.solo.action.config"; + + public static final String ACTION_UPDATE_WIFI_SETTINGS = PACKAGE_NAME + ".UPDATE_WIFI_SETTINGS"; + public static final String EXTRA_WIFI_SSID = "extra_wifi_ssid"; + public static final String EXTRA_WIFI_PASSWORD = "extra_wifi_password"; + + + public static final String ACTION_UPDATE_BUTTON_SETTINGS = PACKAGE_NAME + ".UPDATE_BUTTON_SETTINGS"; + /** + * Used to retrieve the button settings to push to the sololink companion computer. + * + * @see {@link com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter} + */ + public static final String EXTRA_BUTTON_SETTINGS = "extra_button_settings"; + + + public static final String ACTION_UPDATE_CONTROLLER_MODE = PACKAGE_NAME + ".UPDATE_CONTROLLER_MODE"; + /** + * Controller mode to apply. + * + * @see {@link SoloControllerMode} + */ + public static final String EXTRA_CONTROLLER_MODE = "extra_controller_mode"; + + + public static final String ACTION_UPDATE_EU_TX_POWER_COMPLIANCE = PACKAGE_NAME + ".UPDATE_EU_TX_POWER_COMPLIANCE"; + /** + * Boolean value. true if the controller should be made compliant, false otherwise. + */ + public static final String EXTRA_EU_TX_POWER_COMPLIANT = "extra_eu_tx_power_compliant"; + +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloLinkActions.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloLinkActions.java deleted file mode 100644 index 031137d607..0000000000 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloLinkActions.java +++ /dev/null @@ -1,56 +0,0 @@ -package com.o3dr.services.android.lib.drone.companion.solo.action; - -import com.o3dr.services.android.lib.util.Utils; - -/** - * Created by Fredia Huya-Kouadio on 7/10/15. - */ -public class SoloLinkActions { - - //Private to prevent instantiation - private SoloLinkActions(){} - - public static final String ACTION_UPDATE_WIFI_SETTINGS = Utils.PACKAGE_NAME + ".action.UPDATE_WIFI_SETTINGS"; - - public static final String EXTRA_WIFI_SSID = "extra_wifi_ssid"; - public static final String EXTRA_WIFI_PASSWORD = "extra_wifi_password"; - - public static final String ACTION_UPDATE_BUTTON_SETTINGS = Utils.PACKAGE_NAME + ".action.UPDATE_BUTTON_SETTINGS"; - - /** - * Used to retrieve the button settings to push to the sololink companion computer. - * @see {@link com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter} - */ - public static final String EXTRA_BUTTON_SETTINGS = "extra_button_settings"; - - public static final String ACTION_SEND_MESSAGE = Utils.PACKAGE_NAME + "sololink.action.SEND_MESSAGE"; - - /** - * TLV message object to send to the sololink companion computer. - * @see {@link com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket} - */ - public static final String EXTRA_MESSAGE_DATA = "extra_message_data"; - - public static final String ACTION_UPDATE_CONTROLLER_MODE = Utils.PACKAGE_NAME + ".action.UPDATE_CONTROLLER_MODE"; - - /** - * Controller mode to apply. - * @see {@link com.o3dr.services.android.lib.drone.companion.solo.SoloControllerMode} - */ - public static final String EXTRA_CONTROLLER_MODE = "extra_controller_mode"; - - public static final String ACTION_START_VIDEO_STREAM = Utils.PACKAGE_NAME + ".action.START_VIDEO_STREAM"; - - public static final String EXTRA_VIDEO_DISPLAY = "extra_video_display"; - - public static final String EXTRA_VIDEO_TAG = "extra_video_tag"; - - public static final String ACTION_STOP_VIDEO_STREAM = Utils.PACKAGE_NAME + ".action.STOP_VIDEO_STREAM"; - - public static final String ACTION_UPDATE_EU_TX_POWER_COMPLIANCE = Utils.PACKAGE_NAME + ".action.sololink.UPDATE_EU_TX_POWER_COMPLIANCE"; - - /** - * Boolean value. true if the controller should be made compliant, false otherwise. - */ - public static final String EXTRA_EU_TX_POWER_COMPLIANT = "extra_eu_tx_power_compliant"; -} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloShotsActions.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloShotsActions.java new file mode 100644 index 0000000000..9d5a2b9f70 --- /dev/null +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/action/SoloShotsActions.java @@ -0,0 +1,12 @@ +package com.o3dr.services.android.lib.drone.companion.solo.action; + +/** + * Created by Fredia Huya-Kouadio on 7/31/15. + */ +public class SoloShotsActions { + + //Private to prevent instantiation + private SoloShotsActions(){} + + private static final String PACKAGE_NAME = "com.o3dr.services.android.lib.drone.companion.solo.action.shots"; +} diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloControllerMode.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/controller/SoloControllerMode.java similarity index 91% rename from ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloControllerMode.java rename to ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/controller/SoloControllerMode.java index 1ee456604a..579846f943 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/SoloControllerMode.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/controller/SoloControllerMode.java @@ -1,4 +1,4 @@ -package com.o3dr.services.android.lib.drone.companion.solo; +package com.o3dr.services.android.lib.drone.companion.solo.controller; import android.support.annotation.IntDef; diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/ArtooMessageInputReport.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/ControllerMessageInputReport.java similarity index 71% rename from ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/ArtooMessageInputReport.java rename to ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/ControllerMessageInputReport.java index 6b138686f1..3ab72f4d7a 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/ArtooMessageInputReport.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/ControllerMessageInputReport.java @@ -7,14 +7,14 @@ /** * Created by djmedina on 4/15/15. */ -public class ArtooMessageInputReport extends TLVPacket { +public class ControllerMessageInputReport extends TLVPacket { private double timestamp; private short gimbalY; private short gimbalRate; private short battery; - public ArtooMessageInputReport(double timestamp, short gimbalY, short gimbalRate, short battery) { + public ControllerMessageInputReport(double timestamp, short gimbalY, short gimbalRate, short battery) { super(TLVMessageTypes.TYPE_ARTOO_INPUT_REPORT_MESSAGE, 14); this.timestamp = timestamp; this.gimbalY = gimbalY; @@ -55,7 +55,7 @@ public void writeToParcel(Parcel dest, int flags) { dest.writeInt(this.battery); } - protected ArtooMessageInputReport(Parcel in) { + protected ControllerMessageInputReport(Parcel in) { super(in); this.timestamp = in.readDouble(); this.gimbalY = (short) in.readInt(); @@ -63,13 +63,13 @@ protected ArtooMessageInputReport(Parcel in) { this.battery = (short) in.readInt(); } - public static final Creator CREATOR = new Creator() { - public ArtooMessageInputReport createFromParcel(Parcel source) { - return new ArtooMessageInputReport(source); + public static final Creator CREATOR = new Creator() { + public ControllerMessageInputReport createFromParcel(Parcel source) { + return new ControllerMessageInputReport(source); } - public ArtooMessageInputReport[] newArray(int size) { - return new ArtooMessageInputReport[size]; + public ControllerMessageInputReport[] newArray(int size) { + return new ControllerMessageInputReport[size]; } }; } diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloFollowOptions.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloFollowOptions.java index 779fa23ab5..d1e2b22c7f 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloFollowOptions.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloFollowOptions.java @@ -9,8 +9,6 @@ */ public class SoloFollowOptions extends SoloShotOptions { - private static final String TAG = SoloFollowOptions.class.getSimpleName(); - private static final int LOOK_AT_ENABLED_VALUE = 1; private static final int LOOK_AT_DISABLED_VALUE = 0; @@ -22,7 +20,7 @@ public SoloFollowOptions(float cruiseSpeed, boolean lookAt){ } public SoloFollowOptions(){ - this(PAUSED_CRUISE_SPEED, false); + this(PAUSED_CRUISE_SPEED, true); } SoloFollowOptions(float cruiseSpeed, int lookAtValue){ diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloShotOptions.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloShotOptions.java index a36c15d464..b7a6f86ff9 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloShotOptions.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/SoloShotOptions.java @@ -55,4 +55,17 @@ protected SoloShotOptions(Parcel in) { this.cruiseSpeed = in.readFloat(); } + public static final Creator CREATOR = new Creator(){ + + @Override + public SoloShotOptions createFromParcel(Parcel source) { + return new SoloShotOptions(source); + } + + @Override + public SoloShotOptions[] newArray(int size) { + return new SoloShotOptions[size]; + } + }; + } diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/TLVMessageParser.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/TLVMessageParser.java index e9698b4915..8422318da3 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/TLVMessageParser.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/drone/companion/solo/tlv/TLVMessageParser.java @@ -114,7 +114,7 @@ public static TLVPacket parseTLVPacket(ByteBuffer packetBuffer) { final short gimbalRate = packetBuffer.getShort(); final short battery = packetBuffer.getShort(); - return new ArtooMessageInputReport(timestamp, gimbalY, gimbalRate, battery); + return new ControllerMessageInputReport(timestamp, gimbalY, gimbalRate, battery); } case TYPE_SOLO_GOPRO_SET_REQUEST: { diff --git a/ClientLib/src/main/java/com/o3dr/services/android/lib/gcs/follow/FollowType.java b/ClientLib/src/main/java/com/o3dr/services/android/lib/gcs/follow/FollowType.java index 88673f0723..96c9de8166 100644 --- a/ClientLib/src/main/java/com/o3dr/services/android/lib/gcs/follow/FollowType.java +++ b/ClientLib/src/main/java/com/o3dr/services/android/lib/gcs/follow/FollowType.java @@ -47,6 +47,13 @@ public boolean hasParam(String paramKey) { public boolean hasParam(String paramKey) { return false; } + }, + + SOLO_SHOT("Solo Follow Shot"){ + @Override + public boolean hasParam(String paramKey){ + return false; + } }; public static final String EXTRA_FOLLOW_RADIUS = "extra_follow_radius"; @@ -102,6 +109,7 @@ public static List getFollowTypes(boolean includeAdvanced) { followTypes.add(LOOK_AT_ME); if (includeAdvanced) { + followTypes.add(SOLO_SHOT); followTypes.add(SPLINE_LEASH); followTypes.add(SPLINE_ABOVE); } diff --git a/ClientLib/src/main/res/values/version.xml b/ClientLib/src/main/res/values/version.xml index 9a601580d7..74acdf326f 100644 --- a/ClientLib/src/main/res/values/version.xml +++ b/ClientLib/src/main/res/values/version.xml @@ -1,4 +1,4 @@ - 20413 + 20416 \ No newline at end of file diff --git a/ServiceApp/build.gradle b/ServiceApp/build.gradle index b89d3999e4..888c22508f 100644 --- a/ServiceApp/build.gradle +++ b/ServiceApp/build.gradle @@ -33,6 +33,13 @@ dependencies { testCompile 'org.robolectric:robolectric:2.4' } +//Decomposed version name and code (https://plus.google.com/+JakeWharton/posts/6f5TcVPRZij) +def versionMajor = 1 +def versionMinor = 3 +def versionPatch = 2 +def versionBuild = 3 //bump for dogfood builds, public betas, etc. +def versionPrefix = "3DR Services v" + android { compileSdkVersion Integer.parseInt(project.ANDROID_BUILD_SDK_VERSION) buildToolsVersion project.ANDROID_BUILD_TOOLS_VERSION @@ -41,8 +48,9 @@ android { applicationId 'org.droidplanner.services.android' minSdkVersion Integer.parseInt(project.ANDROID_BUILD_MIN_SDK_VERSION) targetSdkVersion Integer.parseInt(project.ANDROID_BUILD_TARGET_SDK_VERSION) - versionCode 10302 - versionName getGitVersion() + + versionCode computeVersionCode(versionMajor, versionMinor, versionPatch, versionBuild) + versionName generateVersionName(versionPrefix, versionMajor, versionMinor, versionPatch) } compileOptions { @@ -97,6 +105,10 @@ android { } buildTypes { + debug { + versionNameSuffix generateVersionNameSuffix(versionBuild, "dev") + } + release { signingConfig signingConfigs.release } @@ -108,20 +120,6 @@ android { } } -/** - * @return The most recent git tag to be used as version name for the app. - */ -def getGitVersion() { - def cmd = "git describe --tag" - try { - def proc = cmd.execute() - return proc.text.trim() - } catch (IOException e) { - //Unable to find 'git' - return "please update version name manually" - } -} - def getAppKeystoreFile() { def filePath = hasProperty('COM_O3DR_SERVICES_KEYSTORE') ? COM_O3DR_SERVICES_KEYSTORE : null return filePath ? file(filePath) : null diff --git a/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java b/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java index cfcfdcce59..c9948743de 100644 --- a/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java +++ b/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java @@ -15,7 +15,7 @@ import com.o3dr.services.android.lib.drone.action.ConnectionActions; import com.o3dr.services.android.lib.drone.attribute.AttributeEvent; import com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra; -import com.o3dr.services.android.lib.drone.companion.solo.action.SoloLinkActions; +import com.o3dr.services.android.lib.drone.companion.solo.action.SoloCameraActions; import com.o3dr.services.android.lib.drone.connection.ConnectionParameter; import com.o3dr.services.android.lib.drone.connection.ConnectionResult; import com.o3dr.services.android.lib.drone.connection.DroneSharePrefs; @@ -38,7 +38,7 @@ import org.droidplanner.services.android.exception.ConnectionException; import org.droidplanner.services.android.core.drone.DroneEventsListener; import org.droidplanner.services.android.utils.CommonApiUtils; -import org.droidplanner.services.android.utils.SoloLinkApiUtils; +import org.droidplanner.services.android.utils.SoloApiUtils; import java.util.ArrayList; import java.util.List; @@ -232,16 +232,16 @@ public void executeAction(Action action, ICommandListener listener) throws Remot disconnect(); break; - case SoloLinkActions.ACTION_START_VIDEO_STREAM: { - final Surface videoSurface = data.getParcelable(SoloLinkActions.EXTRA_VIDEO_DISPLAY); - final String videoTag = data.getString(SoloLinkActions.EXTRA_VIDEO_TAG, ""); - SoloLinkApiUtils.startVideoStream(getDroneManager(), ownerId + videoTag, videoSurface, listener); + case SoloCameraActions.ACTION_START_VIDEO_STREAM: { + final Surface videoSurface = data.getParcelable(SoloCameraActions.EXTRA_VIDEO_DISPLAY); + final String videoTag = data.getString(SoloCameraActions.EXTRA_VIDEO_TAG, ""); + SoloApiUtils.startVideoStream(getDroneManager(), ownerId + videoTag, videoSurface, listener); break; } - case SoloLinkActions.ACTION_STOP_VIDEO_STREAM: { - final String videoTag = data.getString(SoloLinkActions.EXTRA_VIDEO_TAG, ""); - SoloLinkApiUtils.stopVideoStream(getDroneManager(), ownerId + videoTag, listener); + case SoloCameraActions.ACTION_STOP_VIDEO_STREAM: { + final String videoTag = data.getString(SoloCameraActions.EXTRA_VIDEO_TAG, ""); + SoloApiUtils.stopVideoStream(getDroneManager(), ownerId + videoTag, listener); break; } @@ -526,19 +526,6 @@ public void onDroneEvent(DroneInterfaces.DroneEventsType event, MavLinkDrone dro droneEvent = AttributeEvent.MISSION_ITEM_REACHED; break; - case FOLLOW_START: - droneEvent = AttributeEvent.FOLLOW_START; - break; - - case FOLLOW_STOP: - droneEvent = AttributeEvent.FOLLOW_STOP; - break; - - case FOLLOW_UPDATE: - case FOLLOW_CHANGE_TYPE: - droneEvent = AttributeEvent.FOLLOW_UPDATE; - break; - case ALTITUDE: droneEvent = AttributeEvent.ALTITUDE_UPDATED; break; diff --git a/ServiceApp/src/org/droidplanner/services/android/api/MavLinkServiceApi.java b/ServiceApp/src/org/droidplanner/services/android/api/MavLinkServiceApi.java index e8e5eab1c3..06cfb97340 100644 --- a/ServiceApp/src/org/droidplanner/services/android/api/MavLinkServiceApi.java +++ b/ServiceApp/src/org/droidplanner/services/android/api/MavLinkServiceApi.java @@ -14,18 +14,14 @@ */ public class MavLinkServiceApi { - private final SoftReference mServiceRef; + private final DroidPlannerService mService; public MavLinkServiceApi(DroidPlannerService service) { - mServiceRef = new SoftReference<>(service); + mService = service; } private DroidPlannerService getService() { - DroidPlannerService service = mServiceRef.get(); - if (service == null) - throw new IllegalStateException("Lost reference to parent service."); - - return service; + return mService; } public boolean sendData(ConnectionParameter connParams, MAVLinkPacket packet) { diff --git a/ServiceApp/src/org/droidplanner/services/android/core/MAVLink/command/doCmd/MavLinkDoCmds.java b/ServiceApp/src/org/droidplanner/services/android/core/MAVLink/command/doCmd/MavLinkDoCmds.java index ceb1941834..e72c87ccc0 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/MAVLink/command/doCmd/MavLinkDoCmds.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/MAVLink/command/doCmd/MavLinkDoCmds.java @@ -4,12 +4,12 @@ import com.MAVLink.ardupilotmega.msg_mount_control; import com.MAVLink.common.msg_command_long; import com.MAVLink.common.msg_mission_set_current; +import com.MAVLink.enums.GRIPPER_ACTIONS; import com.MAVLink.enums.MAV_CMD; import com.o3dr.services.android.lib.model.ICommandListener; -import org.droidplanner.services.android.core.helpers.coordinates.Coord3D; -import org.droidplanner.services.android.core.mission.commands.EpmGripper; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; +import org.droidplanner.services.android.core.helpers.coordinates.Coord3D; public class MavLinkDoCmds { public static void setROI(MavLinkDrone drone, Coord3D coord, ICommandListener listener) { @@ -53,8 +53,8 @@ public static void empCommand(MavLinkDrone drone, boolean release, ICommandListe msg_command_long msg = new msg_command_long(); msg.target_system = drone.getSysid(); msg.target_component = drone.getCompid(); - msg.command = EpmGripper.MAV_CMD_DO_GRIPPER; - msg.param2 = release ? EpmGripper.GRIPPER_ACTION_RELEASE : EpmGripper.GRIPPER_ACTION_GRAB; + msg.command = MAV_CMD.MAV_CMD_DO_GRIPPER; + msg.param2 = release ? GRIPPER_ACTIONS.GRIPPER_ACTION_RELEASE : GRIPPER_ACTIONS.GRIPPER_ACTION_GRAB; drone.getMavClient().sendMavMessage(msg, listener); } @@ -104,10 +104,10 @@ public static void setServo(MavLinkDrone drone, int channel, int pwm, ICommandLi /** * Set the orientation of a gimbal * - * @param drone target vehicle - * @param pitch the desired gimbal pitch in degrees - * @param roll the desired gimbal roll in degrees - * @param yaw the desired gimbal yaw in degrees + * @param drone target vehicle + * @param pitch the desired gimbal pitch in degrees + * @param roll the desired gimbal roll in degrees + * @param yaw the desired gimbal yaw in degrees * @param listener Register a callback to receive update of the command execution state. */ public static void setGimbalOrientation(MavLinkDrone drone, float pitch, float roll, float yaw, ICommandListener @@ -127,11 +127,12 @@ public static void setGimbalOrientation(MavLinkDrone drone, float pitch, float r /** * Jump to the desired command in the mission list. Repeat this action only the specified number of times - * @param drone target vehicle - * @param waypoint command - * @param listener Register a callback to receive update of the command execution state. + * + * @param drone target vehicle + * @param waypoint command + * @param listener Register a callback to receive update of the command execution state. */ - public static void gotoWaypoint(MavLinkDrone drone, int waypoint, ICommandListener listener){ + public static void gotoWaypoint(MavLinkDrone drone, int waypoint, ICommandListener listener) { if (drone == null) return; msg_mission_set_current msg = new msg_mission_set_current(); diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneInterfaces.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneInterfaces.java index f0d85bbe38..a3af4909fc 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneInterfaces.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneInterfaces.java @@ -182,26 +182,6 @@ public enum DroneEventsType { */ MISSION_WP_UPDATE, - /** - * 'Follow' mode has been enabled. - */ - FOLLOW_START, - - /** - * 'Follow' mode has been disabled. - */ - FOLLOW_STOP, - - /** - * 'Follow' state has been updated. - */ - FOLLOW_UPDATE, - - /** - * - */ - FOLLOW_CHANGE_TYPE, - /** * */ diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneManager.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneManager.java index fa70841be2..5ee59f1167 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneManager.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/DroneManager.java @@ -19,8 +19,12 @@ import com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra; import com.o3dr.services.android.lib.drone.attribute.AttributeType; import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError; -import com.o3dr.services.android.lib.drone.companion.solo.SoloControllerMode; -import com.o3dr.services.android.lib.drone.companion.solo.action.SoloLinkActions; +import com.o3dr.services.android.lib.drone.companion.solo.SoloAttributes; +import com.o3dr.services.android.lib.drone.companion.solo.SoloEventExtras; +import com.o3dr.services.android.lib.drone.companion.solo.SoloEvents; +import com.o3dr.services.android.lib.drone.companion.solo.action.SoloConfigActions; +import com.o3dr.services.android.lib.drone.companion.solo.controller.SoloControllerMode; +import com.o3dr.services.android.lib.drone.companion.solo.action.SoloActions; import com.o3dr.services.android.lib.drone.companion.solo.button.ButtonPacket; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSetting; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter; @@ -62,7 +66,7 @@ import org.droidplanner.services.android.exception.ConnectionException; import org.droidplanner.services.android.utils.AndroidApWarningParser; import org.droidplanner.services.android.utils.CommonApiUtils; -import org.droidplanner.services.android.utils.SoloLinkApiUtils; +import org.droidplanner.services.android.utils.SoloApiUtils; import org.droidplanner.services.android.utils.analytics.GAUtils; import org.droidplanner.services.android.utils.prefs.DroidPlannerPrefs; @@ -127,40 +131,40 @@ public void onTlvPacketReceived(TLVPacket packet) { break; case TLVMessageTypes.TYPE_SOLO_GOPRO_STATE: - notifyDroneAttributeEvent(AttributeEvent.SOLOLINK_GOPRO_STATE_UPDATED, null); + notifyDroneAttributeEvent(SoloEvents.SOLO_GOPRO_STATE_UPDATED, null); break; default: final Bundle messageInfo = new Bundle(); - messageInfo.putParcelable(AttributeEventExtra.EXTRA_SOLOLINK_MESSAGE_DATA, packet); + messageInfo.putParcelable(SoloEventExtras.EXTRA_SOLO_MESSAGE_DATA, packet); - notifyDroneAttributeEvent(AttributeEvent.SOLOLINK_MESSAGE_RECEIVED, messageInfo, true); + notifyDroneAttributeEvent(SoloEvents.SOLO_MESSAGE_RECEIVED, messageInfo, true); break; } } @Override public void onPresetButtonLoaded(int buttonType, SoloButtonSetting buttonSettings) { - notifyDroneAttributeEvent(AttributeEvent.SOLOLINK_BUTTON_SETTINGS_UPDATED, null, true); + notifyDroneAttributeEvent(SoloEvents.SOLO_BUTTON_SETTINGS_UPDATED, null, true); } @Override public void onWifiInfoUpdated(String wifiName, String wifiPassword) { - notifyDroneAttributeEvent(AttributeEvent.SOLOLINK_WIFI_SETTINGS_UPDATED, null, true); + notifyDroneAttributeEvent(SoloEvents.SOLO_WIFI_SETTINGS_UPDATED, null, true); } @Override public void onButtonPacketReceived(ButtonPacket packet) { final Bundle eventInfo = new Bundle(); - eventInfo.putParcelable(AttributeEventExtra.EXTRA_SOLOLINK_BUTTON_EVENT, packet); - notifyDroneAttributeEvent(AttributeEvent.SOLOLINK_BUTTON_EVENT, eventInfo, true); + eventInfo.putParcelable(SoloEventExtras.EXTRA_SOLO_BUTTON_EVENT, packet); + notifyDroneAttributeEvent(SoloEvents.SOLO_BUTTON_EVENT_RECEIVED, eventInfo, true); } @Override public void onEUTxPowerComplianceUpdated(boolean isCompliant) { final Bundle eventInfo = new Bundle(1); - eventInfo.putBoolean(AttributeEventExtra.EXTRA_SOLOLINK_EU_TX_POWER_COMPLIANT, isCompliant); - notifyDroneAttributeEvent(AttributeEvent.SOLOLINK_EU_TX_POWER_COMPLIANCE_UPDATED, eventInfo, true); + eventInfo.putBoolean(SoloEventExtras.EXTRA_SOLO_EU_TX_POWER_COMPLIANT, isCompliant); + notifyDroneAttributeEvent(SoloEvents.SOLO_EU_TX_POWER_COMPLIANCE_UPDATED, eventInfo, true); } }; @@ -241,7 +245,7 @@ public void postDelayed(Runnable thread, long timeout) { this.drone.getStreamRates().setRates(dpPrefs.getRates()); - this.followMe = new Follow(this.drone, handler, new FusedLocation(context, handler)); + this.followMe = new Follow(this, handler, new FusedLocation(context, handler)); drone.addDroneListener(this); drone.getParameters().setParameterListener(this); @@ -521,10 +525,10 @@ public DroneAttribute getAttribute(String attributeType) { case AttributeType.CAMERA: return CommonApiUtils.getCameraProxy(drone, cameraDetails); - case AttributeType.SOLOLINK_STATE: - return SoloLinkApiUtils.getSoloLinkState(this); + case SoloAttributes.SOLO_STATE: + return SoloApiUtils.getSoloLinkState(this); - case AttributeType.SOLOLINK_GOPRO_STATE: + case SoloAttributes.SOLO_GOPRO_STATE: return soloComp.getGoproState(); default: @@ -552,7 +556,7 @@ public void executeAsyncAction(Action action, final ICommandListener listener) { case FollowMeActions.ACTION_ENABLE_FOLLOW_ME: data.setClassLoader(FollowType.class.getClassLoader()); FollowType followType = data.getParcelable(FollowMeActions.EXTRA_FOLLOW_TYPE); - CommonApiUtils.enableFollowMe(this, handler, followType); + CommonApiUtils.enableFollowMe(this, handler, followType, listener); break; case FollowMeActions.ACTION_UPDATE_FOLLOW_PARAMS: @@ -591,34 +595,34 @@ public void executeAsyncAction(Action action, final ICommandListener listener) { break; //************ SOLOLINK ACTIONS *************// - case SoloLinkActions.ACTION_SEND_MESSAGE: - final TLVPacket messageData = data.getParcelable(SoloLinkActions.EXTRA_MESSAGE_DATA); + case SoloActions.ACTION_SEND_MESSAGE: + final TLVPacket messageData = data.getParcelable(SoloActions.EXTRA_MESSAGE_DATA); if (messageData != null) { - SoloLinkApiUtils.sendSoloLinkMessage(this, messageData, listener); + SoloApiUtils.sendSoloLinkMessage(this, messageData, listener); } break; - case SoloLinkActions.ACTION_UPDATE_WIFI_SETTINGS: - final String wifiSsid = data.getString(SoloLinkActions.EXTRA_WIFI_SSID); - final String wifiPassword = data.getString(SoloLinkActions.EXTRA_WIFI_PASSWORD); - SoloLinkApiUtils.updateSoloLinkWifiSettings(this, wifiSsid, wifiPassword, listener); + case SoloConfigActions.ACTION_UPDATE_WIFI_SETTINGS: + final String wifiSsid = data.getString(SoloConfigActions.EXTRA_WIFI_SSID); + final String wifiPassword = data.getString(SoloConfigActions.EXTRA_WIFI_PASSWORD); + SoloApiUtils.updateSoloLinkWifiSettings(this, wifiSsid, wifiPassword, listener); break; - case SoloLinkActions.ACTION_UPDATE_BUTTON_SETTINGS: - final SoloButtonSettingSetter buttonSettings = data.getParcelable(SoloLinkActions.EXTRA_BUTTON_SETTINGS); + case SoloConfigActions.ACTION_UPDATE_BUTTON_SETTINGS: + final SoloButtonSettingSetter buttonSettings = data.getParcelable(SoloConfigActions.EXTRA_BUTTON_SETTINGS); if (buttonSettings != null) { - SoloLinkApiUtils.updateSoloLinkButtonSettings(this, buttonSettings, listener); + SoloApiUtils.updateSoloLinkButtonSettings(this, buttonSettings, listener); } break; - case SoloLinkActions.ACTION_UPDATE_CONTROLLER_MODE: - final @SoloControllerMode.ControllerMode int mode = data.getInt(SoloLinkActions.EXTRA_CONTROLLER_MODE); - SoloLinkApiUtils.updateSoloLinkControllerMode(this, mode, listener); + case SoloConfigActions.ACTION_UPDATE_CONTROLLER_MODE: + final @SoloControllerMode.ControllerMode int mode = data.getInt(SoloConfigActions.EXTRA_CONTROLLER_MODE); + SoloApiUtils.updateSoloLinkControllerMode(this, mode, listener); break; - case SoloLinkActions.ACTION_UPDATE_EU_TX_POWER_COMPLIANCE: - final boolean isCompliant = data.getBoolean(SoloLinkActions.EXTRA_EU_TX_POWER_COMPLIANT, false); - SoloLinkApiUtils.updateSoloLinkEUTxPowerCompliance(this, isCompliant, listener); + case SoloConfigActions.ACTION_UPDATE_EU_TX_POWER_COMPLIANCE: + final boolean isCompliant = data.getBoolean(SoloConfigActions.EXTRA_EU_TX_POWER_COMPLIANT, false); + SoloApiUtils.updateSoloLinkEUTxPowerCompliance(this, isCompliant, listener); break; //**************** CAPABILITY ACTIONS **************// @@ -627,7 +631,7 @@ public void executeAsyncAction(Action action, final ICommandListener listener) { final String featureId = data.getString(CapabilityActions.EXTRA_FEATURE_ID); if (!TextUtils.isEmpty(featureId)) { switch (featureId) { - case CapabilityApi.FeatureIds.SOLOLINK_VIDEO_STREAMING: + case CapabilityApi.FeatureIds.SOLO_VIDEO_STREAMING: case CapabilityApi.FeatureIds.COMPASS_CALIBRATION: if (this.isCompanionComputerEnabled()) { CommonApiUtils.postSuccessEvent(listener); diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/SoloComp.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/SoloComp.java index 6a306b9fa2..ce339d3da8 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/SoloComp.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/SoloComp.java @@ -9,19 +9,20 @@ import android.view.Surface; import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError; -import com.o3dr.services.android.lib.drone.companion.solo.SoloControllerMode; +import com.o3dr.services.android.lib.drone.companion.solo.controller.SoloControllerMode; import com.o3dr.services.android.lib.drone.companion.solo.button.ButtonPacket; import com.o3dr.services.android.lib.drone.companion.solo.button.ButtonTypes; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSetting; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloGoproState; +import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloMessageLocation; import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVMessageTypes; import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket; import com.o3dr.services.android.lib.model.ICommandListener; import org.droidplanner.services.android.core.drone.companion.CompComp; -import org.droidplanner.services.android.core.drone.companion.solo.artoo.ArtooLinkListener; -import org.droidplanner.services.android.core.drone.companion.solo.artoo.ArtooLinkManager; +import org.droidplanner.services.android.core.drone.companion.solo.controller.ControllerLinkListener; +import org.droidplanner.services.android.core.drone.companion.solo.controller.ControllerLinkManager; import org.droidplanner.services.android.core.drone.companion.solo.sololink.SoloLinkListener; import org.droidplanner.services.android.core.drone.companion.solo.sololink.SoloLinkManager; import org.droidplanner.services.android.utils.NetworkUtils; @@ -37,7 +38,7 @@ * Sololink companion computer implementation * Created by Fredia Huya-Kouadio on 7/9/15. */ -public class SoloComp implements CompComp, SoloLinkListener, ArtooLinkListener { +public class SoloComp implements CompComp, SoloLinkListener, ControllerLinkListener { public interface SoloCompListener { void onConnected(); @@ -62,7 +63,7 @@ public interface SoloCompListener { public static final String SSH_USERNAME = "root"; public static final String SSH_PASSWORD = "TjSDBkAu"; - private final ArtooLinkManager artooMgr; + private final ControllerLinkManager artooMgr; private final SoloLinkManager soloLinkMgr; private final Context context; @@ -86,7 +87,7 @@ public SoloComp(Context context, Handler handler) { this.handler = handler; asyncExecutor = Executors.newCachedThreadPool(); - this.artooMgr = new ArtooLinkManager(context, handler, asyncExecutor); + this.artooMgr = new ControllerLinkManager(context, handler, asyncExecutor); this.soloLinkMgr = new SoloLinkManager(context, handler, asyncExecutor); } @@ -330,7 +331,8 @@ public void stopVideoStream(String ownerId, final ICommandListener listener){ Timber.d("Stopping video decoding. Current owner is %s.", videoOwnerId.get()); artooMgr.stopDecoding(new DecoderListener() { @Override - public void onDecodingStarted() {} + public void onDecodingStarted() { + } @Override public void onDecodingError() { @@ -407,4 +409,16 @@ public void run() { } } + public void enableFollowDataConnection(){ + soloLinkMgr.enableFollowDataConnection(); + } + + public void disableFollowDataConnection(){ + soloLinkMgr.disableFollowDataConnection(); + } + + public void updateFollowCenter(SoloMessageLocation location){ + soloLinkMgr.sendTLVPacket(location, true, null); + } + } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/ArtooLinkListener.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/ControllerLinkListener.java similarity index 85% rename from ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/ArtooLinkListener.java rename to ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/ControllerLinkListener.java index 1f4ca8b8a8..611e27c818 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/ArtooLinkListener.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/ControllerLinkListener.java @@ -1,4 +1,4 @@ -package org.droidplanner.services.android.core.drone.companion.solo.artoo; +package org.droidplanner.services.android.core.drone.companion.solo.controller; import org.droidplanner.services.android.core.drone.companion.solo.AbstractLinkManager; import com.o3dr.services.android.lib.drone.companion.solo.button.ButtonPacket; @@ -7,7 +7,7 @@ /** * Created by Fredia Huya-Kouadio on 7/10/15. */ -public interface ArtooLinkListener extends AbstractLinkManager.LinkListener { +public interface ControllerLinkListener extends AbstractLinkManager.LinkListener { void onTlvPacketReceived(TLVPacket packet); diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/ArtooLinkManager.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/ControllerLinkManager.java similarity index 97% rename from ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/ArtooLinkManager.java rename to ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/ControllerLinkManager.java index 60a3464850..4d0054d836 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/ArtooLinkManager.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/ControllerLinkManager.java @@ -1,4 +1,4 @@ -package org.droidplanner.services.android.core.drone.companion.solo.artoo; +package org.droidplanner.services.android.core.drone.companion.solo.controller; import android.content.Context; import android.os.Handler; @@ -7,7 +7,7 @@ import android.view.Surface; import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError; -import com.o3dr.services.android.lib.drone.companion.solo.SoloControllerMode; +import com.o3dr.services.android.lib.drone.companion.solo.controller.SoloControllerMode; import com.o3dr.services.android.lib.drone.companion.solo.button.ButtonPacket; import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVMessageParser; import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket; @@ -33,7 +33,7 @@ /** * Handles artoo link related logic. */ -public class ArtooLinkManager extends AbstractLinkManager { +public class ControllerLinkManager extends AbstractLinkManager { private static final long RECONNECT_COUNTDOWN = 1000l; //ms @@ -148,9 +148,9 @@ public void run() { } }; - private ArtooLinkListener linkListener; + private ControllerLinkListener linkListener; - public ArtooLinkManager(Context context, final Handler handler, ExecutorService asyncExecutor) { + public ControllerLinkManager(Context context, final Handler handler, ExecutorService asyncExecutor) { super(context, new TcpConnection(handler, ARTOO_IP, ARTOO_BUTTON_PORT), handler, asyncExecutor); this.videoMgr = new VideoManager(context, handler, asyncExecutor); @@ -281,7 +281,7 @@ public Pair getSoloLinkWifiInfo() { } @Override - public void start(ArtooLinkListener listener) { + public void start(ControllerLinkListener listener) { this.linkListener = listener; Timber.d("Starting artoo link manager"); diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/VideoManager.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/VideoManager.java similarity index 94% rename from ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/VideoManager.java rename to ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/VideoManager.java index 8f78f21187..a44dcdbd63 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/artoo/VideoManager.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/controller/VideoManager.java @@ -1,4 +1,4 @@ -package org.droidplanner.services.android.core.drone.companion.solo.artoo; +package org.droidplanner.services.android.core.drone.companion.solo.controller; import android.content.Context; import android.os.Handler; @@ -27,7 +27,7 @@ public class VideoManager extends AbstractLinkManager { private final MediaCodecManager mediaCodecManager; VideoManager(Context context, Handler handler, ExecutorService asyncExecutor) { - super(context, new UdpConnection(handler, ArtooLinkManager.ARTOO_UDP_PORT, UDP_BUFFER_SIZE, true, 42), handler, asyncExecutor); + super(context, new UdpConnection(handler, ControllerLinkManager.ARTOO_UDP_PORT, UDP_BUFFER_SIZE, true, 42), handler, asyncExecutor); this.mediaCodecManager = new MediaCodecManager(handler); } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/sololink/SoloLinkManager.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/sololink/SoloLinkManager.java index c19ea4983f..315fc5e3c9 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/sololink/SoloLinkManager.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/companion/solo/sololink/SoloLinkManager.java @@ -6,7 +6,7 @@ import org.droidplanner.services.android.core.drone.companion.solo.AbstractLinkManager; import org.droidplanner.services.android.core.drone.companion.solo.SoloComp; -import org.droidplanner.services.android.core.drone.companion.solo.artoo.ArtooLinkManager; +import org.droidplanner.services.android.core.drone.companion.solo.controller.ControllerLinkManager; import com.o3dr.services.android.lib.drone.companion.solo.button.ButtonTypes; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSetting; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingGetter; @@ -277,11 +277,11 @@ public void enableFollowDataConnection() { public boolean updateSololinkWifi(CharSequence wifiSsid, CharSequence password) { Timber.d(String.format(Locale.US, "Updating solo wifi ssid to %s with password %s", wifiSsid, password)); try { - String ssidUpdateResult = sshLink.execute(ArtooLinkManager.SOLOLINK_SSID_CONFIG_PATH + " --set-wifi-ssid " + + String ssidUpdateResult = sshLink.execute(ControllerLinkManager.SOLOLINK_SSID_CONFIG_PATH + " --set-wifi-ssid " + wifiSsid); - String passwordUpdateResult = sshLink.execute(ArtooLinkManager.SOLOLINK_SSID_CONFIG_PATH + " --set-wifi-password " + + String passwordUpdateResult = sshLink.execute(ControllerLinkManager.SOLOLINK_SSID_CONFIG_PATH + " --set-wifi-password " + password); - String restartResult = sshLink.execute(ArtooLinkManager.SOLOLINK_SSID_CONFIG_PATH + " --reboot"); + String restartResult = sshLink.execute(ControllerLinkManager.SOLOLINK_SSID_CONFIG_PATH + " --reboot"); return true; } catch (IOException e) { Timber.e(e, "Error occurred while updating the sololink wifi ssid."); diff --git a/ServiceApp/src/org/droidplanner/services/android/core/drone/variables/GuidedPoint.java b/ServiceApp/src/org/droidplanner/services/android/core/drone/variables/GuidedPoint.java index a938d84112..7fa209488a 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/drone/variables/GuidedPoint.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/drone/variables/GuidedPoint.java @@ -60,6 +60,9 @@ public void onDroneEvent(DroneEventsType event, MavLinkDrone drone) { } public static boolean isGuidedMode(MavLinkDrone drone) { + if(drone == null) + return false; + final int droneType = drone.getType(); final ApmModes droneMode = drone.getState().getMode(); diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/Follow.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/Follow.java index 4fd2be64d6..3c3b912eb1 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/Follow.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/Follow.java @@ -2,8 +2,11 @@ import android.os.Handler; +import com.o3dr.services.android.lib.drone.attribute.AttributeEvent; + import org.droidplanner.services.android.core.drone.DroneInterfaces.DroneEventsType; import org.droidplanner.services.android.core.drone.DroneInterfaces.OnDroneListener; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.drone.variables.GuidedPoint; import org.droidplanner.services.android.core.drone.variables.State; import org.droidplanner.services.android.core.gcs.location.Location; @@ -23,23 +26,26 @@ public enum FollowStates { } private FollowStates state = FollowStates.FOLLOW_INVALID_STATE; - private MavLinkDrone drone; + private final DroneManager droneMgr; - private LocationFinder locationFinder; + private final LocationFinder locationFinder; private FollowAlgorithm followAlgorithm; - public Follow(MavLinkDrone drone, Handler handler, LocationFinder locationFinder) { - this.drone = drone; - drone.addDroneListener(this); + public Follow(DroneManager droneMgr, Handler handler, LocationFinder locationFinder) { + this.droneMgr = droneMgr; + final MavLinkDrone drone = droneMgr.getDrone(); + if(drone != null) + drone.addDroneListener(this); - followAlgorithm = FollowAlgorithm.FollowModes.LEASH.getAlgorithmType(drone, handler); + followAlgorithm = FollowAlgorithm.FollowModes.LEASH.getAlgorithmType(droneMgr, handler); this.locationFinder = locationFinder; locationFinder.setLocationListener(this); } public void toggleFollowMeState() { - final State droneState = drone.getState(); + final MavLinkDrone drone = droneMgr.getDrone(); + final State droneState = drone == null ? null : drone.getState(); if (droneState == null) { state = FollowStates.FOLLOW_INVALID_STATE; return; @@ -48,7 +54,7 @@ public void toggleFollowMeState() { if (isEnabled()) { disableFollowMe(); } else { - if (drone.isConnected()) { + if (droneMgr.isConnected()) { if (droneState.isArmed()) { GuidedPoint.changeToGuidedMode(drone, null); enableFollowMe(); @@ -68,7 +74,7 @@ private void enableFollowMe() { locationFinder.enableLocationUpdates(); followAlgorithm.enableFollow(); - drone.notifyDroneEvent(DroneEventsType.FOLLOW_START); + droneMgr.onAttributeEvent(AttributeEvent.FOLLOW_START, null); } private void disableFollowMe() { @@ -79,7 +85,7 @@ private void disableFollowMe() { if (isEnabled()) { state = FollowStates.FOLLOW_END; - drone.notifyDroneEvent(DroneEventsType.FOLLOW_STOP); + droneMgr.onAttributeEvent(AttributeEvent.FOLLOW_STOP, null); } } @@ -115,7 +121,7 @@ public void onLocationUpdate(Location location) { state = FollowStates.FOLLOW_START; } - drone.notifyDroneEvent(DroneEventsType.FOLLOW_UPDATE); + droneMgr.onAttributeEvent(AttributeEvent.FOLLOW_UPDATE, null); } @Override @@ -135,7 +141,8 @@ public void setAlgorithm(FollowAlgorithm algorithm) { if(lastLocation != null) followAlgorithm.onLocationReceived(lastLocation); } - drone.notifyDroneEvent(DroneEventsType.FOLLOW_CHANGE_TYPE); + + droneMgr.onAttributeEvent(AttributeEvent.FOLLOW_UPDATE, null); } public FollowAlgorithm getFollowAlgorithm() { diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAbove.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAbove.java index 1f645e625e..b5322ff495 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAbove.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAbove.java @@ -2,14 +2,18 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; public class FollowAbove extends FollowAlgorithm { - public FollowAbove(MavLinkDrone drone, Handler handler) { - super(drone, handler); + protected final MavLinkDrone drone; + + public FollowAbove(DroneManager droneMgr, Handler handler) { + super(droneMgr, handler); + this.drone = droneMgr.getDrone(); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAlgorithm.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAlgorithm.java index dd47157e24..a8cc7d2298 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAlgorithm.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowAlgorithm.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.drone.variables.GuidedPoint; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.gcs.roi.ROIEstimator; @@ -13,12 +14,14 @@ public abstract class FollowAlgorithm { - protected final MavLinkDrone drone; + protected final DroneManager droneMgr; private final ROIEstimator roiEstimator; private final AtomicBoolean isFollowEnabled = new AtomicBoolean(false); - public FollowAlgorithm(MavLinkDrone drone, Handler handler) { - this.drone = drone; + public FollowAlgorithm(DroneManager droneMgr, Handler handler) { + this.droneMgr = droneMgr; + + final MavLinkDrone drone = droneMgr.getDrone(); this.roiEstimator = initROIEstimator(drone, handler); } @@ -28,16 +31,19 @@ protected boolean isFollowEnabled() { public void enableFollow() { isFollowEnabled.set(true); - roiEstimator.enableFollow(); + if(roiEstimator != null) + roiEstimator.enableFollow(); } public void disableFollow() { if(isFollowEnabled.compareAndSet(true, false)) { + final MavLinkDrone drone = droneMgr.getDrone(); if (GuidedPoint.isGuidedMode(drone)) { drone.getGuidedPoint().pauseAtCurrentLocation(null); } - roiEstimator.disableFollow(); + if(roiEstimator != null) + roiEstimator.disableFollow(); } } @@ -54,7 +60,8 @@ protected ROIEstimator getROIEstimator() { public final void onLocationReceived(Location location) { if (isFollowEnabled.get()) { - roiEstimator.onLocationUpdate(location); + if(roiEstimator != null) + roiEstimator.onLocationUpdate(location); processNewLocation(location); } } @@ -77,7 +84,8 @@ public enum FollowModes { SPLINE_LEASH("Vector Leash"), SPLINE_ABOVE("Vector Above"), GUIDED_SCAN("Guided Scan"), - LOOK_AT_ME("Look At Me"); + LOOK_AT_ME("Look At Me"), + SOLO_SHOT("Solo Follow Shot"); private String name; @@ -94,29 +102,31 @@ public FollowModes next() { return values()[(ordinal() + 1) % values().length]; } - public FollowAlgorithm getAlgorithmType(MavLinkDrone drone, Handler handler) { + public FollowAlgorithm getAlgorithmType(DroneManager droneMgr, Handler handler) { switch (this) { case LEASH: default: - return new FollowLeash(drone, handler, 8.0); + return new FollowLeash(droneMgr, handler, 8.0); case LEAD: - return new FollowLead(drone, handler, 15.0); + return new FollowLead(droneMgr, handler, 15.0); case RIGHT: - return new FollowRight(drone, handler, 10.0); + return new FollowRight(droneMgr, handler, 10.0); case LEFT: - return new FollowLeft(drone, handler, 10.0); + return new FollowLeft(droneMgr, handler, 10.0); case CIRCLE: - return new FollowCircle(drone, handler, 15.0, 10.0); + return new FollowCircle(droneMgr, handler, 15.0, 10.0); case ABOVE: - return new FollowAbove(drone, handler); + return new FollowAbove(droneMgr, handler); case SPLINE_LEASH: - return new FollowSplineLeash(drone, handler, 8.0); + return new FollowSplineLeash(droneMgr, handler, 8.0); case SPLINE_ABOVE: - return new FollowSplineAbove(drone, handler); + return new FollowSplineAbove(droneMgr, handler); case GUIDED_SCAN: - return new FollowGuidedScan(drone, handler); + return new FollowGuidedScan(droneMgr, handler); case LOOK_AT_ME: - return new FollowLookAtMe(drone, handler); + return new FollowLookAtMe(droneMgr, handler); + case SOLO_SHOT: + return new FollowSoloShot(droneMgr, handler); } } } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowCircle.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowCircle.java index b2a28435df..b75cf39afd 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowCircle.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowCircle.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.helpers.geoTools.GeoTools; @@ -16,8 +17,8 @@ public class FollowCircle extends FollowWithRadiusAlgorithm { private double circleStep = 2; private double circleAngle = 0.0; - public FollowCircle(MavLinkDrone drone, Handler handler, double radius, double rate) { - super(drone, handler, radius); + public FollowCircle(DroneManager droneMgr, Handler handler, double radius, double rate) { + super(droneMgr, handler, radius); circleStep = rate; } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowGuidedScan.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowGuidedScan.java index 49e361021e..df06b1e12c 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowGuidedScan.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowGuidedScan.java @@ -3,6 +3,7 @@ import android.os.Handler; import org.droidplanner.services.android.core.MAVLink.command.doCmd.MavLinkDoCmds; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.roi.ROIEstimator; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.helpers.coordinates.Coord3D; @@ -30,8 +31,8 @@ public FollowModes getType() { return FollowModes.GUIDED_SCAN; } - public FollowGuidedScan(MavLinkDrone drone, Handler handler) { - super(drone, handler); + public FollowGuidedScan(DroneManager droneMgr, Handler handler) { + super(droneMgr, handler); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowHeadingAngle.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowHeadingAngle.java index 26c08ec4b7..84b1811eef 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowHeadingAngle.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowHeadingAngle.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.helpers.geoTools.GeoTools; @@ -10,10 +11,13 @@ public abstract class FollowHeadingAngle extends FollowWithRadiusAlgorithm { protected double angleOffset; + protected final MavLinkDrone drone; - protected FollowHeadingAngle(MavLinkDrone drone, Handler handler, double radius, double angleOffset) { - super(drone, handler, radius); + protected FollowHeadingAngle(DroneManager droneMgr, Handler handler, double radius, double angleOffset) { + super(droneMgr, handler, radius); this.angleOffset = angleOffset; + + this.drone = droneMgr.getDrone(); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLead.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLead.java index 5d495eb2d1..ea240ff68a 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLead.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLead.java @@ -2,12 +2,13 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; public class FollowLead extends FollowHeadingAngle { - public FollowLead(MavLinkDrone drone, Handler handler, double radius) { - super(drone, handler, radius, 0.0); + public FollowLead(DroneManager droneMgr, Handler handler, double radius) { + super(droneMgr, handler, radius, 0.0); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeash.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeash.java index 0a61197b65..8f296917b8 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeash.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeash.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.helpers.geoTools.GeoTools; @@ -9,8 +10,8 @@ public class FollowLeash extends FollowWithRadiusAlgorithm { - public FollowLeash(MavLinkDrone drone, Handler handler, double radius) { - super(drone, handler, radius); + public FollowLeash(DroneManager droneMgr, Handler handler, double radius) { + super(droneMgr, handler, radius); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeft.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeft.java index 98e88ada39..17687a3072 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeft.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLeft.java @@ -2,12 +2,13 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; public class FollowLeft extends FollowHeadingAngle { - public FollowLeft(MavLinkDrone drone, Handler handler, double radius) { - super(drone, handler, radius, -90.0); + public FollowLeft(DroneManager droneMgr, Handler handler, double radius) { + super(droneMgr, handler, radius, -90.0); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLookAtMe.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLookAtMe.java index 354d30af6d..9aa190eccb 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLookAtMe.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowLookAtMe.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; @@ -10,8 +11,8 @@ */ public class FollowLookAtMe extends FollowAlgorithm { - public FollowLookAtMe(MavLinkDrone drone, Handler handler) { - super(drone, handler); + public FollowLookAtMe(DroneManager droneMgr, Handler handler) { + super(droneMgr, handler); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowRight.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowRight.java index 30636fb6cb..c59f21442d 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowRight.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowRight.java @@ -2,12 +2,13 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; public class FollowRight extends FollowHeadingAngle { - public FollowRight(MavLinkDrone drone, Handler handler, double radius) { - super(drone, handler, radius, 90.0); + public FollowRight(DroneManager droneMgr, Handler handler, double radius) { + super(droneMgr, handler, radius, 90.0); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSoloShot.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSoloShot.java new file mode 100644 index 0000000000..f197114080 --- /dev/null +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSoloShot.java @@ -0,0 +1,66 @@ +package org.droidplanner.services.android.core.gcs.follow; + +import android.os.Handler; + +import com.o3dr.services.android.lib.coordinate.LatLongAlt; +import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloMessageLocation; + +import org.droidplanner.services.android.core.drone.DroneManager; +import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; +import org.droidplanner.services.android.core.drone.companion.solo.SoloComp; +import org.droidplanner.services.android.core.gcs.location.Location; +import org.droidplanner.services.android.core.gcs.roi.ROIEstimator; +import org.droidplanner.services.android.core.helpers.coordinates.Coord3D; + +/** + * Created by Fredia Huya-Kouadio on 8/3/15. + */ +public class FollowSoloShot extends FollowAlgorithm { + + private final SoloComp soloComp; + + private final LatLongAlt locationCoord = new LatLongAlt(0, 0, 0); + private final SoloMessageLocation locationSetter = new SoloMessageLocation(locationCoord); + + public FollowSoloShot(DroneManager droneMgr, Handler handler) { + super(droneMgr, handler); + this.soloComp = droneMgr.getSoloComp(); + } + + @Override + public void enableFollow(){ + super.enableFollow(); + soloComp.enableFollowDataConnection(); + } + + @Override + public void disableFollow(){ + super.disableFollow(); + soloComp.disableFollowDataConnection(); + } + + @Override + protected void processNewLocation(Location location) { + if(location != null){ + final Coord3D receivedCoord = location.getCoord(); + + locationCoord.setAltitude(receivedCoord.getAltitude()); + locationCoord.setLatitude(receivedCoord.getLat()); + locationCoord.setLongitude(receivedCoord.getLng()); + + locationSetter.setCoordinate(locationCoord); + + soloComp.updateFollowCenter(locationSetter); + } + } + + @Override + public FollowModes getType() { + return FollowModes.SOLO_SHOT; + } + + @Override + protected ROIEstimator initROIEstimator(MavLinkDrone drone, Handler handler){ + return null; + } +} diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineAbove.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineAbove.java index 13a9fbe110..b803fbdbf8 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineAbove.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineAbove.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; @@ -10,6 +11,9 @@ * Created by fhuya on 1/5/15. */ public class FollowSplineAbove extends FollowAlgorithm { + + private final MavLinkDrone drone; + @Override public void processNewLocation(Location location) { Coord2D gcsLoc = new Coord2D(location.getCoord().getLat(), location.getCoord().getLng()); @@ -28,7 +32,8 @@ public FollowModes getType() { return FollowModes.SPLINE_ABOVE; } - public FollowSplineAbove(MavLinkDrone drone, Handler handler) { - super(drone, handler); + public FollowSplineAbove(DroneManager droneManager, Handler handler) { + super(droneManager, handler); + drone = droneManager.getDrone(); } } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineLeash.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineLeash.java index c58b9511da..d8473448fe 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineLeash.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowSplineLeash.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.gcs.location.Location; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.helpers.coordinates.Coord3D; @@ -40,7 +41,7 @@ public FollowModes getType() { return FollowModes.SPLINE_LEASH; } - public FollowSplineLeash(MavLinkDrone drone, Handler handler, double length) { - super(drone, handler, length); + public FollowSplineLeash(DroneManager droneMgr, Handler handler, double length) { + super(droneMgr, handler, length); } } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowWithRadiusAlgorithm.java b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowWithRadiusAlgorithm.java index cf04bd1951..69ebcaed15 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowWithRadiusAlgorithm.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/gcs/follow/FollowWithRadiusAlgorithm.java @@ -2,6 +2,7 @@ import android.os.Handler; +import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; import java.util.HashMap; @@ -14,11 +15,13 @@ public abstract class FollowWithRadiusAlgorithm extends FollowAlgorithm { public static final String EXTRA_FOLLOW_RADIUS = "extra_follow_radius"; + protected final MavLinkDrone drone; protected double radius; - public FollowWithRadiusAlgorithm(MavLinkDrone drone, Handler handler, double radius) { - super(drone, handler); + public FollowWithRadiusAlgorithm(DroneManager droneMgr, Handler handler, double radius) { + super(droneMgr, handler); this.radius = radius; + this.drone = droneMgr.getDrone(); } @Override diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/Mission.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/Mission.java index 7101eba653..10878aaf71 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/Mission.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/Mission.java @@ -13,22 +13,23 @@ import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.helpers.coordinates.Coord3D; import org.droidplanner.services.android.core.helpers.geoTools.GeoTools; -import org.droidplanner.services.android.core.mission.commands.CameraTrigger; -import org.droidplanner.services.android.core.mission.commands.ChangeSpeed; -import org.droidplanner.services.android.core.mission.commands.ConditionYaw; -import org.droidplanner.services.android.core.mission.commands.EpmGripper; +import org.droidplanner.services.android.core.mission.commands.CameraTriggerImpl; +import org.droidplanner.services.android.core.mission.commands.ChangeSpeedImpl; +import org.droidplanner.services.android.core.mission.commands.ConditionYawImpl; import org.droidplanner.services.android.core.mission.commands.DoJumpImpl; -import org.droidplanner.services.android.core.mission.commands.ReturnToHome; +import org.droidplanner.services.android.core.mission.commands.EpmGripperImpl; +import org.droidplanner.services.android.core.mission.commands.ReturnToHomeImpl; import org.droidplanner.services.android.core.mission.commands.SetRelayImpl; -import org.droidplanner.services.android.core.mission.commands.SetServo; -import org.droidplanner.services.android.core.mission.commands.Takeoff; -import org.droidplanner.services.android.core.mission.waypoints.Circle; +import org.droidplanner.services.android.core.mission.commands.SetServoImpl; +import org.droidplanner.services.android.core.mission.commands.TakeoffImpl; +import org.droidplanner.services.android.core.mission.waypoints.CircleImpl; import org.droidplanner.services.android.core.mission.waypoints.DoLandStartImpl; -import org.droidplanner.services.android.core.mission.waypoints.Land; -import org.droidplanner.services.android.core.mission.waypoints.RegionOfInterest; +import org.droidplanner.services.android.core.mission.waypoints.LandImpl; +import org.droidplanner.services.android.core.mission.waypoints.RegionOfInterestImpl; import org.droidplanner.services.android.core.mission.waypoints.SpatialCoordItem; -import org.droidplanner.services.android.core.mission.waypoints.SplineWaypoint; -import org.droidplanner.services.android.core.mission.waypoints.Waypoint; +import org.droidplanner.services.android.core.mission.waypoints.SplineWaypointImpl; +import org.droidplanner.services.android.core.mission.waypoints.WaypointImpl; +import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; import java.util.ArrayList; import java.util.Collections; @@ -134,7 +135,7 @@ public double getLastAltitude() { double alt = defaultAlt; try { SpatialCoordItem lastItem = (SpatialCoordItem) items.get(items.size() - 1); - if (!(lastItem instanceof RegionOfInterest)) { + if (!(lastItem instanceof RegionOfInterestImpl)) { alt = lastItem.getCoordinate().getAltitude(); } } catch (Exception e) { @@ -264,43 +265,43 @@ private List processMavLinkMessages(List msgs) { for (msg_mission_item msg : msgs) { switch (msg.command) { case MAV_CMD.MAV_CMD_DO_SET_SERVO: - received.add(new SetServo(msg, this)); + received.add(new SetServoImpl(msg, this)); break; case MAV_CMD.MAV_CMD_NAV_WAYPOINT: - received.add(new Waypoint(msg, this)); + received.add(new WaypointImpl(msg, this)); break; case MAV_CMD.MAV_CMD_NAV_SPLINE_WAYPOINT: - received.add(new SplineWaypoint(msg, this)); + received.add(new SplineWaypointImpl(msg, this)); break; case MAV_CMD.MAV_CMD_NAV_LAND: - received.add(new Land(msg, this)); + received.add(new LandImpl(msg, this)); break; case MAV_CMD.MAV_CMD_DO_LAND_START: received.add(new DoLandStartImpl(msg, this)); break; case MAV_CMD.MAV_CMD_NAV_TAKEOFF: - received.add(new Takeoff(msg, this)); + received.add(new TakeoffImpl(msg, this)); break; case MAV_CMD.MAV_CMD_DO_CHANGE_SPEED: - received.add(new ChangeSpeed(msg, this)); + received.add(new ChangeSpeedImpl(msg, this)); break; case MAV_CMD.MAV_CMD_DO_SET_CAM_TRIGG_DIST: - received.add(new CameraTrigger(msg, this)); + received.add(new CameraTriggerImpl(msg, this)); break; - case EpmGripper.MAV_CMD_DO_GRIPPER: - received.add(new EpmGripper(msg, this)); + case MAV_CMD.MAV_CMD_DO_GRIPPER: + received.add(new EpmGripperImpl(msg, this)); break; case MAV_CMD.MAV_CMD_DO_SET_ROI: - received.add(new RegionOfInterest(msg, this)); + received.add(new RegionOfInterestImpl(msg, this)); break; case MAV_CMD.MAV_CMD_NAV_LOITER_TURNS: - received.add(new Circle(msg, this)); + received.add(new CircleImpl(msg, this)); break; case MAV_CMD.MAV_CMD_NAV_RETURN_TO_LAUNCH: - received.add(new ReturnToHome(msg, this)); + received.add(new ReturnToHomeImpl(msg, this)); break; case MAV_CMD.MAV_CMD_CONDITION_YAW: - received.add(new ConditionYaw(msg, this)); + received.add(new ConditionYawImpl(msg, this)); break; case MAV_CMD.MAV_CMD_DO_SET_RELAY: received.add(new SetRelayImpl(msg, this)); @@ -393,16 +394,16 @@ public List createDronie(Coord2D start, Coord2D end) { } List dronieItems = new ArrayList(); - dronieItems.add(new Takeoff(this, startAltitude)); - dronieItems.add(new RegionOfInterest(this, + dronieItems.add(new TakeoffImpl(this, startAltitude)); + dronieItems.add(new RegionOfInterestImpl(this, new Coord3D(GeoTools.pointAlongTheLine(start, end, roiDistance), (1.0)))); - dronieItems.add(new Waypoint(this, new Coord3D(end, (startAltitude + GeoTools.getDistance(start, end) / 2.0)))); - dronieItems.add(new Waypoint(this, + dronieItems.add(new WaypointImpl(this, new Coord3D(end, (startAltitude + GeoTools.getDistance(start, end) / 2.0)))); + dronieItems.add(new WaypointImpl(this, new Coord3D(slowDownPoint, (startAltitude + GeoTools.getDistance(start, slowDownPoint) / 2.0)))); - dronieItems.add(new ChangeSpeed(this, 1.0)); - dronieItems.add(new Waypoint(this, new Coord3D(start, startAltitude))); - dronieItems.add(new ChangeSpeed(this, defaultSpeed)); - dronieItems.add(new Land(this, start)); + dronieItems.add(new ChangeSpeedImpl(this, 1.0)); + dronieItems.add(new WaypointImpl(this, new Coord3D(start, startAltitude))); + dronieItems.add(new ChangeSpeedImpl(this, defaultSpeed)); + dronieItems.add(new LandImpl(this, start)); return dronieItems; } @@ -416,7 +417,7 @@ public boolean hasTakeoffAndLandOrRTL() { } public boolean isFirstItemTakeoff() { - return !items.isEmpty() && items.get(0) instanceof Takeoff; + return !items.isEmpty() && items.get(0) instanceof TakeoffImpl; } public boolean isLastItemLandOrRTL() { @@ -424,6 +425,6 @@ public boolean isLastItemLandOrRTL() { return false; MissionItem last = items.get(items.size() - 1); - return (last instanceof ReturnToHome) || (last instanceof Land); + return (last instanceof ReturnToHomeImpl) || (last instanceof LandImpl); } } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/MissionItemType.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/MissionItemType.java index 52424ef87a..d186587fa2 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/MissionItemType.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/MissionItemType.java @@ -1,24 +1,24 @@ package org.droidplanner.services.android.core.mission; import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; -import org.droidplanner.services.android.core.mission.commands.CameraTrigger; -import org.droidplanner.services.android.core.mission.commands.ChangeSpeed; -import org.droidplanner.services.android.core.mission.commands.ConditionYaw; -import org.droidplanner.services.android.core.mission.commands.EpmGripper; +import org.droidplanner.services.android.core.mission.commands.CameraTriggerImpl; +import org.droidplanner.services.android.core.mission.commands.ChangeSpeedImpl; +import org.droidplanner.services.android.core.mission.commands.ConditionYawImpl; import org.droidplanner.services.android.core.mission.commands.DoJumpImpl; -import org.droidplanner.services.android.core.mission.commands.ReturnToHome; +import org.droidplanner.services.android.core.mission.commands.EpmGripperImpl; +import org.droidplanner.services.android.core.mission.commands.ReturnToHomeImpl; import org.droidplanner.services.android.core.mission.commands.SetRelayImpl; -import org.droidplanner.services.android.core.mission.commands.SetServo; -import org.droidplanner.services.android.core.mission.commands.Takeoff; +import org.droidplanner.services.android.core.mission.commands.SetServoImpl; +import org.droidplanner.services.android.core.mission.commands.TakeoffImpl; import org.droidplanner.services.android.core.mission.survey.SplineSurveyImpl; import org.droidplanner.services.android.core.mission.survey.SurveyImpl; -import org.droidplanner.services.android.core.mission.waypoints.Circle; +import org.droidplanner.services.android.core.mission.waypoints.CircleImpl; import org.droidplanner.services.android.core.mission.waypoints.DoLandStartImpl; -import org.droidplanner.services.android.core.mission.waypoints.Land; -import org.droidplanner.services.android.core.mission.waypoints.RegionOfInterest; -import org.droidplanner.services.android.core.mission.waypoints.SplineWaypoint; -import org.droidplanner.services.android.core.mission.waypoints.StructureScanner; -import org.droidplanner.services.android.core.mission.waypoints.Waypoint; +import org.droidplanner.services.android.core.mission.waypoints.LandImpl; +import org.droidplanner.services.android.core.mission.waypoints.RegionOfInterestImpl; +import org.droidplanner.services.android.core.mission.waypoints.SplineWaypointImpl; +import org.droidplanner.services.android.core.mission.waypoints.StructureScannerImpl; +import org.droidplanner.services.android.core.mission.waypoints.WaypointImpl; import java.util.Collections; @@ -55,35 +55,35 @@ public String getName() { public MissionItem getNewItem(MissionItem referenceItem) throws IllegalArgumentException { switch (this) { case WAYPOINT: - return new Waypoint(referenceItem); + return new WaypointImpl(referenceItem); case SPLINE_WAYPOINT: - return new SplineWaypoint(referenceItem); + return new SplineWaypointImpl(referenceItem); case TAKEOFF: - return new Takeoff(referenceItem); + return new TakeoffImpl(referenceItem); case CHANGE_SPEED: - return new ChangeSpeed(referenceItem); + return new ChangeSpeedImpl(referenceItem); case CAMERA_TRIGGER: - return new CameraTrigger(referenceItem); + return new CameraTriggerImpl(referenceItem); case EPM_GRIPPER: - return new EpmGripper(referenceItem); + return new EpmGripperImpl(referenceItem); case RTL: - return new ReturnToHome(referenceItem); + return new ReturnToHomeImpl(referenceItem); case LAND: - return new Land(referenceItem); + return new LandImpl(referenceItem); case CIRCLE: - return new Circle(referenceItem); + return new CircleImpl(referenceItem); case ROI: - return new RegionOfInterest(referenceItem); + return new RegionOfInterestImpl(referenceItem); case SURVEY: return new SurveyImpl(referenceItem.getMission(), Collections.emptyList()); case SPLINE_SURVEY: return new SplineSurveyImpl(referenceItem.getMission(), Collections.emptyList()); case CYLINDRICAL_SURVEY: - return new StructureScanner(referenceItem); + return new StructureScannerImpl(referenceItem); case SET_SERVO: - return new SetServo(referenceItem); + return new SetServoImpl(referenceItem); case CONDITION_YAW: - return new ConditionYaw(referenceItem); + return new ConditionYawImpl(referenceItem); case SET_RELAY: return new SetRelayImpl(referenceItem); case DO_LAND_START: diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/CameraTrigger.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/CameraTriggerImpl.java similarity index 84% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/commands/CameraTrigger.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/commands/CameraTriggerImpl.java index cf4ac615dd..df896c15fb 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/CameraTrigger.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/CameraTriggerImpl.java @@ -9,19 +9,19 @@ import java.util.List; -public class CameraTrigger extends MissionCMD { +public class CameraTriggerImpl extends MissionCMD { private double distance = (0); - public CameraTrigger(MissionItem item) { + public CameraTriggerImpl(MissionItem item) { super(item); } - public CameraTrigger(msg_mission_item msg, Mission mission) { + public CameraTriggerImpl(msg_mission_item msg, Mission mission) { super(mission); unpackMAVMessage(msg); } - public CameraTrigger(Mission mission, double triggerDistance) { + public CameraTriggerImpl(Mission mission, double triggerDistance) { super(mission); this.distance = triggerDistance; } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ChangeSpeed.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ChangeSpeedImpl.java similarity index 86% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ChangeSpeed.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ChangeSpeedImpl.java index ebf6b5e23d..6b54166eb3 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ChangeSpeed.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ChangeSpeedImpl.java @@ -10,19 +10,19 @@ import com.MAVLink.enums.MAV_CMD; import com.MAVLink.enums.MAV_FRAME; -public class ChangeSpeed extends MissionCMD { +public class ChangeSpeedImpl extends MissionCMD { private double speed = 5; //meters per second - public ChangeSpeed(MissionItem item) { + public ChangeSpeedImpl(MissionItem item) { super(item); } - public ChangeSpeed(msg_mission_item msg, Mission mission) { + public ChangeSpeedImpl(msg_mission_item msg, Mission mission) { super(mission); unpackMAVMessage(msg); } - public ChangeSpeed(Mission mission, double speed) { + public ChangeSpeedImpl(Mission mission, double speed) { super(mission); this.speed = speed; } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ConditionYaw.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ConditionYawImpl.java similarity index 88% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ConditionYaw.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ConditionYawImpl.java index d906da8c5b..ff45e9f76c 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ConditionYaw.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ConditionYawImpl.java @@ -10,21 +10,21 @@ import com.MAVLink.common.msg_mission_item; import com.MAVLink.enums.MAV_CMD; -public class ConditionYaw extends MissionCMD { +public class ConditionYawImpl extends MissionCMD { private boolean isRelative = false; private double angle = 0; private double angularSpeed = 0; - public ConditionYaw(MissionItem item) { + public ConditionYawImpl(MissionItem item) { super(item); } - public ConditionYaw(msg_mission_item msg, Mission mission) { + public ConditionYawImpl(msg_mission_item msg, Mission mission) { super(mission); unpackMAVMessage(msg); } - public ConditionYaw(Mission mission, double angle, boolean isRelative) { + public ConditionYawImpl(Mission mission, double angle, boolean isRelative) { super(mission); setAngle(angle); setRelative(isRelative); diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/EpmGripper.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/EpmGripperImpl.java similarity index 61% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/commands/EpmGripper.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/commands/EpmGripperImpl.java index 8d4c3dfadf..24ea65eb3a 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/EpmGripper.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/EpmGripperImpl.java @@ -7,25 +7,23 @@ import org.droidplanner.services.android.core.mission.MissionItemType; import com.MAVLink.common.msg_mission_item; +import com.MAVLink.enums.GRIPPER_ACTIONS; +import com.MAVLink.enums.MAV_CMD; -public class EpmGripper extends MissionCMD { - // TODO Update mavlink and use the correct enum here - public final static short MAV_CMD_DO_GRIPPER = 211; - public final static int GRIPPER_ACTION_RELEASE = 0; - public final static int GRIPPER_ACTION_GRAB = 1; +public class EpmGripperImpl extends MissionCMD { private boolean release = true; - public EpmGripper(MissionItem item) { + public EpmGripperImpl(MissionItem item) { super(item); } - public EpmGripper(msg_mission_item msg, Mission mission) { + public EpmGripperImpl(msg_mission_item msg, Mission mission) { super(mission); unpackMAVMessage(msg); } - public EpmGripper(Mission mission, boolean release) { + public EpmGripperImpl(Mission mission, boolean release) { super(mission); this.release = release; } @@ -34,16 +32,16 @@ public EpmGripper(Mission mission, boolean release) { public List packMissionItem() { List list = super.packMissionItem(); msg_mission_item mavMsg = list.get(0); - mavMsg.command = MAV_CMD_DO_GRIPPER; - mavMsg.param2 = release ? GRIPPER_ACTION_RELEASE : GRIPPER_ACTION_GRAB; + mavMsg.command = MAV_CMD.MAV_CMD_DO_GRIPPER; + mavMsg.param2 = release ? GRIPPER_ACTIONS.GRIPPER_ACTION_RELEASE : GRIPPER_ACTIONS.GRIPPER_ACTION_GRAB; return list; } @Override public void unpackMAVMessage(msg_mission_item mavMsg) { - if (mavMsg.param2 == GRIPPER_ACTION_GRAB) { + if (mavMsg.param2 == GRIPPER_ACTIONS.GRIPPER_ACTION_GRAB) { release = false; - } else if (mavMsg.param2 == GRIPPER_ACTION_RELEASE) { + } else if (mavMsg.param2 == GRIPPER_ACTIONS.GRIPPER_ACTION_RELEASE) { release = true; } } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ReturnToHome.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ReturnToHomeImpl.java similarity index 86% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ReturnToHome.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ReturnToHomeImpl.java index e86c105c27..40aa6e1c62 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ReturnToHome.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/ReturnToHomeImpl.java @@ -10,21 +10,21 @@ import java.util.List; -public class ReturnToHome extends MissionCMD { +public class ReturnToHomeImpl extends MissionCMD { private double returnAltitude; - public ReturnToHome(MissionItem item) { + public ReturnToHomeImpl(MissionItem item) { super(item); returnAltitude = (0); } - public ReturnToHome(msg_mission_item msg, Mission mission) { + public ReturnToHomeImpl(msg_mission_item msg, Mission mission) { super(mission); unpackMAVMessage(msg); } - public ReturnToHome(Mission mission) { + public ReturnToHomeImpl(Mission mission) { super(mission); returnAltitude = (0.0); } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/SetServo.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/SetServoImpl.java similarity index 85% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/commands/SetServo.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/commands/SetServoImpl.java index d473823639..2a99be6088 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/SetServo.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/SetServoImpl.java @@ -9,21 +9,21 @@ import com.MAVLink.common.msg_mission_item; import com.MAVLink.enums.MAV_CMD; -public class SetServo extends MissionCMD { +public class SetServoImpl extends MissionCMD { private int pwm; private int channel; - public SetServo(MissionItem item) { + public SetServoImpl(MissionItem item) { super(item); } - public SetServo(msg_mission_item msg, Mission mission) { + public SetServoImpl(msg_mission_item msg, Mission mission) { super(mission); unpackMAVMessage(msg); } - public SetServo(Mission mission, int channel, int pwm) { + public SetServoImpl(Mission mission, int channel, int pwm) { super(mission); this.channel = channel; this.pwm = pwm; diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/Takeoff.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/TakeoffImpl.java similarity index 86% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/commands/Takeoff.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/commands/TakeoffImpl.java index 34b4263d65..47deccecb4 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/Takeoff.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/commands/TakeoffImpl.java @@ -10,29 +10,29 @@ import java.util.List; -public class Takeoff extends MissionCMD { +public class TakeoffImpl extends MissionCMD { public static final double DEFAULT_TAKEOFF_ALTITUDE = 10.0; private double finishedAlt = 10; private double pitch = 0; - public Takeoff(MissionItem item) { + public TakeoffImpl(MissionItem item) { super(item); } - public Takeoff(msg_mission_item msg, Mission mission) { + public TakeoffImpl(msg_mission_item msg, Mission mission) { super(mission); unpackMAVMessage(msg); } - public Takeoff(Mission mission, double altitude) { + public TakeoffImpl(Mission mission, double altitude) { super(mission); this.finishedAlt = altitude; this.pitch = 0; } - public Takeoff(Mission mission, double altitude, double pitch) { + public TakeoffImpl(Mission mission, double altitude, double pitch) { super(mission); this.finishedAlt = altitude; this.pitch = pitch; diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/survey/SurveyImpl.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/survey/SurveyImpl.java index e942b215da..87c9a0495e 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/survey/SurveyImpl.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/survey/SurveyImpl.java @@ -8,7 +8,7 @@ import org.droidplanner.services.android.core.mission.Mission; import org.droidplanner.services.android.core.mission.MissionItem; import org.droidplanner.services.android.core.mission.MissionItemType; -import org.droidplanner.services.android.core.mission.commands.CameraTrigger; +import org.droidplanner.services.android.core.mission.commands.CameraTriggerImpl; import org.droidplanner.services.android.core.polygon.Polygon; import org.droidplanner.services.android.core.survey.CameraInfo; import org.droidplanner.services.android.core.survey.SurveyData; @@ -51,9 +51,9 @@ public List packMissionItem() { List list = new ArrayList(); build(); - list.addAll((new CameraTrigger(mission, surveyData.getLongitudinalPictureDistance())).packMissionItem()); + list.addAll((new CameraTriggerImpl(mission, surveyData.getLongitudinalPictureDistance())).packMissionItem()); packGridPoints(list); - list.addAll((new CameraTrigger(mission, (0.0)).packMissionItem())); + list.addAll((new CameraTriggerImpl(mission, (0.0)).packMissionItem())); return list; } catch (Exception e) { diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Circle.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/CircleImpl.java similarity index 89% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Circle.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/CircleImpl.java index dff99ed252..ef93238577 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Circle.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/CircleImpl.java @@ -12,20 +12,20 @@ import com.MAVLink.enums.MAV_CMD; import com.MAVLink.enums.MAV_FRAME; -public class Circle extends SpatialCoordItem { +public class CircleImpl extends SpatialCoordItem { private double radius = 10.0; private int turns = 1; - public Circle(MissionItem item) { + public CircleImpl(MissionItem item) { super(item); } - public Circle(Mission mission, Coord3D coord) { + public CircleImpl(Mission mission, Coord3D coord) { super(mission, coord); } - public Circle(msg_mission_item msg, Mission mission) { + public CircleImpl(msg_mission_item msg, Mission mission) { super(mission, null); unpackMAVMessage(msg); } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Land.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/LandImpl.java similarity index 83% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Land.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/LandImpl.java index f4ac48c45b..8638a07ba2 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Land.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/LandImpl.java @@ -11,22 +11,22 @@ import java.util.List; -public class Land extends SpatialCoordItem { +public class LandImpl extends SpatialCoordItem { - public Land(MissionItem item) { + public LandImpl(MissionItem item) { super(item); setAltitude((0.0)); } - public Land(Mission mission) { + public LandImpl(Mission mission) { this(mission, new Coord2D(0, 0)); } - public Land(Mission mMission, Coord2D coord) { + public LandImpl(Mission mMission, Coord2D coord) { super(mMission, new Coord3D(coord, (0))); } - public Land(msg_mission_item msg, Mission mission) { + public LandImpl(msg_mission_item msg, Mission mission) { super(mission, null); unpackMAVMessage(msg); } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/RegionOfInterest.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/RegionOfInterestImpl.java similarity index 79% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/RegionOfInterest.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/RegionOfInterestImpl.java index 484613afc4..0023cb125a 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/RegionOfInterest.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/RegionOfInterestImpl.java @@ -10,18 +10,18 @@ import com.MAVLink.common.msg_mission_item; import com.MAVLink.enums.MAV_CMD; -public class RegionOfInterest extends SpatialCoordItem { +public class RegionOfInterestImpl extends SpatialCoordItem { - public RegionOfInterest(MissionItem item) { + public RegionOfInterestImpl(MissionItem item) { super(item); } - public RegionOfInterest(Mission mission,Coord3D coord) { + public RegionOfInterestImpl(Mission mission, Coord3D coord) { super(mission,coord); } - public RegionOfInterest(msg_mission_item msg, Mission mission) { + public RegionOfInterestImpl(msg_mission_item msg, Mission mission) { super(mission, null); unpackMAVMessage(msg); } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/SplineWaypoint.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/SplineWaypointImpl.java similarity index 85% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/SplineWaypoint.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/SplineWaypointImpl.java index cdbffdb99f..c15d218473 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/SplineWaypoint.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/SplineWaypointImpl.java @@ -13,7 +13,7 @@ /** * Handle spline waypoint mavlink packet generation. */ -public class SplineWaypoint extends SpatialCoordItem { +public class SplineWaypointImpl extends SpatialCoordItem { /** * Hold time in decimal seconds. (ignored by fixed wing, time to stay at @@ -21,15 +21,15 @@ public class SplineWaypoint extends SpatialCoordItem { */ private double delay; - public SplineWaypoint(MissionItem item) { + public SplineWaypointImpl(MissionItem item) { super(item); } - public SplineWaypoint(Mission mission, Coord3D coord) { + public SplineWaypointImpl(Mission mission, Coord3D coord) { super(mission, coord); } - public SplineWaypoint(msg_mission_item msg, Mission mission) { + public SplineWaypointImpl(msg_mission_item msg, Mission mission) { super(mission, null); unpackMAVMessage(msg); } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/StructureScanner.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/StructureScannerImpl.java similarity index 91% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/StructureScanner.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/StructureScannerImpl.java index 07165f6ded..2eb4508d95 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/StructureScanner.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/StructureScannerImpl.java @@ -18,18 +18,18 @@ import java.util.ArrayList; import java.util.List; -public class StructureScanner extends SpatialCoordItem { +public class StructureScannerImpl extends SpatialCoordItem { private double radius = (10.0); private double heightStep = (5); private int numberOfSteps = 2; private boolean crossHatch = false; SurveyData survey = new SurveyData(); - public StructureScanner(Mission mission, Coord3D coord) { + public StructureScannerImpl(Mission mission, Coord3D coord) { super(mission, coord); } - public StructureScanner(MissionItem item) { + public StructureScannerImpl(MissionItem item) { super(item); } @@ -45,16 +45,16 @@ public List packMissionItem() { } private void packROI(List list) { - RegionOfInterest roi = new RegionOfInterest(mission, new Coord3D( + RegionOfInterestImpl roi = new RegionOfInterestImpl(mission, new Coord3D( coordinate, (0.0))); list.addAll(roi.packMissionItem()); } private void packCircles(List list) { for (double altitude = coordinate.getAltitude(); altitude <= getTopHeight(); altitude += heightStep) { - Circle circle = new Circle(mission, new Coord3D(coordinate, (altitude))); - circle.setRadius(radius); - list.addAll(circle.packMissionItem()); + CircleImpl circleImpl = new CircleImpl(mission, new Coord3D(coordinate, (altitude))); + circleImpl.setRadius(radius); + list.addAll(circleImpl.packMissionItem()); } } diff --git a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Waypoint.java b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/WaypointImpl.java similarity index 91% rename from ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Waypoint.java rename to ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/WaypointImpl.java index 0e74ef8aa8..3eef96704a 100644 --- a/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/Waypoint.java +++ b/ServiceApp/src/org/droidplanner/services/android/core/mission/waypoints/WaypointImpl.java @@ -10,7 +10,7 @@ import com.MAVLink.common.msg_mission_item; import com.MAVLink.enums.MAV_CMD; -public class Waypoint extends SpatialCoordItem { +public class WaypointImpl extends SpatialCoordItem { private double delay; private double acceptanceRadius; @@ -18,15 +18,15 @@ public class Waypoint extends SpatialCoordItem { private double orbitalRadius; private boolean orbitCCW; - public Waypoint(MissionItem item) { + public WaypointImpl(MissionItem item) { super(item); } - public Waypoint(Mission mission, Coord3D coord) { + public WaypointImpl(Mission mission, Coord3D coord) { super(mission, coord); } - public Waypoint(msg_mission_item msg, Mission mission) { + public WaypointImpl(msg_mission_item msg, Mission mission) { super(mission, null); unpackMAVMessage(msg); } diff --git a/ServiceApp/src/org/droidplanner/services/android/utils/CommonApiUtils.java b/ServiceApp/src/org/droidplanner/services/android/utils/CommonApiUtils.java index 9573c54c80..46638cda36 100644 --- a/ServiceApp/src/org/droidplanner/services/android/utils/CommonApiUtils.java +++ b/ServiceApp/src/org/droidplanner/services/android/utils/CommonApiUtils.java @@ -5,8 +5,6 @@ import android.os.Handler; import android.os.RemoteException; import android.text.TextUtils; -import android.util.Pair; -import android.view.Surface; import com.MAVLink.Messages.MAVLinkMessage; import com.MAVLink.ardupilotmega.msg_ekf_status_report; @@ -22,10 +20,6 @@ import com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationProgress; import com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationResult; import com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationStatus; -import com.o3dr.services.android.lib.drone.companion.solo.SoloControllerMode; -import com.o3dr.services.android.lib.drone.companion.solo.SoloLinkState; -import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter; -import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket; import com.o3dr.services.android.lib.drone.mission.Mission; import com.o3dr.services.android.lib.drone.mission.MissionItemType; import com.o3dr.services.android.lib.drone.mission.item.MissionItem; @@ -57,7 +51,6 @@ import org.droidplanner.services.android.core.MAVLink.command.doCmd.MavLinkDoCmds; import org.droidplanner.services.android.core.drone.DroneManager; import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone; -import org.droidplanner.services.android.core.drone.companion.solo.SoloComp; import org.droidplanner.services.android.core.drone.profiles.VehicleProfile; import org.droidplanner.services.android.core.drone.variables.ApmModes; import org.droidplanner.services.android.core.drone.variables.Camera; @@ -72,6 +65,7 @@ import org.droidplanner.services.android.core.helpers.coordinates.Coord3D; import org.droidplanner.services.android.core.mission.survey.SplineSurveyImpl; import org.droidplanner.services.android.core.mission.survey.SurveyImpl; +import org.droidplanner.services.android.core.mission.waypoints.StructureScannerImpl; import org.droidplanner.services.android.core.survey.Footprint; import org.droidplanner.services.android.utils.file.IO.ParameterMetadataLoader; import org.xmlpull.v1.XmlPullParserException; @@ -303,6 +297,10 @@ public static FollowAlgorithm.FollowModes followTypeToMode(FollowType followType case LOOK_AT_ME: followMode = FollowAlgorithm.FollowModes.LOOK_AT_ME; break; + + case SOLO_SHOT: + followMode = FollowAlgorithm.FollowModes.SOLO_SHOT; + break; } return followMode; } @@ -351,6 +349,10 @@ public static FollowType followModeToType(FollowAlgorithm.FollowModes followMode case LOOK_AT_ME: followType = FollowType.LOOK_AT_ME; break; + + case SOLO_SHOT: + followType = FollowType.SOLO_SHOT; + break; } return followType; @@ -934,7 +936,7 @@ public static void setGuidedAltitude(MavLinkDrone drone, double altitude) { drone.getGuidedPoint().changeGuidedAltitude(altitude); } - public static void enableFollowMe(DroneManager droneMgr, Handler droneHandler, FollowType followType) { + public static void enableFollowMe(DroneManager droneMgr, Handler droneHandler, FollowType followType, ICommandListener listener) { if (droneMgr == null) return; @@ -950,7 +952,11 @@ public static void enableFollowMe(DroneManager droneMgr, Handler droneHandler, F FollowAlgorithm currentAlg = followMe.getFollowAlgorithm(); if (currentAlg.getType() != selectedMode) { - followMe.setAlgorithm(selectedMode.getAlgorithmType(droneMgr.getDrone(), droneHandler)); + if(selectedMode == FollowAlgorithm.FollowModes.SOLO_SHOT && !SoloApiUtils.isSoloLinkFeatureAvailable(droneMgr, listener)) + return; + + followMe.setAlgorithm(selectedMode.getAlgorithmType(droneMgr, droneHandler)); + postSuccessEvent(listener); } } } @@ -1014,7 +1020,7 @@ public static Survey buildSplineSurvey(MavLinkDrone drone, Survey survey) { public static StructureScanner buildStructureScanner(MavLinkDrone drone, StructureScanner item) { org.droidplanner.services.android.core.mission.Mission droneMission = drone == null ? null : drone.getMission(); - org.droidplanner.services.android.core.mission.waypoints.StructureScanner updatedScan = (org.droidplanner.services.android.core.mission.waypoints.StructureScanner) ProxyUtils + StructureScannerImpl updatedScan = (StructureScannerImpl) ProxyUtils .getMissionItemImpl(droneMission, item); StructureScanner proxyScanner = (StructureScanner) ProxyUtils.getProxyMissionItem(updatedScan); diff --git a/ServiceApp/src/org/droidplanner/services/android/utils/ProxyUtils.java b/ServiceApp/src/org/droidplanner/services/android/utils/ProxyUtils.java index 7908a9ab5f..df449609a4 100644 --- a/ServiceApp/src/org/droidplanner/services/android/utils/ProxyUtils.java +++ b/ServiceApp/src/org/droidplanner/services/android/utils/ProxyUtils.java @@ -26,13 +26,24 @@ import org.droidplanner.services.android.core.helpers.coordinates.Coord2D; import org.droidplanner.services.android.core.mission.Mission; -import org.droidplanner.services.android.core.mission.commands.ConditionYaw; +import org.droidplanner.services.android.core.mission.commands.CameraTriggerImpl; +import org.droidplanner.services.android.core.mission.commands.ChangeSpeedImpl; +import org.droidplanner.services.android.core.mission.commands.ConditionYawImpl; import org.droidplanner.services.android.core.mission.commands.DoJumpImpl; -import org.droidplanner.services.android.core.mission.commands.ReturnToHome; +import org.droidplanner.services.android.core.mission.commands.EpmGripperImpl; +import org.droidplanner.services.android.core.mission.commands.ReturnToHomeImpl; import org.droidplanner.services.android.core.mission.commands.SetRelayImpl; +import org.droidplanner.services.android.core.mission.commands.SetServoImpl; +import org.droidplanner.services.android.core.mission.commands.TakeoffImpl; import org.droidplanner.services.android.core.mission.survey.SplineSurveyImpl; import org.droidplanner.services.android.core.mission.survey.SurveyImpl; +import org.droidplanner.services.android.core.mission.waypoints.CircleImpl; import org.droidplanner.services.android.core.mission.waypoints.DoLandStartImpl; +import org.droidplanner.services.android.core.mission.waypoints.LandImpl; +import org.droidplanner.services.android.core.mission.waypoints.RegionOfInterestImpl; +import org.droidplanner.services.android.core.mission.waypoints.SplineWaypointImpl; +import org.droidplanner.services.android.core.mission.waypoints.StructureScannerImpl; +import org.droidplanner.services.android.core.mission.waypoints.WaypointImpl; import org.droidplanner.services.android.core.survey.CameraInfo; import org.droidplanner.services.android.core.survey.SurveyData; @@ -88,7 +99,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case CAMERA_TRIGGER: { CameraTrigger proxy = (CameraTrigger) proxyItem; - org.droidplanner.services.android.core.mission.commands.CameraTrigger temp = new org.droidplanner.services.android.core.mission.commands.CameraTrigger(mission, (proxy.getTriggerDistance())); + CameraTriggerImpl temp = new CameraTriggerImpl(mission, (proxy.getTriggerDistance())); missionItemImpl = temp; break; @@ -96,7 +107,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case CHANGE_SPEED: { ChangeSpeed proxy = (ChangeSpeed) proxyItem; - org.droidplanner.services.android.core.mission.commands.ChangeSpeed temp = new org.droidplanner.services.android.core.mission.commands.ChangeSpeed(mission, proxy.getSpeed()); + ChangeSpeedImpl temp = new ChangeSpeedImpl(mission, proxy.getSpeed()); missionItemImpl = temp; break; @@ -104,7 +115,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case EPM_GRIPPER: { EpmGripper proxy = (EpmGripper) proxyItem; - org.droidplanner.services.android.core.mission.commands.EpmGripper temp = new org.droidplanner.services.android.core.mission.commands.EpmGripper(mission, proxy.isRelease()); + EpmGripperImpl temp = new EpmGripperImpl(mission, proxy.isRelease()); missionItemImpl = temp; break; @@ -112,7 +123,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case RETURN_TO_LAUNCH: { ReturnToLaunch proxy = (ReturnToLaunch) proxyItem; - ReturnToHome temp = new ReturnToHome(mission); + ReturnToHomeImpl temp = new ReturnToHomeImpl(mission); temp.setHeight((proxy.getReturnAltitude())); missionItemImpl = temp; @@ -121,8 +132,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case SET_SERVO: { SetServo proxy = (SetServo) proxyItem; - org.droidplanner.services.android.core.mission.commands.SetServo temp = new org.droidplanner.services.android.core - .mission.commands.SetServo(mission, proxy.getChannel(), proxy.getPwm()); + SetServoImpl temp = new SetServoImpl(mission, proxy.getChannel(), proxy.getPwm()); missionItemImpl = temp; break; @@ -130,8 +140,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case TAKEOFF: { Takeoff proxy = (Takeoff) proxyItem; - org.droidplanner.services.android.core.mission.commands.Takeoff temp = new org.droidplanner.services.android.core - .mission.commands.Takeoff(mission, proxy.getTakeoffAltitude(), proxy.getTakeoffPitch()); + TakeoffImpl temp = new TakeoffImpl(mission, (proxy.getTakeoffAltitude())); missionItemImpl = temp; break; @@ -139,8 +148,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case CIRCLE: { Circle proxy = (Circle) proxyItem; - org.droidplanner.services.android.core.mission.waypoints.Circle temp = new org.droidplanner.services.android.core - .mission.waypoints.Circle(mission, MathUtils.latLongAltToCoord3D(proxy + CircleImpl temp = new CircleImpl(mission, MathUtils.latLongAltToCoord3D(proxy .getCoordinate())); temp.setRadius(proxy.getRadius()); temp.setTurns(proxy.getTurns()); @@ -151,8 +159,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case LAND: { Land proxy = (Land) proxyItem; - org.droidplanner.services.android.core.mission.waypoints.Land temp = new org.droidplanner.services.android.core - .mission.waypoints.Land(mission, MathUtils.latLongToCoord2D(proxy + LandImpl temp = new LandImpl(mission, MathUtils.latLongToCoord2D(proxy .getCoordinate())); missionItemImpl = temp; @@ -170,7 +177,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case REGION_OF_INTEREST: { RegionOfInterest proxy = (RegionOfInterest) proxyItem; - org.droidplanner.services.android.core.mission.waypoints.RegionOfInterest temp = new org.droidplanner.services.android.core.mission.waypoints.RegionOfInterest(mission, + RegionOfInterestImpl temp = new RegionOfInterestImpl(mission, MathUtils.latLongAltToCoord3D(proxy.getCoordinate())); missionItemImpl = temp; @@ -179,7 +186,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case SPLINE_WAYPOINT: { SplineWaypoint proxy = (SplineWaypoint) proxyItem; - org.droidplanner.services.android.core.mission.waypoints.SplineWaypoint temp = new org.droidplanner.services.android.core.mission.waypoints.SplineWaypoint(mission, + SplineWaypointImpl temp = new SplineWaypointImpl(mission, MathUtils.latLongAltToCoord3D(proxy.getCoordinate())); temp.setDelay(proxy.getDelay()); @@ -189,7 +196,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case STRUCTURE_SCANNER: { StructureScanner proxy = (StructureScanner) proxyItem; - org.droidplanner.services.android.core.mission.waypoints.StructureScanner temp = new org.droidplanner.services.android.core.mission.waypoints.StructureScanner(mission, + StructureScannerImpl temp = new StructureScannerImpl(mission, MathUtils.latLongAltToCoord3D(proxy.getCoordinate())); temp.setRadius((int) proxy.getRadius()); temp.setNumberOfSteps(proxy.getStepsCount()); @@ -206,8 +213,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case WAYPOINT: { Waypoint proxy = (Waypoint) proxyItem; - org.droidplanner.services.android.core.mission.waypoints.Waypoint temp = new org.droidplanner.services.android.core - .mission.waypoints.Waypoint(mission, MathUtils.latLongAltToCoord3D(proxy + WaypointImpl temp = new WaypointImpl(mission, MathUtils.latLongAltToCoord3D(proxy .getCoordinate())); temp.setAcceptanceRadius(proxy.getAcceptanceRadius()); temp.setDelay(proxy.getDelay()); @@ -271,7 +277,7 @@ public static org.droidplanner.services.android.core.mission.MissionItem getMiss case YAW_CONDITION: { YawCondition proxy = (YawCondition) proxyItem; - ConditionYaw temp = new ConditionYaw(mission, proxy.getAngle(), proxy.isRelative()); + ConditionYawImpl temp = new ConditionYawImpl(mission, proxy.getAngle(), proxy.isRelative()); temp.setAngularSpeed(proxy.getAngularSpeed()); missionItemImpl = temp; @@ -305,7 +311,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. MissionItem proxyMissionItem; switch (itemImpl.getType()) { case WAYPOINT: { - org.droidplanner.services.android.core.mission.waypoints.Waypoint source = (org.droidplanner.services.android.core.mission.waypoints.Waypoint) itemImpl; + WaypointImpl source = (WaypointImpl) itemImpl; Waypoint temp = new Waypoint(); temp.setCoordinate(MathUtils.coord3DToLatLongAlt(source.getCoordinate())); @@ -320,7 +326,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. } case SPLINE_WAYPOINT: { - org.droidplanner.services.android.core.mission.waypoints.SplineWaypoint source = (org.droidplanner.services.android.core.mission.waypoints.SplineWaypoint) itemImpl; + SplineWaypointImpl source = (SplineWaypointImpl) itemImpl; SplineWaypoint temp = new SplineWaypoint(); temp.setCoordinate(MathUtils.coord3DToLatLongAlt(source.getCoordinate())); @@ -331,7 +337,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. } case TAKEOFF: { - org.droidplanner.services.android.core.mission.commands.Takeoff source = (org.droidplanner.services.android.core.mission.commands.Takeoff) itemImpl; + TakeoffImpl source = (TakeoffImpl) itemImpl; Takeoff temp = new Takeoff(); temp.setTakeoffAltitude(source.getFinishedAlt()); @@ -341,7 +347,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. break; } case RTL: { - ReturnToHome source = (ReturnToHome) itemImpl; + ReturnToHomeImpl source = (ReturnToHomeImpl) itemImpl; ReturnToLaunch temp = new ReturnToLaunch(); temp.setReturnAltitude(source.getHeight()); @@ -350,7 +356,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. break; } case LAND: { - org.droidplanner.services.android.core.mission.waypoints.Land source = (org.droidplanner.services.android.core.mission.waypoints.Land) itemImpl; + LandImpl source = (LandImpl) itemImpl; Land temp = new Land(); temp.setCoordinate(MathUtils.coord3DToLatLongAlt(source.getCoordinate())); @@ -368,7 +374,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. break; } case CIRCLE: { - org.droidplanner.services.android.core.mission.waypoints.Circle source = (org.droidplanner.services.android.core.mission.waypoints.Circle) itemImpl; + CircleImpl source = (CircleImpl) itemImpl; Circle temp = new Circle(); temp.setCoordinate(MathUtils.coord3DToLatLongAlt(source.getCoordinate())); @@ -380,7 +386,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. } case ROI: { - org.droidplanner.services.android.core.mission.waypoints.RegionOfInterest source = (org.droidplanner.services.android.core.mission.waypoints.RegionOfInterest) itemImpl; + RegionOfInterestImpl source = (RegionOfInterestImpl) itemImpl; RegionOfInterest temp = new RegionOfInterest(); temp.setCoordinate(MathUtils.coord3DToLatLongAlt(source.getCoordinate())); @@ -442,7 +448,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. } case CYLINDRICAL_SURVEY: { - org.droidplanner.services.android.core.mission.waypoints.StructureScanner source = (org.droidplanner.services.android.core.mission.waypoints.StructureScanner) itemImpl; + StructureScannerImpl source = (StructureScannerImpl) itemImpl; StructureScanner temp = new StructureScanner(); temp.setSurveyDetail(getSurveyDetail(source.getSurveyData())); @@ -458,7 +464,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. } case CHANGE_SPEED: { - org.droidplanner.services.android.core.mission.commands.ChangeSpeed source = (org.droidplanner.services.android.core.mission.commands.ChangeSpeed) itemImpl; + ChangeSpeedImpl source = (ChangeSpeedImpl) itemImpl; ChangeSpeed temp = new ChangeSpeed(); temp.setSpeed(source.getSpeed()); @@ -468,7 +474,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. } case CAMERA_TRIGGER: { - org.droidplanner.services.android.core.mission.commands.CameraTrigger source = (org.droidplanner.services.android.core.mission.commands.CameraTrigger) itemImpl; + CameraTriggerImpl source = (CameraTriggerImpl) itemImpl; CameraTrigger temp = new CameraTrigger(); temp.setTriggerDistance(source.getTriggerDistance()); @@ -477,7 +483,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. break; } case EPM_GRIPPER: { - org.droidplanner.services.android.core.mission.commands.EpmGripper source = (org.droidplanner.services.android.core.mission.commands.EpmGripper) itemImpl; + EpmGripperImpl source = (EpmGripperImpl) itemImpl; EpmGripper temp = new EpmGripper(); temp.setRelease(source.isRelease()); @@ -487,7 +493,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. } case SET_SERVO: { - org.droidplanner.services.android.core.mission.commands.SetServo source = (org.droidplanner.services.android.core.mission.commands.SetServo) itemImpl; + SetServoImpl source = (SetServoImpl) itemImpl; SetServo temp = new SetServo(); temp.setChannel(source.getChannel()); @@ -497,7 +503,7 @@ public static MissionItem getProxyMissionItem(org.droidplanner.services.android. break; } case CONDITION_YAW: { - ConditionYaw source = (ConditionYaw) itemImpl; + ConditionYawImpl source = (ConditionYawImpl) itemImpl; YawCondition temp = new YawCondition(); temp.setAngle(source.getAngle()); diff --git a/ServiceApp/src/org/droidplanner/services/android/utils/SoloLinkApiUtils.java b/ServiceApp/src/org/droidplanner/services/android/utils/SoloApiUtils.java similarity index 90% rename from ServiceApp/src/org/droidplanner/services/android/utils/SoloLinkApiUtils.java rename to ServiceApp/src/org/droidplanner/services/android/utils/SoloApiUtils.java index f1b974e2d2..aa8ce5cce6 100644 --- a/ServiceApp/src/org/droidplanner/services/android/utils/SoloLinkApiUtils.java +++ b/ServiceApp/src/org/droidplanner/services/android/utils/SoloApiUtils.java @@ -5,8 +5,8 @@ import android.view.Surface; import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError; -import com.o3dr.services.android.lib.drone.companion.solo.SoloControllerMode; -import com.o3dr.services.android.lib.drone.companion.solo.SoloLinkState; +import com.o3dr.services.android.lib.drone.companion.solo.controller.SoloControllerMode; +import com.o3dr.services.android.lib.drone.companion.solo.SoloState; import com.o3dr.services.android.lib.drone.companion.solo.tlv.SoloButtonSettingSetter; import com.o3dr.services.android.lib.drone.companion.solo.tlv.TLVPacket; import com.o3dr.services.android.lib.model.ICommandListener; @@ -19,24 +19,24 @@ /** * Created by Fredia Huya-Kouadio on 7/29/15. */ -public class SoloLinkApiUtils { +public class SoloApiUtils { //Private to prevent instantiation. - private SoloLinkApiUtils() { + private SoloApiUtils() { } - public static SoloLinkState getSoloLinkState(DroneManager droneManager) { + public static SoloState getSoloLinkState(DroneManager droneManager) { if (droneManager == null || !droneManager.isCompanionComputerEnabled()) return null; final SoloComp soloComp = droneManager.getSoloComp(); final Pair wifiSettings = soloComp.getWifiSettings(); - return new SoloLinkState(soloComp.getAutopilotVersion(), soloComp.getControllerFirmwareVersion(), + return new SoloState(soloComp.getAutopilotVersion(), soloComp.getControllerFirmwareVersion(), soloComp.getControllerVersion(), soloComp.getVehicleVersion(), wifiSettings.second, wifiSettings.first, soloComp.isEUTxPowerCompliant(), soloComp.getButtonSettings()); } - private static boolean isSoloLinkFeatureAvailable(DroneManager droneManager, ICommandListener listener) { + static boolean isSoloLinkFeatureAvailable(DroneManager droneManager, ICommandListener listener) { if (droneManager == null) return false; diff --git a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeCameraTriggerTest.java b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeCameraTriggerImplTest.java similarity index 82% rename from ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeCameraTriggerTest.java rename to ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeCameraTriggerImplTest.java index 765bafb08f..d354c433b3 100644 --- a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeCameraTriggerTest.java +++ b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeCameraTriggerImplTest.java @@ -6,15 +6,15 @@ import junit.framework.TestCase; import org.droidplanner.services.android.core.mission.Mission; -import org.droidplanner.services.android.core.mission.commands.CameraTrigger; +import org.droidplanner.services.android.core.mission.commands.CameraTriggerImpl; import java.util.List; -public class ChangeCameraTriggerTest extends TestCase { +public class ChangeCameraTriggerImplTest extends TestCase { public void testPackMissionItem() { Mission mission = new Mission(null); - CameraTrigger item = new CameraTrigger(mission, (12.0)); + CameraTriggerImpl item = new CameraTriggerImpl(mission, (12.0)); List listOfMsg = item.packMissionItem(); assertEquals(1, listOfMsg.size()); diff --git a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeSpeedTest.java b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeSpeedImplTest.java similarity index 86% rename from ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeSpeedTest.java rename to ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeSpeedImplTest.java index a1b4706c1e..a57a0aaf16 100644 --- a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeSpeedTest.java +++ b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ChangeSpeedImplTest.java @@ -5,16 +5,16 @@ import junit.framework.TestCase; import org.droidplanner.services.android.core.mission.Mission; -import org.droidplanner.services.android.core.mission.commands.ChangeSpeed; +import org.droidplanner.services.android.core.mission.commands.ChangeSpeedImpl; import com.MAVLink.common.msg_mission_item; import com.MAVLink.enums.MAV_CMD; -public class ChangeSpeedTest extends TestCase { +public class ChangeSpeedImplTest extends TestCase { public void testPackMissionItem() { Mission mission = new Mission(null); - ChangeSpeed item = new ChangeSpeed(mission, 12.0); + ChangeSpeedImpl item = new ChangeSpeedImpl(mission, 12.0); List listOfMsg = item.packMissionItem(); assertEquals(1, listOfMsg.size()); diff --git a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ConditionYawTest.java b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ConditionYawImplTest.java similarity index 84% rename from ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ConditionYawTest.java rename to ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ConditionYawImplTest.java index c1b7d2e83a..aa72398225 100644 --- a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ConditionYawTest.java +++ b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/ConditionYawImplTest.java @@ -5,16 +5,16 @@ import junit.framework.TestCase; import org.droidplanner.services.android.core.mission.Mission; -import org.droidplanner.services.android.core.mission.commands.ConditionYaw; +import org.droidplanner.services.android.core.mission.commands.ConditionYawImpl; import com.MAVLink.common.msg_mission_item; import com.MAVLink.enums.MAV_CMD; -public class ConditionYawTest extends TestCase { +public class ConditionYawImplTest extends TestCase { public void testPackMissionItem() { Mission mission = new Mission(null); - ConditionYaw item = new ConditionYaw(mission, 12,false); + ConditionYawImpl item = new ConditionYawImpl(mission, 12,false); List listOfMsg = item.packMissionItem(); assertEquals(1, listOfMsg.size()); diff --git a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/LandTest.java b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/LandImplTest.java similarity index 88% rename from ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/LandTest.java rename to ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/LandImplTest.java index ed363eef94..67815a54e0 100644 --- a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/LandTest.java +++ b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/LandImplTest.java @@ -9,11 +9,11 @@ import com.MAVLink.common.msg_mission_item; import com.MAVLink.enums.MAV_CMD; -public class LandTest extends TestCase { +public class LandImplTest extends TestCase { public void testPackMissionItem() { Mission mission = new Mission(null); - Land item = new Land(mission); + LandImpl item = new LandImpl(mission); List listOfMsg = item.packMissionItem(); assertEquals(1, listOfMsg.size()); diff --git a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/SpatialCoordItemTest.java b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/SpatialCoordItemTest.java index 93836c754a..f97d29b313 100644 --- a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/SpatialCoordItemTest.java +++ b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/SpatialCoordItemTest.java @@ -12,7 +12,7 @@ public class SpatialCoordItemTest extends TestCase { public void testPackMissionItem() { Mission mission = new Mission(null); - Waypoint item = new Waypoint(mission, new Coord3D(0.1, 1, (2))); + WaypointImpl item = new WaypointImpl(mission, new Coord3D(0.1, 1, (2))); msg_mission_item mavMsg = item.packMissionItem().get(0); diff --git a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/TakeoffTest.java b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/TakeoffImplTest.java similarity index 87% rename from ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/TakeoffTest.java rename to ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/TakeoffImplTest.java index 361331b2af..31c8e126c2 100644 --- a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/TakeoffTest.java +++ b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/TakeoffImplTest.java @@ -6,15 +6,15 @@ import junit.framework.TestCase; import org.droidplanner.services.android.core.mission.Mission; -import org.droidplanner.services.android.core.mission.commands.Takeoff; +import org.droidplanner.services.android.core.mission.commands.TakeoffImpl; import java.util.List; -public class TakeoffTest extends TestCase { +public class TakeoffImplTest extends TestCase { public void testPackMissionItem() { Mission mission = new Mission(null); - Takeoff item = new Takeoff(mission, (50.0)); + TakeoffImpl item = new TakeoffImpl(mission, (50.0)); List listOfMsg = item.packMissionItem(); assertEquals(1, listOfMsg.size()); diff --git a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/WaypointTest.java b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/WaypointImplTest.java similarity index 86% rename from ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/WaypointTest.java rename to ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/WaypointImplTest.java index b5ba578563..ff3f2f92e9 100644 --- a/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/WaypointTest.java +++ b/ServiceApp/test/java/org/droidplanner/services/android/core/mission/waypoints/WaypointImplTest.java @@ -10,11 +10,11 @@ import java.util.List; -public class WaypointTest extends TestCase { +public class WaypointImplTest extends TestCase { public void testPackMissionItem() { Mission mission = new Mission(null); - Waypoint item = new Waypoint(mission, new Coord3D(0, 1, (2))); + WaypointImpl item = new WaypointImpl(mission, new Coord3D(0, 1, (2))); List listOfMsg = item.packMissionItem(); assertEquals(1, listOfMsg.size()); diff --git a/build.gradle b/build.gradle index 6d542129cc..7d5eafc53d 100644 --- a/build.gradle +++ b/build.gradle @@ -13,6 +13,43 @@ buildscript { } } +def computeVersionCode(int versionMajor, int versionMinor, int versionPatch, int versionBuild){ + return versionMajor * 100000 + versionMinor * 1000 + versionPatch * 10 + versionBuild +} + +def generateVersionName(String versionPrefix, int versionMajor, int versionMinor, int versionPatch){ + return "${versionPrefix}${versionMajor}.${versionMinor}.${versionPatch}" +} + +def generateVersionNameSuffix(int versionBuild, String releaseType){ + return ".${versionBuild} ${releaseType}-${getGitShortHash()}" +} + +/** + * @return The most recent git tag to be used as version name for the app. + */ +def getGitVersion() { + def cmd = "git describe --tag" + try { + def proc = cmd.execute() + return proc.text.trim() + } catch (IOException e) { + //Unable to find 'git' + return "please update version name manually" + } +} + +def getGitShortHash(){ + def cmd = "git rev-parse --short HEAD" + try{ + def proc = cmd.execute() + return proc.text.trim() + } catch(IOException e){ + //Unable to find git + return "" + } +} + allprojects { repositories { jcenter() diff --git a/samples/StarterApp/src/main/java/com/o3dr/sample/hellodrone/MainActivity.java b/samples/StarterApp/src/main/java/com/o3dr/sample/hellodrone/MainActivity.java index 6d2def6c07..498ea38144 100644 --- a/samples/StarterApp/src/main/java/com/o3dr/sample/hellodrone/MainActivity.java +++ b/samples/StarterApp/src/main/java/com/o3dr/sample/hellodrone/MainActivity.java @@ -18,7 +18,7 @@ import com.o3dr.android.client.ControlTower; import com.o3dr.android.client.Drone; -import com.o3dr.android.client.apis.SoloLinkApi; +import com.o3dr.android.client.apis.solo.SoloCameraApi; import com.o3dr.android.client.apis.VehicleApi; import com.o3dr.android.client.interfaces.DroneListener; import com.o3dr.android.client.interfaces.TowerListener; @@ -26,6 +26,8 @@ import com.o3dr.services.android.lib.coordinate.LatLongAlt; import com.o3dr.services.android.lib.drone.attribute.AttributeEvent; import com.o3dr.services.android.lib.drone.attribute.AttributeType; +import com.o3dr.services.android.lib.drone.companion.solo.SoloAttributes; +import com.o3dr.services.android.lib.drone.companion.solo.SoloState; import com.o3dr.services.android.lib.drone.connection.ConnectionParameter; import com.o3dr.services.android.lib.drone.connection.ConnectionResult; import com.o3dr.services.android.lib.drone.connection.ConnectionType; @@ -187,6 +189,7 @@ public void onDroneEvent(String event, Bundle extras) { alertUser("Drone Connected"); updateConnectedButton(this.drone.isConnected()); updateArmButton(); + checkSoloState(); break; case AttributeEvent.STATE_DISCONNECTED: @@ -232,6 +235,16 @@ public void onDroneEvent(String event, Bundle extras) { } + private void checkSoloState() { + final SoloState soloState = drone.getAttribute(SoloAttributes.SOLO_STATE); + if(soloState == null){ + alertUser("Unable to retrieve the solo state."); + } + else{ + alertUser("Solo state is up to date."); + } + } + @Override public void onDroneConnectionFailed(ConnectionResult result) { alertUser("Connection Failed:" + result.getErrorMessage()); @@ -425,7 +438,7 @@ protected void updateVehicleMode() { // ========================================================== protected void alertUser(String message) { - Toast.makeText(getApplicationContext(), message, Toast.LENGTH_LONG).show(); + Toast.makeText(getApplicationContext(), message, Toast.LENGTH_SHORT).show(); Log.d(TAG, message); } @@ -440,7 +453,7 @@ protected double distanceBetweenPoints(LatLongAlt pointA, LatLongAlt pointB) { } private void takePhoto() { - SoloLinkApi.getApi(drone).takePhoto(new AbstractCommandListener() { + SoloCameraApi.getApi(drone).takePhoto(new AbstractCommandListener() { @Override public void onSuccess() { alertUser("Photo taken."); @@ -459,7 +472,7 @@ public void onTimeout() { } private void toggleVideoRecording() { - SoloLinkApi.getApi(drone).toggleVideoRecording(new AbstractCommandListener() { + SoloCameraApi.getApi(drone).toggleVideoRecording(new AbstractCommandListener() { @Override public void onSuccess() { alertUser("Video recording toggled."); @@ -478,7 +491,7 @@ public void onTimeout() { } private void startVideoStream(Surface videoSurface){ - SoloLinkApi.getApi(drone).startVideoStream(videoSurface, new AbstractCommandListener() { + SoloCameraApi.getApi(drone).startVideoStream(videoSurface, new AbstractCommandListener() { @Override public void onSuccess() { if(stopVideoStream != null) @@ -501,7 +514,7 @@ public void onTimeout() { } private void stopVideoStream() { - SoloLinkApi.getApi(drone).stopVideoStream(new SimpleCommandListener() { + SoloCameraApi.getApi(drone).stopVideoStream(new SimpleCommandListener() { @Override public void onSuccess() { if (stopVideoStream != null)