Skip to content

Commit 9d5de9b

Browse files
committed
Merge pull request #332 from dronekit/release-1.4.4
Release 1.4.4
2 parents 70f9f1c + e2cf6dc commit 9d5de9b

File tree

126 files changed

+4488
-1793
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

126 files changed

+4488
-1793
lines changed

ClientLib/build.gradle

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,13 +3,12 @@ apply plugin: 'com.android.library'
33
ext {
44
VERSION_MAJOR = 2
55
VERSION_MINOR = 6
6-
VERSION_PATCH = 8
7-
VERSION_BUILD = 0
6+
VERSION_PATCH = 9
87
VERSION_SUFFIX = "release"
98

109
PUBLISH_ARTIFACT_ID = 'dronekit-android'
1110
PUBLISH_VERSION = generateVersionName("", VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH, VERSION_SUFFIX)
12-
PUBLISH_VERSION_CODE = computeVersionCode(VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH, VERSION_BUILD)
11+
PUBLISH_VERSION_CODE = computeVersionCode(VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH)
1312
PROJECT_DESCRIPTION = "Android DroneKit client library."
1413
PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android', 'DroneKit']
1514
PROJECT_LICENSES = ['Apache-2.0']
@@ -41,6 +40,10 @@ android {
4140
abortOnError false
4241
}
4342

43+
testOptions {
44+
unitTests.returnDefaultValues = true
45+
}
46+
4447
android.libraryVariants.all { variant ->
4548
variant.outputs.each { output ->
4649
def file = output.outputFile

ClientLib/src/main/java/com/o3dr/android/client/apis/ControlApi.java

Lines changed: 78 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -1,27 +1,25 @@
11
package com.o3dr.android.client.apis;
22

33
import android.os.Bundle;
4-
import android.support.annotation.IntDef;
54

65
import com.o3dr.android.client.Drone;
76
import com.o3dr.services.android.lib.coordinate.LatLong;
87
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
98
import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError;
10-
import com.o3dr.services.android.lib.drone.property.Attitude;
119
import com.o3dr.services.android.lib.drone.property.Gps;
1210
import com.o3dr.services.android.lib.model.AbstractCommandListener;
1311
import com.o3dr.services.android.lib.model.action.Action;
1412

15-
import java.lang.annotation.Retention;
16-
import java.lang.annotation.RetentionPolicy;
1713
import java.util.concurrent.ConcurrentHashMap;
1814

1915
import static com.o3dr.services.android.lib.drone.action.ControlActions.ACTION_DO_GUIDED_TAKEOFF;
16+
import static com.o3dr.services.android.lib.drone.action.ControlActions.ACTION_ENABLE_MANUAL_CONTROL;
2017
import static com.o3dr.services.android.lib.drone.action.ControlActions.ACTION_SEND_GUIDED_POINT;
2118
import static com.o3dr.services.android.lib.drone.action.ControlActions.ACTION_SET_CONDITION_YAW;
2219
import static com.o3dr.services.android.lib.drone.action.ControlActions.ACTION_SET_GUIDED_ALTITUDE;
2320
import static com.o3dr.services.android.lib.drone.action.ControlActions.ACTION_SET_VELOCITY;
2421
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_ALTITUDE;
22+
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_DO_ENABLE;
2523
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_FORCE_GUIDED_POINT;
2624
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_GUIDED_POINT;
2725
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_VELOCITY_X;
@@ -33,20 +31,13 @@
3331

3432
/**
3533
* Provides access to the vehicle control functionality.
36-
*
34+
* <p/>
3735
* Use of this api might required the vehicle to be in a specific flight mode (i.e: GUIDED)
38-
*
36+
* <p/>
3937
* Created by Fredia Huya-Kouadio on 9/7/15.
4038
*/
4139
public class ControlApi extends Api {
4240

43-
public static final int EARTH_NED_COORDINATE_FRAME = 0;
44-
public static final int VEHICLE_COORDINATE_FRAME = 1;
45-
46-
@IntDef({EARTH_NED_COORDINATE_FRAME, VEHICLE_COORDINATE_FRAME})
47-
@Retention(RetentionPolicy.SOURCE)
48-
public @interface CoordinateFrame{}
49-
5041
private static final ConcurrentHashMap<Drone, ControlApi> apiCache = new ConcurrentHashMap<>();
5142
private static final Builder<ControlApi> apiBuilder = new Builder<ControlApi>() {
5243
@Override
@@ -57,16 +48,17 @@ public ControlApi build(Drone drone) {
5748

5849
/**
5950
* Retrieves a control api instance.
51+
*
6052
* @param drone
6153
* @return
6254
*/
63-
public static ControlApi getApi(final Drone drone){
55+
public static ControlApi getApi(final Drone drone) {
6456
return getApi(drone, apiCache, apiBuilder);
6557
}
6658

6759
private final Drone drone;
6860

69-
private ControlApi(Drone drone){
61+
private ControlApi(Drone drone) {
7062
this.drone = drone;
7163
}
7264

@@ -123,13 +115,14 @@ public void climbTo(double altitude) {
123115

124116
/**
125117
* Instructs the vehicle to turn to the specified target angle
118+
*
126119
* @param targetAngle Target angle in degrees [0-360], with 0 == north.
127-
* @param turnRate Turning rate normalized to the range [-1.0f, 1.0f]. Positive values for clockwise turns, and negative values for counter-clockwise turns.
128-
* @param isRelative True is the target angle is relative to the current vehicle attitude, false otherwise if it's absolute.
129-
* @param listener Register a callback to receive update of the command execution state.
120+
* @param turnRate Turning rate normalized to the range [-1.0f, 1.0f]. Positive values for clockwise turns, and negative values for counter-clockwise turns.
121+
* @param isRelative True is the target angle is relative to the current vehicle attitude, false otherwise if it's absolute.
122+
* @param listener Register a callback to receive update of the command execution state.
130123
*/
131-
public void turnTo(float targetAngle, float turnRate, boolean isRelative, AbstractCommandListener listener){
132-
if(!isWithinBounds(targetAngle, 0, 360) || !isWithinBounds(turnRate, -1.0f, 1.0f)){
124+
public void turnTo(float targetAngle, float turnRate, boolean isRelative, AbstractCommandListener listener) {
125+
if (!isWithinBounds(targetAngle, 0, 360) || !isWithinBounds(turnRate, -1.0f, 1.0f)) {
133126
postErrorEvent(CommandExecutionError.COMMAND_FAILED, listener);
134127
return;
135128
}
@@ -141,7 +134,21 @@ public void turnTo(float targetAngle, float turnRate, boolean isRelative, Abstra
141134
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_CONDITION_YAW, params), listener);
142135
}
143136

144-
private void moveAtVelocity(float vx, float vy, float vz, AbstractCommandListener listener){
137+
/**
138+
* Move the vehicle along the specified normalized velocity vector.
139+
*
140+
* @param vx x velocity normalized to the range [-1.0f, 1.0f]. Generally correspond to the pitch of the vehicle.
141+
* @param vy y velocity normalized to the range [-1.0f, 1.0f]. Generally correspond to the roll of the vehicle.
142+
* @param vz z velocity normalized to the range [-1.0f, 1.0f]. Generally correspond to the thrust of the vehicle.
143+
* @param listener Register a callback to receive update of the command execution state.
144+
* @since 2.6.9
145+
*/
146+
public void manualControl(float vx, float vy, float vz, AbstractCommandListener listener) {
147+
if (!isWithinBounds(vx, -1f, 1f) || !isWithinBounds(vy, -1f, 1f) || !isWithinBounds(vz, -1f, 1f)) {
148+
postErrorEvent(CommandExecutionError.COMMAND_FAILED, listener);
149+
return;
150+
}
151+
145152
Bundle params = new Bundle();
146153
params.putFloat(EXTRA_VELOCITY_X, vx);
147154
params.putFloat(EXTRA_VELOCITY_Y, vy);
@@ -150,41 +157,63 @@ private void moveAtVelocity(float vx, float vy, float vz, AbstractCommandListene
150157
}
151158

152159
/**
153-
* Move the vehicle along the specified velocity vector.
154-
*
155-
* @param referenceFrame Reference frame to use. Can be one of
156-
* {@link #EARTH_NED_COORDINATE_FRAME},
157-
* {@link #VEHICLE_COORDINATE_FRAME}
160+
* [Dis|En]able manual control on the vehicle.
161+
* The result of the action will be conveyed through the passed listener.
158162
*
159-
* @param vx x velocity normalized to the range [-1.0f, 1.0f].
160-
* @param vy y velocity normalized to the range [-1.0f, 1.0f].
161-
* @param vz z velocity normalized to the range [-1.0f, 1.0f].
162-
* @param listener Register a callback to receive update of the command execution state.
163+
* @param enable True to enable manual control, false to disable.
164+
* @param listener Register a callback to receive the result of the operation.
165+
* @since 2.6.9
163166
*/
164-
public void moveAtVelocity(@CoordinateFrame int referenceFrame, float vx, float vy, float vz, AbstractCommandListener listener){
165-
if(!isWithinBounds(vx, -1f, 1f) || !isWithinBounds(vy, -1f, 1f) || !isWithinBounds(vz, -1f, 1f)){
166-
postErrorEvent(CommandExecutionError.COMMAND_FAILED, listener);
167-
return;
168-
}
169-
170-
float projectedX = vx;
171-
float projectedY = vy;
172-
173-
if(referenceFrame == VEHICLE_COORDINATE_FRAME) {
174-
Attitude attitude = drone.getAttribute(AttributeType.ATTITUDE);
175-
double attitudeInRad = Math.toRadians(attitude.getYaw());
167+
public void enableManualControl(final boolean enable, final ManualControlStateListener listener) {
168+
AbstractCommandListener listenerWrapper = listener == null ? null
169+
: new AbstractCommandListener() {
170+
@Override
171+
public void onSuccess() {
172+
if (enable) {
173+
listener.onManualControlEnabled();
174+
} else {
175+
listener.onManualControlDisabled();
176+
}
177+
}
176178

177-
final double cosAttitude = Math.cos(attitudeInRad);
178-
final double sinAttitude = Math.sin(attitudeInRad);
179+
@Override
180+
public void onError(int executionError) {
181+
if (enable) {
182+
listener.onManualControlDisabled();
183+
}
184+
}
179185

180-
projectedX = (float) (vx * cosAttitude) - (float) (vy * sinAttitude);
181-
projectedY = (float) (vx * sinAttitude) + (float) (vy * cosAttitude);
182-
}
186+
@Override
187+
public void onTimeout() {
188+
if (enable) {
189+
listener.onManualControlDisabled();
190+
}
191+
}
192+
};
183193

184-
moveAtVelocity(projectedX, projectedY, vz, listener);
194+
Bundle params = new Bundle();
195+
params.putBoolean(EXTRA_DO_ENABLE, enable);
196+
drone.performAsyncActionOnDroneThread(new Action(ACTION_ENABLE_MANUAL_CONTROL, params), listenerWrapper);
185197
}
186198

187-
private static boolean isWithinBounds(float value, float lowerBound, float upperBound){
199+
private static boolean isWithinBounds(float value, float lowerBound, float upperBound) {
188200
return value <= upperBound && value >= lowerBound;
189201
}
202+
203+
/**
204+
* Used to monitor the state of manual control for the vehicle.
205+
*
206+
* @since 2.6.9
207+
*/
208+
public interface ManualControlStateListener {
209+
/**
210+
* Manual control is enabled on the vehicle.
211+
*/
212+
void onManualControlEnabled();
213+
214+
/**
215+
* Manual control is disabled on the vehicle.
216+
*/
217+
void onManualControlDisabled();
218+
}
190219
}

ClientLib/src/main/java/com/o3dr/android/client/utils/geotag/GeoTagAsyncTask.java

Lines changed: 28 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,7 @@
11
package com.o3dr.android.client.utils.geotag;
22

3-
import android.content.Context;
43
import android.media.ExifInterface;
54
import android.os.AsyncTask;
6-
import android.os.Build;
7-
import android.os.Environment;
85

96
import com.MAVLink.ardupilotmega.msg_camera_feedback;
107
import com.o3dr.android.client.utils.data.tlog.TLogParser;
@@ -15,8 +12,10 @@
1512
import java.io.IOException;
1613
import java.io.InputStream;
1714
import java.io.OutputStream;
15+
import java.text.SimpleDateFormat;
1816
import java.util.ArrayList;
1917
import java.util.Collection;
18+
import java.util.Date;
2019
import java.util.HashMap;
2120
import java.util.List;
2221
import java.util.Map;
@@ -25,8 +24,9 @@
2524
* GeoTagAsyncTask images based on camera mavlink messages.
2625
*/
2726
public abstract class GeoTagAsyncTask extends AsyncTask<Void, Integer, GeoTagAsyncTask.ResultObject> {
28-
private static final String STORE_PHOTO_DIR_NAME = "GeoTag";
29-
private final Context context;
27+
private static final String STORE_PHOTO_PREFIX = "GeoTag";
28+
private static final SimpleDateFormat formatter = new SimpleDateFormat("MM-dd-yy-HH");
29+
private final File rootDir;
3030
private final List<TLogParser.Event> events;
3131
private final ArrayList<File> photos;
3232

@@ -35,12 +35,12 @@ public abstract class GeoTagAsyncTask extends AsyncTask<Void, Integer, GeoTagAsy
3535
*
3636
* Warning: this copies data to external storage
3737
*
38-
* @param context {@link Context}
38+
* @param rootDir {@link File}
3939
* @param events {@link List<com.o3dr.android.client.utils.data.tlog.TLogParser.Event>} list of events to geotag photos.
4040
* @param photos {@link List<File>} list of files of photos to geotag.
4141
*/
42-
public GeoTagAsyncTask(Context context, List<TLogParser.Event> events, ArrayList<File> photos) {
43-
this.context = context;
42+
public GeoTagAsyncTask(File rootDir, List<TLogParser.Event> events, ArrayList<File> photos) {
43+
this.rootDir = rootDir;
4444
this.events = events;
4545
this.photos = photos;
4646
}
@@ -50,8 +50,6 @@ protected ResultObject doInBackground(Void... params) {
5050
ResultObject resultObject = new ResultObject();
5151

5252
try {
53-
File saveDir = new File(getSaveRootDir(context), STORE_PHOTO_DIR_NAME);
54-
5553
HashMap<File, File> geoTaggedFiles = new HashMap<>();
5654
HashMap<File, Exception> failedFiles = new HashMap<>();
5755
resultObject.setResult(geoTaggedFiles, failedFiles);
@@ -60,7 +58,13 @@ protected ResultObject doInBackground(Void... params) {
6058
return resultObject;
6159
}
6260

63-
if (!saveDir.exists() && !saveDir.mkdir()) {
61+
File saveDir = findNextDirName(rootDir);
62+
63+
if (isCancelled()) {
64+
return resultObject;
65+
}
66+
67+
if (!saveDir.mkdirs()) {
6468
resultObject.setException(new IllegalStateException("Failed to create directory for images"));
6569
return resultObject;
6670
}
@@ -184,22 +188,6 @@ public void setException(Exception exception) {
184188
}
185189
}
186190

187-
private static File getSaveRootDir(Context context) {
188-
File saveDir = context.getExternalFilesDir(null);
189-
190-
if (Build.VERSION.SDK_INT >= Build.VERSION_CODES.LOLLIPOP) {
191-
File dirs[] = context.getExternalFilesDirs(null);
192-
for (File dir : dirs) {
193-
// dir can be null if the device contains an external SD card slot but no SD card is present.
194-
if (dir != null && Environment.isExternalStorageRemovable(dir)) {
195-
saveDir = dir;
196-
break;
197-
}
198-
}
199-
}
200-
return saveDir;
201-
}
202-
203191
private static boolean hasEnoughMemory(File file, Collection<File> photos) {
204192
long freeBytes = file.getUsableSpace();
205193
long bytesNeeded = 0;
@@ -260,4 +248,17 @@ private static String convertLatLngToDMS(double coord) {
260248
protected interface GeoTagAlgorithm {
261249
HashMap<TLogParser.Event, File> match(List<TLogParser.Event> events, ArrayList<File> photos);
262250
}
251+
252+
private static File findNextDirName(File rootDir) {
253+
Date date = new Date();
254+
File file;
255+
int i = 0;
256+
do {
257+
String dirName = STORE_PHOTO_PREFIX + "_" + formatter.format(date) + "_" + i;
258+
file = new File(rootDir, dirName);
259+
i++;
260+
} while (file.exists());
261+
262+
return file;
263+
}
263264
}

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

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,10 @@ public class ControlActions {
4040
*/
4141
public static final String EXTRA_VELOCITY_Z = "extra_velocity_z";
4242

43+
public static final String ACTION_ENABLE_MANUAL_CONTROL = PACKAGE_NAME + ".ENABLE_MANUAL_CONTROL";
44+
45+
public static final String EXTRA_DO_ENABLE = "extra_do_enable";
46+
4347
//Private to prevent instantiation
4448
private ControlActions(){}
4549

0 commit comments

Comments
 (0)