Skip to content

Commit 0e76753

Browse files
committed
bug fixes.
1 parent c0fe872 commit 0e76753

File tree

9 files changed

+36
-26
lines changed

9 files changed

+36
-26
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.3.08'
5+
PUBLISH_VERSION = '2.3.09'
66
PROJECT_DESCRIPTION = "DroneKit-Android 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 14
1919
targetSdkVersion 21
20-
versionCode 20308
20+
versionCode 20309
2121
versionName PUBLISH_VERSION
2222
}
2323

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ public class AttributeEvent {
1414

1515
/**
1616
* Signals an autopilot error.
17-
* @see {@link com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra#EXTRA_AUTOPILOT_ERROR_TYPE}
17+
* @see {@link com.o3dr.services.android.lib.drone.attribute.AttributeEventExtra#EXTRA_AUTOPILOT_ERROR_ID}
1818
*/
1919
public static final String AUTOPILOT_ERROR = PACKAGE_NAME + ".AUTOPILOT_ERROR";
2020

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ public class AttributeEventExtra {
1212
* @see {@link com.o3dr.services.android.lib.drone.attribute.error.ErrorType}
1313
* @see {@link com.o3dr.services.android.lib.drone.attribute.AttributeEvent#AUTOPILOT_ERROR}
1414
*/
15-
public static final String EXTRA_AUTOPILOT_ERROR_TYPE = PACKAGE_NAME + ".AUTOPILOT_ERROR_TYPE";
15+
public static final String EXTRA_AUTOPILOT_ERROR_ID = PACKAGE_NAME + ".AUTOPILOT_ERROR_ID";
1616

1717
/**
1818
* Used to access autopilot messages.

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

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
import android.os.Parcel;
55
import android.os.Parcelable;
66
import android.support.annotation.StringRes;
7+
import android.text.TextUtils;
78

89
import com.o3dr.android.client.R;
910

@@ -69,6 +70,13 @@ public CharSequence getLabel(Context context){
6970
return context.getText(this.labelResId);
7071
}
7172

73+
public static ErrorType getErrorById(String errorId){
74+
if(TextUtils.isEmpty(errorId))
75+
return null;
76+
77+
return ErrorType.valueOf(errorId);
78+
}
79+
7280
@Override
7381
public int describeContents(){
7482
return 0;

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

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -16,20 +16,20 @@ public class State implements Parcelable {
1616
private boolean isFlying;
1717
private String calibrationStatus;
1818
private VehicleMode vehicleMode = VehicleMode.UNKNOWN;
19-
private String autopilotError;
19+
private String autopilotErrorId;
2020
private int mavlinkVersion = INVALID_MAVLINK_VERSION;
2121
private long flightStartTime;
2222

2323
public State(){}
2424

25-
public State(boolean isConnected, VehicleMode mode, boolean armed, boolean flying, String autopilotError,
25+
public State(boolean isConnected, VehicleMode mode, boolean armed, boolean flying, String autopilotErrorId,
2626
int mavlinkVersion, String calibrationStatus, long flightStartTime){
2727
this.isConnected = isConnected;
2828
this.vehicleMode = mode;
2929
this.armed = armed;
3030
this.isFlying = flying;
3131
this.flightStartTime = flightStartTime;
32-
this.autopilotError = autopilotError;
32+
this.autopilotErrorId = autopilotErrorId;
3333
this.mavlinkVersion = mavlinkVersion;
3434
this.calibrationStatus = calibrationStatus;
3535
}
@@ -74,16 +74,16 @@ public VehicleMode getVehicleMode() {
7474
return vehicleMode;
7575
}
7676

77-
public String getAutopilotError() {
78-
return autopilotError;
77+
public String getAutopilotErrorId() {
78+
return autopilotErrorId;
7979
}
8080

81-
public void setAutopilotError(String autopilotError) {
82-
this.autopilotError = autopilotError;
81+
public void setAutopilotErrorId(String autopilotErrorId) {
82+
this.autopilotErrorId = autopilotErrorId;
8383
}
8484

8585
public boolean isWarning(){
86-
return TextUtils.isEmpty(autopilotError);
86+
return TextUtils.isEmpty(autopilotErrorId);
8787
}
8888

8989
public boolean isCalibrating(){
@@ -122,7 +122,7 @@ public void writeToParcel(Parcel dest, int flags) {
122122
dest.writeByte(isFlying ? (byte) 1 : (byte) 0);
123123
dest.writeString(this.calibrationStatus);
124124
dest.writeParcelable(this.vehicleMode, 0);
125-
dest.writeString(this.autopilotError);
125+
dest.writeString(this.autopilotErrorId);
126126
dest.writeInt(this.mavlinkVersion);
127127
dest.writeLong(this.flightStartTime);
128128
}
@@ -133,7 +133,7 @@ private State(Parcel in) {
133133
this.isFlying = in.readByte() != 0;
134134
this.calibrationStatus = in.readString();
135135
this.vehicleMode = in.readParcelable(VehicleMode.class.getClassLoader());
136-
this.autopilotError = in.readString();
136+
this.autopilotErrorId = in.readString();
137137
this.mavlinkVersion = in.readInt();
138138
this.flightStartTime = in.readLong();
139139
}

ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -587,9 +587,8 @@ public void onDroneEvent(DroneInterfaces.DroneEventsType event, Drone drone) {
587587
break;
588588

589589
case AUTOPILOT_WARNING:
590-
final ErrorType errorType = ErrorType.valueOf(drone.getState().getErrorType());
591590
extrasBundle = new Bundle(1);
592-
extrasBundle.putParcelable(AttributeEventExtra.EXTRA_AUTOPILOT_ERROR_TYPE, errorType);
591+
extrasBundle.putString(AttributeEventExtra.EXTRA_AUTOPILOT_ERROR_ID, drone.getState().getErrorId());
593592
droneEvent = AttributeEvent.AUTOPILOT_ERROR;
594593
break;
595594

ServiceApp/src/org/droidplanner/services/android/api/DroneApiUtils.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -350,7 +350,7 @@ static State getState(Drone drone, boolean isConnected) {
350350
String calibrationMessage = calibration.isCalibrating() ? calibration.getMessage() : null;
351351

352352
return new State(isConnected, DroneApiUtils.getVehicleMode(droneMode), droneState.isArmed(), droneState.isFlying(),
353-
droneState.getErrorType(), drone.getMavlinkVersion(), calibrationMessage,
353+
droneState.getErrorId(), drone.getMavlinkVersion(), calibrationMessage,
354354
droneState.getFlightStartTime());
355355
}
356356

dependencyLibs/Core/src/org/droidplanner/core/drone/variables/State.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ public class State extends DroneVariable {
1515

1616
private final AutopilotWarningParser warningParser;
1717

18-
private String errorType;
18+
private String errorId;
1919
private boolean armed = false;
2020
private boolean isFlying = false;
2121
private ApmModes mode = ApmModes.UNKNOWN;
@@ -38,7 +38,7 @@ public State(Drone myDrone, Clock clock, Handler handler, AutopilotWarningParser
3838
this.clock = clock;
3939
this.watchdog = handler;
4040
this.warningParser = warningParser;
41-
this.errorType = warningParser.getDefaultWarning();
41+
this.errorId = warningParser.getDefaultWarning();
4242
resetFlightStartTime();
4343
}
4444

@@ -54,8 +54,8 @@ public ApmModes getMode() {
5454
return mode;
5555
}
5656

57-
public String getErrorType() {
58-
return errorType;
57+
public String getErrorId() {
58+
return errorId;
5959
}
6060

6161
public void setIsFlying(boolean newState) {
@@ -74,8 +74,8 @@ public boolean parseAutopilotError(String errorMsg){
7474
if(parsedError == null || parsedError.trim().isEmpty())
7575
return false;
7676

77-
if (!parsedError.equals(this.errorType)) {
78-
this.errorType = parsedError;
77+
if (!parsedError.equals(this.errorId)) {
78+
this.errorId = parsedError;
7979
myDrone.notifyDroneEvent(DroneEventsType.AUTOPILOT_WARNING);
8080
}
8181

@@ -85,7 +85,7 @@ public boolean parseAutopilotError(String errorMsg){
8585
}
8686

8787
public void repeatWarning(){
88-
if(errorType == null || errorType.length() == 0 || errorType.equals(warningParser.getDefaultWarning()))
88+
if(errorId == null || errorId.length() == 0 || errorId.equals(warningParser.getDefaultWarning()))
8989
return;
9090

9191
watchdog.removeCallbacks(watchdogCallback);
@@ -125,8 +125,8 @@ protected void resetWarning() {
125125
if(defaultWarning == null)
126126
defaultWarning = "";
127127

128-
if (!defaultWarning.equals(this.errorType)) {
129-
this.errorType = defaultWarning;
128+
if (!defaultWarning.equals(this.errorId)) {
129+
this.errorId = defaultWarning;
130130
myDrone.notifyDroneEvent(DroneEventsType.AUTOPILOT_WARNING);
131131
}
132132
}

release_android_library.gradle

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,8 @@ task androidJavadocs(type: Javadoc) {
2929
title = projectDescription
3030
exclude '**/*.aidl'
3131
classpath += project.files(android.getBootClasspath().join(File.pathSeparator))
32+
options.links("http://docs.oracle.com/javase/7/docs/api/")
33+
options.links("https://developer.android.com/reference/packages.html")
3234
}
3335

3436
task androidJavadocsJar(type: Jar, dependsOn: androidJavadocs){
@@ -77,6 +79,7 @@ bintray {
7779
pkg {
7880
repo = getMavenRepo()
7981
name = projectArtifactId
82+
userOrg = '3d-robotics'
8083
desc = projectDescription
8184
websiteUrl = 'https://github.com/DroidPlanner/DroneKit-Android'
8285
issueTrackerUrl = 'https://github.com/DroidPlanner/DroneKit-Android/issues'

0 commit comments

Comments
 (0)