Skip to content

Commit 7db5963

Browse files
committed
Merge pull request #318 from dronekit/release-1.4.3.beta.3
Release 1.4.3 beta 3
2 parents 77be01c + 1081549 commit 7db5963

File tree

81 files changed

+1246
-1128
lines changed

Some content is hidden

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

81 files changed

+1246
-1128
lines changed

ClientLib/build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@ ext {
55
VERSION_MINOR = 6
66
VERSION_PATCH = 8
77
VERSION_BUILD = 0
8-
VERSION_SUFFIX = "beta"
8+
VERSION_SUFFIX = "release"
99

1010
PUBLISH_ARTIFACT_ID = 'dronekit-android'
1111
PUBLISH_VERSION = generateVersionName("", VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH, VERSION_SUFFIX)

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

Lines changed: 7 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()) {

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

Lines changed: 60 additions & 15 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,7 +28,6 @@
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

@@ -36,6 +40,13 @@
3640
*/
3741
public class ControlApi extends Api {
3842

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+
3950
private static final ConcurrentHashMap<Drone, ControlApi> apiCache = new ConcurrentHashMap<>();
4051
private static final Builder<ControlApi> apiBuilder = new Builder<ControlApi>() {
4152
@Override
@@ -113,33 +124,67 @@ public void climbTo(double altitude) {
113124
/**
114125
* Instructs the vehicle to turn to the specified target angle
115126
* @param targetAngle Target angle in degrees [0-360], with 0 == north.
116-
* @param turnSpeed Speed during turn in degrees per second
117-
* @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.
118128
* @param isRelative True is the target angle is relative to the current vehicle attitude, false otherwise if it's absolute.
119129
* @param listener Register a callback to receive update of the command execution state.
120130
*/
121-
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+
122137
Bundle params = new Bundle();
123138
params.putFloat(EXTRA_YAW_TARGET_ANGLE, targetAngle);
124-
params.putFloat(EXTRA_YAW_CHANGE_RATE, turnSpeed);
125-
params.putBoolean(EXTRA_YAW_IS_CLOCKWISE, isClockwise);
139+
params.putFloat(EXTRA_YAW_CHANGE_RATE, turnRate);
126140
params.putBoolean(EXTRA_YAW_IS_RELATIVE, isRelative);
127141
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_CONDITION_YAW, params), listener);
128142
}
129143

130-
/**
131-
* Move the vehicle along the specified velocity vector.
132-
*
133-
* @param vx x velocity in meter / s
134-
* @param vy y velocity in meter / s
135-
* @param vz z velocity in meter / s
136-
* @param listener Register a callback to receive update of the command execution state.
137-
*/
138-
public void moveAtVelocity(float vx, float vy, float vz, AbstractCommandListener listener){
144+
private void moveAtVelocity(float vx, float vy, float vz, AbstractCommandListener listener){
139145
Bundle params = new Bundle();
140146
params.putFloat(EXTRA_VELOCITY_X, vx);
141147
params.putFloat(EXTRA_VELOCITY_Y, vy);
142148
params.putFloat(EXTRA_VELOCITY_Z, vz);
143149
drone.performAsyncActionOnDroneThread(new Action(ACTION_SET_VELOCITY, params), listener);
144150
}
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+
}
145190
}

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,6 @@ public class ControlActions {
2121
public static final String ACTION_SET_CONDITION_YAW = PACKAGE_NAME + ".SET_CONDITION_YAW";
2222
public static final String EXTRA_YAW_TARGET_ANGLE = "extra_yaw_target_angle";
2323
public static final String EXTRA_YAW_CHANGE_RATE = "extra_yaw_change_rate";
24-
public static final String EXTRA_YAW_IS_CLOCKWISE = "extra_yaw_is_clockwise";
2524
public static final String EXTRA_YAW_IS_RELATIVE = "extra_yaw_is_relative";
2625

2726
public static final String ACTION_SET_VELOCITY = PACKAGE_NAME + ".SET_VELOCITY";

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/mission/MissionItemType.java

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import com.o3dr.services.android.lib.drone.mission.item.command.ChangeSpeed;
1010
import com.o3dr.services.android.lib.drone.mission.item.command.DoJump;
1111
import com.o3dr.services.android.lib.drone.mission.item.command.EpmGripper;
12+
import com.o3dr.services.android.lib.drone.mission.item.command.ResetROI;
1213
import com.o3dr.services.android.lib.drone.mission.item.command.ReturnToLaunch;
1314
import com.o3dr.services.android.lib.drone.mission.item.command.SetRelay;
1415
import com.o3dr.services.android.lib.drone.mission.item.command.SetServo;
@@ -241,6 +242,7 @@ protected Creator<SplineSurvey> getMissionItemCreator() {
241242
return SplineSurvey.CREATOR;
242243
}
243244
},
245+
244246
DO_JUMP("Do Jump") {
245247
@Override
246248
public MissionItem getNewItem() {
@@ -251,6 +253,18 @@ public MissionItem getNewItem() {
251253
protected Creator<DoJump> getMissionItemCreator() {
252254
return DoJump.CREATOR;
253255
}
256+
},
257+
258+
RESET_ROI("Reset ROI") {
259+
@Override
260+
public MissionItem getNewItem() {
261+
return new ResetROI();
262+
}
263+
264+
@Override
265+
protected Creator<ResetROI> getMissionItemCreator() {
266+
return ResetROI.CREATOR;
267+
}
254268
};
255269

256270
private final static String EXTRA_MISSION_ITEM_TYPE = "extra_mission_item_type";
Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
package com.o3dr.services.android.lib.drone.mission.item.command;
2+
3+
import android.os.Parcel;
4+
5+
import com.o3dr.services.android.lib.drone.mission.MissionItemType;
6+
import com.o3dr.services.android.lib.drone.mission.item.MissionItem;
7+
8+
/**
9+
* Reset the current region of interest lock.
10+
* Created by Fredia Huya-Kouadio on 10/20/15.
11+
* @since 2.6.8
12+
*/
13+
public class ResetROI extends MissionItem implements MissionItem.Command {
14+
15+
public ResetROI(){
16+
super(MissionItemType.RESET_ROI);
17+
}
18+
19+
public ResetROI(ResetROI copy){
20+
this();
21+
}
22+
23+
@Override
24+
public MissionItem clone() {
25+
return new ResetROI(this);
26+
}
27+
28+
@Override
29+
public int describeContents() {
30+
return 0;
31+
}
32+
33+
@Override
34+
public void writeToParcel(Parcel dest, int flags) {
35+
super.writeToParcel(dest, flags);
36+
}
37+
38+
protected ResetROI(Parcel in) {
39+
super(in);
40+
}
41+
42+
public static final Creator<ResetROI> CREATOR = new Creator<ResetROI>() {
43+
public ResetROI createFromParcel(Parcel source) {
44+
return new ResetROI(source);
45+
}
46+
47+
public ResetROI[] newArray(int size) {
48+
return new ResetROI[size];
49+
}
50+
};
51+
}

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/mission/item/command/Takeoff.java

Lines changed: 12 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -6,15 +6,15 @@
66
import com.o3dr.services.android.lib.drone.mission.MissionItemType;
77

88
/**
9+
* The vehicle will climb straight up from it’s current location to the altitude specified (in meters).
10+
* This should be the first command of nearly all missions.
11+
* If the mission is begun while the copter is already flying, the vehicle will climb straight up to the specified altitude.
12+
* If the vehicle is already above the specified altitude the takeoff command will be ignored and the mission will move onto the next command immediately.
13+
*
914
* Created by fhuya on 11/6/14.
1015
*/
1116
public class Takeoff extends MissionItem implements MissionItem.Command, android.os.Parcelable {
1217

13-
/**
14-
* Default takeoff altitude in meters.
15-
*/
16-
public static final double DEFAULT_TAKEOFF_ALTITUDE = 10.0;
17-
1818
private double takeoffAltitude;
1919
private double takeoffPitch;
2020

@@ -28,10 +28,17 @@ public Takeoff(Takeoff copy){
2828
takeoffPitch = copy.takeoffPitch;
2929
}
3030

31+
/**
32+
* @return take off altitude in meters
33+
*/
3134
public double getTakeoffAltitude() {
3235
return takeoffAltitude;
3336
}
3437

38+
/**
39+
* Sets the take off altitude
40+
* @param takeoffAltitude Altitude value in meters
41+
*/
3542
public void setTakeoffAltitude(double takeoffAltitude) {
3643
this.takeoffAltitude = takeoffAltitude;
3744
}

ClientLib/src/main/java/com/o3dr/services/android/lib/drone/mission/item/spatial/RegionOfInterest.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
import com.o3dr.services.android.lib.drone.mission.item.MissionItem;
88

99
/**
10+
* Points the nose of the vehicle and camera gimbal at the “region of interest”.
1011
* Created by fhuya on 11/6/14.
1112
*/
1213
public class RegionOfInterest extends BaseSpatialItem implements android.os.Parcelable {

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

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,14 @@ public void setPosition(LatLong mPosition) {
9494
this.mPosition = mPosition;
9595
}
9696

97+
/**
98+
* @return True if there's a 3D GPS lock, false otherwise.
99+
* @since 2.6.8
100+
*/
101+
public boolean has3DLock(){
102+
return (mFixType == LOCK_3D_TYPE) || (mFixType == LOCK_3D_DGPS_TYPE) || (mFixType == LOCK_3D_RTK_TYPE);
103+
}
104+
97105
@Override
98106
public boolean equals(Object o) {
99107
if (this == o) return true;

ServiceApp/build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ dependencies {
4242
def versionMajor = 1
4343
def versionMinor = 4
4444
def versionPatch = 3
45-
def versionBuild = 2 //bump for dogfood builds, public betas, etc.
45+
def versionBuild = 3 //bump for dogfood builds, public betas, etc.
4646
def versionPrefix = "3DR Services v"
4747

4848
//Log levels values

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

Lines changed: 0 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -458,18 +458,6 @@ public void onDroneEvent(DroneInterfaces.DroneEventsType event, MavLinkDrone dro
458458
droneEvent = AttributeEvent.HOME_UPDATED;
459459
break;
460460

461-
case GPS:
462-
droneEvent = AttributeEvent.GPS_POSITION;
463-
break;
464-
465-
case GPS_FIX:
466-
droneEvent = AttributeEvent.GPS_FIX;
467-
break;
468-
469-
case GPS_COUNT:
470-
droneEvent = AttributeEvent.GPS_COUNT;
471-
break;
472-
473461
case CALIBRATION_IMU:
474462
final String calIMUMessage = drone.getCalibrationSetup().getMessage();
475463
extrasBundle = new Bundle(1);

ServiceApp/src/org/droidplanner/services/android/core/MAVLink/MavLinkModes.java renamed to ServiceApp/src/org/droidplanner/services/android/core/MAVLink/MavLinkCommands.java

Lines changed: 26 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import org.droidplanner.services.android.core.drone.variables.ApmModes;
44

55
import com.MAVLink.common.msg_command_long;
6+
import com.MAVLink.common.msg_manual_control;
67
import com.MAVLink.common.msg_mission_item;
78
import com.MAVLink.common.msg_set_position_target_global_int;
89
import com.MAVLink.common.msg_set_mode;
@@ -13,7 +14,7 @@
1314

1415
import org.droidplanner.services.android.core.drone.autopilot.MavLinkDrone;
1516

16-
public class MavLinkModes {
17+
public class MavLinkCommands {
1718

1819
private static final int MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE = ((1 << 0) | (1 << 1) | (1 << 2));
1920
private static final int MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE = ((1 << 3) | (1 << 4) | (1 << 5));
@@ -111,4 +112,28 @@ public static void setConditionYaw(MavLinkDrone drone, float targetAngle, float
111112

112113
drone.getMavClient().sendMavMessage(msg, listener);
113114
}
115+
116+
/**
117+
* API for sending manually control to the vehicle using standard joystick axes nomenclature, along with a joystick-like input device.
118+
* Unused axes can be disabled and buttons are also transmit as boolean values.
119+
* @see <a href="MANUAL_CONTROL">https://pixhawk.ethz.ch/mavlink/#MANUAL_CONTROL</a>
120+
*
121+
* @param drone
122+
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
123+
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
124+
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
125+
* @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
126+
* @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
127+
* @param listener
128+
*/
129+
public static void sendManualControl(MavLinkDrone drone, short x, short y, short z, short r, int buttons, ICommandListener listener){
130+
msg_manual_control msg = new msg_manual_control();
131+
msg.target = drone.getSysid();
132+
msg.x = x;
133+
msg.y = y;
134+
msg.z = z;
135+
msg.r = r;
136+
msg.buttons = buttons;
137+
drone.getMavClient().sendMavMessage(msg, listener);
138+
}
114139
}

0 commit comments

Comments
 (0)