Skip to content

Commit

Permalink
Merge pull request #1237 from DroidPlanner/StructureScanneUpdate
Browse files Browse the repository at this point in the history
Structure scanner update
  • Loading branch information
arthurbenemann committed Oct 30, 2014
2 parents 1df878b + 2732a46 commit ea10f30
Show file tree
Hide file tree
Showing 5 changed files with 87 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,32 @@
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>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ public class CamerasAdapter extends ArrayAdapter<String> {
private CameraInfoLoader loader;
private Context context;
private String title = "";
CameraInfo defaultCamera = new CameraInfo();
public CameraInfo defaultCamera = new CameraInfo();

public CamerasAdapter(Context context, int resource) {
super(context, resource);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,14 @@
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.helpers.units.Altitude;
import org.droidplanner.core.mission.MissionItemType;
import org.droidplanner.core.mission.survey.CameraInfo;
import org.droidplanner.core.mission.waypoints.StructureScanner;

import android.content.Context;
Expand All @@ -15,18 +19,22 @@
import android.view.View;
import android.widget.CheckBox;
import android.widget.CompoundButton;
import android.widget.Spinner;

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

private CheckBox checkBoxAdvanced;
private CardWheelHorizontalView radiusPicker, startAltitudeStepPicker,
endAltitudeStepPicker, mNumberStepsPicker;
stepHeightStepPicker, mNumberStepsPicker;
private SpinnerSelfSelect cameraSpinner;
private CamerasAdapter cameraAdapter;
private List<StructureScanner> missionItems;

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

@Override
Expand All @@ -38,14 +46,21 @@ public void onViewCreated(View view, Bundle savedInstanceState) {
typeSpinner.setSelection(commandAdapter
.getPosition(MissionItemType.CYLINDRICAL_SURVEY));

missionItems = (List<StructureScanner>) getMissionItems();
// Use the first one as reference.
final StructureScanner firstItem = ((List<StructureScanner>) getMissionItems())
.get(0);
final StructureScanner 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);
cameraSpinner.setSelection(0);

radiusPicker = (CardWheelHorizontalView) view
.findViewById(R.id.radiusPicker);
radiusPicker.setViewAdapter(new NumericWheelAdapter(context,
R.layout.wheel_text_centered, 2, 50, "%d m"));
R.layout.wheel_text_centered, 2, 100, "%d m"));
radiusPicker.addChangingListener(this);
radiusPicker.setCurrentValue((int) firstItem.getRadius()
.valueInMeters());
Expand All @@ -59,13 +74,13 @@ public void onViewCreated(View view, Bundle savedInstanceState) {
startAltitudeStepPicker.setCurrentValue((int) firstItem
.getCoordinate().getAltitude().valueInMeters());

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

mNumberStepsPicker = (CardWheelHorizontalView) view
Expand All @@ -79,6 +94,7 @@ public void onViewCreated(View view, Bundle savedInstanceState) {
.findViewById(R.id.checkBoxSurveyCrossHatch);
checkBoxAdvanced.setOnCheckedChangeListener(this);
checkBoxAdvanced.setChecked(firstItem.isCrossHatchEnabled());

}

@Override
Expand All @@ -93,11 +109,9 @@ public void onChanged(CardWheelHorizontalView cardWheel, int oldValue,
switch (cardWheel.getId()) {
case R.id.radiusPicker:
getItem().setRadius(newValue);
getMissionProxy().getMission().notifyMissionUpdate();
break;
case R.id.startAltitudePicker:
getItem().setAltitude( new Altitude(newValue));
getMissionProxy().getMission().notifyMissionUpdate();
break;
case R.id.heightStepPicker:
getItem().setAltitudeStep(newValue);
Expand All @@ -106,6 +120,19 @@ public void onChanged(CardWheelHorizontalView cardWheel, int oldValue,
getItem().setNumberOfSteps(newValue);
break;
}
getMissionProxy().getMission().notifyMissionUpdate();
}

@Override
public void onSpinnerItemSelected(Spinner spinner, int position) {
if (spinner.equals(cameraSpinner)) {
CameraInfo cameraInfo = cameraAdapter.getCamera(position);
cameraAdapter.setTitle(cameraInfo.name);
for (StructureScanner scan : missionItems) {
scan.setCamera(cameraInfo);
}
getMissionProxy().getMission().notifyMissionUpdate();
}
}

private StructureScanner getItem() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public Double getSensorLongitudinalSize() {

@Override
public String toString() {
return "ImageWidth:" + sensorWidth + " ImageHeight:" + sensorHeight + " FocalLength:"
return "Camera:"+name+" ImageWidth:" + sensorWidth + " ImageHeight:" + sensorHeight + " FocalLength:"
+ focalLength + " Overlap:" + overlap + " Sidelap:" + sidelap
+ " isInLandscapeOrientation:" + isInLandscapeOrientation;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,9 @@
import org.droidplanner.core.mission.Mission;
import org.droidplanner.core.mission.MissionItem;
import org.droidplanner.core.mission.MissionItemType;
import org.droidplanner.core.mission.survey.CameraInfo;
import org.droidplanner.core.mission.survey.Survey;
import org.droidplanner.core.mission.survey.SurveyData;
import org.droidplanner.core.mission.survey.grid.GridBuilder;
import org.droidplanner.core.polygon.Polygon;

Expand All @@ -23,6 +25,7 @@ public class StructureScanner extends SpatialCoordItem {
private Altitude heightStep = new Altitude(5);
private int numberOfSteps = 2;
private boolean crossHatch = false;
SurveyData survey = new SurveyData();

public StructureScanner(Mission mission, Coord3D coord) {
super(mission,coord);
Expand Down Expand Up @@ -66,14 +69,20 @@ private void packHatch(List<msg_mission_item> list) {

Coord2D corner = GeoTools.newCoordFromBearingAndDistance(coordinate,
-45, radius.valueInMeters()*2);
GridBuilder grid = new GridBuilder(polygon, 0.0,
radius.valueInMeters() / 4, corner );


survey.setAltitude(getTopHeight());

try {
survey.update(0.0, survey.getAltitude(), survey.getOverlap(), survey.getSidelap());
GridBuilder grid = new GridBuilder(polygon, survey, corner);
for (Coord2D point : grid.generate(false).gridPoints) {
list.add(Survey.packSurveyPoint(point, getTopHeight()));
}
grid.setAngle(90.0);
for (Coord2D point : grid.generate(false).gridPoints) {

survey.update(90.0, survey.getAltitude(), survey.getOverlap(), survey.getSidelap());
GridBuilder grid2 = new GridBuilder(polygon, survey, corner);
for (Coord2D point : grid2.generate(false).gridPoints) {
list.add(Survey.packSurveyPoint(point, getTopHeight()));
}
} catch (Exception e) { // Should never fail, since it has good polygons
Expand Down Expand Up @@ -109,8 +118,8 @@ public MissionItemType getType() {



private Length getTopHeight() {
return new Length(coordinate.getAltitude().valueInMeters()+ (numberOfSteps-1)*heightStep.valueInMeters());
private Altitude getTopHeight() {
return new Altitude(coordinate.getAltitude().valueInMeters()+ (numberOfSteps-1)*heightStep.valueInMeters());
}

public Altitude getEndAltitude() {
Expand Down Expand Up @@ -149,4 +158,9 @@ public void setNumberOfSteps(int newValue) {
numberOfSteps = newValue;
}

public void setCamera(CameraInfo cameraInfo) {
survey.setCameraInfo(cameraInfo);

}

}

0 comments on commit ea10f30

Please sign in to comment.