diff --git a/Android/res/layout/fragment_editor_detail_waypoint.xml b/Android/res/layout/fragment_editor_detail_waypoint.xml index 2715ee8d23..c38884fec9 100644 --- a/Android/res/layout/fragment_editor_detail_waypoint.xml +++ b/Android/res/layout/fragment_editor_detail_waypoint.xml @@ -104,6 +104,18 @@ android:background="@drawable/mode_desc_rectangle" android:text="@string/waypointInfo_Waypoint"/> + + + android:layout_marginStart="1dp"> + android:layout_below="@+id/rowAltitudeView" + android:layout_centerHorizontal="true" /> \ No newline at end of file diff --git a/Android/res/values-sw540dp/dimens.xml b/Android/res/values-sw540dp/dimens.xml index 7d73c625c9..f6d7ee6b33 100644 --- a/Android/res/values-sw540dp/dimens.xml +++ b/Android/res/values-sw540dp/dimens.xml @@ -13,7 +13,7 @@ 56dp - 24sp + 22sp 80dp diff --git a/Android/res/values/arrays.xml b/Android/res/values/arrays.xml index f42dca2567..a4f8873893 100644 --- a/Android/res/values/arrays.xml +++ b/Android/res/values/arrays.xml @@ -102,6 +102,13 @@ Waypoint Type + + + Absolute + Relative + Terrain + + Auto-tune Roll / Pitch diff --git a/Android/res/values/dimens.xml b/Android/res/values/dimens.xml index cf50e22f39..80f74cda89 100644 --- a/Android/res/values/dimens.xml +++ b/Android/res/values/dimens.xml @@ -11,7 +11,7 @@ 0dp - 20sp + 18sp 70dp diff --git a/Android/src/org/droidplanner/android/fragments/DroneMap.java b/Android/src/org/droidplanner/android/fragments/DroneMap.java index 353145105d..e6f5090937 100644 --- a/Android/src/org/droidplanner/android/fragments/DroneMap.java +++ b/Android/src/org/droidplanner/android/fragments/DroneMap.java @@ -13,6 +13,7 @@ import android.view.ViewGroup; import com.o3dr.android.client.Drone; +import com.o3dr.services.android.lib.coordinate.Frame; 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; @@ -217,7 +218,7 @@ protected LatLongAlt getCurrentFlightPoint(){ if (droneGps != null && droneGps.isValid()) { Altitude droneAltitude = drone.getAttribute(AttributeType.ALTITUDE); LatLongAlt point = new LatLongAlt(droneGps.getPosition(), - droneAltitude.getAltitude()); + droneAltitude.getAltitude(), Frame.GLOBAL_RELATIVE); return point; } return null; diff --git a/Android/src/org/droidplanner/android/fragments/EditorMapFragment.java b/Android/src/org/droidplanner/android/fragments/EditorMapFragment.java index a532fe871c..b03f1166d0 100644 --- a/Android/src/org/droidplanner/android/fragments/EditorMapFragment.java +++ b/Android/src/org/droidplanner/android/fragments/EditorMapFragment.java @@ -44,6 +44,7 @@ public View onCreateView(LayoutInflater inflater, ViewGroup viewGroup, Bundle bu @Override public void onMapLongClick(LatLong point) { + editorListener.onMapClick(point); } @Override diff --git a/Android/src/org/droidplanner/android/fragments/mode/ModeFollowFragment.java b/Android/src/org/droidplanner/android/fragments/mode/ModeFollowFragment.java index 5e6c592d05..d4d2f35b83 100644 --- a/Android/src/org/droidplanner/android/fragments/mode/ModeFollowFragment.java +++ b/Android/src/org/droidplanner/android/fragments/mode/ModeFollowFragment.java @@ -17,6 +17,7 @@ import com.o3dr.android.client.Drone; import com.o3dr.android.client.apis.FollowApi; +import com.o3dr.services.android.lib.coordinate.Frame; 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; @@ -252,7 +253,7 @@ public void onGuidedClick(LatLong coord) { Toast.makeText(getContext(), R.string.guided_scan_roi_set_message, Toast.LENGTH_LONG).show(); final double roiHeight = roiHeightWheel.getCurrentValue().toBase().getValue(); - final LatLongAlt roiCoord = new LatLongAlt(coord.getLatitude(), coord.getLongitude(), roiHeight); + final LatLongAlt roiCoord = new LatLongAlt(coord, roiHeight, Frame.GLOBAL_RELATIVE); pushROITargetToVehicle(drone, roiCoord); updateROITargetMarker(coord); diff --git a/Android/src/org/droidplanner/android/graphic/map/GraphicHome.java b/Android/src/org/droidplanner/android/graphic/map/GraphicHome.java index a32c25ed71..1bfcd4e294 100644 --- a/Android/src/org/droidplanner/android/graphic/map/GraphicHome.java +++ b/Android/src/org/droidplanner/android/graphic/map/GraphicHome.java @@ -8,6 +8,7 @@ import com.o3dr.android.client.Drone; import com.o3dr.android.client.apis.VehicleApi; +import com.o3dr.services.android.lib.coordinate.Frame; import com.o3dr.services.android.lib.coordinate.LatLong; import com.o3dr.services.android.lib.coordinate.LatLongAlt; import com.o3dr.services.android.lib.drone.attribute.AttributeType; @@ -63,7 +64,7 @@ public void setPosition(LatLong position){ final LatLongAlt homeCoord = currentHome.getCoordinate(); final double homeAlt = homeCoord == null ? 0 : homeCoord.getAltitude(); - final LatLongAlt newHome = new LatLongAlt(position, homeAlt); + final LatLongAlt newHome = new LatLongAlt(position, homeAlt, homeCoord.getFrame()); VehicleApi.getApi(drone).setVehicleHome(newHome, new AbstractCommandListener() { @Override public void onSuccess() { diff --git a/Android/src/org/droidplanner/android/graphic/map/GuidedScanROIMarkerInfo.java b/Android/src/org/droidplanner/android/graphic/map/GuidedScanROIMarkerInfo.java index 76676e9cfa..73c62b4e90 100644 --- a/Android/src/org/droidplanner/android/graphic/map/GuidedScanROIMarkerInfo.java +++ b/Android/src/org/droidplanner/android/graphic/map/GuidedScanROIMarkerInfo.java @@ -4,6 +4,7 @@ import android.graphics.Bitmap; import android.graphics.BitmapFactory; +import com.o3dr.services.android.lib.coordinate.Frame; import com.o3dr.services.android.lib.coordinate.LatLong; import com.o3dr.services.android.lib.coordinate.LatLongAlt; @@ -28,7 +29,7 @@ public void setPosition(LatLong coord){ if(roiCoord != null) defaultHeight = roiCoord.getAltitude(); - this.roiCoord = new LatLongAlt(coord.getLatitude(), coord.getLongitude(), defaultHeight); + this.roiCoord = new LatLongAlt(coord, defaultHeight, Frame.GLOBAL_RELATIVE); } } diff --git a/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java b/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java index f120e78c76..3b44b3cadb 100644 --- a/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java +++ b/Android/src/org/droidplanner/android/proxy/mission/MissionProxy.java @@ -13,6 +13,7 @@ import com.google.android.gms.analytics.HitBuilders; import com.o3dr.android.client.Drone; import com.o3dr.android.client.apis.MissionApi; +import com.o3dr.services.android.lib.coordinate.Frame; 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; @@ -245,9 +246,10 @@ public void addWaypoints(List points) { double alt = getLastAltitude(); List missionItemsToAdd = new ArrayList(points.size()); for (LatLong point : points) { + // TODO !BB! Make this method the last used frame Waypoint waypoint = new Waypoint(); - waypoint.setCoordinate(new LatLongAlt(point.getLatitude(), point.getLongitude(), - (float) alt)); + waypoint.getCoordinate().set(point); + waypoint.getCoordinate().setAltitude(alt); missionItemsToAdd.add(waypoint); } @@ -275,9 +277,10 @@ public void addSplineWaypoints(List points) { double alt = getLastAltitude(); List missionItemsToAdd = new ArrayList(points.size()); for (LatLong point : points) { + // TODO !BB! Make this method the last used frame SplineWaypoint splineWaypoint = new SplineWaypoint(); - splineWaypoint.setCoordinate(new LatLongAlt(point.getLatitude(), point.getLongitude(), - (float) alt)); + splineWaypoint.getCoordinate().set(point); + splineWaypoint.getCoordinate().setAltitude(alt); missionItemsToAdd.add(splineWaypoint); } @@ -294,7 +297,8 @@ public void addMissionItems(List missionItems) { public void addSpatialWaypoint(BaseSpatialItem spatialItem, LatLong point) { double alt = getLastAltitude(); - spatialItem.setCoordinate(new LatLongAlt(point.getLatitude(), point.getLongitude(), alt)); + spatialItem.getCoordinate().set(point); + spatialItem.getCoordinate().setAltitude(alt); addMissionItem(spatialItem); } @@ -304,9 +308,10 @@ public void addSpatialWaypoint(BaseSpatialItem spatialItem, LatLong point) { * @param point point used to generate the mission waypoint */ public void addWaypoint(LatLong point) { - double alt = getLastAltitude(); + double alt = getLastAltitude(); // TODO !BB! Make this method the last used frame Waypoint waypoint = new Waypoint(); - waypoint.setCoordinate(new LatLongAlt(point.getLatitude(), point.getLongitude(), alt)); + waypoint.getCoordinate().set(point); + waypoint.getCoordinate().setAltitude(alt); addMissionItem(waypoint); } @@ -316,9 +321,10 @@ public void addWaypoint(LatLong point) { * @param point point used as location for the spline waypoint. */ public void addSplineWaypoint(LatLong point) { - double alt = getLastAltitude(); + double alt = getLastAltitude(); // TODO !BB! Make this method the last used frame SplineWaypoint splineWaypoint = new SplineWaypoint(); - splineWaypoint.setCoordinate(new LatLongAlt(point.getLatitude(), point.getLongitude(), alt)); + splineWaypoint.getCoordinate().set(point); + splineWaypoint.getCoordinate().setAltitude(alt); addMissionItem(splineWaypoint); } @@ -659,8 +665,7 @@ public void move(MissionItemProxy item, LatLong position) { MissionItem missionItem = item.getMissionItem(); if (missionItem instanceof SpatialItem) { SpatialItem spatialItem = (SpatialItem) missionItem; - spatialItem.setCoordinate(new LatLongAlt(position.getLatitude(), - position.getLongitude(), spatialItem.getCoordinate().getAltitude())); + spatialItem.getCoordinate().set(position); if (spatialItem instanceof StructureScanner) { this.drone.buildMissionItemsAsync(new StructureScanner[]{(StructureScanner) spatialItem}, diff --git a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionDetailFragment.java b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionDetailFragment.java index 733f5f0e1c..bc9506cb25 100644 --- a/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionDetailFragment.java +++ b/Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionDetailFragment.java @@ -12,10 +12,12 @@ import android.view.LayoutInflater; import android.view.View; import android.view.ViewGroup; +import android.widget.AdapterView; import android.widget.Spinner; import android.widget.TextView; import com.o3dr.android.client.Drone; +import com.o3dr.services.android.lib.coordinate.Frame; 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; @@ -166,8 +168,8 @@ public void onSpinnerItemSelected(Spinner spinner, int position) { for (LatLong coordinate : polygonPoints) { MissionItem newItem = selectedType.getNewItem(); if (newItem instanceof MissionItem.SpatialItem) { - ((MissionItem.SpatialItem) newItem).setCoordinate(new LatLongAlt(coordinate - .getLatitude(), coordinate.getLongitude(), altitude)); + ((MissionItem.SpatialItem) newItem).getCoordinate().set(coordinate); + ((MissionItem.SpatialItem) newItem).getCoordinate().setAltitude(altitude); } newItems.add(new MissionItemProxy(mMissionProxy, newItem)); @@ -206,11 +208,69 @@ public void onSpinnerItemSelected(Spinner spinner, int position) { } }; + private final Spinner.OnItemSelectedListener missionFrameListener = new Spinner.OnItemSelectedListener() { + + @Override + public void onItemSelected(AdapterView parent, View view, int position, long id) { + frameSpinner = (Spinner) view.findViewById(R.id.frameSpinner); + + if (frameSpinner != null && mSelectedProxies.isEmpty()) + return; + + MissionItemType selectedType = commandAdapter.getItem(position); + List>> updatedList = new ArrayList<>( + mSelectedProxies.size()); + + for (MissionItemProxy missionItemProxy : mSelectedProxies) { + + MissionItem currentItem = missionItemProxy.getMissionItem(); + + List updatedItems = new ArrayList<>(); + + if (currentItem instanceof MissionItem.SpatialItem) { + // Only items that have frames need to be updated + MissionItem.SpatialItem spatialItem = ((MissionItem.SpatialItem) currentItem); + + boolean updated = false; + switch (position) { + case 0: + updated = spatialItem.getCoordinate().setFrame(Frame.GLOBAL_ABS); + break; + case 1: + updated = spatialItem.getCoordinate().setFrame(Frame.GLOBAL_RELATIVE); + break; + case 2: + updated = spatialItem.getCoordinate().setFrame(Frame.GLOBAL_TERRAIN); + break; + default: + // Do Nothing + break; + } + + if (updated) { + updatedItems.add(missionItemProxy); + updatedList.add(Pair.create(missionItemProxy, updatedItems)); + } + } + } + if (!updatedList.isEmpty()) { + mListener.onWaypointTypeChanged(selectedType, updatedList); + dismiss(); // TODO:!BB! do we want to dismiss the dialog + } + } + + @Override + public void onNothingSelected(AdapterView parent) { + + } + }; + protected int getResource() { return R.layout.fragment_editor_detail_generic; } protected SpinnerSelfSelect typeSpinner; + protected Spinner frameSpinner; protected AdapterMissionItems commandAdapter; private OnMissionDetailListener mListener; @@ -424,6 +484,8 @@ public void onApiConnected() { typeSpinner = (SpinnerSelfSelect) view.findViewById(R.id.spinnerWaypointType); typeSpinner.setAdapter(commandAdapter); typeSpinner.setOnSpinnerItemSelectedListener(missionItemSpinnerListener); + + setupFrameSpinner(view); } public void onResume(){ @@ -497,6 +559,41 @@ private boolean hasSpatialOrComplexItems(List items) { return false; } + private void setupFrameSpinner(View view) { + + frameSpinner = (Spinner) view.findViewById(R.id.frameSpinner); + + if (frameSpinner == null) // no frame option just return + return; + + for (MissionItemProxy itemProxy : mSelectedProxies) { + MissionItem currentItem = itemProxy.getMissionItem(); + + if (currentItem instanceof MissionItem.SpatialItem) { + Frame frame = ((MissionItem.SpatialItem) currentItem).getCoordinate().getFrame(); +// List strList = new ArrayList<>("@arrays/") // TODO !BB! Get List from array string + switch (frame) { + case GLOBAL_ABS: + frameSpinner.setSelection(0); + break; + case LOCAL_NED: // TODO !BB! Fix to add NED + break; + case MISSION: // TODO !BB! Fix to add Mission + break; + case GLOBAL_RELATIVE: + frameSpinner.setSelection(1); + break; + case LOCAL_ENU: // TODO !BB! Fix to add ENU + break; + case GLOBAL_TERRAIN: + frameSpinner.setSelection(2); + break; + } + } + frameSpinner.setOnItemSelectedListener(missionFrameListener); + } + } + @Override public void onApiDisconnected() { } diff --git a/Android/src/org/droidplanner/android/utils/SpaceTime.kt b/Android/src/org/droidplanner/android/utils/SpaceTime.kt index e09b9ca3a3..aa234f3307 100644 --- a/Android/src/org/droidplanner/android/utils/SpaceTime.kt +++ b/Android/src/org/droidplanner/android/utils/SpaceTime.kt @@ -2,13 +2,14 @@ package org.droidplanner.android.utils import android.os.Parcel import android.os.Parcelable +import com.o3dr.services.android.lib.coordinate.Frame import com.o3dr.services.android.lib.coordinate.LatLongAlt /** * @author ne0fhyk (Fredia Huya-Kouadio) */ class SpaceTime(latitude: Double, longitude: Double, altitude: Double, var timeInMs: Long) : - LatLongAlt(latitude, longitude, altitude) { + LatLongAlt(latitude, longitude, altitude, Frame.GLOBAL_RELATIVE) { constructor(space: LatLongAlt, timeInMs: Long): this(space.latitude, space.longitude, space.altitude, timeInMs) diff --git a/Android/src/org/droidplanner/android/view/adapterViews/MissionItemListAdapter.java b/Android/src/org/droidplanner/android/view/adapterViews/MissionItemListAdapter.java index 250cff273d..20a9b76abc 100644 --- a/Android/src/org/droidplanner/android/view/adapterViews/MissionItemListAdapter.java +++ b/Android/src/org/droidplanner/android/view/adapterViews/MissionItemListAdapter.java @@ -9,6 +9,7 @@ import android.view.ViewGroup; import android.widget.TextView; +import com.o3dr.services.android.lib.coordinate.Frame; import com.o3dr.services.android.lib.drone.mission.item.MissionItem; import com.o3dr.services.android.lib.drone.mission.item.command.CameraTrigger; import com.o3dr.services.android.lib.drone.mission.item.command.ChangeSpeed; @@ -132,8 +133,6 @@ public void onClick(View v) { final MissionProxy missionProxy = proxy.getMissionProxy(); final MissionItem missionItem = proxy.getMissionItem(); - nameView.setText(String.format(Locale.US, "%3d", missionProxy.getOrder(proxy))); - int leftDrawable; // Spatial item's icons @@ -183,7 +182,8 @@ public void onClick(View v) { leftDrawable = R.drawable.ic_mission_wp; } - altitudeView.setCompoundDrawablesWithIntrinsicBounds(leftDrawable, 0, 0, 0); + String frameType = ""; + nameView.setCompoundDrawablesWithIntrinsicBounds(leftDrawable, 0, 0, 0); if (missionItem instanceof MissionItem.SpatialItem) { MissionItem.SpatialItem waypoint = (MissionItem.SpatialItem) missionItem; @@ -197,6 +197,8 @@ public void onClick(View v) { else altitudeView.setTextColor(Color.WHITE); + frameType = waypoint.getCoordinate().getFrame().getAbbreviation(); + } else if (missionItem instanceof Survey) { double altitude = ((Survey) missionItem).getSurveyDetail().getAltitude(); LengthUnit convertedAltitude = lengthUnitProvider.boxBaseValueToTarget(altitude); @@ -218,6 +220,7 @@ public void onClick(View v) { altitudeView.setTextColor(Color.YELLOW); else altitudeView.setTextColor(Color.WHITE); + }else if(missionItem instanceof ChangeSpeed){ final double speed = ((ChangeSpeed) missionItem).getSpeed(); final SpeedUnit convertedSpeed = speedUnitProvider.boxBaseValueToTarget(speed); @@ -226,5 +229,7 @@ public void onClick(View v) { else { altitudeView.setText(""); } + + nameView.setText(String.format(Locale.US, "%3d %s", missionProxy.getOrder(proxy), frameType.toUpperCase())); } }