Skip to content

Commit 70f9f1c

Browse files
committed
Merge pull request #308 from dronekit/release-1.4.3
Release 1.4.3
2 parents b855145 + 7db5963 commit 70f9f1c

File tree

319 files changed

+3891
-2699
lines changed

Some content is hidden

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

319 files changed

+3891
-2699
lines changed

ClientLib/build.gradle

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

910
PUBLISH_ARTIFACT_ID = 'dronekit-android'
10-
PUBLISH_VERSION = generateVersionName("", VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH)
11+
PUBLISH_VERSION = generateVersionName("", VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH, VERSION_SUFFIX)
1112
PUBLISH_VERSION_CODE = computeVersionCode(VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH, VERSION_BUILD)
1213
PROJECT_DESCRIPTION = "Android DroneKit client library."
1314
PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android', 'DroneKit']

ClientLib/src/main/AndroidManifest.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
22
package="com.o3dr.android.client">
33

4+
<uses-permission android:name="android.permission.INTERNET"/>
5+
46
<application>
57
<activity
68
android:name=".utils.InstallServiceDialog"

ClientLib/src/main/java/com/o3dr/android/client/Drone.java

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -233,17 +233,23 @@ public void post(Runnable action) {
233233
handler.post(action);
234234
}
235235

236+
/**
237+
* Reset the vehicle flight timer.
238+
*/
236239
public void resetFlightTimer() {
237240
elapsedFlightTime = 0;
238241
startTime = SystemClock.elapsedRealtime();
239242
}
240243

