Skip to content

Commit 71fad97

Browse files
committed
Merge pull request #228 from dronekit/release-1.3.2
Release 1.3.2
2 parents 0a29036 + 2d469ce commit 71fad97

File tree

42 files changed

+781
-432
lines changed

Some content is hidden

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

42 files changed

+781
-432
lines changed

ClientLib/build.gradle

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ apply plugin: 'com.android.library'
22

33
ext {
44
PUBLISH_ARTIFACT_ID = 'dronekit-android'
5-
PUBLISH_VERSION = '2.5.9'
5+
PUBLISH_VERSION = '2.5.15'
66
PROJECT_DESCRIPTION = "Android DroneKit client library."
77
PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android', 'DroneKit']
88
PROJECT_LICENSES = ['Apache-2.0']
@@ -17,7 +17,7 @@ android {
1717
defaultConfig {
1818
minSdkVersion Integer.parseInt(project.ANDROID_BUILD_MIN_SDK_VERSION)
1919
targetSdkVersion Integer.parseInt(project.ANDROID_BUILD_TARGET_SDK_VERSION)
20-
versionCode 20509
20+
versionCode 20515
2121
versionName PUBLISH_VERSION
2222
}
2323

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

Lines changed: 44 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@
4848
import java.util.concurrent.ConcurrentLinkedQueue;
4949
import java.util.concurrent.ExecutorService;
5050
import java.util.concurrent.Executors;
51+
import java.util.concurrent.atomic.AtomicReference;
5152

5253
/**
5354
* Created by fhuya on 11/4/14.
@@ -99,7 +100,7 @@ public void binderDied() {
99100
private DroneObserver droneObserver;
100101
private DroneApiListener apiListener;
101102

102-
private IDroneApi droneApi;
103+
private final AtomicReference<IDroneApi> droneApiRef = new AtomicReference<>(null);
103104
private ConnectionParameter connectionParameter;
104105
private ExecutorService asyncScheduler;
105106

@@ -132,34 +133,39 @@ Context getContext(){
132133
return this.context;
133134
}
134135

135-
void start() {
136+
synchronized void start() {
136137
if (!serviceMgr.isTowerConnected())
137138
throw new IllegalStateException("Service manager must be connected.");
138139

139-
if (isStarted())
140+
IDroneApi droneApi = droneApiRef.get();
141+
if (isStarted(droneApi))
140142
return;
141143

142144
try {
143-
this.droneApi = serviceMgr.get3drServices().registerDroneApi(this.apiListener, serviceMgr.getApplicationId());
144-
this.droneApi.asBinder().linkToDeath(binderDeathRecipient, 0);
145+
droneApi = serviceMgr.get3drServices().registerDroneApi(this.apiListener, serviceMgr.getApplicationId());
146+
droneApi.asBinder().linkToDeath(binderDeathRecipient, 0);
145147
} catch (RemoteException e) {
146148
throw new IllegalStateException("Unable to retrieve a valid drone handle.");
147149
}
148150

149151
if (asyncScheduler == null || asyncScheduler.isShutdown())
150152
asyncScheduler = Executors.newFixedThreadPool(1);
151153

152-
addAttributesObserver(this.droneObserver);
154+
addAttributesObserver(droneApi, this.droneObserver);
153155
resetFlightTimer();
156+
157+
droneApiRef.set(droneApi);
154158
}
155159

156-
void destroy() {
157-
removeAttributesObserver(this.droneObserver);
160+
synchronized void destroy() {
161+
IDroneApi droneApi = droneApiRef.get();
162+
163+
removeAttributesObserver(droneApi, this.droneObserver);
158164

159165
try {
160-
if (isStarted()) {
161-
this.droneApi.asBinder().unlinkToDeath(binderDeathRecipient, 0);
162-
serviceMgr.get3drServices().releaseDroneApi(this.droneApi);
166+
if (isStarted(droneApi)) {
167+
droneApi.asBinder().unlinkToDeath(binderDeathRecipient, 0);
168+
serviceMgr.get3drServices().releaseDroneApi(droneApi);
163169
}
164170
} catch (RemoteException | NoSuchElementException e) {
165171
Log.e(TAG, e.getMessage(), e);
@@ -170,7 +176,7 @@ void destroy() {
170176
asyncScheduler = null;
171177
}
172178

173-
droneListeners.clear();
179+
droneApiRef.set(null);
174180
}
175181

176182
private void checkForGroundCollision() {
@@ -193,6 +199,7 @@ private void checkForGroundCollision() {
193199
}
194200

195201
private void handleRemoteException(RemoteException e) {
202+
final IDroneApi droneApi = droneApiRef.get();
196203
if (droneApi != null && !droneApi.asBinder().pingBinder()) {
197204
final String errorMsg = e.getMessage();
198205
Log.e(TAG, errorMsg, e);
@@ -245,7 +252,8 @@ public long getFlightTime() {
245252
}
246253

247254
public <T extends Parcelable> T getAttribute(String type) {
248-
if (!isStarted() || type == null)
255+
final IDroneApi droneApi = droneApiRef.get();
256+
if (!isStarted(droneApi) || type == null)
249257
return this.getAttributeDefaultValue(type);
250258

251259
T attribute = null;
@@ -273,7 +281,8 @@ public <T extends Parcelable> void getAttributeAsync(final String attributeType,
273281
if (callback == null)
274282
throw new IllegalArgumentException("Callback must be non-null.");
275283

276-
if (!isStarted()) {
284+
final IDroneApi droneApi = droneApiRef.get();
285+
if (!isStarted(droneApi)) {
277286
handler.post(new Runnable() {
278287
@Override
279288
public void run() {
@@ -414,7 +423,8 @@ public boolean performActionOnDroneThread(Action action, AbstractCommandListener
414423
}
415424

416425
public boolean performActionOnHandler(Action action, final Handler handler, final AbstractCommandListener listener) {
417-
if (isStarted()) {
426+
final IDroneApi droneApi = droneApiRef.get();
427+
if (isStarted(droneApi)) {
418428
try {
419429
droneApi.executeAction(action, wrapListener(handler, listener));
420430
return true;
@@ -435,7 +445,8 @@ public boolean performAsyncActionOnDroneThread(Action action, AbstractCommandLis
435445
}
436446

437447
public boolean performAsyncActionOnHandler(Action action, Handler handler, AbstractCommandListener listener) {
438-
if (isStarted()) {
448+
final IDroneApi droneApi = droneApiRef.get();
449+
if (isStarted(droneApi)) {
439450
try {
440451
droneApi.executeAsyncAction(action, wrapListener(handler, listener));
441452
return true;
@@ -447,13 +458,18 @@ public boolean performAsyncActionOnHandler(Action action, Handler handler, Abstr
447458
return false;
448459
}
449460

450-
public boolean isStarted() {
461+
private boolean isStarted(IDroneApi droneApi) {
451462
return droneApi != null && droneApi.asBinder().pingBinder();
452463
}
453464

465+
public boolean isStarted(){
466+
return isStarted(droneApiRef.get());
467+
}
468+
454469
public boolean isConnected() {
470+
final IDroneApi droneApi = droneApiRef.get();
455471
State droneState = getAttribute(AttributeType.STATE);
456-
return isStarted() && droneState.isConnected();
472+
return isStarted(droneApi) && droneState.isConnected();
457473
}
458474

459475
public ConnectionParameter getConnectionParameter() {
@@ -492,18 +508,19 @@ public void registerDroneListener(DroneListener listener) {
492508
droneListeners.add(listener);
493509
}
494510

495-
private void addAttributesObserver(IObserver observer) {
496-
if (isStarted()) {
511+
private void addAttributesObserver(IDroneApi droneApi, IObserver observer) {
512+
if (isStarted(droneApi)) {
497513
try {
498-
this.droneApi.addAttributesObserver(observer);
514+
droneApi.addAttributesObserver(observer);
499515
} catch (RemoteException e) {
500516
handleRemoteException(e);
501517
}
502518
}
503519
}
504520

505521
public void addMavlinkObserver(MavlinkObserver observer) {
506-
if (isStarted()) {
522+
final IDroneApi droneApi = droneApiRef.get();
523+
if (isStarted(droneApi)) {
507524
try {
508525
droneApi.addMavlinkObserver(observer);
509526
} catch (RemoteException e) {
@@ -513,7 +530,8 @@ public void addMavlinkObserver(MavlinkObserver observer) {
513530
}
514531

515532
public void removeMavlinkObserver(MavlinkObserver observer) {
516-
if (isStarted()) {
533+
final IDroneApi droneApi = droneApiRef.get();
534+
if (isStarted(droneApi)) {
517535
try {
518536
droneApi.removeMavlinkObserver(observer);
519537
} catch (RemoteException e) {
@@ -529,10 +547,10 @@ public void unregisterDroneListener(DroneListener listener) {
529547
droneListeners.remove(listener);
530548
}
531549

532-
private void removeAttributesObserver(IObserver observer) {
533-
if (isStarted()) {
550+
private void removeAttributesObserver(IDroneApi droneApi, IObserver observer) {
551+
if (isStarted(droneApi)) {
534552
try {
535-
this.droneApi.removeAttributesObserver(observer);
553+
droneApi.removeAttributesObserver(observer);
536554
} catch (RemoteException e) {
537555
handleRemoteException(e);
538556
}

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

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ public GimbalApi build() {
3232
});
3333
}
3434

35-
private interface GimbalOrientationListener {
35+
public interface GimbalOrientationListener {
3636
/**
3737
* Called when the gimbal orientation is updated.
3838
* @param orientation GimbalOrientation object
@@ -88,7 +88,7 @@ public GimbalOrientation getGimbalOrientation(){
8888
}
8989

9090
/**
91-
* Enables control of the gimbal. After calling this method, use {@link GimbalApi#updateGimbalOrientation(double, double, double, GimbalOrientationListener)}
91+
* Enables control of the gimbal. After calling this method, use {@link GimbalApi#updateGimbalOrientation(float, float, float, GimbalOrientationListener)}
9292
* to update the gimbal orientation.
9393
* @param listener non-null GimbalStatusListener callback.
9494
*/
@@ -129,7 +129,7 @@ public void onError(int error){
129129
}
130130

131131
/**
132-
* Disables control of the gimbal. After calling this method, no call to {@link GimbalApi#updateGimbalOrientation(double, double, double, GimbalOrientationListener)}
132+
* Disables control of the gimbal. After calling this method, no call to {@link GimbalApi#updateGimbalOrientation(float, float, float, GimbalOrientationListener)}
133133
* will be allowed.
134134
* @param listener non-null GimbalStatusListener callback.
135135
*/
@@ -169,7 +169,7 @@ public void onError(int error){
169169
* @param yaw the desired gimbal yaw in degrees
170170
* @param listener Register a callback to receive update of the command execution state. Must be non-null.
171171
*/
172-
public void updateGimbalOrientation(double pitch, double roll, double yaw, final GimbalOrientationListener listener){
172+
public void updateGimbalOrientation(float pitch, float roll, float yaw, final GimbalOrientationListener listener){
173173
if(listener == null)
174174
throw new NullPointerException("Listener must be non-null.");
175175

@@ -184,9 +184,9 @@ public void run() {
184184
}
185185

186186
Bundle params = new Bundle();
187-
params.putDouble(GIMBAL_PITCH, pitch);
188-
params.putDouble(GIMBAL_ROLL, roll);
189-
params.putDouble(GIMBAL_YAW, yaw);
187+
params.putFloat(GIMBAL_PITCH, pitch);
188+
params.putFloat(GIMBAL_ROLL, roll);
189+
params.putFloat(GIMBAL_YAW, yaw);
190190
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_GIMBAL_ORIENTATION, params), new SimpleCommandListener(){
191191
@Override
192192
public void onTimeout(){

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

Lines changed: 34 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,17 @@ public void updateControllerMode(@SoloControllerMode.ControllerMode int controll
9494
drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_CONTROLLER_MODE, params), listener);
9595
}
9696

97+
/**
98+
* Updates the EU tx power compliance.
99+
* @param isCompliant true for the controller to be made compliant, false otherwise.
100+
* @param listener Register a callback to receive update of the command execution status.
101+
*/
102+
public void updateEUTxPowerCompliance(boolean isCompliant, AbstractCommandListener listener) {
103+
Bundle params = new Bundle();
104+
params.putBoolean(EXTRA_EU_TX_POWER_COMPLIANT, isCompliant);
105+
drone.performAsyncActionOnDroneThread(new Action(ACTION_UPDATE_EU_TX_POWER_COMPLIANCE, params), listener);
106+
}
107+
97108
/**
98109
* Take a photo with the connected gopro.
99110
* @param listener Register a callback to receive update of the command execution status.
@@ -132,6 +143,26 @@ public void onTimeout() {
132143
* @param listener Register a callback to receive update of the command execution status.
133144
*/
134145
public void toggleVideoRecording(final AbstractCommandListener listener){
146+
sendVideoRecordingCommand(SoloGoproRecord.TOGGLE_RECORDING, listener);
147+
}
148+
149+
/**
150+
* Starts video recording on the connected gopro.
151+
* @param listener Register a callback to receive update of the command execution status.
152+
*/
153+
public void startVideoRecording(final AbstractCommandListener listener){
154+
sendVideoRecordingCommand(SoloGoproRecord.START_RECORDING, listener);
155+
}
156+
157+
/**
158+
* Stops video recording on the connected gopro.
159+
* @param listener Register a callback to receive update of the command execution status.
160+
*/
161+
public void stopVideoRecording(final AbstractCommandListener listener){
162+
sendVideoRecordingCommand(SoloGoproRecord.STOP_RECORDING, listener);
163+
}
164+
165+
private void sendVideoRecordingCommand(@SoloGoproRecord.RecordCommand final int recordCommand, final AbstractCommandListener listener){
135166
//Set the gopro to video mode
136167
final SoloGoproSetRequest videoModeRequest = new SoloGoproSetRequest(SoloGoproSetRequest.CAPTURE_MODE,
137168
SoloGoproSetRequest.CAPTURE_MODE_VIDEO);
@@ -140,20 +171,20 @@ public void toggleVideoRecording(final AbstractCommandListener listener){
140171
@Override
141172
public void onSuccess() {
142173
//Send the command to toggle video recording
143-
final SoloGoproRecord videoToggle = new SoloGoproRecord(SoloGoproRecord.TOGGLE_RECORDING);
174+
final SoloGoproRecord videoToggle = new SoloGoproRecord(recordCommand);
144175
sendMessage(videoToggle, listener);
145176
}
146177

147178
@Override
148179
public void onError(int executionError) {
149-
if(listener != null){
180+
if (listener != null) {
150181
listener.onError(executionError);
151182
}
152183
}
153184

154185
@Override
155186
public void onTimeout() {
156-
if(listener != null){
187+
if (listener != null) {
157188
listener.onTimeout();
158189
}
159190
}

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
@@ -204,11 +204,17 @@ public class AttributeEvent {
204204
*/
205205
public static final String SOLOLINK_MESSAGE_RECEIVED = PACKAGE_NAME + ".SOLOLINK_MESSAGE_RECEIVED";
206206

207+
/**
208+
* Triggers upon updates to the EU tx power compliance.
209+
*/
210+
public static final String SOLOLINK_EU_TX_POWER_COMPLIANCE_UPDATED = PACKAGE_NAME + ".SOLOLINK_EU_TX_POWER_COMPLIANCE_UPDATED";
211+
207212
/**
208213
* Signals the gimbal orientation was updated.
209214
* @see {@link AttributeEventExtra#EXTRA_GIMBAL_ORIENTATION_PITCH}
210215
* @see {@link AttributeEventExtra#EXTRA_GIMBAL_ORIENTATION_ROLL}
211216
* @see {@link AttributeEventExtra#EXTRA_GIMBAL_ORIENTATION_YAW}
212217
*/
213218
public static final String GIMBAL_ORIENTATION_UPDATED = PACKAGE_NAME + ".GIMBAL_ORIENTATION_UPDATED";
219+
214220
}

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

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,4 +106,9 @@ public class AttributeEventExtra {
106106
*/
107107
public static final String EXTRA_GIMBAL_ORIENTATION_YAW = PACKAGE_NAME + ".EXTRA_GIMBAL_ORIENTATION_YAW";
108108

109+
/**
110+
* Used to retrieve the boolean value specifying whether the controller is compliant with the EU tx power levels.
111+
* @see {@link AttributeEvent#SOLOLINK_EU_TX_POWER_COMPLIANCE_UPDATED}
112+
*/
113+
public static final String EXTRA_SOLOLINK_EU_TX_POWER_COMPLIANT = PACKAGE_NAME + ".EXTRA_SOLOLINK_EU_TX_POWER_COMPLIANT";
109114
}

0 commit comments

Comments
 (0)