diff --git a/AidlLib/build.gradle b/AidlLib/build.gradle index 0984907441..c3beb78b17 100644 --- a/AidlLib/build.gradle +++ b/AidlLib/build.gradle @@ -7,8 +7,8 @@ android { defaultConfig { minSdkVersion 14 targetSdkVersion 21 - versionCode 20052 - versionName '2.0.52' + versionCode 20053 + versionName '2.0.53' } defaultPublishConfig "release" diff --git a/AidlLib/src/com/o3dr/services/android/lib/drone/mission/item/complex/CameraDetail.java b/AidlLib/src/com/o3dr/services/android/lib/drone/mission/item/complex/CameraDetail.java index 5828a5436a..9f4eb0ffdc 100644 --- a/AidlLib/src/com/o3dr/services/android/lib/drone/mission/item/complex/CameraDetail.java +++ b/AidlLib/src/com/o3dr/services/android/lib/drone/mission/item/complex/CameraDetail.java @@ -3,8 +3,6 @@ import android.os.Parcel; import android.os.Parcelable; -import java.io.Serializable; - /** * Created by fhuya on 11/6/14. */ @@ -19,6 +17,17 @@ public class CameraDetail implements Parcelable { private final double sidelap; private final boolean isInLandscapeOrientation; + public CameraDetail() { + name = "Canon SX260"; + sensorWidth = 6.12; + sensorHeight = 4.22; + sensorResolution = 12.1; + focalLength = 5.0; + overlap = 50.0; + sidelap = 60.0; + isInLandscapeOrientation = true; + } + public CameraDetail(String name, double sensorWidth, double sensorHeight, double sensorResolution, double focalLength, double overlap, double sidelap, boolean isInLandscapeOrientation) { @@ -32,7 +41,7 @@ public CameraDetail(String name, double sensorWidth, double sensorHeight, double this.isInLandscapeOrientation = isInLandscapeOrientation; } - public CameraDetail(CameraDetail copy){ + public CameraDetail(CameraDetail copy) { this(copy.name, copy.sensorWidth, copy.sensorHeight, copy.sensorResolution, copy.focalLength, copy.overlap, copy.sidelap, copy.isInLandscapeOrientation); } diff --git a/ClientLib/mobile/build.gradle b/ClientLib/mobile/build.gradle index 5138903a31..5c098cbc7a 100644 --- a/ClientLib/mobile/build.gradle +++ b/ClientLib/mobile/build.gradle @@ -2,7 +2,7 @@ apply plugin: 'com.android.library' ext { PUBLISH_ARTIFACT_ID = '3dr-services-lib' - PUBLISH_VERSION = '2.2.16' + PUBLISH_VERSION = '2.2.17' PROJECT_DESCRIPTION = "3DR Services Client Library" PROJECT_LABELS = ['3DR', '3DR Services', 'DroneAPI', 'Android'] PROJECT_LICENSES = ['Apache-2.0'] @@ -15,7 +15,7 @@ android { defaultConfig { minSdkVersion 14 targetSdkVersion 21 - versionCode 20216 + versionCode 20217 versionName PUBLISH_VERSION } diff --git a/ClientLib/mobile/libs/AidlLib.jar b/ClientLib/mobile/libs/AidlLib.jar index b17a554d2a..9e2aef6cd1 100644 Binary files a/ClientLib/mobile/libs/AidlLib.jar and b/ClientLib/mobile/libs/AidlLib.jar differ diff --git a/ServiceApp/art/ic_launcher.svg b/ServiceApp/art/ic_launcher.svg new file mode 100644 index 0000000000..02b5396945 --- /dev/null +++ b/ServiceApp/art/ic_launcher.svg @@ -0,0 +1,315 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ServiceApp/art/ic_stat_notify.svg b/ServiceApp/art/ic_stat_notify.svg new file mode 100644 index 0000000000..cac206be75 --- /dev/null +++ b/ServiceApp/art/ic_stat_notify.svg @@ -0,0 +1,169 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + diff --git a/ServiceApp/assets/recommended_apps/recommended_apps.json b/ServiceApp/assets/AppStore/recommendedApps.json similarity index 100% rename from ServiceApp/assets/recommended_apps/recommended_apps.json rename to ServiceApp/assets/AppStore/recommendedApps.json diff --git a/ServiceApp/assets/CameraInfo/NEX5_16mm.xml b/ServiceApp/assets/CameraInfo/Sony NEX5 16mm.xml similarity index 100% rename from ServiceApp/assets/CameraInfo/NEX5_16mm.xml rename to ServiceApp/assets/CameraInfo/Sony NEX5 16mm.xml diff --git a/ServiceApp/assets/CameraInfo/NEX5_25mm.xml b/ServiceApp/assets/CameraInfo/Sony NEX5 25mm.xml similarity index 100% rename from ServiceApp/assets/CameraInfo/NEX5_25mm.xml rename to ServiceApp/assets/CameraInfo/Sony NEX5 25mm.xml diff --git a/ServiceApp/assets/CameraInfo/RX100_M3_24mm.xml b/ServiceApp/assets/CameraInfo/Sony RX100 M3 24mm.xml similarity index 85% rename from ServiceApp/assets/CameraInfo/RX100_M3_24mm.xml rename to ServiceApp/assets/CameraInfo/Sony RX100 M3 24mm.xml index 48b56764f5..772c9c1476 100644 --- a/ServiceApp/assets/CameraInfo/RX100_M3_24mm.xml +++ b/ServiceApp/assets/CameraInfo/Sony RX100 M3 24mm.xml @@ -4,5 +4,5 @@ 13.2 8.8 20.2 - 24.0 + 8.8 diff --git a/ServiceApp/assets/CameraInfo/RX100_M3_70mm.xml b/ServiceApp/assets/CameraInfo/Sony RX100 M3 70mm.xml similarity index 85% rename from ServiceApp/assets/CameraInfo/RX100_M3_70mm.xml rename to ServiceApp/assets/CameraInfo/Sony RX100 M3 70mm.xml index 442a06617d..97c02a3721 100644 --- a/ServiceApp/assets/CameraInfo/RX100_M3_70mm.xml +++ b/ServiceApp/assets/CameraInfo/Sony RX100 M3 70mm.xml @@ -4,5 +4,5 @@ 13.2 8.8 20.2 - 70.0 + 25.7 diff --git a/ServiceApp/assets/CameraInfo/Sony RX100_M3 50mm.xml b/ServiceApp/assets/CameraInfo/Sony RX100_M3 50mm.xml new file mode 100644 index 0000000000..7f83813549 --- /dev/null +++ b/ServiceApp/assets/CameraInfo/Sony RX100_M3 50mm.xml @@ -0,0 +1,8 @@ + + + RX100_M3 24mm + 13.2 + 8.8 + 20.2 + 18.3 + diff --git a/ServiceApp/assets/Parameters/ParameterMetaData.xml b/ServiceApp/assets/Parameters/ParameterMetaData.xml index e5220e2243..d933aa5806 100644 --- a/ServiceApp/assets/Parameters/ParameterMetaData.xml +++ b/ServiceApp/assets/Parameters/ParameterMetaData.xml @@ -2311,8 +2311,8 @@ Advanced - Mavlink version - Allows reconising the mavlink version + MAVLink version + Allows recognising the MAVLink version 1 255 Advanced diff --git a/ServiceApp/build.gradle b/ServiceApp/build.gradle index b75650a5ed..b7a7661643 100644 --- a/ServiceApp/build.gradle +++ b/ServiceApp/build.gradle @@ -27,7 +27,7 @@ android { applicationId 'org.droidplanner.services.android' minSdkVersion 14 targetSdkVersion 21 - versionCode 10207 + versionCode 10209 versionName getGitVersion() } diff --git a/ServiceApp/res/drawable-hdpi/ic_launcher.png b/ServiceApp/res/drawable-hdpi/ic_launcher.png index 6acfd527e7..d70fb7aebf 100644 Binary files a/ServiceApp/res/drawable-hdpi/ic_launcher.png and b/ServiceApp/res/drawable-hdpi/ic_launcher.png differ diff --git a/ServiceApp/res/drawable-hdpi/ic_stat_notify.png b/ServiceApp/res/drawable-hdpi/ic_stat_notify.png new file mode 100644 index 0000000000..71ac52a64b Binary files /dev/null and b/ServiceApp/res/drawable-hdpi/ic_stat_notify.png differ diff --git a/ServiceApp/res/drawable-mdpi/ic_launcher.png b/ServiceApp/res/drawable-mdpi/ic_launcher.png index 447d48f3f5..1b6c4dd131 100644 Binary files a/ServiceApp/res/drawable-mdpi/ic_launcher.png and b/ServiceApp/res/drawable-mdpi/ic_launcher.png differ diff --git a/ServiceApp/res/drawable-mdpi/ic_stat_notify.png b/ServiceApp/res/drawable-mdpi/ic_stat_notify.png new file mode 100644 index 0000000000..8983007627 Binary files /dev/null and b/ServiceApp/res/drawable-mdpi/ic_stat_notify.png differ diff --git a/ServiceApp/res/drawable-xhdpi/ic_launcher.png b/ServiceApp/res/drawable-xhdpi/ic_launcher.png index 990fbd0138..9f61f15aa9 100644 Binary files a/ServiceApp/res/drawable-xhdpi/ic_launcher.png and b/ServiceApp/res/drawable-xhdpi/ic_launcher.png differ diff --git a/ServiceApp/res/drawable-xhdpi/ic_stat_notify.png b/ServiceApp/res/drawable-xhdpi/ic_stat_notify.png new file mode 100644 index 0000000000..e48c3c600f Binary files /dev/null and b/ServiceApp/res/drawable-xhdpi/ic_stat_notify.png differ diff --git a/ServiceApp/res/drawable-xxhdpi/ic_launcher.png b/ServiceApp/res/drawable-xxhdpi/ic_launcher.png index e4ef3bf5c4..c90b2c171c 100644 Binary files a/ServiceApp/res/drawable-xxhdpi/ic_launcher.png and b/ServiceApp/res/drawable-xxhdpi/ic_launcher.png differ diff --git a/ServiceApp/res/drawable-xxhdpi/ic_stat_notify.png b/ServiceApp/res/drawable-xxhdpi/ic_stat_notify.png new file mode 100644 index 0000000000..e777215b54 Binary files /dev/null and b/ServiceApp/res/drawable-xxhdpi/ic_stat_notify.png differ diff --git a/ServiceApp/src/org/droidplanner/services/android/api/DroidPlannerService.java b/ServiceApp/src/org/droidplanner/services/android/api/DroidPlannerService.java index 254799d8c7..7410d64c84 100644 --- a/ServiceApp/src/org/droidplanner/services/android/api/DroidPlannerService.java +++ b/ServiceApp/src/org/droidplanner/services/android/api/DroidPlannerService.java @@ -18,11 +18,13 @@ import com.google.android.gms.analytics.HitBuilders; import com.o3dr.services.android.lib.drone.connection.ConnectionParameter; import com.o3dr.services.android.lib.drone.connection.ConnectionType; +import com.o3dr.services.android.lib.drone.mission.item.complex.CameraDetail; import com.o3dr.services.android.lib.model.IApiListener; import com.o3dr.services.android.lib.model.IDroidPlannerServices; import org.droidplanner.core.MAVLink.connection.MavLinkConnection; import org.droidplanner.core.MAVLink.connection.MavLinkConnectionListener; +import org.droidplanner.core.survey.CameraInfo; import org.droidplanner.services.android.R; import org.droidplanner.services.android.communication.connection.AndroidMavLinkConnection; import org.droidplanner.services.android.communication.connection.AndroidTcpConnection; @@ -35,7 +37,11 @@ import org.droidplanner.services.android.ui.activity.MainActivity; import org.droidplanner.services.android.utils.Utils; import org.droidplanner.services.android.utils.analytics.GAUtils; +import org.droidplanner.services.android.utils.file.IO.CameraInfoLoader; +import java.util.ArrayList; +import java.util.Collections; +import java.util.List; import java.util.concurrent.ConcurrentHashMap; /** @@ -73,6 +79,9 @@ public class DroidPlannerService extends Service { private DroneAccess droneAccess; private MavLinkServiceApi mavlinkApi; + private CameraInfoLoader cameraInfoLoader; + private List cachedCameraDetails; + DroneApi registerDroneApi(IApiListener listener, String appId) { if (listener == null) return null; @@ -223,6 +232,32 @@ void disconnectMAVConnection(ConnectionParameter connParams, String listenerTag) } } + synchronized List getCameraDetails() { + if (cachedCameraDetails == null) { + List cameraInfoNames = cameraInfoLoader.getCameraInfoList(); + + List cameraInfos = new ArrayList<>(cameraInfoNames.size()); + for (String infoName : cameraInfoNames) { + try { + cameraInfos.add(cameraInfoLoader.openFile(infoName)); + } catch (Exception e) { + Log.e(TAG, e.getMessage(), e); + } + } + + List cameraDetails = new ArrayList<>(cameraInfos.size()); + for (CameraInfo camInfo : cameraInfos) { + cameraDetails.add(new CameraDetail(camInfo.name, camInfo.sensorWidth, + camInfo.sensorHeight, camInfo.sensorResolution, camInfo.focalLength, + camInfo.overlap, camInfo.sidelap, camInfo.isInLandscapeOrientation)); + } + + cachedCameraDetails = cameraDetails; + } + + return cachedCameraDetails; + } + @Override public IBinder onBind(Intent intent) { Log.d(TAG, "Binding intent: " + intent); @@ -251,6 +286,7 @@ public void onCreate() { droneAccess = new DroneAccess(this); dpServices = new DPServices(this); lbm = LocalBroadcastManager.getInstance(context); + this.cameraInfoLoader = new CameraInfoLoader(context); updateForegroundNotification(); } @@ -261,7 +297,7 @@ private void updateForegroundNotification() { //Put the service in the foreground final Notification.Builder notifBuilder = new Notification.Builder(context) .setContentTitle("3DR Services") - .setSmallIcon(R.drawable.ic_launcher) + .setSmallIcon(R.drawable.ic_stat_notify) .setContentIntent(PendingIntent.getActivity(context, 0, new Intent(context, MainActivity.class).addFlags(Intent.FLAG_ACTIVITY_NEW_TASK), 0)); diff --git a/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java b/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java index 4eb7a66beb..7c04fa4e31 100644 --- a/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java +++ b/ServiceApp/src/org/droidplanner/services/android/api/DroneApi.java @@ -118,7 +118,6 @@ public final class DroneApi extends IDroneApi.Stub implements DroneEventsListene private final DroidPlannerService service; private ConnectionParameter connectionParams; - private List cachedCameraDetails; DroneApi(DroidPlannerService dpService, Looper looper, MavLinkServiceApi mavlinkApi, IApiListener listener, String ownerId) { @@ -234,27 +233,32 @@ public Bundle getAttribute(String type) throws RemoteException { } private CameraProxy getCameraProxy() { - if (droneMgr == null) - return null; + final CameraDetail camDetail; + final FootPrint currentFieldOfView; + final List proxyPrints = new ArrayList<>(); - Drone drone = droneMgr.getDrone(); - Camera droneCamera = drone.getCamera(); + if (droneMgr == null) { + camDetail = new CameraDetail(); + currentFieldOfView = new FootPrint(); + } + else{ + Drone drone = droneMgr.getDrone(); + Camera droneCamera = drone.getCamera(); - List footprints = droneCamera.getFootprints(); - final int printsCount = footprints.size(); + camDetail = ProxyUtils.getCameraDetail(droneCamera.getCamera()); - List proxyPrints = new ArrayList(footprints.size()); - for (Footprint footprint : footprints) { - proxyPrints.add(getProxyCameraFootPrint(footprint)); - } + List footprints = droneCamera.getFootprints(); + for (Footprint footprint : footprints) { + proxyPrints.add(getProxyCameraFootPrint(footprint)); + } - GPS droneGps = drone.getGps(); - final FootPrint currentFieldOfView = droneGps.isPositionValid() - ? getProxyCameraFootPrint(droneCamera.getCurrentFieldOfView()) - : new FootPrint(); + GPS droneGps = drone.getGps(); + currentFieldOfView = droneGps.isPositionValid() + ? getProxyCameraFootPrint(droneCamera.getCurrentFieldOfView()) + : new FootPrint(); + } - return new CameraProxy(ProxyUtils.getCameraDetail(droneCamera.getCamera()), - currentFieldOfView, proxyPrints, getCameraDetails()); + return new CameraProxy(camDetail, currentFieldOfView, proxyPrints, service.getCameraDetails()); } private Gps getGps() { @@ -815,36 +819,6 @@ private FollowState getFollowState() { return new FollowState(state, followModeToType(currentAlg.getType()), params); } - private List getCameraDetails() { - if (droneMgr == null) - return Collections.emptyList(); - - if (cachedCameraDetails == null) { - final CameraInfoLoader camInfoLoader = this.droneMgr.getCameraInfoLoader(); - List cameraInfoNames = camInfoLoader.getCameraInfoList(); - - List cameraInfos = new ArrayList(cameraInfoNames.size()); - for (String infoName : cameraInfoNames) { - try { - cameraInfos.add(camInfoLoader.openFile(infoName)); - } catch (Exception e) { - Log.e(TAG, e.getMessage(), e); - } - } - - List cameraDetails = new ArrayList(cameraInfos.size()); - for (CameraInfo camInfo : cameraInfos) { - cameraDetails.add(new CameraDetail(camInfo.name, camInfo.sensorWidth, - camInfo.sensorHeight, camInfo.sensorResolution, camInfo.focalLength, - camInfo.overlap, camInfo.sidelap, camInfo.isInLandscapeOrientation)); - } - - cachedCameraDetails = cameraDetails; - } - - return cachedCameraDetails; - } - private static FootPrint getProxyCameraFootPrint(Footprint footprint) { if (footprint == null) return null; @@ -879,10 +853,8 @@ public void buildComplexMissionItem(Bundle itemBundle) { } private Survey buildSurvey(Survey survey) { - if (droneMgr == null) - return survey; - - org.droidplanner.core.mission.Mission droneMission = this.droneMgr.getDrone().getMission(); + org.droidplanner.core.mission.Mission droneMission = droneMgr == null ? null + : this.droneMgr.getDrone().getMission(); org.droidplanner.core.mission.survey.Survey updatedSurvey = (org.droidplanner.core.mission.survey.Survey) ProxyUtils.getMissionItemImpl (droneMission, survey); @@ -890,10 +862,8 @@ private Survey buildSurvey(Survey survey) { } private StructureScanner buildStructureScanner(StructureScanner item) { - if (droneMgr == null) - return item; - - org.droidplanner.core.mission.Mission droneMission = this.droneMgr.getDrone().getMission(); + org.droidplanner.core.mission.Mission droneMission = droneMgr == null ? null + : this.droneMgr.getDrone().getMission(); org.droidplanner.core.mission.waypoints.StructureScanner updatedScan = (org.droidplanner.core.mission.waypoints.StructureScanner) ProxyUtils .getMissionItemImpl(droneMission, item); diff --git a/ServiceApp/src/org/droidplanner/services/android/communication/service/UploaderService.java b/ServiceApp/src/org/droidplanner/services/android/communication/service/UploaderService.java index 9ad3042825..74a4aecbd7 100644 --- a/ServiceApp/src/org/droidplanner/services/android/communication/service/UploaderService.java +++ b/ServiceApp/src/org/droidplanner/services/android/communication/service/UploaderService.java @@ -152,7 +152,7 @@ protected void onHandleIntent(Intent intent) { private NotificationCompat.Builder generateNotificationBuilder() { return new NotificationCompat.Builder(getApplicationContext()) .setContentTitle(getString(R.string.uploader_notification_title)) - .setSmallIcon(R.drawable.ic_launcher) + .setSmallIcon(R.drawable.ic_stat_notify) // .setProgress(fileSize, 0, false) .setAutoCancel(true).setPriority(NotificationCompat.PRIORITY_HIGH); } diff --git a/ServiceApp/src/org/droidplanner/services/android/drone/DroneManager.java b/ServiceApp/src/org/droidplanner/services/android/drone/DroneManager.java index e116cdd410..7aab55e28d 100644 --- a/ServiceApp/src/org/droidplanner/services/android/drone/DroneManager.java +++ b/ServiceApp/src/org/droidplanner/services/android/drone/DroneManager.java @@ -53,7 +53,6 @@ public class DroneManager implements MAVLinkStreams.MavlinkInputStream, private final Context context; private final Drone drone; private final Follow followMe; - private final CameraInfoLoader cameraInfoLoader; private final MavLinkMsgHandler mavLinkMsgHandler; private MagnetometerCalibration magCalibration; private final ConnectionParameter connectionParameter; @@ -61,7 +60,6 @@ public class DroneManager implements MAVLinkStreams.MavlinkInputStream, public DroneManager(Context context, ConnectionParameter connParams, final Handler handler, MavLinkServiceApi mavlinkApi) { this.context = context; this.connectionParameter = connParams; - this.cameraInfoLoader = new CameraInfoLoader(context); MAVLinkClient mavClient = new MAVLinkClient(context, this, connParams, mavlinkApi); @@ -324,10 +322,6 @@ public boolean isConnected() { return drone.isConnected(); } - public CameraInfoLoader getCameraInfoLoader() { - return cameraInfoLoader; - } - @Override public void onDroneEvent(DroneInterfaces.DroneEventsType event, Drone drone) { if (connectedApps.isEmpty()) diff --git a/ServiceApp/src/org/droidplanner/services/android/location/FusedLocation.java b/ServiceApp/src/org/droidplanner/services/android/location/FusedLocation.java index fb57825bc8..b255bd9ffd 100644 --- a/ServiceApp/src/org/droidplanner/services/android/location/FusedLocation.java +++ b/ServiceApp/src/org/droidplanner/services/android/location/FusedLocation.java @@ -26,7 +26,7 @@ public class FusedLocation implements LocationFinder, com.google.android.gms.loc private static final String TAG = FusedLocation.class.getSimpleName(); - private static final long MIN_TIME_MS = 0; + private static final long MIN_TIME_MS = 16; private static final float MIN_DISTANCE_M = 0.0f; private static final float LOCATION_ACCURACY_THRESHOLD = 15.0f; private static final float JUMP_FACTOR = 4.0f; @@ -90,9 +90,10 @@ public void onLocationChanged(Location androidLocation) { float distanceToLast = -1.0f; long timeSinceLast = -1L; + final long androidLocationTime = androidLocation.getTime(); if (mLastLocation != null) { distanceToLast = androidLocation.distanceTo(mLastLocation); - timeSinceLast = (androidLocation.getTime() - mLastLocation.getTime()) / 1000; + timeSinceLast = (androidLocationTime - mLastLocation.getTime()) / 1000; } final float currentSpeed = distanceToLast > 0f && timeSinceLast > 0 @@ -101,9 +102,14 @@ public void onLocationChanged(Location androidLocation) { final boolean isLocationAccurate = isLocationAccurate(androidLocation.getAccuracy(), currentSpeed); org.droidplanner.core.gcs.location.Location location = new org.droidplanner.core.gcs.location.Location( - new Coord3D(androidLocation.getLatitude(), androidLocation.getLongitude(), - new Altitude(androidLocation.getAltitude())), androidLocation.getBearing(), - androidLocation.getSpeed(), isLocationAccurate, androidLocation.getTime()); + new Coord3D( + androidLocation.getLatitude(), + androidLocation.getLongitude(), + new Altitude(androidLocation.getAltitude())), + androidLocation.getBearing(), + androidLocation.hasSpeed() ? androidLocation.getSpeed() : currentSpeed, + isLocationAccurate, + androidLocationTime); mLastLocation = androidLocation; receiver.onLocationUpdate(location); @@ -141,7 +147,7 @@ public void setLocationListener(LocationReceiver receiver) { @Override public void onGoogleApiConnectionError(ConnectionResult result) { - if(receiver != null) + if (receiver != null) receiver.onLocationUnavailable(); GooglePlayServicesUtil.showErrorNotification(result.getErrorCode(), this.context); @@ -149,7 +155,7 @@ public void onGoogleApiConnectionError(ConnectionResult result) { @Override public void onUnavailableGooglePlayServices(int status) { - if(receiver != null) + if (receiver != null) receiver.onLocationUnavailable(); GooglePlayServicesUtil.showErrorNotification(status, this.context); @@ -161,5 +167,6 @@ public void onManagerStarted() { } @Override - public void onManagerStopped() {} + public void onManagerStopped() { + } } diff --git a/ServiceApp/src/org/droidplanner/services/android/ui/adapter/RecommendedAppsAdapter.java b/ServiceApp/src/org/droidplanner/services/android/ui/adapter/RecommendedAppsAdapter.java index 118468986c..91d73d4414 100644 --- a/ServiceApp/src/org/droidplanner/services/android/ui/adapter/RecommendedAppsAdapter.java +++ b/ServiceApp/src/org/droidplanner/services/android/ui/adapter/RecommendedAppsAdapter.java @@ -2,10 +2,8 @@ import android.content.Context; import android.content.Intent; -import android.content.res.Resources; import android.graphics.Bitmap; import android.graphics.BitmapFactory; -import android.graphics.drawable.Drawable; import android.net.Uri; import android.os.AsyncTask; import android.support.v7.widget.RecyclerView; @@ -56,7 +54,7 @@ public ViewHolder(View itemView, TextView title, TextView description, ImageView private static final String TAG = RecommendedAppsAdapter.class.getSimpleName(); - private static final String RECOMMENDED_APPS_DATA_PATH = "recommended_apps/recommended_apps.json"; + private static final String RECOMMENDED_APPS_DATA_PATH = "AppStore/recommendedApps.json"; /* JSON Attributes */ private static final String APPS_DATA_ATTRIBUTE = "apps"; diff --git a/ServiceApp/src/org/droidplanner/services/android/utils/file/DirectoryPath.java b/ServiceApp/src/org/droidplanner/services/android/utils/file/DirectoryPath.java index e27d54b220..a147cd0210 100644 --- a/ServiceApp/src/org/droidplanner/services/android/utils/file/DirectoryPath.java +++ b/ServiceApp/src/org/droidplanner/services/android/utils/file/DirectoryPath.java @@ -5,23 +5,35 @@ import android.content.Context; import android.os.Environment; +import org.droidplanner.services.android.R; + public class DirectoryPath { /** - * Main path used to store files related to the program + * Main path used to store private data files related to the program * - * @return Path to DroidPlanner/ folder in external storage + * @return Path to 3DR Services private data folder in external storage */ - static public String get3DRServicesPath(Context context) { + static public String getPrivateDataPath(Context context) { File dataDir = context.getExternalFilesDir(null); return dataDir.getAbsolutePath(); } + /** + * Main path used to store public data files related to the app. + * @param context application context + * @return Path to 3DR Services public data directory. + */ + public static String getPublicDataPath(Context context){ + final String root = Environment.getExternalStorageDirectory().getPath(); + return root + "/3DRServices/"; + } + /** * Folder where telemetry log files are stored */ static public File getTLogPath(Context context, String appId) { - File f = new File(get3DRServicesPath(context) + "/tlogs/" + appId); + File f = new File(getPrivateDataPath(context) + "/tlogs/" + appId); if(!f.exists()) { f.mkdirs(); } @@ -43,21 +55,14 @@ static public File getTLogSentPath(Context context, String appId) { * Storage folder for user camera description files */ public static String getCameraInfoPath(Context context) { - return get3DRServicesPath(context) + "/camera_info/"; + return getPublicDataPath(context) + "/CameraInfo/"; } /** * Storage folder for stacktraces */ public static String getLogCatPath(Context context) { - return get3DRServicesPath(context) + "/log_cat/"; - } - - /** - * Storage folder for SRTM data - */ - static public String getSrtmPath(Context context) { - return get3DRServicesPath(context) + "/srtm/"; + return getPrivateDataPath(context) + "/log_cat/"; } } diff --git a/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/ParameterMetadataMapReader.java b/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/ParameterMetadataMapReader.java index 8115f19944..a5465ac523 100644 --- a/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/ParameterMetadataMapReader.java +++ b/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/ParameterMetadataMapReader.java @@ -33,7 +33,7 @@ public static Map load(Context context, String metada // use user supplied file in ~/Parameters if available, else fallback to // asset from resources final InputStream inputStream; - final File file = new File(DirectoryPath.get3DRServicesPath(context) + PARAMETERMETADATA_PATH); + final File file = new File(DirectoryPath.getPublicDataPath(context) + PARAMETERMETADATA_PATH); if (file.exists()) { inputStream = new FileInputStream(file); return open(inputStream, metadataType); diff --git a/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/VehicleProfileReader.java b/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/VehicleProfileReader.java index 1e0268e0df..828fb3c8d8 100644 --- a/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/VehicleProfileReader.java +++ b/ServiceApp/src/org/droidplanner/services/android/utils/file/IO/VehicleProfileReader.java @@ -41,7 +41,7 @@ public static VehicleProfile load(Context context, FirmwareType vehicleType) { try { VehicleProfile newProfile = new VehicleProfile(); - File file = new File(DirectoryPath.get3DRServicesPath(context) + path); + File file = new File(DirectoryPath.getPublicDataPath(context) + path); if (file.exists()) { loadProfileFromFile(newProfile, file); } else { diff --git a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/Follow.java b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/Follow.java index f6bf18e39f..e9d1e5b0b8 100644 --- a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/Follow.java +++ b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/Follow.java @@ -62,11 +62,11 @@ public void toggleFollowMeState() { private void enableFollowMe() { lastLocation = null; + state = FollowStates.FOLLOW_START; locationFinder.enableLocationUpdates(); followAlgorithm.enableFollow(); - state = FollowStates.FOLLOW_START; drone.notifyDroneEvent(DroneEventsType.FOLLOW_START); } @@ -90,14 +90,16 @@ public boolean isEnabled() { public void onDroneEvent(DroneEventsType event, Drone drone) { switch (event) { case MODE: - if (!GuidedPoint.isGuidedMode(drone)) { + if (isEnabled() && !GuidedPoint.isGuidedMode(drone)) { disableFollowMe(); } break; case HEARTBEAT_TIMEOUT: case DISCONNECTED: - disableFollowMe(); + if(isEnabled()) { + disableFollowMe(); + } break; } } diff --git a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowAlgorithm.java b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowAlgorithm.java index e10fd9d0f0..7c6006cc43 100644 --- a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowAlgorithm.java +++ b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowAlgorithm.java @@ -31,12 +31,13 @@ public void enableFollow() { } public void disableFollow() { - isFollowEnabled.set(false); - if (GuidedPoint.isGuidedMode(drone)) { - drone.getGuidedPoint().pauseAtCurrentLocation(); - } + if(isFollowEnabled.compareAndSet(true, false)) { + if (GuidedPoint.isGuidedMode(drone)) { + drone.getGuidedPoint().pauseAtCurrentLocation(); + } - roiEstimator.disableFollow(); + roiEstimator.disableFollow(); + } } public void updateAlgorithmParams(Map paramsMap) { diff --git a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineAbove.java b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineAbove.java index e9b26d804f..35674066f2 100644 --- a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineAbove.java +++ b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineAbove.java @@ -13,6 +13,8 @@ public class FollowSplineAbove extends FollowAlgorithm { @Override public void processNewLocation(Location location) { Coord2D gcsLoc = new Coord2D(location.getCoord().getLat(), location.getCoord().getLng()); + + //TODO: some device (nexus 6) do not report the speed (always 0).. figure out workaround. double speed = location.getSpeed(); double bearing = location.getBearing(); double bearingInRad = Math.toRadians(bearing); diff --git a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineLeash.java b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineLeash.java index 62b721d849..6e78882520 100644 --- a/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineLeash.java +++ b/dependencyLibs/Core/src/org/droidplanner/core/gcs/follow/FollowSplineLeash.java @@ -25,6 +25,7 @@ public void processNewLocation(Location location) { double headingGCSToDrone = GeoTools.getHeadingFromCoordinates(userLoc, droneLoc); Coord2D goCoord = GeoTools.newCoordFromBearingAndDistance(userLoc, headingGCSToDrone, radius); + //TODO: some device (nexus 6) do not report the speed (always 0).. figure out workaround. double speed = location.getSpeed(); double bearing = location.getBearing(); double bearingInRad = Math.toRadians(bearing); diff --git a/dependencyLibs/Core/src/org/droidplanner/core/gcs/roi/ROIEstimator.java b/dependencyLibs/Core/src/org/droidplanner/core/gcs/roi/ROIEstimator.java index 5f2dd1fc44..f9aeed0185 100644 --- a/dependencyLibs/Core/src/org/droidplanner/core/gcs/roi/ROIEstimator.java +++ b/dependencyLibs/Core/src/org/droidplanner/core/gcs/roi/ROIEstimator.java @@ -45,14 +45,16 @@ public void enableFollow() { } public void disableFollow() { - disableWatchdog(); - isFollowEnabled.set(false); - MavLinkDoCmds.resetROI(drone); + if(isFollowEnabled.compareAndSet(true, false)){ + realLocation = null; + MavLinkDoCmds.resetROI(drone); + disableWatchdog(); + } } @Override public final void onLocationUpdate(Location location) { - if(!isFollowEnabled.get()) + if (!isFollowEnabled.get()) return; realLocation = location; @@ -67,7 +69,7 @@ public void onLocationUnavailable() { disableWatchdog(); } - protected void disableWatchdog(){ + protected void disableWatchdog() { watchdog.removeCallbacks(watchdogCallback); } @@ -76,17 +78,17 @@ protected void updateROI() { return; } - Coord2D gcsCoord = new Coord2D(realLocation.getCoord().getLat(), realLocation.getCoord().getLng()); + Coord2D gcsCoord = realLocation.getCoord(); double bearing = realLocation.getBearing(); double distanceTraveledSinceLastPoint = realLocation.getSpeed() * (System.currentTimeMillis() - timeOfLastLocation) / 1000f; Coord2D goCoord = GeoTools.newCoordFromBearingAndDistance(gcsCoord, bearing, distanceTraveledSinceLastPoint); - if (distanceTraveledSinceLastPoint > 0.0) { - MavLinkDoCmds.setROI(drone, new Coord3D(goCoord.getLat(), goCoord.getLng(), new Altitude(0.0))); - } - watchdog.postDelayed(watchdogCallback, TIMEOUT); + MavLinkDoCmds.setROI(drone, new Coord3D(goCoord.getLat(), goCoord.getLng(), new Altitude(0.0))); + + if (realLocation.getSpeed() > 0) + watchdog.postDelayed(watchdogCallback, TIMEOUT); } public boolean isFollowEnabled() { diff --git a/dependencyLibs/Core/src/org/droidplanner/core/helpers/geoTools/GeoTools.java b/dependencyLibs/Core/src/org/droidplanner/core/helpers/geoTools/GeoTools.java index 276abed3ca..4525e1deac 100644 --- a/dependencyLibs/Core/src/org/droidplanner/core/helpers/geoTools/GeoTools.java +++ b/dependencyLibs/Core/src/org/droidplanner/core/helpers/geoTools/GeoTools.java @@ -54,8 +54,7 @@ public static Double latToMeters(double lat) { * distance to be added * @return New point with the added distance */ - public static Coord2D newCoordFromBearingAndDistance(Coord2D origin, double bearing, - double distance) { + public static Coord2D newCoordFromBearingAndDistance(Coord2D origin, double bearing, double distance) { double lat = origin.getLat(); double lon = origin.getLng();