241-
public void stopTimer() {
244+
private void stopTimer() {
242245
// lets calc the final elapsed timer
243246
elapsedFlightTime += SystemClock.elapsedRealtime() - startTime;
244247
startTime = SystemClock.elapsedRealtime();
245248
}
246249

250+
/**
251+
* @return Vehicle flight time in seconds.
252+
*/
247253
public long getFlightTime() {
248254
State droneState = getAttribute(AttributeType.STATE);
249255
if (droneState != null && droneState.isFlying()) {
@@ -682,6 +688,10 @@ public void loadWaypoints() {
682688
MissionApi.getApi(this).loadWaypoints();
683689
}
684690

691+
public Handler getHandler(){
692+
return handler;
693+
}
694+
685695
void notifyDroneConnectionFailed(final ConnectionResult result) {
686696
if (droneListeners.isEmpty())
687697
return;

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

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
package com.o3dr.android.client.apis;
22

33
import com.o3dr.android.client.Drone;
4+
import com.o3dr.services.android.lib.model.AbstractCommandListener;
45

56
import java.util.concurrent.ConcurrentHashMap;
67

@@ -36,4 +37,22 @@ protected static <T extends Api> T getApi(Drone drone, ConcurrentHashMap<Drone,
3637

3738
return apiInstance;
3839
}
40+
41+
protected static void postSuccessEvent(final AbstractCommandListener listener){
42+
if(listener != null){
43+
listener.onSuccess();
44+
}
45+
}
46+
47+
protected static void postErrorEvent(int error, AbstractCommandListener listener){
48+
if(listener != null){
49+
listener.onError(error);
50+
}
51+
}
52+
53+
protected static void postTimeoutEvent(AbstractCommandListener listener){
54+
if(listener != null){
55+
listener.onTimeout();
56+
}
57+
}
3958
}
Lines changed: 94 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,94 @@
1+
package com.o3dr.android.client.apis;
2+
3+
import android.os.Bundle;
4+
import android.support.annotation.NonNull;
5+
import android.view.Surface;
6+
7+
import com.o3dr.android.client.Drone;
8+
import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError;
9+
import com.o3dr.services.android.lib.model.AbstractCommandListener;
10+
import com.o3dr.services.android.lib.model.action.Action;
11+
12+
import java.util.concurrent.ConcurrentHashMap;
13+
14+
import static com.o3dr.services.android.lib.drone.action.CameraActions.ACTION_START_VIDEO_STREAM;
15+
import static com.o3dr.services.android.lib.drone.action.CameraActions.ACTION_STOP_VIDEO_STREAM;
16+
import static com.o3dr.services.android.lib.drone.action.CameraActions.EXTRA_VIDEO_DISPLAY;
17+
import static com.o3dr.services.android.lib.drone.action.CameraActions.EXTRA_VIDEO_PROPS_UDP_PORT;
18+
import static com.o3dr.services.android.lib.drone.action.CameraActions.EXTRA_VIDEO_TAG;
19+
import static com.o3dr.services.android.lib.drone.action.CameraActions.EXTRA_VIDEO_PROPERTIES;
20+
21+
/**
22+
* Provides support to control generic camera functionality
23+
* Created by Fredia Huya-Kouadio on 10/11/15.
24+
*
25+
* @since 2.6.8
26+
*/
27+
public class CameraApi extends Api {
28+
29+
private static final ConcurrentHashMap<Drone, CameraApi> apiCache = new ConcurrentHashMap<>();
30+
private static final Builder<CameraApi> apiBuilder = new Builder<CameraApi>() {
31+
@Override
32+
public CameraApi build(Drone drone) {
33+
return new CameraApi(drone);
34+
}
35+
};
36+
37+
/**
38+
* Used to specify the udp port from which to access the streamed video.
39+
*/
40+
public static final String VIDEO_PROPS_UDP_PORT = EXTRA_VIDEO_PROPS_UDP_PORT;
41+
42+
/**
43+
* Retrieves a camera api instance
44+
*
45+
* @param drone
46+
* @return
47+
*/
48+
public static CameraApi getApi(final Drone drone) {
49+
return getApi(drone, apiCache, apiBuilder);
50+
}
51+
52+
private final Drone drone;
53+
54+
private CameraApi(Drone drone) {
55+
this.drone = drone;
56+
}
57+
58+
/**
59+
* Attempt to grab ownership and start the video stream from the connected drone. Can fail if
60+
* the video stream is already owned by another client.
61+
*
62+
* @param surface Surface object onto which the video is decoded.
63+
* @param tag Video tag.
64+
* @param videoProps Non-null video properties. @see VIDEO_PROPS_UDP_PORT
65+
* @param listener Register a callback to receive update of the command execution status.
66+
* @since 2.6.8
67+
*/
68+
public void startVideoStream(@NonNull final Surface surface, final String tag, @NonNull Bundle videoProps, final AbstractCommandListener listener) {
69+
if (surface == null || videoProps == null) {
70+
postErrorEvent(CommandExecutionError.COMMAND_FAILED, listener);
71+
return;
72+
}
73+
74+
final Bundle params = new Bundle();
75+
params.putParcelable(EXTRA_VIDEO_DISPLAY, surface);
76+
params.putString(EXTRA_VIDEO_TAG, tag);
77+
params.putBundle(EXTRA_VIDEO_PROPERTIES, videoProps);
78+
79+
drone.performAsyncActionOnDroneThread(new Action(ACTION_START_VIDEO_STREAM, params), listener);
80+
}
81+
82+
/**
83+
* Stop the video stream from the connected drone, and release ownership.
84+
*
85+
* @param tag Video tag.
86+
* @param listener Register a callback to receive update of the command execution status.
87+
* @since 2.6.8
88+
*/
89+
public void stopVideoStream(final String tag, final AbstractCommandListener listener) {
90+
final Bundle params = new Bundle();
91+
params.putString(EXTRA_VIDEO_TAG, tag);
92+
drone.performAsyncActionOnDroneThread(new Action(ACTION_STOP_VIDEO_STREAM, params), listener);
93+
}
94+
}

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

Lines changed: 63 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,19 @@
11
package com.o3dr.android.client.apis;
22

33
import android.os.Bundle;
4+
import android.support.annotation.IntDef;
45

56
import com.o3dr.android.client.Drone;
67
import com.o3dr.services.android.lib.coordinate.LatLong;
78
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
9+
import com.o3dr.services.android.lib.drone.attribute.error.CommandExecutionError;
10+
import com.o3dr.services.android.lib.drone.property.Attitude;
811
import com.o3dr.services.android.lib.drone.property.Gps;
912
import com.o3dr.services.android.lib.model.AbstractCommandListener;
1013
import com.o3dr.services.android.lib.model.action.Action;
1114

15+
import java.lang.annotation.Retention;
16+
import java.lang.annotation.RetentionPolicy;
1217
import java.util.concurrent.ConcurrentHashMap;
1318

1419
import static com.o3dr.services.android.lib.drone.action.ControlActions.ACTION_DO_GUIDED_TAKEOFF;
@@ -23,16 +28,25 @@
2328
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_VELOCITY_Y;
2429
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_VELOCITY_Z;
2530
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_YAW_CHANGE_RATE;
26-
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_YAW_IS_CLOCKWISE;
2731
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_YAW_IS_RELATIVE;
2832
import static com.o3dr.services.android.lib.drone.action.ControlActions.EXTRA_YAW_TARGET_ANGLE;
2933

3034
/**
3135
* Provides access to the vehicle control functionality.
36+
*
37+
* Use of this api might required the vehicle to be in a specific flight mode (i.e: GUIDED)
38+
*
3239
* Created by Fredia Huya-Kouadio on 9/7/15.
3340
*/
3441
public class ControlApi extends Api {
3542

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+
3650
private static final ConcurrentHashMap<Drone, ControlApi> apiCache = new ConcurrentHashMap<>();
3751
private static final Builder<ControlApi> apiBuilder = new Builder<ControlApi>() {
3852
@Override
@@ -110,32 +124,67 @@ public void climbTo(double altitude) {
110124
/**
111125
* Instructs the vehicle to turn to the specified target angle
112126
* @param targetAngle Target angle in degrees [0-360], with 0 == north.
113-
* @param turnSpeed Speed during turn in degrees per second
114-
* @param isClockwise True for clockwise turn, false for counter clockwise turn
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.
115128
* @param isRelative True is the target angle is relative to the current vehicle attitude, false otherwise if it's absolute.
116129
* @param listener Register a callback to receive update of the command execution state.
117130
*/
118-
public void turnTo(float targetAngle, float turnSpeed, boolean isClockwise, boolean isRelative, AbstractCommandListener listener){
131+
public void turnTo(float targetAngle, float turnRate, boolean isRelative, AbstractCommandListener listener){
132+
if(!isWithinBounds(targetAngle, 0, 360) || !isWithinBounds(turnRate, -1.0f, 1.0f)){
133+
postErrorEvent(CommandExecutionError.COMMAND_FAILED, listener);
134+
return;
135+
}
136+
119137
Bundle params = new Bundle();
120138
params.putFloat(EXTRA_YAW_TARGET_ANGLE, targetAngle);
121-
params.putFloat(EXTRA_YAW_CHANGE_RATE, turnSpeed);
122-
params.putBoolean(EXTRA_YAW_IS_CLOCKWISE, isClockwise);
139+
params.putFloat(EXTRA_YAW_CHANGE_RATE, turnRate);
123140
params.putBoolean(EXTRA_YAW_IS_RELATIVE, isRelative);
124141
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_CONDITION_YAW, params), listener);
125142
}
126143

127-
/**
128-
* Set the vehicle velocity vector.
129-
* @param vx x velocity in meter / s
130-
* @param vy y velocity in meter / s
131-
* @param vz z velocity in meter / s
132-
* @param listener Register a callback to receive update of the command execution state.
133-
*/
134-
public void setVelocity(float vx, float vy, float vz, AbstractCommandListener listener){
144+
private void moveAtVelocity(float vx, float vy, float vz, AbstractCommandListener listener){
135145
Bundle params = new Bundle();
136146
params.putFloat(EXTRA_VELOCITY_X, vx);
137147
params.putFloat(EXTRA_VELOCITY_Y, vy);
138148
params.putFloat(EXTRA_VELOCITY_Z, vz);
139149
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_VELOCITY, params), listener);
140150
}
151+
152+
/**
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}
158+
*
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+
*/
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());
176+
177+
final double cosAttitude = Math.cos(attitudeInRad);
178+
final double sinAttitude = Math.sin(attitudeInRad);
179+
180+
projectedX = (float) (vx * cosAttitude) - (float) (vy * sinAttitude);
181+
projectedY = (float) (vx * sinAttitude) + (float) (vy * cosAttitude);
182+
}
183+
184+
moveAtVelocity(projectedX, projectedY, vz, listener);
185+
}
186+
187+
private static boolean isWithinBounds(float value, float lowerBound, float upperBound){
188+
return value <= upperBound && value >= lowerBound;
189+
}
141190
}

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

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -132,6 +132,7 @@ public void onError(int error){
132132
/**
133133
* Disables control of the gimbal. After calling this method, no call to {@link GimbalApi#updateGimbalOrientation(float, float, float, GimbalOrientationListener)}
134134
* will be allowed.
135+
* @since 2.5.0
135136
* @param listener non-null GimbalStatusListener callback.
136137
*/
137138
public void stopGimbalControl(final GimbalOrientationListener listener){
@@ -148,8 +149,12 @@ public void run() {
148149
return;
149150
}
150151

152+
gimbalListeners.remove(listener);
153+
151154
//Reset the gimbal mount to the default.
152-
drone.performAsyncActionOnDroneThread(new Action(ACTION_RESET_GIMBAL_MOUNT_MODE, null), new SimpleCommandListener(){
155+
Bundle params = new Bundle(1);
156+
params.putInt(GIMBAL_MOUNT_MODE, MAV_MOUNT_MODE.MAV_MOUNT_MODE_RC_TARGETING);
157+
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_GIMBAL_MOUNT_MODE, params), new SimpleCommandListener(){
153158
@Override
154159
public void onTimeout(){
155160
listener.onGimbalOrientationCommandError(CommandExecutionError.COMMAND_FAILED);

0 commit comments

Comments
 (0)