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

WIP: Update to Tower to support Alt Frames like Terrain #1826

Open
wants to merge 6 commits into
base: develop
Choose a base branch
from
Open
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
12 changes: 12 additions & 0 deletions Android/res/layout/fragment_editor_detail_waypoint.xml
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,18 @@
android:background="@drawable/mode_desc_rectangle"
android:text="@string/waypointInfo_Waypoint"/>

<Spinner
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:id="@+id/frameSpinner"
android:entries="@array/MissionItemFrame"
android:dropDownWidth="match_parent"
style="@style/DropDownItem"
android:textSize="@+id/textLabels"
android:textAlignment="textEnd"
android:gravity="end|center_vertical"
android:layout_gravity="end|center_vertical" />

<org.droidplanner.android.view.spinnerWheel.CardWheelHorizontalView
android:id="@+id/altitudePicker"
android:layout_width="match_parent"
Expand Down
18 changes: 8 additions & 10 deletions Android/res/layout/fragment_editor_list_item.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,34 +16,32 @@ Used to Style the horizontal list of mission items.
android:padding="3dp"
android:layout_marginBottom="2dp"
android:layout_marginLeft="1dp"
android:layout_marginStart="1dp"
>
android:layout_marginStart="1dp">

<TextView
android:id="@+id/rowNameView"
android:id="@+id/rowAltitudeView"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_alignParentTop="true"
android:layout_centerHorizontal="true"
android:layout_marginBottom="4dp"
tools:text="44"
tools:text="200m"
android:textColor="#FFFFFF"
android:textSize="@dimen/editor_list_item_text_size"
android:textStyle="bold"

/>

<TextView
android:id="@+id/rowAltitudeView"
android:layout_alignParentLeft="true"
android:layout_below="@+id/rowNameView"
android:id="@+id/rowNameView"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
tools:text="200m"
tools:text="2"
android:textColor="#FFFFFF"
android:textStyle="bold"
android:drawableLeft="@drawable/ic_mission_wp"
android:drawableRight="@drawable/ic_mission_wp"
android:drawablePadding="2dp"
/>
android:layout_below="@+id/rowAltitudeView"
android:layout_centerHorizontal="true" />

</RelativeLayout>
2 changes: 1 addition & 1 deletion Android/res/values-sw540dp/dimens.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<dimen name="editor_button_height">56dp</dimen>

<!-- Dimension for the editor list items -->
<dimen name="editor_list_item_text_size">24sp</dimen>
<dimen name="editor_list_item_text_size">22sp</dimen>

<!-- Dimension for the editor mission fragment -->
<dimen name="editor_mission_fragment_height">80dp</dimen>
Expand Down
7 changes: 7 additions & 0 deletions Android/res/values/arrays.xml
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,13 @@
<string-array name="ExampleWaypointType">
<item>Waypoint Type</item>
</string-array>

<string-array name="MissionItemFrame">
<item>Absolute</item>
<item>Relative</item>
<item>Terrain</item>
</string-array>

<string-array name="RC_Tuning">
<item>Auto-tune</item>
<item>Roll / Pitch</item>
Expand Down
2 changes: 1 addition & 1 deletion Android/res/values/dimens.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<dimen name="editor_button_margin">0dp</dimen>

<!-- Dimension for the editor list items -->
<dimen name="editor_list_item_text_size">20sp</dimen>
<dimen name="editor_list_item_text_size">18sp</dimen>

<!-- Dimension for the editor mission fragment -->
<dimen name="editor_mission_fragment_height">70dp</dimen>
Expand Down
3 changes: 2 additions & 1 deletion Android/src/org/droidplanner/android/fragments/DroneMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ public View onCreateView(LayoutInflater inflater, ViewGroup viewGroup, Bundle bu

@Override
public void onMapLongClick(LatLong point) {
editorListener.onMapClick(point);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand All @@ -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);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -245,9 +246,10 @@ public void addWaypoints(List<LatLong> points) {
double alt = getLastAltitude();
List<MissionItem> missionItemsToAdd = new ArrayList<MissionItem>(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);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@billbonney Here and below, Waypoint#getCoordinate() is not guaranteed to be non-null, so this changes will result in several npe errors.

waypoint.getCoordinate().setAltitude(alt);
missionItemsToAdd.add(waypoint);
}

Expand Down Expand Up @@ -275,9 +277,10 @@ public void addSplineWaypoints(List<LatLong> points) {
double alt = getLastAltitude();
List<MissionItem> missionItemsToAdd = new ArrayList<MissionItem>(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);
}

Expand All @@ -294,7 +297,8 @@ public void addMissionItems(List<MissionItem> 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);
}

Expand All @@ -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);
}

Expand All @@ -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);
}

Expand Down Expand Up @@ -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},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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));
Expand Down Expand Up @@ -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);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@billbonney You should be able to remove this assignment since frameSpinner is already set in setupFrameSpinner().


if (frameSpinner != null && mSelectedProxies.isEmpty())
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@billbonney This has the effect that if frameSpinner is null the early return will be aborted. Is that the intended effect?

return;

MissionItemType selectedType = commandAdapter.getItem(position);
List<Pair<MissionItemProxy, List<MissionItemProxy>>> updatedList = new ArrayList<>(
mSelectedProxies.size());

for (MissionItemProxy missionItemProxy : mSelectedProxies) {

MissionItem currentItem = missionItemProxy.getMissionItem();

List<MissionItemProxy> updatedItems = new ArrayList<>();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@billbonney Looks like there's at most one entry in the updatedItems list for every loop, hence the list doesn't seem needed.


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:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@billbonney Here and below, use java constants for the case labels.

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
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@billbonney I don't think so. It should auto dismiss after the user's selection.

}
}

@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;

Expand Down Expand Up @@ -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(){
Expand Down Expand Up @@ -497,6 +559,41 @@ private boolean hasSpatialOrComplexItems(List<MissionItemProxy> 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<String> strList = new ArrayList<>("@arrays/") // TODO !BB! Get List from array string
switch (frame) {
case GLOBAL_ABS:
frameSpinner.setSelection(0);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@billbonney Use java constants as arguments for the setSelection(...) method.

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() {
}
Expand Down
Loading