|
2 | 2 |
|
3 | 3 | import com.MAVLink.common.msg_mission_item; |
4 | 4 | import com.MAVLink.enums.MAV_CMD; |
| 5 | +import com.o3dr.services.android.lib.coordinate.LatLong; |
| 6 | +import com.o3dr.services.android.lib.coordinate.LatLongAlt; |
5 | 7 |
|
6 | 8 | import org.droidplanner.services.android.impl.core.helpers.geoTools.GeoTools; |
7 | 9 | import org.droidplanner.services.android.impl.core.mission.MissionImpl; |
|
12 | 14 | import org.droidplanner.services.android.impl.core.survey.CameraInfo; |
13 | 15 | import org.droidplanner.services.android.impl.core.survey.SurveyData; |
14 | 16 | import org.droidplanner.services.android.impl.core.survey.grid.GridBuilder; |
15 | | -import com.o3dr.services.android.lib.coordinate.LatLong; |
16 | | -import com.o3dr.services.android.lib.coordinate.LatLongAlt; |
17 | 17 |
|
18 | 18 | import java.util.ArrayList; |
19 | 19 | import java.util.List; |
20 | 20 |
|
21 | 21 | public class StructureScannerImpl extends SpatialCoordItem { |
22 | | - private double radius = (10.0); |
23 | | - private double heightStep = (5); |
| 22 | + private double radius = 10.0; |
| 23 | + private double heightStep = 5; |
24 | 24 | private int numberOfSteps = 2; |
25 | 25 | private boolean crossHatch = false; |
26 | 26 | SurveyData survey = new SurveyData(); |
@@ -50,10 +50,12 @@ private void packROI(List<msg_mission_item> list) { |
50 | 50 | } |
51 | 51 |
|
52 | 52 | private void packCircles(List<msg_mission_item> list) { |
53 | | - for (double altitude = coordinate.getAltitude(); altitude <= getTopHeight(); altitude += heightStep) { |
54 | | - CircleImpl circleImpl = new CircleImpl(missionImpl, new LatLongAlt(coordinate, (altitude))); |
| 53 | + double altitude = coordinate.getAltitude(); |
| 54 | + for (int iSteps = 0; iSteps < numberOfSteps; iSteps++) { |
| 55 | + CircleImpl circleImpl = new CircleImpl(missionImpl, new LatLongAlt(coordinate, altitude)); |
55 | 56 | circleImpl.setRadius(radius); |
56 | 57 | list.addAll(circleImpl.packMissionItem()); |
| 58 | + altitude+= heightStep; |
57 | 59 | } |
58 | 60 | } |
59 | 61 |
|
|
0 commit comments