Skip to content

Commit feec999

Browse files
authored
Merge pull request #446 from dronekit/bug_fixes
Fix infinite loop when heightStep is 0
2 parents 0f1e038 + 039ca40 commit feec999

File tree

1 file changed

+8
-6
lines changed

1 file changed

+8
-6
lines changed

ClientLib/src/main/java/org/droidplanner/services/android/impl/core/mission/waypoints/StructureScannerImpl.java

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22

33
import com.MAVLink.common.msg_mission_item;
44
import com.MAVLink.enums.MAV_CMD;
5+
import com.o3dr.services.android.lib.coordinate.LatLong;
6+
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
57

68
import org.droidplanner.services.android.impl.core.helpers.geoTools.GeoTools;
79
import org.droidplanner.services.android.impl.core.mission.MissionImpl;
@@ -12,15 +14,13 @@
1214
import org.droidplanner.services.android.impl.core.survey.CameraInfo;
1315
import org.droidplanner.services.android.impl.core.survey.SurveyData;
1416
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;
1717

1818
import java.util.ArrayList;
1919
import java.util.List;
2020

2121
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;
2424
private int numberOfSteps = 2;
2525
private boolean crossHatch = false;
2626
SurveyData survey = new SurveyData();
@@ -50,10 +50,12 @@ private void packROI(List<msg_mission_item> list) {
5050
}
5151

5252
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));
5556
circleImpl.setRadius(radius);
5657
list.addAll(circleImpl.packMissionItem());
58+
altitude+= heightStep;
5759
}
5860
}
5961

0 commit comments

Comments
 (0)