From a22fea8bbf6869a08d395c0911d3f86adf0a5261 Mon Sep 17 00:00:00 2001 From: ne0fhyk Date: Thu, 18 Aug 2016 10:25:15 -0700 Subject: [PATCH 1/5] Add the option export the drone flight path as a mission --- Android/res/menu/menu_flight_map.xml | 5 ++ Android/res/values/strings.xml | 2 + .../android/fragments/DroneMap.java | 49 +++++++++++++------ .../android/fragments/FlightMapFragment.java | 18 ++++++- .../org/droidplanner/android/maps/DPMap.java | 9 ++-- .../android/maps/GoogleMapFragment.java | 25 ++-------- .../tlog/viewers/TLogPositionViewer.kt | 17 ++----- .../android/utils/DroneHelper.java | 27 ++++++++++ 8 files changed, 96 insertions(+), 56 deletions(-) diff --git a/Android/res/menu/menu_flight_map.xml b/Android/res/menu/menu_flight_map.xml index e94c9e74e8..089a48e242 100644 --- a/Android/res/menu/menu_flight_map.xml +++ b/Android/res/menu/menu_flight_map.xml @@ -1,6 +1,11 @@ + + + No tlog position data Clear flight path Export as mission + Export flight path as mission + Try flying a bit first :) diff --git a/Android/src/org/droidplanner/android/fragments/DroneMap.java b/Android/src/org/droidplanner/android/fragments/DroneMap.java index 01c0c47221..8f1da48d45 100644 --- a/Android/src/org/droidplanner/android/fragments/DroneMap.java +++ b/Android/src/org/droidplanner/android/fragments/DroneMap.java @@ -14,8 +14,10 @@ import com.o3dr.android.client.Drone; import com.o3dr.services.android.lib.coordinate.LatLong; +import com.o3dr.services.android.lib.coordinate.LatLongAlt; import com.o3dr.services.android.lib.drone.attribute.AttributeEvent; import com.o3dr.services.android.lib.drone.attribute.AttributeType; +import com.o3dr.services.android.lib.drone.property.Altitude; import com.o3dr.services.android.lib.drone.property.CameraProxy; import com.o3dr.services.android.lib.drone.property.Gps; @@ -86,10 +88,7 @@ public void onReceive(Context context, Intent intent) { case AttributeEvent.GPS_POSITION: { graphicDrone.updateMarker(DroneMap.this); mMapFragment.updateDroneLeashPath(guided); - final Gps droneGps = drone.getAttribute(AttributeType.GPS); - if (droneGps != null && droneGps.isValid()) { - mMapFragment.addFlightPathPoint(droneGps.getPosition()); - } + updateFlightPath(); break; } @@ -137,6 +136,8 @@ public void onReceive(Context context, Intent intent) { } }; + protected final LinkedList flightPathPoints = new LinkedList<>(); + private final Map> missionMarkers = new HashMap<>(); private final LinkedList externalMarkersToAdd = new LinkedList<>(); private final LinkedList externalPolylinesToAdd = new LinkedList<>(); @@ -189,6 +190,18 @@ public void onApiConnected() { onMissionUpdate(); } + private void updateFlightPath(){ + if(showFlightPath()) { + final Gps droneGps = drone.getAttribute(AttributeType.GPS); + if (droneGps != null && droneGps.isValid()) { + Altitude droneAltitude = drone.getAttribute(AttributeType.ALTITUDE); + LatLongAlt flightPoint = new LatLongAlt(droneGps.getPosition(), + droneAltitude.getAltitude()); + addFlightPathPoint(flightPoint); + } + } + } + protected final void onMissionUpdate(){ mMapFragment.updateMissionPath(missionProxy); @@ -251,7 +264,7 @@ private void updateMapFragment(Bundle savedInstanceState) { mMapFragment = (DPMap) fm.findFragmentById(R.id.map_fragment_container); if (mMapFragment == null || mMapFragment.getProvider() != mapProvider) { final Bundle mapArgs = new Bundle(); - mapArgs.putInt(DPMap.EXTRA_MAX_FLIGHT_PATH_SIZE, getMaxFlightPathSize()); + mapArgs.putBoolean(DPMap.EXTRA_SHOW_FLIGHT_PATH, showFlightPath()); mMapFragment = mapProvider.getMapFragment(); ((Fragment) mMapFragment).setArguments(mapArgs); @@ -275,22 +288,27 @@ private void updateMapFragment(Bundle savedInstanceState) { } if(savedInstanceState != null){ - LatLong[] flightPathPoints = (LatLong[]) savedInstanceState.getParcelableArray(EXTRA_DRONE_FLIGHT_PATH); - if(flightPathPoints != null && flightPathPoints.length > 0){ - for(LatLong point : flightPathPoints) { - mMapFragment.addFlightPathPoint(point); + flightPathPoints.clear(); + LatLongAlt[] flightPoints = (LatLongAlt[]) savedInstanceState.getParcelableArray(EXTRA_DRONE_FLIGHT_PATH); + if(flightPoints != null && flightPoints.length > 0){ + for(LatLongAlt point : flightPoints) { + addFlightPathPoint(point); } } } } + private void addFlightPathPoint(LatLongAlt point) { + mMapFragment.addFlightPathPoint(point); + flightPathPoints.add(point); + } + @Override public void onSaveInstanceState(Bundle outState){ super.onSaveInstanceState(outState); if(mMapFragment != null) { - List flightPath = mMapFragment.getFlightPath(); - if(flightPath != null && !flightPath.isEmpty()){ - outState.putParcelableArray(EXTRA_DRONE_FLIGHT_PATH, flightPath.toArray(new LatLong[flightPath.size()])); + if(!flightPathPoints.isEmpty()){ + outState.putParcelableArray(EXTRA_DRONE_FLIGHT_PATH, flightPathPoints.toArray(new LatLongAlt[flightPathPoints.size()])); } } } @@ -320,14 +338,15 @@ public void onAttach(Activity activity) { mAppPrefs = DroidPlannerPrefs.getInstance(context); } - protected int getMaxFlightPathSize() { - return 0; - } + protected boolean showFlightPath(){ + return false; + } protected void clearFlightPath(){ if (mMapFragment != null) { mMapFragment.clearFlightPath(); } + flightPathPoints.clear(); } /** diff --git a/Android/src/org/droidplanner/android/fragments/FlightMapFragment.java b/Android/src/org/droidplanner/android/fragments/FlightMapFragment.java index 1d8038b596..a36f2fffae 100644 --- a/Android/src/org/droidplanner/android/fragments/FlightMapFragment.java +++ b/Android/src/org/droidplanner/android/fragments/FlightMapFragment.java @@ -18,11 +18,13 @@ import com.o3dr.services.android.lib.coordinate.LatLong; import com.o3dr.services.android.lib.drone.attribute.AttributeEvent; import com.o3dr.services.android.lib.drone.attribute.AttributeType; +import com.o3dr.services.android.lib.drone.mission.Mission; import com.o3dr.services.android.lib.drone.property.Gps; import com.o3dr.services.android.lib.drone.property.GuidedState; import com.o3dr.services.android.lib.drone.property.State; import org.droidplanner.android.R; +import org.droidplanner.android.activities.EditorActivity; import org.droidplanner.android.dialogs.GuidedDialog; import org.droidplanner.android.dialogs.GuidedDialog.GuidedDialogListener; import org.droidplanner.android.graphic.map.GraphicHome; @@ -103,8 +105,8 @@ public void onPause() { } @Override - protected int getMaxFlightPathSize() { - return 1000; + protected boolean showFlightPath(){ + return true; } @Override @@ -143,6 +145,18 @@ public boolean onOptionsItemSelected(MenuItem item) { clearFlightPath(); return true; + case R.id.menu_export_flight_path_as_mission: + if (flightPathPoints.isEmpty()) { + Toast.makeText(getContext(), R.string.error_empty_flight_path, Toast.LENGTH_LONG).show(); + return true; + } + + Mission exportedMission = DroneHelper.exportPathAsMission(getContext(), flightPathPoints); + startActivity(new Intent(getActivity(), EditorActivity.class) + .setAction(EditorActivity.ACTION_VIEW_MISSION) + .putExtra(EditorActivity.EXTRA_MISSION, exportedMission)); + return true; + default: return super.onOptionsItemSelected(item); } diff --git a/Android/src/org/droidplanner/android/maps/DPMap.java b/Android/src/org/droidplanner/android/maps/DPMap.java index 61fc229992..d740353b50 100644 --- a/Android/src/org/droidplanner/android/maps/DPMap.java +++ b/Android/src/org/droidplanner/android/maps/DPMap.java @@ -6,6 +6,7 @@ import android.os.Parcelable; import com.o3dr.services.android.lib.coordinate.LatLong; +import com.o3dr.services.android.lib.coordinate.LatLongAlt; import com.o3dr.services.android.lib.drone.property.FootPrint; import org.droidplanner.android.maps.providers.DPMapProvider; @@ -22,8 +23,8 @@ public interface DPMap { String PACKAGE_NAME = DPMap.class.getPackage().getName(); - String EXTRA_MAX_FLIGHT_PATH_SIZE = PACKAGE_NAME + "" - + ".EXTRA_MAX_FLIGHT_PATH_SIZE"; + String EXTRA_SHOW_FLIGHT_PATH = PACKAGE_NAME + "" + + ".EXTRA_SHOW_FLIGHT_PATH"; int FLIGHT_PATH_DEFAULT_COLOR = 0xfffd693f; int FLIGHT_PATH_DEFAULT_WIDTH = 6; @@ -62,7 +63,7 @@ public interface DPMap { * @param coord * drone's coordinate */ - void addFlightPathPoint(LatLong coord); + void addFlightPathPoint(LatLongAlt coord); /** * Draw the footprint of the camera in the ground @@ -120,8 +121,6 @@ public interface DPMap { */ void downloadMapTiles(MapDownloader mapDownloader, DPMap.VisibleMapArea mapRegion, int minimumZ, int maximumZ); - List getFlightPath(); - /** * @return the map center coordinates. */ diff --git a/Android/src/org/droidplanner/android/maps/GoogleMapFragment.java b/Android/src/org/droidplanner/android/maps/GoogleMapFragment.java index 191c41b098..a91ec60d3b 100644 --- a/Android/src/org/droidplanner/android/maps/GoogleMapFragment.java +++ b/Android/src/org/droidplanner/android/maps/GoogleMapFragment.java @@ -55,6 +55,7 @@ import com.google.android.gms.maps.model.VisibleRegion; import com.o3dr.android.client.Drone; import com.o3dr.services.android.lib.coordinate.LatLong; +import com.o3dr.services.android.lib.coordinate.LatLongAlt; import com.o3dr.services.android.lib.drone.attribute.AttributeEvent; import com.o3dr.services.android.lib.drone.attribute.AttributeType; import com.o3dr.services.android.lib.drone.property.FootPrint; @@ -253,7 +254,7 @@ protected void doRun() { private Polyline flightPath; private Polyline missionPath; private Polyline mDroneLeashPath; - private int maxFlightPathSize; + private boolean showFlightPath; /* * DP Map listeners @@ -330,7 +331,7 @@ public View onCreateView(LayoutInflater inflater, ViewGroup viewGroup, Bundle bu final Bundle args = getArguments(); if (args != null) { - maxFlightPathSize = args.getInt(EXTRA_MAX_FLIGHT_PATH_SIZE); + showFlightPath = args.getBoolean(EXTRA_SHOW_FLIGHT_PATH); } return view; @@ -452,13 +453,13 @@ public DPMapProvider getProvider() { } @Override - public void addFlightPathPoint(final LatLong coord) { + public void addFlightPathPoint(final LatLongAlt coord) { final LatLng position = DroneHelper.coordToLatLng(coord); getMapAsync(new OnMapReadyCallback() { @Override public void onMapReady(GoogleMap googleMap) { - if (maxFlightPathSize > 0) { + if (showFlightPath) { if (flightPath == null) { PolylineOptions flightPathOptions = new PolylineOptions(); flightPathOptions.color(FLIGHT_PATH_DEFAULT_COLOR) @@ -467,9 +468,6 @@ public void onMapReady(GoogleMap googleMap) { } List oldFlightPath = flightPath.getPoints(); - while (oldFlightPath.size() > maxFlightPathSize) { - oldFlightPath.remove(0); - } oldFlightPath.add(position); flightPath.setPoints(oldFlightPath); } @@ -477,19 +475,6 @@ public void onMapReady(GoogleMap googleMap) { }); } - @Override - public List getFlightPath(){ - if(flightPath == null) - return null; - - List flightPathPoints = flightPath.getPoints(); - List flightPath = new ArrayList<>(flightPathPoints.size()); - for(LatLng point : flightPathPoints){ - flightPath.add(DroneHelper.latLngToCoord(point)); - } - return flightPath; - } - @Override public void clearMarkers() { for(MarkerInfo markerInfo : markersMap.values()){ diff --git a/Android/src/org/droidplanner/android/tlog/viewers/TLogPositionViewer.kt b/Android/src/org/droidplanner/android/tlog/viewers/TLogPositionViewer.kt index 34bbae58d7..e6b4bde1d1 100644 --- a/Android/src/org/droidplanner/android/tlog/viewers/TLogPositionViewer.kt +++ b/Android/src/org/droidplanner/android/tlog/viewers/TLogPositionViewer.kt @@ -8,11 +8,7 @@ import android.support.v7.widget.RecyclerView import android.view.* import com.MAVLink.common.msg_global_position_int import com.o3dr.android.client.utils.data.tlog.TLogParser -import com.o3dr.services.android.lib.coordinate.LatLong import com.o3dr.services.android.lib.coordinate.LatLongAlt -import com.o3dr.services.android.lib.drone.mission.Mission -import com.o3dr.services.android.lib.drone.mission.item.spatial.SplineWaypoint -import com.o3dr.services.android.lib.util.MathUtils import org.droidplanner.android.R import org.droidplanner.android.activities.EditorActivity import org.droidplanner.android.droneshare.data.SessionContract @@ -20,6 +16,7 @@ import org.droidplanner.android.tlog.adapters.TLogPositionEventAdapter import org.droidplanner.android.tlog.event.TLogEventDetail import org.droidplanner.android.tlog.event.TLogEventListener import org.droidplanner.android.tlog.event.TLogEventMapFragment +import org.droidplanner.android.utils.DroneHelper import org.droidplanner.android.view.FastScroller /** @@ -117,20 +114,12 @@ class TLogPositionViewer : TLogViewer(), TLogEventListener { R.id.menu_export_mission -> { // Generate a mission from the drone historical gps position. val events = tlogPositionAdapter?.getItems() ?: return true - val positions = mutableListOf() + val positions = mutableListOf() for(event in events){ positions.add(msg_global_position_intToLatLongAlt(event!!.mavLinkMessage as msg_global_position_int)) } - // Simplify the generated path - val simplifiedPath = MathUtils.simplify(positions, toleranceInPixels) - val mission = Mission() - for(point in simplifiedPath){ - val missionItem = SplineWaypoint() - missionItem.coordinate = point as LatLongAlt - mission.addMissionItem(missionItem) - } - + val mission = DroneHelper.exportPathAsMission(context, positions) startActivity(Intent(activity, EditorActivity::class.java) .setAction(EditorActivity.ACTION_VIEW_MISSION) .putExtra(EditorActivity.EXTRA_MISSION, mission)) diff --git a/Android/src/org/droidplanner/android/utils/DroneHelper.java b/Android/src/org/droidplanner/android/utils/DroneHelper.java index 9368f92a32..6d50e5514b 100644 --- a/Android/src/org/droidplanner/android/utils/DroneHelper.java +++ b/Android/src/org/droidplanner/android/utils/DroneHelper.java @@ -1,10 +1,15 @@ package org.droidplanner.android.utils; +import android.content.Context; import android.content.res.Resources; import android.location.Location; import com.google.android.gms.maps.model.LatLng; import com.o3dr.services.android.lib.coordinate.LatLong; +import com.o3dr.services.android.lib.coordinate.LatLongAlt; +import com.o3dr.services.android.lib.drone.mission.Mission; +import com.o3dr.services.android.lib.drone.mission.item.spatial.SplineWaypoint; +import com.o3dr.services.android.lib.util.MathUtils; import java.util.ArrayList; import java.util.List; @@ -35,4 +40,26 @@ public static int scaleDpToPixels(double value, Resources res) { final float scale = res.getDisplayMetrics().density; return (int) Math.round(value * scale); } + + /** + * Export the given path as a Mission + * @param context + * @param pathPoints + * @return + */ + public static Mission exportPathAsMission(Context context, List pathPoints) { + Mission exportedMission = new Mission(); + if(pathPoints != null && !pathPoints.isEmpty()) { + double toleranceInPixels = scaleDpToPixels(15, context.getResources()); + List simplifiedPath = MathUtils.simplify(pathPoints, toleranceInPixels); + + for(LatLong point : simplifiedPath) { + SplineWaypoint waypoint = new SplineWaypoint(); + waypoint.setCoordinate((LatLongAlt) point); + exportedMission.addMissionItem(waypoint); + } + } + + return exportedMission; + } } From a33e96ae0ea90ca02902aa0e1da67c7e52b9f81b Mon Sep 17 00:00:00 2001 From: ne0fhyk Date: Thu, 18 Aug 2016 10:34:43 -0700 Subject: [PATCH 2/5] Fixes invalid altitude for waypoint mission item on first display --- .../item/fragments/MissionSplineWaypointFragment.java | 7 +++---- .../mission/item/fragments/MissionWaypointFragment.java | 8 ++++---- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSplineWaypointFragment.java b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSplineWaypointFragment.java index 231d291e43..9b9ff786c6 100644 --- a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSplineWaypointFragment.java +++ b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSplineWaypointFragment.java @@ -33,12 +33,14 @@ public void onApiConnected() { final Context context = getContext(); typeSpinner.setSelection(commandAdapter.getPosition(MissionItemType.SPLINE_WAYPOINT)); + SplineWaypoint item = (SplineWaypoint) getMissionItems().get(0); final NumericWheelAdapter delayAdapter = new NumericWheelAdapter(context, R.layout.wheel_text_centered, 0, 60, "%d s"); CardWheelHorizontalView delayPicker = (CardWheelHorizontalView) view.findViewById(R.id .waypointDelayPicker); delayPicker.setViewAdapter(delayAdapter); + delayPicker.setCurrentValue((int) item.getDelay()); delayPicker.addScrollListener(this); final LengthUnitProvider lengthUP = getLengthUnitProvider(); @@ -47,11 +49,8 @@ public void onApiConnected() { CardWheelHorizontalView altitudePicker = (CardWheelHorizontalView) view.findViewById (R.id.altitudePicker); altitudePicker.setViewAdapter(altitudeAdapter); - altitudePicker.addScrollListener(this); - - SplineWaypoint item = (SplineWaypoint) getMissionItems().get(0); - delayPicker.setCurrentValue((int) item.getDelay()); altitudePicker.setCurrentValue(lengthUP.boxBaseValueToTarget(item.getCoordinate().getAltitude())); + altitudePicker.addScrollListener(this); } @Override diff --git a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionWaypointFragment.java b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionWaypointFragment.java index f50c467695..97cb11d723 100644 --- a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionWaypointFragment.java +++ b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionWaypointFragment.java @@ -31,10 +31,13 @@ public void onApiConnected() { typeSpinner.setSelection(commandAdapter.getPosition(MissionItemType.WAYPOINT)); + final Waypoint item = (Waypoint) getMissionItems().get(0); + final NumericWheelAdapter delayAdapter = new NumericWheelAdapter(context, R.layout.wheel_text_centered, 0, 60, "%d s"); CardWheelHorizontalView delayPicker = (CardWheelHorizontalView) view.findViewById(R.id .waypointDelayPicker); delayPicker.setViewAdapter(delayAdapter); + delayPicker.setCurrentValue((int) item.getDelay()); delayPicker.addScrollListener(this); final LengthUnitProvider lengthUP = getLengthUnitProvider(); @@ -43,11 +46,8 @@ public void onApiConnected() { CardWheelHorizontalView altitudePicker = (CardWheelHorizontalView) view.findViewById(R.id .altitudePicker); altitudePicker.setViewAdapter(altitudeAdapter); - altitudePicker.addScrollListener(this); - - final Waypoint item = (Waypoint) getMissionItems().get(0); - delayPicker.setCurrentValue((int) item.getDelay()); altitudePicker.setCurrentValue(lengthUP.boxBaseValueToTarget(item.getCoordinate().getAltitude())); + altitudePicker.addScrollListener(this); } @Override From 7257136c3b6811be85c330428e25c3fea2cd1f6b Mon Sep 17 00:00:00 2001 From: ne0fhyk Date: Thu, 18 Aug 2016 18:05:18 -0700 Subject: [PATCH 3/5] Add the option to start the survey camera before the first waypoint. --- .../layout/fragment_editor_detail_survey.xml | 7 +++++++ .../item/fragments/MissionSurveyFragment.java | 17 +++++++++++++++++ 2 files changed, 24 insertions(+) diff --git a/Android/res/layout/fragment_editor_detail_survey.xml b/Android/res/layout/fragment_editor_detail_survey.xml index 31667e9493..7561610aa6 100644 --- a/Android/res/layout/fragment_editor_detail_survey.xml +++ b/Android/res/layout/fragment_editor_detail_survey.xml @@ -164,6 +164,13 @@ + + surveyList = getMissionItems(); + if(!surveyList.isEmpty()) { + for(T survey : surveyList) { + survey.setStartCameraBeforeFirstWaypoint(isChecked); + } + } + } + }); getBroadcastManager().registerReceiver(eventReceiver, eventFilter); } From 14f6fc2b816ee3e64de0da9d67a8d22480da3da5 Mon Sep 17 00:00:00 2001 From: ne0fhyk Date: Thu, 18 Aug 2016 18:32:49 -0700 Subject: [PATCH 4/5] Add the option to lock the copter yaw for survey missions --- .../layout/fragment_editor_detail_survey.xml | 13 +++++- Android/res/values/strings.xml | 2 + .../android/activities/EditorActivity.java | 4 -- .../item/fragments/MissionSurveyFragment.java | 44 ++++++++++++++----- 4 files changed, 45 insertions(+), 18 deletions(-) diff --git a/Android/res/layout/fragment_editor_detail_survey.xml b/Android/res/layout/fragment_editor_detail_survey.xml index 7561610aa6..9ac021b38a 100644 --- a/Android/res/layout/fragment_editor_detail_survey.xml +++ b/Android/res/layout/fragment_editor_detail_survey.xml @@ -166,10 +166,19 @@ + + + android:minHeight="48dp" + android:text="@string/lock_copter_orientation"/> Export as mission Export flight path as mission Try flying a bit first :) + Start camera before first waypoint + Lock copter orientation diff --git a/Android/src/org/droidplanner/android/activities/EditorActivity.java b/Android/src/org/droidplanner/android/activities/EditorActivity.java index d89736e01b..1c7626263d 100644 --- a/Android/src/org/droidplanner/android/activities/EditorActivity.java +++ b/Android/src/org/droidplanner/android/activities/EditorActivity.java @@ -350,10 +350,6 @@ private void openMissionFile() { @Override public void onFileSelected(String filepath) { File missionFile = new File(filepath); - if(missionFile.equals(openedMissionFile)){ - // Nothing to do. - return; - } openedMissionFile = missionFile; openMissionFile(Uri.fromFile(missionFile)); } diff --git a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java index 4729b833be..3dc1834c82 100644 --- a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java +++ b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java @@ -38,7 +38,7 @@ import java.util.List; public class MissionSurveyFragment extends MissionDetailFragment implements - CardWheelHorizontalView.OnCardWheelScrollListener, Drone.OnMissionItemsBuiltCallback { + CardWheelHorizontalView.OnCardWheelScrollListener, Drone.OnMissionItemsBuiltCallback, CompoundButton.OnCheckedChangeListener { private static final String TAG = MissionSurveyFragment.class.getSimpleName(); @@ -149,6 +149,7 @@ public void onApiConnected() { mAltitudePicker.addScrollListener(this); CheckBox startCameraBeforeFirstWaypointCheck = (CheckBox) view.findViewById(id.check_start_camera_before_first_waypoint); + CheckBox lockCopterYawCheck = (CheckBox) view.findViewById(id.check_lock_copter_yaw); if(!getMissionItems().isEmpty()) { final T referenceItem = getMissionItems().get(0); @@ -158,18 +159,15 @@ public void onApiConnected() { typeSpinner.setSelection(commandAdapter.getPosition(MissionItemType.SURVEY)); startCameraBeforeFirstWaypointCheck.setChecked(referenceItem.isStartCameraBeforeFirstWaypoint()); - } - startCameraBeforeFirstWaypointCheck.setOnCheckedChangeListener(new CompoundButton.OnCheckedChangeListener() { - @Override - public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) { - final List surveyList = getMissionItems(); - if(!surveyList.isEmpty()) { - for(T survey : surveyList) { - survey.setStartCameraBeforeFirstWaypoint(isChecked); - } - } + + SurveyDetail surveyDetail = referenceItem.getSurveyDetail(); + if(surveyDetail != null) { + lockCopterYawCheck.setChecked(surveyDetail.getLockOrientation()); } - }); + } + + startCameraBeforeFirstWaypointCheck.setOnCheckedChangeListener(this); + lockCopterYawCheck.setOnCheckedChangeListener(this); getBroadcastManager().registerReceiver(eventReceiver, eventFilter); } @@ -335,4 +333,26 @@ public void onMissionItemsBuilt(MissionItem.ComplexItem[] complexItems) { getMissionProxy().notifyMissionUpdate(); } + + @Override + public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) { + final List surveyList = getMissionItems(); + if(!surveyList.isEmpty()) { + int viewId = buttonView.getId(); + for(T survey : surveyList) { + switch(viewId) { + case R.id.check_start_camera_before_first_waypoint: + survey.setStartCameraBeforeFirstWaypoint(isChecked); + break; + + case id.check_lock_copter_yaw: + SurveyDetail surveyDetail = survey.getSurveyDetail(); + if(surveyDetail != null) { + surveyDetail.setLockOrientation(isChecked); + } + break; + } + } + } + } } From a947a7449fc61bf6779927794c4ef74a7a875f72 Mon Sep 17 00:00:00 2001 From: ne0fhyk Date: Fri, 19 Aug 2016 01:30:12 -0700 Subject: [PATCH 5/5] Persist the settings for the survey mission item. --- .../android/proxy/mission/MissionProxy.java | 4 + .../item/fragments/MissionSurveyFragment.java | 4 + .../utils/prefs/DroidPlannerPrefs.java | 94 +++++++++++++++++++ 3 files changed, 102 insertions(+) diff --git a/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java b/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java index 572fc1e6c9..1420e7df8c 100644 --- a/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java +++ b/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java @@ -228,6 +228,10 @@ public void addSurveyPolygon(List points, boolean spline) { survey = new Survey(); } survey.setPolygonPoints(points); + + // Load the last survey preferences. + dpPrefs.loadSurveyPreferences(drone, survey); + addMissionItem(survey); } diff --git a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java index 3dc1834c82..c5dab338d9 100644 --- a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java +++ b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionSurveyFragment.java @@ -207,6 +207,8 @@ public void onScrollingEnded(CardWheelHorizontalView cardWheel, Object startValu surveyDetail.setSidelap(mSidelapPicker.getCurrentValue()); } + getAppPrefs().persistSurveyPreferences(surveyList.get(0)); + final MissionItem.ComplexItem[] surveys = surveyList .toArray(new MissionItem.ComplexItem[surveyList.size()]); @@ -353,6 +355,8 @@ public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) { break; } } + + getAppPrefs().persistSurveyPreferences(surveyList.get(0)); } } } diff --git a/Android/src/org/droidplanner/android/utils/prefs/DroidPlannerPrefs.java b/Android/src/org/droidplanner/android/utils/prefs/DroidPlannerPrefs.java index a5838880d2..ded2fcd6b8 100644 --- a/Android/src/org/droidplanner/android/utils/prefs/DroidPlannerPrefs.java +++ b/Android/src/org/droidplanner/android/utils/prefs/DroidPlannerPrefs.java @@ -7,7 +7,13 @@ import android.support.v4.content.LocalBroadcastManager; import android.text.TextUtils; +import com.o3dr.android.client.Drone; +import com.o3dr.services.android.lib.drone.attribute.AttributeType; 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.drone.mission.item.complex.Survey; +import com.o3dr.services.android.lib.drone.mission.item.complex.SurveyDetail; +import com.o3dr.services.android.lib.drone.property.CameraProxy; import org.droidplanner.android.fragments.widget.TowerWidgets; import org.droidplanner.android.fragments.widget.video.WidgetVideoPreferences; @@ -16,6 +22,7 @@ import org.droidplanner.android.utils.unit.systems.UnitSystem; import java.util.HashMap; +import java.util.List; import java.util.Map; /** @@ -167,6 +174,15 @@ public class DroidPlannerPrefs { public static final String PREF_WEATHER_INFO = "pref_weather_info"; + // Survey user preferences + private static final String PREF_SURVEY_CAMERA_NAME = "pref_survey_camera_name"; + private static final String PREF_SURVEY_ALTITUDE = "pref_survey_altitude"; + private static final String PREF_SURVEY_ANGLE = "pref_survey_angle"; + private static final String PREF_SURVEY_OVERLAP = "pref_survey_overlap"; + private static final String PREF_SURVEY_SIDELAP = "pref_survey_sidelap"; + private static final String PREF_SURVEY_LOCK_ORIENTATION = "pref_survey_lock_orientation"; + private static final String PREF_SURVEY_START_CAMERA_BEFORE_FIRST_WAYPOINT = "pref_survey_start_camera_before_first_waypoint"; + // Public for legacy usage public final SharedPreferences prefs; private final LocalBroadcastManager lbm; @@ -557,4 +573,82 @@ public void setUVCVideoAspectRatio(Float aspectRatio){ public Float getUVCVideoAspectRatio(){ return prefs.getFloat(PREF_UVC_VIDEO_ASPECT_RATIO, DEFAULT_UVC_VIDEO_ASPECT_RATIO); } + + public void persistSurveyPreferences(Survey survey){ + if(survey == null || survey.getSurveyDetail() == null) + return; + + SurveyDetail surveyDetail = survey.getSurveyDetail(); + + SharedPreferences.Editor editor = prefs.edit(); + // Persist the camera. + editor.putString(PREF_SURVEY_CAMERA_NAME, surveyDetail.getCameraDetail().getName()); + + // Persist the survey angle. + editor.putFloat(PREF_SURVEY_ANGLE, (float) surveyDetail.getAngle()); + + // Persist the altitude. + editor.putFloat(PREF_SURVEY_ALTITUDE, (float) surveyDetail.getAltitude()); + + // Persist the overlap. + editor.putFloat(PREF_SURVEY_OVERLAP, (float) surveyDetail.getOverlap()); + + // Persist the sidelap. + editor.putFloat(PREF_SURVEY_SIDELAP, (float) surveyDetail.getSidelap()); + + // Persist the check for starting the camera before the first waypoint. + editor.putBoolean(PREF_SURVEY_START_CAMERA_BEFORE_FIRST_WAYPOINT, survey.isStartCameraBeforeFirstWaypoint()); + + // Persist the check for locking the copter orientation. + editor.putBoolean(PREF_SURVEY_LOCK_ORIENTATION, surveyDetail.getLockOrientation()); + + editor.apply(); + } + + public void loadSurveyPreferences(Drone drone, Survey loadTarget) { + if(drone == null || loadTarget == null) + return; + + // Load the check for starting the camera before the first waypoint. + loadTarget.setStartCameraBeforeFirstWaypoint(prefs.getBoolean(PREF_SURVEY_START_CAMERA_BEFORE_FIRST_WAYPOINT, false)); + + SurveyDetail surveyDetail = loadTarget.getSurveyDetail(); + if(surveyDetail == null){ + surveyDetail = new SurveyDetail(); + loadTarget.setSurveyDetail(surveyDetail); + } + + // Load the check for locking the copter orientation. + surveyDetail.setLockOrientation(prefs.getBoolean(PREF_SURVEY_LOCK_ORIENTATION, false)); + + // Load the sidelap. + surveyDetail.setSidelap(prefs.getFloat(PREF_SURVEY_SIDELAP, 60)); + + // Load the overlap. + surveyDetail.setOverlap(prefs.getFloat(PREF_SURVEY_OVERLAP, 50)); + + // Load the altitude. + surveyDetail.setAltitude(prefs.getFloat(PREF_SURVEY_ALTITUDE, 50)); + + // Load the survey angle. + surveyDetail.setAngle(prefs.getFloat(PREF_SURVEY_ANGLE, 0)); + + // Load the camera name + String cameraName = prefs.getString(PREF_SURVEY_CAMERA_NAME, null); + if(!TextUtils.isEmpty(cameraName)){ + CameraProxy camera = drone.getAttribute(AttributeType.CAMERA); + if(camera != null) { + // Load the available cameras + List cameraDetails = camera.getAvailableCameraInfos(); + if(!cameraDetails.isEmpty()){ + for(CameraDetail cameraDetail : cameraDetails) { + if (cameraName.equalsIgnoreCase(cameraDetail.getName())){ + surveyDetail.setCameraDetail(cameraDetail); + break; + } + } + } + } + } + } }