Skip to content

Commit 1570baa

Browse files
Merge branch 'master' into beta
2 parents bdc6f09 + 3f3247a commit 1570baa

File tree

14 files changed

+197
-6
lines changed

14 files changed

+197
-6
lines changed

Android/AndroidManifest.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
33
xmlns:tools="http://schemas.android.com/tools"
44
package="org.droidplanner"
5-
android:versionCode="94"
5+
android:versionCode="95"
66
android:versionName="please run version.sh to get the version name">
77

88
<uses-sdk

Android/src/org/droidplanner/android/fragments/mode/ModeFollowFragment.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,7 @@ protected void updateLabel() {
9292
@Override
9393
public void onItemSelected(AdapterView<?> parent, View view, int position, long id) {
9494
followMe.setType(adapter.getItem(position));
95+
updateLabel();
9596
}
9697

9798
@Override

ChangeLog.md

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,9 @@ Our convention for release control is the following (for a release like DPvA.B.C
88
All the changes are logged below (preferable with the pull request numbers in parenteses):
99

1010
# Releases
11+
## Droidplanner v2.7.4
12+
* Added extra follow-modes (#1057)
13+
* Fix error on Mavlink message handling (#1056,#1050)
1114

1215
## Droidplanner v2.7.3
1316
* German translation improvements (#1034,#1045)

Core/src/org/droidplanner/core/MAVLink/connection/MavLinkConnection.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -127,9 +127,9 @@ private void handleData(Parser parser, int bufferSize, byte[] buffer) {
127127
for (int i = 0; i < bufferSize; i++) {
128128
MAVLinkPacket receivedPacket = parser.mavlink_parse_char(buffer[i] & 0x00ff);
129129
if (receivedPacket != null) {
130-
queueToLog(receivedPacket);
131130
MAVLinkMessage msg = receivedPacket.unpack();
132131
reportReceivedMessage(msg);
132+
queueToLog(receivedPacket);
133133
}
134134
}
135135
}

Core/src/org/droidplanner/core/gcs/follow/Follow.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ public class Follow implements OnDroneListener, LocationReceiver {
3232

3333
public Follow(Drone drone, Handler handler, LocationFinder locationFinder) {
3434
this.drone = drone;
35-
followAlgorithm = new FollowAbove(drone, new Length(0.0));
35+
followAlgorithm = FollowAlgorithm.FollowModes.LEASH.getAlgorithmType(drone);
3636
this.locationFinder = locationFinder;
3737
locationFinder.setLocationListner(this);
3838
roiEstimator = new ROIEstimator(handler, drone);

Core/src/org/droidplanner/core/gcs/follow/FollowAbove.java

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,11 @@
11
package org.droidplanner.core.gcs.follow;
22

33
import org.droidplanner.core.gcs.location.Location;
4+
import org.droidplanner.core.helpers.coordinates.Coord2D;
45
import org.droidplanner.core.helpers.units.Length;
56
import org.droidplanner.core.model.Drone;
67

8+
79
public class FollowAbove extends FollowAlgorithm {
810

911
public FollowAbove(Drone drone, Length radius) {
@@ -17,7 +19,8 @@ public FollowModes getType() {
1719

1820
@Override
1921
public void processNewLocation(Location location) {
20-
drone.getGuidedPoint().newGuidedCoord(location.getCoord());
22+
Coord2D gcsCoord = new Coord2D(location.getCoord().getLat(), location.getCoord().getLng());
23+
drone.getGuidedPoint().newGuidedCoord(gcsCoord);
2124
}
2225

2326
}

Core/src/org/droidplanner/core/gcs/follow/FollowAlgorithm.java

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ public void changeRadius(Double increment) {
2525
}
2626

2727
public enum FollowModes {
28-
LEASH("Leash"), ABOVE("Above");
28+
LEASH("Leash"), LEAD("Lead"), RIGHT("Right"), LEFT("Left"), CIRCLE("Orbit"), ABOVE("Above");
2929

3030
private String name;
3131

@@ -46,6 +46,14 @@ public FollowAlgorithm getAlgorithmType(Drone drone) {
4646
switch (this) {
4747
case LEASH:
4848
return new FollowLeash(drone, new Length(8.0));
49+
case LEAD:
50+
return new FollowLead(drone, new Length(15.0));
51+
case RIGHT:
52+
return new FollowRight(drone, new Length(10.0));
53+
case LEFT:
54+
return new FollowLeft(drone, new Length(10.0));
55+
case CIRCLE:
56+
return new FollowCircle(drone, new Length(15.0), 10.0);
4957
case ABOVE:
5058
return new FollowAbove(drone, new Length(0.0));
5159
}
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
package org.droidplanner.core.gcs.follow;
2+
3+
import org.droidplanner.core.gcs.location.Location;
4+
import org.droidplanner.core.helpers.coordinates.Coord2D;
5+
import org.droidplanner.core.helpers.geoTools.GeoTools;
6+
import org.droidplanner.core.helpers.math.MathUtil;
7+
import org.droidplanner.core.helpers.units.Length;
8+
import org.droidplanner.core.model.Drone;
9+
10+
11+
public class FollowCircle extends FollowAlgorithm {
12+
13+
/**
14+
* °/s
15+
*/
16+
private double circleStep = 2;
17+
private double circleAngle = 0.0;
18+
19+
public FollowCircle(Drone drone, Length radius, double rate) {
20+
super(drone, radius);
21+
circleStep = rate;
22+
}
23+
24+
@Override
25+
public FollowModes getType() {
26+
return FollowModes.CIRCLE;
27+
}
28+
29+
@Override
30+
public void processNewLocation(Location location) {
31+
Coord2D gcsCoord = new Coord2D(location.getCoord().getLat(), location.getCoord().getLng());
32+
Coord2D goCoord = GeoTools.newCoordFromBearingAndDistance(gcsCoord, circleAngle,
33+
radius.valueInMeters());
34+
circleAngle = MathUtil.constrainAngle(circleAngle + circleStep);
35+
drone.getGuidedPoint().newGuidedCoord(goCoord);
36+
}
37+
}
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
package org.droidplanner.core.gcs.follow;
2+
3+
import org.droidplanner.core.gcs.location.Location;
4+
import org.droidplanner.core.helpers.coordinates.Coord2D;
5+
import org.droidplanner.core.helpers.geoTools.GeoTools;
6+
import org.droidplanner.core.helpers.units.Length;
7+
import org.droidplanner.core.model.Drone;
8+
9+
10+
public abstract class FollowHeadingAngle extends FollowAlgorithm {
11+
12+
protected double angleOffset;
13+
14+
protected FollowHeadingAngle(Drone drone, Length radius, double angleOffset) {
15+
super(drone, radius);
16+
this.angleOffset = angleOffset;
17+
}
18+
19+
@Override
20+
public void processNewLocation(Location location) {
21+
22+
Coord2D gcsCoord = new Coord2D(location.getCoord().getLat(), location.getCoord().getLng());
23+
double bearing = location.getBearing();
24+
25+
Coord2D goCoord = GeoTools.newCoordFromBearingAndDistance(gcsCoord, bearing + angleOffset,
26+
radius.valueInMeters());
27+
drone.getGuidedPoint().newGuidedCoord(goCoord);
28+
}
29+
30+
}
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
package org.droidplanner.core.gcs.follow;
2+
3+
import org.droidplanner.core.helpers.units.Length;
4+
import org.droidplanner.core.model.Drone;
5+
6+
public class FollowLead extends FollowHeadingAngle {
7+
8+
public FollowLead(Drone drone, Length radius) {
9+
super(drone, radius, 0.0);
10+
}
11+
12+
@Override
13+
public FollowModes getType() {
14+
return FollowModes.LEAD;
15+
}
16+
17+
}

0 commit comments

Comments
 (0)