Skip to content

Commit b855145

Browse files
committed
Merge pull request #286 from dronekit/release-1.4.2
Release 1.4.2
2 parents bff1207 + 0f6d5eb commit b855145

33 files changed

+717
-182
lines changed

ClientLib/build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ apply plugin: 'com.android.library'
33
ext {
44
VERSION_MAJOR = 2
55
VERSION_MINOR = 6
6-
VERSION_PATCH = 3
6+
VERSION_PATCH = 6
77
VERSION_BUILD = 0
88

99
PUBLISH_ARTIFACT_ID = 'dronekit-android'

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

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040
import com.o3dr.services.android.lib.drone.property.VehicleMode;
4141
import com.o3dr.services.android.lib.gcs.follow.FollowState;
4242
import com.o3dr.services.android.lib.gcs.follow.FollowType;
43+
import com.o3dr.services.android.lib.gcs.returnToMe.ReturnToMeState;
4344
import com.o3dr.services.android.lib.mavlink.MavlinkMessageWrapper;
4445
import com.o3dr.services.android.lib.model.AbstractCommandListener;
4546
import com.o3dr.services.android.lib.model.IDroneApi;
@@ -359,6 +360,9 @@ private <T extends Parcelable> T getAttributeDefaultValue(String attributeType)
359360
case AttributeType.MAGNETOMETER_CALIBRATION_STATUS:
360361
return (T) new MagnetometerCalibrationStatus();
361362

363+
case AttributeType.RETURN_TO_ME_STATE:
364+
return (T) new ReturnToMeState();
365+
362366
case AttributeType.CAMERA:
363367
case SoloAttributes.SOLO_STATE:
364368
case SoloAttributes.SOLO_GOPRO_STATE:

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

Lines changed: 25 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,7 @@
55
import com.o3dr.android.client.Drone;
66
import com.o3dr.services.android.lib.coordinate.LatLong;
77
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
8-
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
98
import com.o3dr.services.android.lib.drone.connection.ConnectionParameter;
10-
import com.o3dr.services.android.lib.drone.property.Gps;
119
import com.o3dr.services.android.lib.drone.property.Parameters;
1210
import com.o3dr.services.android.lib.drone.property.VehicleMode;
1311
import com.o3dr.services.android.lib.model.AbstractCommandListener;
@@ -22,10 +20,12 @@
2220
import static com.o3dr.services.android.lib.drone.action.ParameterActions.ACTION_WRITE_PARAMETERS;
2321
import static com.o3dr.services.android.lib.drone.action.ParameterActions.EXTRA_PARAMETERS;
2422
import static com.o3dr.services.android.lib.drone.action.StateActions.ACTION_ARM;
23+
import static com.o3dr.services.android.lib.drone.action.StateActions.ACTION_ENABLE_RETURN_TO_ME;
2524
import static com.o3dr.services.android.lib.drone.action.StateActions.ACTION_SET_VEHICLE_HOME;
2625
import static com.o3dr.services.android.lib.drone.action.StateActions.ACTION_SET_VEHICLE_MODE;
2726
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_ARM;
2827
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_EMERGENCY_DISARM;
28+
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_IS_RETURN_TO_ME_ENABLED;
2929
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_VEHICLE_HOME_LOCATION;
3030
import static com.o3dr.services.android.lib.drone.action.StateActions.EXTRA_VEHICLE_MODE;
3131

@@ -158,54 +158,49 @@ public void writeParameters(Parameters parameters) {
158158
*/
159159

160160
/**
161+
* @param altitude altitude in meters
161162
* @deprecated Use {@link ControlApi#takeoff(double, AbstractCommandListener)} instead.
162163
* Perform a guided take off.
163-
*
164-
* @param altitude altitude in meters
165164
*/
166165
public void takeoff(double altitude) {
167166
controlApi.takeoff(altitude, null);
168167
}
169168

170169
/**
171-
* @deprecated Use {@link ControlApi#takeoff(double, AbstractCommandListener)} instead.
172-
* Perform a guided take off.
173-
*
174170
* @param altitude altitude in meters
175171
* @param listener Register a callback to receive update of the command execution state.
172+
* @deprecated Use {@link ControlApi#takeoff(double, AbstractCommandListener)} instead.
173+
* Perform a guided take off.
176174
*/
177175
public void takeoff(double altitude, AbstractCommandListener listener) {
178176
controlApi.takeoff(altitude, listener);
179177
}
180178

181179
/**
182-
* @deprecated Use {@link ControlApi#goTo(LatLong, boolean, AbstractCommandListener)} instead.
183-
* Send a guided point to the connected drone.
184-
*
185180
* @param point guided point location
186181
* @param force true to enable guided mode is required.
182+
* @deprecated Use {@link ControlApi#goTo(LatLong, boolean, AbstractCommandListener)} instead.
183+
* Send a guided point to the connected drone.
187184
*/
188185
public void sendGuidedPoint(LatLong point, boolean force) {
189186
controlApi.goTo(point, force, null);
190187
}
191188

192189
/**
193-
* @deprecated Use {@link ControlApi#goTo(LatLong, boolean, AbstractCommandListener)} instead.
194-
* Send a guided point to the connected drone.
195-
*
196190
* @param point guided point location
197191
* @param force true to enable guided mode is required.
198192
* @param listener Register a callback to receive update of the command execution state.
193+
* @deprecated Use {@link ControlApi#goTo(LatLong, boolean, AbstractCommandListener)} instead.
194+
* Send a guided point to the connected drone.
199195
*/
200196
public void sendGuidedPoint(LatLong point, boolean force, AbstractCommandListener listener) {
201197
controlApi.goTo(point, force, listener);
202198
}
203199

204200
/**
201+
* @param altitude altitude in meters
205202
* @deprecated Use {@link ControlApi#climbTo(double)} instead.
206203
* Set the altitude for the guided point.
207-
*
208-
* @param altitude altitude in meters
209204
*/
210205
public void setGuidedAltitude(double altitude) {
211206
controlApi.climbTo(altitude);
@@ -220,23 +215,34 @@ public void pauseAtCurrentLocation() {
220215
}
221216

222217
/**
218+
* @param listener Register a callback to receive update of the command execution state.
223219
* @deprecated Use {@link ControlApi#pauseAtCurrentLocation(AbstractCommandListener)} instead.
224220
* Pause the vehicle at its current location.
225-
*
226-
* @param listener Register a callback to receive update of the command execution state.
227221
*/
228222
public void pauseAtCurrentLocation(final AbstractCommandListener listener) {
229223
controlApi.pauseAtCurrentLocation(listener);
230224
}
231225

232226
/**
233227
* Changes the vehicle home location.
228+
*
234229
* @param homeLocation New home coordinate
235-
* @param listener Register a callback to receive update of the command execution state.
230+
* @param listener Register a callback to receive update of the command execution state.
236231
*/
237-
public void setVehicleHome(final LatLongAlt homeLocation, final AbstractCommandListener listener){
232+
public void setVehicleHome(final LatLongAlt homeLocation, final AbstractCommandListener listener) {
238233
Bundle params = new Bundle();
239234
params.putParcelable(EXTRA_VEHICLE_HOME_LOCATION, homeLocation);
240235
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_VEHICLE_HOME, params), listener);
241236
}
237+
238+
/**
239+
* Enables 'return to me'
240+
* @param isEnabled
241+
* @param listener
242+
*/
243+
public void enableReturnToMe(boolean isEnabled, final AbstractCommandListener listener){
244+
Bundle params = new Bundle();
245+
params.putBoolean(EXTRA_IS_RETURN_TO_ME_ENABLED, isEnabled);
246+
drone.performAsyncActionOnDroneThread(new Action(ACTION_ENABLE_RETURN_TO_ME, params), listener);
247+
}
242248
}

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

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,9 @@ public class StateActions {
1717
public static final String ACTION_SET_VEHICLE_HOME = Utils.PACKAGE_NAME + ".action.SET_VEHICLE_HOME";
1818
public static final String EXTRA_VEHICLE_HOME_LOCATION = "extra_vehicle_home_location";
1919

20+
public static final String ACTION_ENABLE_RETURN_TO_ME = Utils.PACKAGE_NAME + ".action.ENABLE_RETURN_TO_ME";
21+
public static final String EXTRA_IS_RETURN_TO_ME_ENABLED = "extra_is_return_to_me_enabled";
22+
2023
//Private to prevent instantiation
2124
private StateActions(){}
2225
}

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEvent.java

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -207,4 +207,10 @@ private AttributeEvent() {
207207
*/
208208
public static final String GIMBAL_ORIENTATION_UPDATED = PACKAGE_NAME + ".GIMBAL_ORIENTATION_UPDATED";
209209

210+
/**
211+
* Signals an update to the return to me state.
212+
* Retrieves the current state via {@link AttributeEventExtra#EXTRA_RETURN_TO_ME_STATE}
213+
*/
214+
public static final String RETURN_TO_ME_STATE_UPDATE = PACKAGE_NAME + ".RETURN_TO_ME_STATE_UPDATE";
215+
210216
}

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeEventExtra.java

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,4 +110,10 @@ private AttributeEventExtra() {
110110
*/
111111
public static final String EXTRA_GIMBAL_ORIENTATION_YAW = PACKAGE_NAME + ".EXTRA_GIMBAL_ORIENTATION_YAW";
112112

113+
/**
114+
* Used to retrieve the return to me state.
115+
* @see {@link AttributeEvent#RETURN_TO_ME_STATE_UPDATE}
116+
*/
117+
public static final String EXTRA_RETURN_TO_ME_STATE = PACKAGE_NAME + ".EXTRA_RETURN_TO_ME_STATE";
118+
113119
}

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/attribute/AttributeType.java

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -101,4 +101,10 @@ private AttributeType(){}
101101
*/
102102
public static final String MAGNETOMETER_CALIBRATION_STATUS = PACKAGE_NAME + ".MAGNETOMETER_CALIBRATION_STATUS";
103103

104+
/**
105+
* Used to retrieve the 'return to me' state.
106+
* @see {@link com.o3dr.services.android.lib.gcs.returnToMe.ReturnToMeState}
107+
*/
108+
public static final String RETURN_TO_ME_STATE = PACKAGE_NAME + ".RETURN_TO_ME_STATE";
109+
104110
}

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/property/State.java

