Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix issue 1176 #1195

Merged
merged 4 commits into from
Oct 22, 2014
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions Android/src/org/droidplanner/android/fragments/DroneMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ public void run() {

final boolean isThereMissionMarkers = !missionMarkerInfos.isEmpty();
final boolean isHomeValid = home.isValid();
final boolean isGuidedVisible = guided.isVisible();

// Get the list of markers currently on the map.
final Set<MarkerInfo> markersOnTheMap = mMapFragment.getMarkerInfoList();
Expand All @@ -51,6 +52,10 @@ public void run() {
markersOnTheMap.remove(home);
}

if(isGuidedVisible){
markersOnTheMap.remove(guided);
}

if (isThereMissionMarkers) {
markersOnTheMap.removeAll(missionMarkerInfos);
}
Expand All @@ -62,6 +67,10 @@ public void run() {
mMapFragment.updateMarker(home);
}

if(isGuidedVisible){
mMapFragment.updateMarker(guided);
}

if (isThereMissionMarkers) {
mMapFragment.updateMarkers(missionMarkerInfos, isMissionDraggable());
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,32 +1,35 @@
package org.droidplanner.android.gcs.location;

import org.droidplanner.android.utils.GoogleApiClientManager;
import org.droidplanner.android.utils.GoogleApiClientManager.GoogleApiClientTask;
import org.droidplanner.core.gcs.location.Location.LocationFinder;
import org.droidplanner.core.gcs.location.Location.LocationReceiver;
import org.droidplanner.core.helpers.coordinates.Coord2D;

import android.content.Context;
import android.location.Location;
import android.os.Bundle;
import android.util.Log;

import com.google.android.gms.common.ConnectionResult;
import com.google.android.gms.common.GooglePlayServicesClient;
import com.google.android.gms.location.LocationClient;
import com.google.android.gms.location.LocationRequest;
import com.google.android.gms.location.LocationServices;

/**
* Feeds Location Data from Android's FusedLocation LocationProvider
*
*/
public class FusedLocation implements LocationFinder, GooglePlayServicesClient.ConnectionCallbacks,
GooglePlayServicesClient.OnConnectionFailedListener,
com.google.android.gms.location.LocationListener {
public class FusedLocation implements LocationFinder, com.google.android.gms.location.LocationListener {

private static final long MIN_TIME_MS = 500;
private static final String TAG = FusedLocation.class.getSimpleName();

private static final long MIN_TIME_MS = 1000;
private static final float MIN_DISTANCE_M = 0.0f;
private static final float LOCATION_ACCURACY_THRESHOLD = 10.0f;
private static final float LOCATION_ACCURACY_THRESHOLD = 15.0f;
private static final float JUMP_FACTOR = 4.0f;

private LocationClient mLocationClient;
private final GoogleApiClientManager gApiMgr;
private final GoogleApiClientTask requestLocationUpdate;
private final GoogleApiClientTask removeLocationUpdate;

private LocationReceiver receiver;

private Location mLastLocation;
Expand All @@ -35,43 +38,42 @@ public class FusedLocation implements LocationFinder, GooglePlayServicesClient.C
private long mSpeedReadings;

public FusedLocation(Context context) {
mLocationClient = new LocationClient(context, this, this);
mLocationClient.connect();
gApiMgr = new GoogleApiClientManager(context, LocationServices.API);

requestLocationUpdate = gApiMgr.new GoogleApiClientTask() {
@Override
protected void doRun() {
final LocationRequest locationRequest = LocationRequest.create();
locationRequest.setPriority(LocationRequest.PRIORITY_HIGH_ACCURACY);
locationRequest.setInterval(MIN_TIME_MS);
locationRequest.setFastestInterval(MIN_TIME_MS);
locationRequest.setSmallestDisplacement(MIN_DISTANCE_M);
LocationServices.FusedLocationApi.requestLocationUpdates(getGoogleApiClient(),
locationRequest, FusedLocation.this);
}
};

removeLocationUpdate = gApiMgr.new GoogleApiClientTask() {
@Override
protected void doRun() {
LocationServices.FusedLocationApi.removeLocationUpdates(getGoogleApiClient(),
FusedLocation.this);
}
};

gApiMgr.start();
}

@Override
public void enableLocationUpdates() {
mSpeedReadings = 0;
mTotalSpeed = 0f;

LocationRequest mLocationRequest = LocationRequest.create();
mLocationRequest.setPriority(LocationRequest.PRIORITY_HIGH_ACCURACY);
mLocationRequest.setInterval(MIN_TIME_MS);
mLocationRequest.setFastestInterval(MIN_TIME_MS);
mLocationRequest.setSmallestDisplacement(MIN_DISTANCE_M);
mLocationClient.requestLocationUpdates(mLocationRequest, this);
gApiMgr.addTask(requestLocationUpdate);
}

@Override
public void disableLocationUpdates() {
if (mLocationClient.isConnected()) {
mLocationClient.removeLocationUpdates(this);
}
}

@Override
public void onConnectionFailed(ConnectionResult arg0) {

}

@Override
public void onConnected(Bundle arg0) {

}

@Override
public void onDisconnected() {

gApiMgr.addTask(removeLocationUpdate);
}

@Override
Expand All @@ -82,16 +84,19 @@ public void onLocationChanged(Location androidLocation) {

if(mLastLocation != null) {
distanceToLast = androidLocation.distanceTo(mLastLocation);
timeSinceLast = (androidLocation.getTime() - mLastLocation.getTime());
timeSinceLast = (androidLocation.getTime() - mLastLocation.getTime()) / 1000;
}

final float currentSpeed = distanceToLast > 0f && timeSinceLast > 0
? (distanceToLast / (timeSinceLast / 1000))
? (distanceToLast / timeSinceLast)
: 0f;
final boolean isLocationAccurate = isLocationAccurate(androidLocation.getAccuracy(),
currentSpeed);
Log.d(TAG, "Is location accurate: " + isLocationAccurate);

org.droidplanner.core.gcs.location.Location location = new org.droidplanner.core.gcs.location.Location(
new Coord2D(androidLocation.getLatitude(), androidLocation.getLongitude()),
androidLocation.getBearing(), androidLocation.getSpeed(), isLocationAccurate(androidLocation.getAccuracy(), currentSpeed));
androidLocation.getBearing(), androidLocation.getSpeed(), isLocationAccurate);

mLastLocation = androidLocation;
receiver.onLocationChanged(location);
Expand All @@ -100,6 +105,7 @@ public void onLocationChanged(Location androidLocation) {

private boolean isLocationAccurate(float accuracy, float currentSpeed){
if(accuracy >= LOCATION_ACCURACY_THRESHOLD){
Log.d(TAG, "High accuracy: " + accuracy);
return false;
}

Expand All @@ -112,6 +118,7 @@ private boolean isLocationAccurate(float accuracy, float currentSpeed){
if(avg >= 1.0){
//Reject unreasonable updates.
if(currentSpeed >= (avg * JUMP_FACTOR)){
Log.d(TAG, "High current speed: " + currentSpeed);
return false;
}
}
Expand All @@ -123,6 +130,5 @@ private boolean isLocationAccurate(float accuracy, float currentSpeed){
@Override
public void setLocationListener(LocationReceiver receiver) {
this.receiver = receiver;

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -69,9 +69,9 @@ public class GoogleMapFragment extends SupportMapFragment implements DPMap, Loca
public static final String MAP_TYPE_TERRAIN = "Terrain";

// TODO: update the interval based on the user's current activity.
private static final long USER_LOCATION_UPDATE_INTERVAL = 10000; // ms
private static final long USER_LOCATION_UPDATE_FASTEST_INTERVAL = 5000; // ms
private static final float USER_LOCATION_UPDATE_MIN_DISPLACEMENT = 10; // m
private static final long USER_LOCATION_UPDATE_INTERVAL = 30000; // ms
private static final long USER_LOCATION_UPDATE_FASTEST_INTERVAL = 10000; // ms
private static final float USER_LOCATION_UPDATE_MIN_DISPLACEMENT = 15; // m

private final HashBiMap<MarkerInfo, Marker> mBiMarkersMap = new HashBiMap<MarkerInfo, Marker>();

Expand Down