Skip to content

Commit

Permalink
Android: Added base implementation for the Survey3D object
Browse files Browse the repository at this point in the history
  • Loading branch information
arthurbenemann committed Nov 25, 2014
1 parent 1dd6593 commit 8cc3b18
Show file tree
Hide file tree
Showing 5 changed files with 294 additions and 2 deletions.
169 changes: 169 additions & 0 deletions Android/res/layout/fragment_editor_detail_survey3d.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,169 @@
<?xml version="1.0" encoding="utf-8"?>
<RelativeLayout xmlns:android="http://schemas.android.com/apk/res/android"
xmlns:tools="http://schemas.android.com/tools"
style="@style/missionItemDetailLayout" >

<org.droidplanner.android.widgets.spinners.SpinnerSelfSelect
android:id="@+id/spinnerWaypointType"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_alignParentTop="true"
android:layout_margin="5dp"
android:entries="@array/ExampleWaypointType" />

<RelativeLayout
android:id="@+id/title_rect"
android:layout_width="match_parent"
android:layout_height="64dp"
android:layout_alignParentTop="true"
android:background="@drawable/wp_title_rectangle" >

<TextView
android:id="@+id/WaypointIndex"
style="@style/largeMissionDetailText"
android:layout_width="64dp"
android:layout_height="wrap_content"
android:layout_centerVertical="true"
tools:text="22" />

<View
android:id="@+id/title_div"
android:layout_width="1dp"
android:layout_height="54dp"
android:layout_alignParentTop="true"
android:layout_marginTop="5dp"
android:layout_toRightOf="@id/WaypointIndex"
android:background="@drawable/wp_title_div" />

<RelativeLayout
android:id="@+id/title_content"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_centerVertical="true"
android:layout_toRightOf="@id/title_div"
android:orientation="vertical" >

<TextView
android:id="@+id/WaypointType"
style="@style/missionHeaderTitle"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_marginLeft="12dp"
android:text="@string/waypointType_BuildingMapper"
android:textAllCaps="true" />

<TextView
android:id="@+id/DistanceLabel"
style="@style/missionHeaderlabel"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_alignLeft="@id/WaypointType"
android:layout_below="@id/WaypointType"
android:text="@string/distance_to_home" />

<TextView
android:id="@+id/DistanceValue"
style="@style/missionHeaderValue"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_alignBaseline="@id/DistanceLabel"
android:layout_marginLeft="12dp"
android:layout_toRightOf="@id/DistanceLabel"
tools:text="20m" />
</RelativeLayout>
</RelativeLayout>

<ImageView
android:id="@+id/menuHint"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_alignBottom="@id/title_rect"
android:layout_alignParentRight="true"
android:layout_margin="10dp"
android:src="@drawable/ic_menu_hint"
tools:ignore="ContentDescription" />

<ScrollView
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_below="@id/title_rect" >

<LinearLayout
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:orientation="vertical" >

<TextView
style="@style/ModeDetailText"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:background="@drawable/mode_desc_rectangle"
android:text="Map a building" />

<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
android:id="@+id/radiusPicker"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="@string/circle_radius" />

<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
android:id="@+id/startAltitudePicker"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="Start altitude" />

<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
android:id="@+id/heightStepPicker"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="Step height" />

<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
android:id="@+id/stepsPicker"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="Number of steps" />

<CheckBox
android:id="@+id/checkBoxSurveyCrossHatch"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_marginLeft="8dp"
android:fontFamily="sans-serif-light"
android:padding="5dp"
android:text="Cross Hatch"
android:textSize="20sp" />

<RelativeLayout
android:layout_width="match_parent"
android:layout_height="wrap_content" >

<TextView
android:id="@+id/staticText"
style="@style/ModeDetailText"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_gravity="left"
android:text="@string/camera_"
android:textAppearance="?android:attr/textAppearanceMedium" />