Lines changed: 27 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -3,12 +3,18 @@
33
import android.os.Parcel;
44
import android.os.Parcelable;
55
import android.text.TextUtils;
6+
import android.util.Log;
7+
8+
import org.json.JSONException;
9+
import org.json.JSONObject;
610

711
/**
812
* Created by fhuya on 10/28/14.
913
*/
1014
public class State implements DroneAttribute {
1115

16+
private static final String TAG = State.class.getSimpleName();
17+
1218
public static final int INVALID_MAVLINK_VERSION = -1;
1319

1420
private boolean isConnected;
@@ -25,15 +31,18 @@ public class State implements DroneAttribute {
2531

2632
private Vibration vehicleVibration = new Vibration();
2733

28-
private String vehicleUid;
34+
private final JSONObject vehicleUid;
2935

3036
public State() {
37+
this.vehicleUid = new JSONObject();
3138
}
3239

3340
public State(boolean isConnected, VehicleMode mode, boolean armed, boolean flying,
3441
String autopilotErrorId, int mavlinkVersion, String calibrationStatus,
3542
long flightStartTime, EkfStatus ekfStatus, boolean isTelemetryLive,
3643
Vibration vibration) {
44+
this.vehicleUid = new JSONObject();
45+
3746
this.isConnected = isConnected;
3847
this.armed = armed;
3948
this.isFlying = flying;
@@ -146,12 +155,16 @@ public Vibration getVehicleVibration() {
146155
return vehicleVibration;
147156
}
148157

149-
public String getVehicleUid() {
158+
public JSONObject getVehicleUid() {
150159
return vehicleUid;
151160
}
152161

153-
public void setVehicleUid(String vehicleUid) {
154-
this.vehicleUid = vehicleUid;
162+
public void addToVehicleUid(String uidLabel, String uid) {
163+
try {
164+
this.vehicleUid.put(uidLabel, uid);
165+
} catch (JSONException e) {
166+
Log.e(TAG, e.getMessage(), e);
167+
}
155168
}
156169

157170
@Override
@@ -172,7 +185,7 @@ public void writeToParcel(Parcel dest, int flags) {
172185
dest.writeParcelable(this.ekfStatus, 0);
173186
dest.writeByte(isTelemetryLive ? (byte) 1 : (byte) 0);
174187
dest.writeParcelable(this.vehicleVibration, 0);
175-
dest.writeString(this.vehicleUid);
188+
dest.writeString(this.vehicleUid.toString());
176189
}
177190

178191
private State(Parcel in) {
@@ -187,7 +200,15 @@ private State(Parcel in) {
187200
this.ekfStatus = in.readParcelable(EkfStatus.class.getClassLoader());
188201
this.isTelemetryLive = in.readByte() != 0;
189202
this.vehicleVibration = in.readParcelable(Vibration.class.getClassLoader());
190-
this.vehicleUid = in.readString();
203+
204+
JSONObject temp;
205+
try {
206+
temp = new JSONObject(in.readString());
207+
} catch (JSONException e) {
208+
temp = new JSONObject();
209+
}
210+
211+
this.vehicleUid = temp;
191212
}
192213

193214
public static final Creator<State> CREATOR = new Creator<State>() {
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
package com.o3dr.services.android.lib.gcs.returnToMe;
2+
3+
parcelable ReturnToMeState;
Lines changed: 96 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,96 @@
1+
package com.o3dr.services.android.lib.gcs.returnToMe;
2+
3+
import android.os.Parcel;
4+
import android.support.annotation.IntDef;
5+
6+
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
7+
import com.o3dr.services.android.lib.drone.property.DroneAttribute;
8+
9+
import java.lang.annotation.Retention;
10+
import java.lang.annotation.RetentionPolicy;
11+
12+
/**
13+
* Created by Fredia Huya-Kouadio on 9/22/15.
14+
*/
15+
public class ReturnToMeState implements DroneAttribute {
16+
17+
@IntDef({STATE_IDLE, STATE_USER_LOCATION_UNAVAILABLE, STATE_USER_LOCATION_INACCURATE,
18+
STATE_WAITING_FOR_VEHICLE_GPS, STATE_UPDATING_HOME, STATE_ERROR_UPDATING_HOME})
19+
@Retention(RetentionPolicy.SOURCE)
20+
public @interface ReturnToMeStates{}
21+
22+
public static final int STATE_IDLE = 0;
23+
public static final int STATE_USER_LOCATION_UNAVAILABLE = 1;
24+
public static final int STATE_USER_LOCATION_INACCURATE = 2;
25+
public static final int STATE_WAITING_FOR_VEHICLE_GPS = 3;
26+
public static final int STATE_UPDATING_HOME = 4;
27+
public static final int STATE_ERROR_UPDATING_HOME = 5;
28+
29+
private LatLongAlt originalHomeLocation;
30+
private LatLongAlt currentHomeLocation;
31+
32+
@ReturnToMeStates
33+
private int state = STATE_IDLE;
34+
35+
public ReturnToMeState(){}
36+
37+
public ReturnToMeState(@ReturnToMeStates int state){
38+
this.state = state;
39+
}
40+
41+
@ReturnToMeStates
42+
public int getState() {
43+
return state;
44+
}
45+
46+
public void setState(@ReturnToMeStates int state) {
47+
this.state = state;
48+
}
49+
50+
public LatLongAlt getCurrentHomeLocation() {
51+
return currentHomeLocation;
52+
}
53+
54+
public void setCurrentHomeLocation(LatLongAlt currentHomeLocation) {
55+
this.currentHomeLocation = currentHomeLocation;
56+
}
57+
58+
public LatLongAlt getOriginalHomeLocation() {
59+
return originalHomeLocation;
60+
}
61+
62+
public void setOriginalHomeLocation(LatLongAlt originalHomeLocation) {
63+
this.originalHomeLocation = originalHomeLocation;
64+
}
65+
66+
@Override
67+
public int describeContents() {
68+
return 0;
69+
}
70+
71+
@Override
72+
public void writeToParcel(Parcel dest, int flags) {
73+
dest.writeInt(this.state);
74+
75+
dest.writeParcelable(this.originalHomeLocation, 0);
76+
dest.writeParcelable(this.currentHomeLocation, 0);
77+
}
78+
79+
protected ReturnToMeState(Parcel in) {
80+
@ReturnToMeStates final int temp = in.readInt();
81+
this.state = temp;
82+
83+
this.originalHomeLocation = in.readParcelable(LatLongAlt.class.getClassLoader());
84+
this.currentHomeLocation = in.readParcelable(LatLongAlt.class.getClassLoader());
85+
}
86+
87+
public static final Creator<ReturnToMeState> CREATOR = new Creator<ReturnToMeState>() {
88+
public ReturnToMeState createFromParcel(Parcel source) {
89+
return new ReturnToMeState(source);
90+
}
91+
92+
public ReturnToMeState[] newArray(int size) {
93+
return new ReturnToMeState[size];
94+
}
95+
};
96+
}
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
11
<?xml version="1.0" encoding="utf-8"?>
22
<resources>
3-
<integer name="core_lib_version">20503</integer>
3+
<integer name="core_lib_version">20505</integer>
44
</resources>

ServiceApp/AndroidManifest.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
android:allowBackup="true"
4040
android:theme="@style/AppTheme"
4141
android:icon="@drawable/ic_launcher"
42+
android:largeHeap="true"
4243
android:label="@string/app_title">
4344

4445
<meta-data

0 commit comments

Comments
 (0)