Skip to content

Commit 5de9286

Browse files
committed
Merge pull request #57 from 3drobotics/release-1.5.1
Release 1.5.1
2 parents a4e5f4e + 3584ed6 commit 5de9286

File tree

147 files changed

+4697
-2240
lines changed

Some content is hidden

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

147 files changed

+4697
-2240
lines changed

.gitignore

+3
Original file line numberDiff line numberDiff line change
@@ -45,3 +45,6 @@ crashlytics.properties
4545

4646
# Vagrant
4747
.vagrant/
48+
49+
# Fabric (crashlytics)
50+
fabric.properties

.travis.yml

+15-7
Original file line numberDiff line numberDiff line change
@@ -10,19 +10,27 @@ android:
1010
components:
1111
- platform-tools
1212
- tools
13+
14+
# The BuildTools version used by your project
15+
- build-tools-23.0.2
16+
17+
# The SDK version used to compile your project
18+
- android-23
19+
20+
# Additional components
21+
- extra-google-google_play_services
22+
- extra-google-m2repository
23+
- extra-android-m2repository
24+
- extra-android-support
25+
1326
licenses:
1427
- 'android-sdk-license-.+'
1528

1629
before_script:
17-
- echo yes | android update sdk -u -a -t tools
18-
- echo yes | android update sdk -u -a -t build-tools-22.0.1
19-
- echo yes | android update sdk -u -a -t android-22
20-
- echo yes | android update sdk -u -a -t extra-google-m2repository
21-
- echo yes | android update sdk -u -a -t extra-android-m2repository
22-
- echo yes | android update sdk -u -a -t extra-android-support,extra-google-google_play_services
2330
- export GRADLE_OPTS="-XX:MaxPermSize=2048m -Xmx1536m"
2431

25-
script: ./gradlew clean build
32+
script: ./gradlew cleanJar clean testDevDebug assembleDevDebug -PdisablePreDex
33+
2634
after_success:
2735
- chmod a+x .utility/push-docs-to-gh-pages.sh
2836
- .utility/push-docs-to-gh-pages.sh

ClientLib/build.gradle

+11-11
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ apply plugin: 'com.android.library'
22