<org.droidplanner.android.widgets.spinners.SpinnerSelfSelect
android:id="@+id/cameraFileSpinner"
android:layout_width="196dp"
android:layout_height="wrap_content"
android:layout_alignBottom="@id/staticText"
android:layout_alignParentRight="true"
android:layout_alignTop="@id/staticText"
android:layout_gravity="center"
android:layout_toRightOf="@id/staticText"
android:entries="@array/ExampleCameraArray" />
</RelativeLayout>

</LinearLayout>
</ScrollView>

</RelativeLayout>
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import org.droidplanner.core.mission.commands.ReturnToHome;
import org.droidplanner.core.mission.commands.Takeoff;
import org.droidplanner.core.mission.survey.Survey;
import org.droidplanner.core.mission.survey.Survey3D;
import org.droidplanner.core.mission.waypoints.SpatialCoordItem;
import org.droidplanner.core.mission.waypoints.SplineWaypoint;
import org.droidplanner.core.mission.waypoints.Waypoint;
Expand Down Expand Up @@ -139,11 +140,11 @@ public void removeItemList(List<MissionItemProxy> items) {
* 2D points making up the survey
*/
public void addSurveyPolygon(List<Coord2D> points) {
Survey survey = new Survey(mMission, points);
Survey3D survey = new Survey3D(mMission, points);
mMissionItems.add(new MissionItemProxy(this, survey));
mMission.addMissionItem(survey);
try {
survey.build();
//survey.build();
} catch (Exception e) {
e.printStackTrace();
}
Expand Down Expand Up @@ -615,7 +616,10 @@ public List<List<Coord2D>> getPolygonsPath() {
for (MissionItem item : mMission.getItems()) {
if (item instanceof Survey) {
polygonPaths.add(((Survey)item).polygon.getPoints());
}else if (item instanceof Survey3D) {
polygonPaths.add(((Survey3D)item).polygon.getPoints());
}

}
return polygonPaths;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,15 @@
import org.droidplanner.core.mission.MissionItem;
import org.droidplanner.core.mission.commands.Takeoff;
import org.droidplanner.core.mission.survey.Survey;
import org.droidplanner.core.mission.survey.Survey3D;
import org.droidplanner.core.mission.waypoints.Circle;
import org.droidplanner.core.mission.waypoints.SpatialCoordItem;
import org.droidplanner.core.mission.waypoints.SplineWaypoint;
import org.droidplanner.core.mission.waypoints.StructureScanner;
import org.droidplanner.core.survey.grid.Grid;

import com.MAVLink.common.msg_mission_item;

import android.content.Context;
import android.graphics.Color;
import android.view.LayoutInflater;
Expand Down Expand Up @@ -115,6 +118,9 @@ public List<Coord2D> getPath(Coord2D previousPoint) {
pathPoints.addAll(grid.gridPoints);
}
break;
case SURVEY3D:
pathPoints.addAll(((Survey3D) mMissionItem).getPath());
break;
case CYLINDRICAL_SURVEY:
StructureScanner survey = (StructureScanner)mMissionItem;
pathPoints.addAll(survey.getPath());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,9 @@ public static MissionDetailFragment newInstance(MissionItemType itemType) {
case SURVEY:
fragment = new MissionSurveyFragment();
break;
case SURVEY3D:
fragment = new MissionSurvey3DFragment();
break;
case TAKEOFF:
fragment = new MissionTakeoffFragment();
break;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
package org.droidplanner.android.proxy.mission.item.fragments;

import java.util.List;

import org.droidplanner.R;
import org.droidplanner.R.id;
import org.droidplanner.android.proxy.mission.item.adapters.CamerasAdapter;
import org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView;
import org.droidplanner.android.widgets.spinnerWheel.adapters.NumericWheelAdapter;
import org.droidplanner.android.widgets.spinners.SpinnerSelfSelect;
import org.droidplanner.core.mission.MissionItemType;
import org.droidplanner.core.mission.survey.Survey3D;
import org.droidplanner.core.survey.CameraInfo;

import android.content.Context;
import android.os.Bundle;
import android.util.Log;
import android.view.View;
import android.widget.CheckBox;
import android.widget.CompoundButton;
import android.widget.Spinner;

public class MissionSurvey3DFragment extends MissionDetailFragment implements
CardWheelHorizontalView.OnCardWheelChangedListener, CompoundButton.OnCheckedChangeListener {

private CheckBox checkBoxAdvanced;
private CardWheelHorizontalView startAltitudeStepPicker, stepHeightStepPicker;
private SpinnerSelfSelect cameraSpinner;
private CamerasAdapter cameraAdapter;
private List<Survey3D> missionItems;

@Override
protected int getResource() {
return R.layout.fragment_editor_detail_survey3d;
}

@Override
public void onViewCreated(View view, Bundle savedInstanceState) {
super.onViewCreated(view, savedInstanceState);
final Context context = getActivity().getApplicationContext();

Log.d("DEBUG", "onViewCreated");
typeSpinner.setSelection(commandAdapter.getPosition(MissionItemType.SURVEY3D));

missionItems = (List<Survey3D>) getMissionItems();
// Use the first one as reference.
final Survey3D firstItem = missionItems.get(0);

cameraAdapter = new CamerasAdapter(getActivity(),
android.R.layout.simple_spinner_dropdown_item);
cameraSpinner = (SpinnerSelfSelect) view.findViewById(id.cameraFileSpinner);
cameraSpinner.setAdapter(cameraAdapter);
cameraSpinner.setOnSpinnerItemSelectedListener(this);
cameraAdapter.setTitle(firstItem.getCamera().name);

startAltitudeStepPicker = (CardWheelHorizontalView) view
.findViewById(R.id.startAltitudePicker);
startAltitudeStepPicker.setViewAdapter(new NumericWheelAdapter(context,
R.layout.wheel_text_centered, MIN_ALTITUDE, MAX_ALTITUDE, "%d m"));
startAltitudeStepPicker.addChangingListener(this);
//startAltitudeStepPicker.setCurrentValue((int) firstItem.getCoordinate().getAltitude().valueInMeters());

stepHeightStepPicker = (CardWheelHorizontalView) view.findViewById(R.id.heightStepPicker);
stepHeightStepPicker.setViewAdapter(new NumericWheelAdapter(context,
R.layout.wheel_text_centered, 1, MAX_ALTITUDE, "%d m"));
stepHeightStepPicker.addChangingListener(this);
//stepHeightStepPicker.setCurrentValue((int) firstItem.getEndAltitude().valueInMeters());

checkBoxAdvanced = (CheckBox) view.findViewById(R.id.checkBoxSurveyCrossHatch);
checkBoxAdvanced.setOnCheckedChangeListener(this);
//checkBoxAdvanced.setChecked(firstItem.isCrossHatchEnabled());

}

@Override
public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) {
//getItem().enableCrossHatch(isChecked);
getMissionProxy().getMission().notifyMissionUpdate();
}

@Override
public void onChanged(CardWheelHorizontalView cardWheel, int oldValue, int newValue) {
switch (cardWheel.getId()) {
case R.id.startAltitudePicker:
//getItem().setAltitude(new Altitude(newValue));
break;
case R.id.heightStepPicker:
//getItem().setAltitudeStep(newValue);
break;
}
getMissionProxy().getMission().notifyMissionUpdate();
}

@Override
public void onSpinnerItemSelected(Spinner spinner, int position) {
if (spinner.getId() == id.cameraFileSpinner) {
CameraInfo cameraInfo = cameraAdapter.getCamera(position);
cameraAdapter.setTitle(cameraInfo.name);
for (Survey3D scan : missionItems) {
scan.setCameraInfo(cameraInfo);
}
getMissionProxy().getMission().notifyMissionUpdate();
}
}

private Survey3D getItem() {
Survey3D cylindricalSurvey = (Survey3D) getMissionItems().get(0);
return cylindricalSurvey;
}
}

0 comments on commit 8cc3b18

Please sign in to comment.