Skip to content

Commit

Permalink
Follow me api update.
Browse files Browse the repository at this point in the history
fixed invalid behavior in GuidedPoint when trying to trigger `pauseAtCurrentLocation`.
Made roi estimation dependant upon the selected follow algorithm.
Completed back-end implementation for the 'GuidedScan' follow mode.
  • Loading branch information
m4gr3d committed Jan 28, 2015
1 parent 8695eb2 commit 211e2a9
Show file tree
Hide file tree
Showing 27 changed files with 541 additions and 322 deletions.
4 changes: 2 additions & 2 deletions AidlLib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@ android {
defaultConfig {
minSdkVersion 14
targetSdkVersion 21
versionCode 20039
versionName '2.0.39'
versionCode 20043
versionName '2.0.43'
}

defaultPublishConfig "release"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,7 @@ public class FollowMeActions {
public static final String ACTION_ENABLE_FOLLOW_ME = Utils.PACKAGE_NAME + ".action.ENABLE_FOLLOW_ME";
public static final String EXTRA_FOLLOW_TYPE = "extra_follow_type";

public static final String ACTION_UPDATE_FOLLOW_ME_RADIUS = Utils.PACKAGE_NAME + ".action.UPDATE_FOLLOW_ME_RADIUS";
public static final String EXTRA_FOLLOW_ME_RADIUS = "extra_follow_me_radius";
public static final String ACTION_UPDATE_FOLLOW_PARAMS = Utils.PACKAGE_NAME + ".action.UPDATE_FOLLOW_PARAMS";

public static final String ACTION_DISABLE_FOLLOW_ME = Utils.PACKAGE_NAME + ".action.DISABLE_FOLLOW_ME";

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package com.o3dr.services.android.lib.gcs.follow;

import android.os.Bundle;
import android.os.Parcel;
import android.os.Parcelable;

Expand All @@ -16,35 +17,31 @@ public class FollowState implements Parcelable {
public static final int STATE_END = 5;

private int state;
private double radius;
private Bundle modeParams;
private FollowType mode;

public FollowState(){}

public FollowState(int state, double radius, FollowType mode) {
public FollowState(int state, FollowType mode, Bundle modeParams) {
this.state = state;
this.radius = radius;
this.modeParams = modeParams;
this.mode = mode;
}

public void setState(int state) {
this.state = state;
}

public void setRadius(double radius) {
this.radius = radius;
}

public void setMode(FollowType mode) {
this.mode = mode;
}

public int getState() {
return state;
public Bundle getParams(){
return modeParams;
}

public double getRadius() {
return radius;
public int getState() {
return state;
}

public FollowType getMode() {
Expand All @@ -63,14 +60,15 @@ public int describeContents() {
@Override
public void writeToParcel(Parcel dest, int flags) {
dest.writeInt(this.state);
dest.writeDouble(this.radius);
dest.writeParcelable(this.mode, 0);
dest.writeBundle(modeParams);
dest.writeInt(this.mode == null ? -1 : this.mode.ordinal());
}

private FollowState(Parcel in) {
this.state = in.readInt();
this.radius = in.readDouble();
this.mode = in.readParcelable(FollowType.class.getClassLoader());
modeParams = in.readBundle();
int tmpMode = in.readInt();
this.mode = tmpMode == -1 ? null : FollowType.values()[tmpMode];
}

public static final Parcelable.Creator<FollowState> CREATOR = new Parcelable.Creator<FollowState>() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,26 +16,52 @@ public enum FollowType implements Parcelable {
RIGHT("Right"),
LEFT("Left"),
CIRCLE("Circle"),
ABOVE("Above", false),
ABOVE("Above"){
@Override
public boolean hasParam(String paramKey){
return false;
}
},
SPLINE_LEASH("Vector Leash"),
SPLINE_ABOVE("Vector Above", false),
GUIDED_SCAN("Guided Scan", false);
SPLINE_ABOVE("Vector Above"){
@Override
public boolean hasParam(String paramKey){
return false;
}
},
GUIDED_SCAN("Guided Scan"){
@Override
public boolean hasParam(String paramKey){
switch(paramKey){
case EXTRA_FOLLOW_ROI_TARGET:
return true;

default:
return false;
}
}
};

public static final String EXTRA_FOLLOW_RADIUS = "extra_follow_radius";
public static final String EXTRA_FOLLOW_ROI_TARGET = "extra_follow_roi_target";

private final String typeLabel;
private final boolean hasRadius;

private FollowType(String typeLabel){
this.typeLabel = typeLabel;
this.hasRadius = true;
}

private FollowType(String typeLabel, boolean hasRadius) {
this.typeLabel = typeLabel;
this.hasRadius = hasRadius;
}
public boolean hasParam(String paramKey){
switch(paramKey){
case EXTRA_FOLLOW_RADIUS:
return true;

public boolean hasRadius() {
return hasRadius;
case EXTRA_FOLLOW_ROI_TARGET:
return false;

default:
return false;
}
}

public String getTypeLabel() {
Expand Down Expand Up @@ -65,11 +91,11 @@ public static List<FollowType> getFollowTypes(boolean includeAdvanced){
followTypes.add(LEFT);
followTypes.add(CIRCLE);
followTypes.add(ABOVE);
followTypes.add(GUIDED_SCAN);

if(includeAdvanced){
followTypes.add(SPLINE_LEASH);
followTypes.add(SPLINE_ABOVE);
followTypes.add(GUIDED_SCAN);
}

return followTypes;
Expand Down
4 changes: 2 additions & 2 deletions ClientLib/mobile/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ apply plugin: 'com.android.library'

ext {
PUBLISH_ARTIFACT_ID = '3dr-services-lib'
PUBLISH_VERSION = '2.2.2'
PUBLISH_VERSION = '2.2.6'
PROJECT_DESCRIPTION = "3DR Services Client Library"
PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android']
PROJECT_LICENSES = ['Apache-2.0']
Expand All @@ -15,7 +15,7 @@ android {
defaultConfig {
minSdkVersion 14
targetSdkVersion 21
versionCode 20202
versionCode 20206
versionName PUBLISH_VERSION
}

Expand Down
Binary file modified ClientLib/mobile/libs/AidlLib.jar
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -556,10 +556,6 @@ public void enableFollowMe(FollowType followType) {
FollowApi.enableFollowMe(this, followType);
}

public void setFollowMeRadius(double radius) {
FollowApi.updateFollowMeRadius(this, radius);
}

public void disableFollowMe() {
FollowApi.disableFollowMe(this);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,7 @@

import static com.o3dr.services.android.lib.gcs.action.FollowMeActions.ACTION_DISABLE_FOLLOW_ME;
import static com.o3dr.services.android.lib.gcs.action.FollowMeActions.ACTION_ENABLE_FOLLOW_ME;
import static com.o3dr.services.android.lib.gcs.action.FollowMeActions.ACTION_UPDATE_FOLLOW_ME_RADIUS;
import static com.o3dr.services.android.lib.gcs.action.FollowMeActions.EXTRA_FOLLOW_ME_RADIUS;
import static com.o3dr.services.android.lib.gcs.action.FollowMeActions.*;
import static com.o3dr.services.android.lib.gcs.action.FollowMeActions.EXTRA_FOLLOW_TYPE;

/**
Expand All @@ -28,15 +27,8 @@ public static void enableFollowMe(Drone drone, FollowType followType) {
drone.performAsyncAction(new Action(ACTION_ENABLE_FOLLOW_ME, params));
}

/**
* Sets the follow-me radius.
*
* @param radius radius in meters.
*/
public static void updateFollowMeRadius(Drone drone, double radius) {
Bundle params = new Bundle();
params.putDouble(EXTRA_FOLLOW_ME_RADIUS, radius);
drone.performAsyncAction(new Action(ACTION_UPDATE_FOLLOW_ME_RADIUS, params));
public static void updateFollowParams(Drone drone, Bundle params){
drone.performAsyncAction(new Action(ACTION_UPDATE_FOLLOW_PARAMS, params));
}

/**
Expand Down
2 changes: 1 addition & 1 deletion ServiceApp/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ android {
applicationId 'org.droidplanner.services.android'
minSdkVersion 14
targetSdkVersion 21
versionCode 10108
versionCode 10109
versionName getGitVersion()
}

Expand Down
76 changes: 65 additions & 11 deletions ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,7 @@
import java.util.HashMap;
import java.util.List;
import java.util.Map;
import java.util.Set;
import java.util.concurrent.ConcurrentLinkedQueue;

import ellipsoidFit.FitPoints;
Expand All @@ -104,6 +105,7 @@ public final class DroneApi extends IDroneApi.Stub implements DroneEventsListene

private final SoftReference<DroidPlannerService> serviceRef;
private final Context context;
private final DroneInterfaces.Handler droneHandler;

private final ConcurrentLinkedQueue<IObserver> observersList;
private final ConcurrentLinkedQueue<IMavlinkObserver> mavlinkObserversList;
Expand All @@ -113,9 +115,26 @@ public final class DroneApi extends IDroneApi.Stub implements DroneEventsListene

private List<CameraDetail> cachedCameraDetails;

DroneApi(DroidPlannerService dpService, Handler handler, MavLinkServiceApi mavlinkApi, IApiListener listener,
DroneApi(DroidPlannerService dpService, final Handler handler, MavLinkServiceApi mavlinkApi, IApiListener listener,
String ownerId) {

this.context = dpService.getApplicationContext();
this.droneHandler = new DroneInterfaces.Handler() {
@Override
public void removeCallbacks(Runnable thread) {
handler.removeCallbacks(thread);
}

@Override
public void post(Runnable thread) {
handler.post(thread);
}

@Override
public void postDelayed(Runnable thread, long timeout) {
handler.postDelayed(thread, timeout);
}
};

this.ownerId = ownerId;

Expand Down Expand Up @@ -666,13 +685,15 @@ public void enableFollowMe(FollowType followType) {
if (!followMe.isEnabled())
followMe.toggleFollowMeState();

followMe.setType(selectedMode);
FollowAlgorithm currentAlg = followMe.getFollowAlgorithm();
if(currentAlg.getType() != selectedMode) {
followMe.setAlgorithm(selectedMode.getAlgorithmType(droneMgr.getDrone(), droneHandler));
}
}
}

private FollowState getFollowState() {
final Follow followMe = this.droneMgr.getFollowMe();
final double radius = followMe.getRadius().valueInMeters();

final int state;
switch (followMe.getState()) {
Expand Down Expand Up @@ -703,7 +724,26 @@ private FollowState getFollowState() {
break;
}

return new FollowState(state, radius, followModeToType(followMe.getType()));
final FollowAlgorithm currentAlg = followMe.getFollowAlgorithm();
Map<String, Object> modeParams = currentAlg.getParams();
Bundle params = new Bundle();
for(Map.Entry<String, Object> entry : modeParams.entrySet()){
switch(entry.getKey()){
case FollowType.EXTRA_FOLLOW_ROI_TARGET:
Coord2D target = (Coord2D) entry.getValue();
if(target != null){
params.putParcelable(entry.getKey(), new LatLong(target.getLat(), target.getLng()));
}
break;

case FollowType.EXTRA_FOLLOW_RADIUS:
Double radius = (Double) entry.getValue();
if(radius != null)
params.putDouble(entry.getKey(), radius);
break;
}
}
return new FollowState(state, followModeToType(currentAlg.getType()), params);
}

private List<CameraDetail> getCameraDetails() {
Expand Down Expand Up @@ -952,9 +992,27 @@ public void performAction(Action action) throws RemoteException {
enableFollowMe(followType);
break;

case FollowMeActions.ACTION_UPDATE_FOLLOW_ME_RADIUS:
double radius = data.getDouble(FollowMeActions.EXTRA_FOLLOW_ME_RADIUS);
setFollowMeRadius(radius);
case FollowMeActions.ACTION_UPDATE_FOLLOW_PARAMS:
data.setClassLoader(LatLong.class.getClassLoader());

final FollowAlgorithm followAlgorithm = this.droneMgr.getFollowMe().getFollowAlgorithm();
if(followAlgorithm != null){
Map<String, Object> paramsMap = new HashMap<>();
Set<String> dataKeys = data.keySet();
for(String key: dataKeys){
if(FollowType.EXTRA_FOLLOW_ROI_TARGET.equals(key)){
LatLong target = data.getParcelable(key);
if(target != null) {
Coord2D roiTarget = new Coord2D(target.getLatitude(), target.getLongitude());
paramsMap.put(key, roiTarget);
}
}
else
paramsMap.put(key, data.get(key));
}

followAlgorithm.updateAlgorithmParams(paramsMap);
}
break;

case FollowMeActions.ACTION_DISABLE_FOLLOW_ME:
Expand Down Expand Up @@ -1111,10 +1169,6 @@ private static FollowType followModeToType(FollowAlgorithm.FollowModes followMod
return followType;
}

public void setFollowMeRadius(double radius) {
this.droneMgr.getFollowMe().changeRadius(radius);
}

public void disableFollowMe() {
Follow follow = this.droneMgr.getFollowMe();
if (follow.isEnabled())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,17 +7,18 @@
import org.droidplanner.core.MAVLink.connection.MavLinkConnectionListener;
import org.droidplanner.services.android.communication.connection.AndroidMavLinkConnection;

import java.lang.ref.SoftReference;
import java.lang.ref.WeakReference;

/**
* MavLinkService app api.
*/
public class MavLinkServiceApi {

private final WeakReference<DroidPlannerService> mServiceRef;
private final SoftReference<DroidPlannerService> mServiceRef;

public MavLinkServiceApi(DroidPlannerService service) {
mServiceRef = new WeakReference<DroidPlannerService>(service);
mServiceRef = new SoftReference<>(service);
}

private DroidPlannerService getService() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,9 @@ public void connect() throws ConnectionException {
}

public void disconnect() throws ConnectionException {
if(followMe.isEnabled())
followMe.toggleFollowMeState();

MAVLinkClient mavClient = (MAVLinkClient) drone.getMavClient();
if (mavClient.isConnected())
mavClient.closeConnection();
Expand Down
Loading

0 comments on commit 211e2a9

Please sign in to comment.