33
ext {
44
VERSION_MAJOR = 2
5-
VERSION_MINOR = 7
5+
VERSION_MINOR = 8
66
VERSION_PATCH = 0
77
VERSION_SUFFIX = "release"
88

@@ -15,12 +15,12 @@ ext {
1515
}
1616

1717
android {
18-
compileSdkVersion Integer.parseInt(project.ANDROID_BUILD_SDK_VERSION)
19-
buildToolsVersion project.ANDROID_BUILD_TOOLS_VERSION
18+
compileSdkVersion android_build_sdk_version
19+
buildToolsVersion android_build_tools_version
2020

2121
defaultConfig {
22-
minSdkVersion Integer.parseInt(project.ANDROID_BUILD_MIN_SDK_VERSION)
23-
targetSdkVersion Integer.parseInt(project.ANDROID_BUILD_TARGET_SDK_VERSION)
22+
minSdkVersion android_build_min_sdk_version
23+
targetSdkVersion android_build_target_sdk_version
2424
versionCode PUBLISH_VERSION_CODE
2525
versionName PUBLISH_VERSION
2626
}
@@ -55,13 +55,13 @@ android {
5555
}
5656

5757
dependencies {
58-
compile 'com.android.support:support-v4:22.2.1'
59-
compile 'com.google.android.gms:play-services-base:7.3.0'
58+
compile "com.android.support:support-v4:${support_lib_version}"
59+
compile "com.google.android.gms:play-services-base:${play_services_version}"
6060

61-
compile project(':dependencyLibs:Mavlink')
62-
compile files('libs/Mavlink.jar')
61+
debugCompile project(':Mavlink')
62+
releaseCompile files('libs/Mavlink.jar')
6363
}
6464

65-
assemble.dependsOn ':dependencyLibs:Mavlink:jar'
65+
assemble.dependsOn ':Mavlink:jar'
6666

67-
apply from: "${rootDir}/release_android_library.gradle"
67+
apply from: "../release_android_library.gradle"

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

+85-44
Original file line numberDiff line numberDiff line change
@@ -16,11 +16,14 @@
1616
import com.o3dr.android.client.apis.MissionApi;
1717
import com.o3dr.android.client.apis.VehicleApi;
1818
import com.o3dr.android.client.interfaces.DroneListener;
19+
import com.o3dr.android.client.utils.TxPowerComplianceCountries;
1920
import com.o3dr.services.android.lib.coordinate.LatLong;
2021
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
2122
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
2223
import com.o3dr.services.android.lib.drone.calibration.magnetometer.MagnetometerCalibrationStatus;
2324
import com.o3dr.services.android.lib.drone.companion.solo.SoloAttributes;
25+
import com.o3dr.services.android.lib.drone.companion.solo.SoloEventExtras;
26+
import com.o3dr.services.android.lib.drone.companion.solo.SoloEvents;
2427
import com.o3dr.services.android.lib.drone.connection.ConnectionParameter;
2528
import com.o3dr.services.android.lib.drone.connection.ConnectionResult;
2629
import com.o3dr.services.android.lib.drone.mission.Mission;
@@ -132,17 +135,19 @@ void init(ControlTower controlTower, Handler handler) {
132135
this.droneObserver = new DroneObserver(this);
133136
}
134137

135-
Context getContext(){
138+
Context getContext() {
136139
return this.context;
137140
}
138141

139142
synchronized void start() {
140-
if (!serviceMgr.isTowerConnected())
143+
if (!serviceMgr.isTowerConnected()) {
141144
throw new IllegalStateException("Service manager must be connected.");
145+
}
142146

143147
IDroneApi droneApi = droneApiRef.get();
144-
if (isStarted(droneApi))
148+
if (isStarted(droneApi)) {
145149
return;
150+
}
146151

147152
try {
148153
droneApi = serviceMgr.get3drServices().registerDroneApi(this.apiListener, serviceMgr.getApplicationId());
@@ -151,8 +156,9 @@ synchronized void start() {
151156
throw new IllegalStateException("Unable to retrieve a valid drone handle.");
152157
}
153158

154-
if (asyncScheduler == null || asyncScheduler.isShutdown())
159+
if (asyncScheduler == null || asyncScheduler.isShutdown()) {
155160
asyncScheduler = Executors.newFixedThreadPool(1);
161+
}
156162

157163
addAttributesObserver(droneApi, this.droneObserver);
158164
resetFlightTimer();
@@ -185,16 +191,17 @@ synchronized void destroy() {
185191
private void checkForGroundCollision() {
186192
Speed speed = getAttribute(AttributeType.SPEED);
187193
Altitude altitude = getAttribute(AttributeType.ALTITUDE);
188-
if (speed == null || altitude == null)
194+
if (speed == null || altitude == null) {
189195
return;
196+
}
190197

191198
double verticalSpeed = speed.getVerticalSpeed();
192199
double altitudeValue = altitude.getAltitude();
193200

194201
boolean isCollisionImminent = altitudeValue
195-
+ (verticalSpeed * COLLISION_SECONDS_BEFORE_COLLISION) < 0
196-
&& verticalSpeed < COLLISION_DANGEROUS_SPEED_METERS_PER_SECOND
197-
&& altitudeValue > COLLISION_SAFE_ALTITUDE_METERS;
202+
+ (verticalSpeed * COLLISION_SECONDS_BEFORE_COLLISION) < 0
203+
&& verticalSpeed < COLLISION_DANGEROUS_SPEED_METERS_PER_SECOND
204+
&& altitudeValue > COLLISION_SAFE_ALTITUDE_METERS;
198205

199206
Bundle extrasBundle = new Bundle(1);
200207
extrasBundle.putBoolean(EXTRA_IS_GROUND_COLLISION_IMMINENT, isCollisionImminent);
@@ -214,8 +221,9 @@ public double getSpeedParameter() {
214221
Parameters params = getAttribute(AttributeType.PARAMETERS);
215222
if (params != null) {
216223
Parameter speedParam = params.getParameter("WPNAV_SPEED");
217-
if (speedParam != null)
224+
if (speedParam != null) {
218225
return speedParam.getValue();
226+
}
219227
}
220228

221229
return 0;
@@ -227,8 +235,9 @@ public double getSpeedParameter() {
227235
* @param action Runnabl that will be executed.
228236
*/
229237
public void post(Runnable action) {
230-
if (handler == null || action == null)
238+
if (handler == null || action == null) {
231239
return;
240+
}
232241

233242
handler.post(action);
234243
}
@@ -262,8 +271,9 @@ public long getFlightTime() {
262271

263272
public <T extends Parcelable> T getAttribute(String type) {
264273
final IDroneApi droneApi = droneApiRef.get();
265-
if (!isStarted(droneApi) || type == null)
274+
if (!isStarted(droneApi) || type == null) {
266275
return this.getAttributeDefaultValue(type);
276+
}
267277

268278
T attribute = null;
269279
Bundle carrier = null;
@@ -277,7 +287,7 @@ public <T extends Parcelable> T getAttribute(String type) {
277287
try {
278288
carrier.setClassLoader(contextClassLoader);
279289
attribute = carrier.getParcelable(type);
280-
}catch(Exception e){
290+
} catch (Exception e) {
281291
Log.e(TAG, e.getMessage(), e);
282292
}
283293
}
@@ -287,8 +297,9 @@ public <T extends Parcelable> T getAttribute(String type) {
287297

288298
public <T extends Parcelable> void getAttributeAsync(final String attributeType,
289299
final OnAttributeRetrievedCallback<T> callback) {
290-
if (callback == null)
300+
if (callback == null) {
291301
throw new IllegalArgumentException("Callback must be non-null.");
302+
}
292303

293304
final IDroneApi droneApi = droneApiRef.get();
294305
if (!isStarted(droneApi)) {
@@ -309,19 +320,21 @@ public void run() {
309320
handler.post(new Runnable() {
310321
@Override
311322
public void run() {
312-
if (attribute == null)
323+
if (attribute == null) {
313324
callback.onRetrievalFailed();
314-
else
325+
} else {
315326
callback.onRetrievalSucceed(attribute);
327+
}
316328
}
317329
});
318330
}
319331
});
320332
}
321333

322334
private <T extends Parcelable> T getAttributeDefaultValue(String attributeType) {
323-
if (attributeType == null)
335+
if (attributeType == null) {
324336
return null;
337+
}
325338

326339
switch (attributeType) {
327340
case AttributeType.ALTITUDE:
@@ -475,7 +488,7 @@ private boolean isStarted(IDroneApi droneApi) {
475488
return droneApi != null && droneApi.asBinder().pingBinder();
476489
}
477490

478-
public boolean isStarted(){
491+
public boolean isStarted() {
479492
return isStarted(droneApiRef.get());
480493
}
481494

@@ -491,11 +504,13 @@ public ConnectionParameter getConnectionParameter() {
491504

492505
public <T extends MissionItem> void buildMissionItemsAsync(final MissionItem.ComplexItem<T>[] missionItems,
493506
final OnMissionItemsBuiltCallback<T> callback) {
494-
if (callback == null)
507+
if (callback == null) {
495508
throw new IllegalArgumentException("Callback must be non-null.");
509+
}
496510

497-
if (missionItems == null || missionItems.length == 0)
511+
if (missionItems == null || missionItems.length == 0) {
498512
return;
513+
}
499514

500515
asyncScheduler.execute(new Runnable() {
501516
@Override
@@ -514,11 +529,13 @@ public void run() {
514529
}
515530

516531
public void registerDroneListener(DroneListener listener) {
517-
if (listener == null)
532+
if (listener == null) {
518533
return;
534+
}
519535

520-
if (!droneListeners.contains(listener))
536+
if (!droneListeners.contains(listener)) {
521537
droneListeners.add(listener);
538+
}
522539
}
523540

524541
private void addAttributesObserver(IDroneApi droneApi, IObserver observer) {
@@ -554,8 +571,9 @@ public void removeMavlinkObserver(MavlinkObserver observer) {
554571
}
555572

556573
public void unregisterDroneListener(DroneListener listener) {
557-
if (listener == null)
574+
if (listener == null) {
558575
return;
576+
}
559577

560578
droneListeners.remove(listener);
561579
}
@@ -689,13 +707,14 @@ public void loadWaypoints() {
689707
MissionApi.getApi(this).loadWaypoints();
690708
}
691709

692-
public Handler getHandler(){
710+
public Handler getHandler() {
693711
return handler;
694712
}
695713

696714
void notifyDroneConnectionFailed(final ConnectionResult result) {
697-
if (droneListeners.isEmpty())
715+
if (droneListeners.isEmpty()) {
698716
return;
717+
}
699718

700719
handler.post(new Runnable() {
701720
@Override
@@ -708,38 +727,59 @@ public void run() {
708727

709728
void notifyAttributeUpdated(final String attributeEvent, final Bundle extras) {
710729
//Update the bundle classloader
711-
if (extras != null)
730+
if (extras != null) {
712731
extras.setClassLoader(contextClassLoader);
732+
}
713733

714-
if (AttributeEvent.STATE_UPDATED.equals(attributeEvent)) {
715-
getAttributeAsync(AttributeType.STATE, new OnAttributeRetrievedCallback<State>() {
716-
@Override
717-
public void onRetrievalSucceed(State state) {
718-
if (state.isFlying())
719-
resetFlightTimer();
720-
else
721-
stopTimer();
722-
}
734+
switch (attributeEvent) {
735+
case AttributeEvent.STATE_UPDATED:
736+
getAttributeAsync(AttributeType.STATE, new OnAttributeRetrievedCallback<State>() {
737+
@Override
738+
public void onRetrievalSucceed(State state) {
739+
if (state.isFlying()) {
740+
resetFlightTimer();
741+
} else {
742+
stopTimer();
743+
}
744+
}
723745

724-
@Override
725-
public void onRetrievalFailed() {
726-
stopTimer();
727-
}
728-
});
729-
} else if (AttributeEvent.SPEED_UPDATED.equals(attributeEvent)) {
730-
checkForGroundCollision();
746+
@Override
747+
public void onRetrievalFailed() {
748+
stopTimer();
749+
}
750+
});
751+
break;
752+
753+
case AttributeEvent.SPEED_UPDATED:
754+
checkForGroundCollision();
755+
break;
756+
757+
//TODO remove this when deprecated methods are deleted in 3.0
758+
// This ensures that the api is backwards compatible
759+
case SoloEvents.SOLO_TX_POWER_COMPLIANCE_COUNTRY_UPDATED:
760+
String compliantCountry = extras.getString(SoloEventExtras.EXTRA_SOLO_TX_POWER_COMPLIANT_COUNTRY);
761+
final Bundle eventInfo = new Bundle(1);
762+
boolean isEUCompliant = !TxPowerComplianceCountries.getDefaultCountry().name().equals(compliantCountry);
763+
eventInfo.putBoolean(SoloEventExtras.EXTRA_SOLO_EU_TX_POWER_COMPLIANT, isEUCompliant);
764+
sendEventToListeners(SoloEvents.SOLO_EU_TX_POWER_COMPLIANCE_UPDATED, eventInfo);
765+
break;
731766
}
732767

733-
if (droneListeners.isEmpty())
768+
sendEventToListeners(attributeEvent, extras);
769+
}
770+
771+
private void sendEventToListeners(final String attributeEvent, final Bundle extras) {
772+
if (droneListeners.isEmpty()) {
734773
return;
774+
}
735775

736776
handler.post(new Runnable() {
737777
@Override
738778
public void run() {
739779
for (DroneListener listener : droneListeners) {
740780
try {
741781
listener.onDroneEvent(attributeEvent, extras);
742-
}catch(Exception e){
782+
} catch (Exception e) {
743783
Log.e(TAG, e.getMessage(), e);
744784
}
745785
}
@@ -748,8 +788,9 @@ public void run() {
748788
}
749789

750790
void notifyDroneServiceInterrupted(final String errorMsg) {
751-
if (droneListeners.isEmpty())
791+
if (droneListeners.isEmpty()) {
752792
return;
793+
}
753794

754795
handler.post(new Runnable() {
755796
@Override

0 commit comments

Comments
 (0)