Skip to content

Commit 8d65045

Browse files
Merge branch 'master' into beta
2 parents c6c6c54 + 458a776 commit 8d65045

File tree

23 files changed

+429
-88
lines changed

23 files changed

+429
-88
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="108"
5+
android:versionCode="109"
66
android:versionName="please run version.sh to get the version name">
77

88
<uses-sdk

Android/res/layout/fragment_editor_detail_cond_yaw.xml

Lines changed: 0 additions & 72 deletions
This file was deleted.
Lines changed: 108 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
<?xml version="1.0" encoding="utf-8"?>
2+
<RelativeLayout xmlns:android="http://schemas.android.com/apk/res/android"
3+
xmlns:tools="http://schemas.android.com/tools"
4+
style="@style/missionItemDetailLayout" >
5+
6+
<org.droidplanner.android.widgets.spinners.SpinnerSelfSelect
7+
android:id="@+id/spinnerWaypointType"
8+
android:layout_width="match_parent"
9+
android:layout_height="wrap_content"
10+
android:layout_alignParentTop="true"
11+
android:layout_margin="5dp"
12+
android:entries="@array/ExampleWaypointType" />
13+
14+
<RelativeLayout
15+
android:id="@+id/title_rect"
16+
android:layout_width="match_parent"
17+
android:layout_height="64dp"
18+
android:layout_alignParentTop="true"
19+
android:background="@drawable/wp_title_rectangle" >
20+
21+
<TextView
22+
android:id="@+id/WaypointIndex"
23+
style="@style/largeMissionDetailText"
24+
android:layout_width="64dp"
25+
android:layout_height="wrap_content"
26+
android:layout_centerVertical="true"
27+
tools:text="22" />
28+
29+
<View
30+
android:id="@+id/title_div"
31+
android:layout_width="1dp"
32+
android:layout_height="54dp"
33+
android:layout_alignParentTop="true"
34+
android:layout_marginTop="5dp"
35+
android:layout_toRightOf="@id/WaypointIndex"
36+
android:background="@drawable/wp_title_div" />
37+
38+
<RelativeLayout
39+
android:id="@+id/title_content"
40+
android:layout_width="match_parent"
41+
android:layout_height="wrap_content"
42+
android:layout_centerVertical="true"
43+
android:layout_toRightOf="@id/title_div"
44+
android:orientation="vertical" >
45+
46+
<TextView
47+
android:id="@+id/WaypointType"
48+
style="@style/missionHeaderTitle"
49+
android:layout_width="wrap_content"
50+
android:layout_height="wrap_content"
51+
android:layout_marginLeft="12dp"
52+
android:text="@string/waypointType_Condition_Yaw" />
53+
54+
<TextView
55+
android:id="@+id/DistanceLabel"
56+
style="@style/missionHeaderlabel"
57+
android:layout_width="wrap_content"
58+
android:layout_height="wrap_content"
59+
android:layout_alignLeft="@id/WaypointType"
60+
android:layout_below="@id/WaypointType" />
61+
</RelativeLayout>
62+
</RelativeLayout>
63+
64+
<ImageView
65+
android:id="@+id/menuHint"
66+
android:layout_width="wrap_content"
67+
android:layout_height="wrap_content"
68+
android:layout_alignBottom="@id/title_rect"
69+
android:layout_alignParentRight="true"
70+
android:layout_margin="10dp"
71+
android:src="@drawable/ic_menu_hint"
72+
tools:ignore="ContentDescription" />
73+
74+
<LinearLayout
75+
android:layout_width="match_parent"
76+
android:layout_height="wrap_content"
77+
android:layout_below="@id/title_rect"
78+
android:orientation="vertical"
79+
android:paddingBottom="5dp" >
80+
81+
<TextView
82+
style="@style/ModeDetailText"
83+
android:layout_width="match_parent"
84+
android:layout_height="wrap_content"
85+
android:background="@drawable/mode_desc_rectangle"
86+
android:padding="12dp"
87+
android:text="@string/waypointInfo_CondYaw" />
88+
89+
<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
90+
android:id="@+id/picker1"
91+
style="@style/missionItemDetailCard"
92+
android:layout_width="match_parent"
93+
android:layout_height="wrap_content"
94+
android:orientation="vertical"
95+
android:text="@string/mission_control_condition_yaw_angle" >
96+
97+
</org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView>
98+
99+
<CheckBox
100+
android:id="@+id/checkBox1"
101+
style="@style/missionItemDetailCard"
102+
android:layout_width="match_parent"
103+
android:layout_height="wrap_content"
104+
android:text="@string/mission_control_condition_yaw_relative" />
105+
106+
</LinearLayout>
107+
108+
</RelativeLayout>

Android/res/values/strings.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -181,6 +181,7 @@
181181
<string name="waypointType_RTL">Return To Launch</string>
182182
<string name="waypointType_Land">Land</string>
183183
<string name="waypointType_Change_Speed">Change Speed</string>
184+
<string name="waypointType_Condition_Yaw">Set Yaw</string>
184185
<string name="waypointType_Camera_Trigger">Camera Trigger</string>
185186
<string name="waypointType_Set_Servo">Set Servo</string>
186187
<string name="waypointType_EPM">EPM</string>
@@ -367,6 +368,8 @@
367368
<string name="mission_control_follow">Follow</string>
368369
<string name="mission_control_dronie">Dronie</string>
369370
<string name="mission_control_change_speed">Change Speed</string>
371+
<string name="mission_control_condition_yaw_angle">Target angle</string>
372+
<string name="mission_control_condition_yaw_relative">Relative Angle</string>
370373
<string name="telemetry_label">Telemetry</string>
371374
<string name="flight_modes_label">Flight modes</string>
372375
<string name="menu_info_bar">Info Bar</string>

Android/src/org/droidplanner/android/fragments/DroneMap.java

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,8 @@ public void run() {
7676
}
7777

7878
mMapFragment.updateMissionPath(missionProxy);
79+
80+
mMapFragment.updatePolygonsPaths(missionProxy.getPolygonsPath());
7981

8082
mHandler.removeCallbacks(this);
8183
}

Android/src/org/droidplanner/android/fragments/EditorMapFragment.java

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
import org.droidplanner.android.maps.DPMap;
77
import org.droidplanner.android.maps.MarkerInfo;
88
import org.droidplanner.android.proxy.mission.item.markers.MissionItemMarkerInfo;
9+
import org.droidplanner.android.proxy.mission.item.markers.PolygonMarkerInfo;
910
import org.droidplanner.android.proxy.mission.item.markers.SurveyMarkerInfoProvider;
1011
import org.droidplanner.android.utils.prefs.AutoPanMode;
1112
import org.droidplanner.core.helpers.coordinates.Coord2D;
@@ -70,10 +71,12 @@ public void onMarkerDragEnd(MarkerInfo markerInfo) {
7071
}
7172

7273
private void checkForWaypointMarker(MarkerInfo markerInfo) {
73-
if (!(markerInfo instanceof SurveyMarkerInfoProvider)
74-
&& (markerInfo instanceof MissionItemMarkerInfo)) {
74+
if ((markerInfo instanceof MissionItemMarkerInfo)) {
7575
missionProxy.move(((MissionItemMarkerInfo) markerInfo).getMarkerOrigin(),
7676
markerInfo.getPosition());
77+
}else if ((markerInfo instanceof PolygonMarkerInfo)) {
78+
PolygonMarkerInfo marker = (PolygonMarkerInfo) markerInfo;
79+
missionProxy.movePolygonPoint(marker.getSurvey(), marker.getIndex(), markerInfo.getPosition());
7780
}
7881
}
7982

Android/src/org/droidplanner/android/maps/DPMap.java

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,9 @@ public interface DPMap extends DroneInterfaces.OnDroneListener {
3232
public static final int DRONE_LEASH_DEFAULT_COLOR = Color.WHITE;
3333
public static final int DRONE_LEASH_DEFAULT_WIDTH = 2;
3434

35+
public static final int POLYGONS_PATH_DEFAULT_COLOR = Color.RED;
36+
public static final int POLYGONS_PATH_DEFAULT_WIDTH = 4;
37+
3538
public static final String PREF_LAT = "pref_map_lat";
3639
public static final float DEFAULT_LATITUDE = 37.8575523f;
3740

@@ -343,6 +346,12 @@ interface OnMarkerDragListener {
343346
* source to use to draw the mission path
344347
*/
345348
public void updateMissionPath(PathSource pathSource);
349+
350+
/**
351+
* Updates the polygons on the map.
352+
*
353+
*/
354+
public void updatePolygonsPaths(List<List<Coord2D>> paths);
346355

347356
/**
348357
* Zoom to fit coordinates on map

Android/src/org/droidplanner/android/maps/MarkerInfo.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -163,4 +163,5 @@ public boolean isVisible() {
163163
}
164164
}
165165

166+
166167
}

Android/src/org/droidplanner/android/maps/providers/google_map/GoogleMapFragment.java

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,8 @@
5454
import com.google.android.gms.maps.model.LatLngBounds;
5555
import com.google.android.gms.maps.model.Marker;
5656
import com.google.android.gms.maps.model.MarkerOptions;
57+
import com.google.android.gms.maps.model.Polygon;
58+
import com.google.android.gms.maps.model.PolygonOptions;
5759
import com.google.android.gms.maps.model.Polyline;
5860
import com.google.android.gms.maps.model.PolylineOptions;
5961
import com.google.android.gms.maps.model.TileOverlay;
@@ -110,6 +112,8 @@ public class GoogleMapFragment extends SupportMapFragment implements DPMap, Loca
110112
protected boolean useMarkerClickAsMapClick = false;
111113
private boolean isMapLayoutFinished = false;
112114

115+
private List<Polygon> polygonsPaths = new ArrayList<Polygon>();
116+
113117
@Override
114118
public View onCreateView(LayoutInflater inflater, ViewGroup viewGroup,
115119
Bundle bundle) {
@@ -516,6 +520,27 @@ public void updateMissionPath(PathSource pathSource) {
516520

517521
missionPath.setPoints(pathPoints);
518522
}
523+
524+
525+
@Override
526+
public void updatePolygonsPaths(List<List<Coord2D>> paths){
527+
for (Polygon poly : polygonsPaths) {
528+
poly.remove();
529+
}
530+
531+
for (List<Coord2D> contour : paths) {
532+
PolygonOptions pathOptions = new PolygonOptions();
533+
pathOptions.strokeColor(POLYGONS_PATH_DEFAULT_COLOR).strokeWidth(
534+
POLYGONS_PATH_DEFAULT_WIDTH);
535+
final List<LatLng> pathPoints = new ArrayList<LatLng>(contour.size());
536+
for (Coord2D coord : contour) {
537+
pathPoints.add(DroneHelper.CoordToLatLang(coord));
538+
}
539+
pathOptions.addAll(pathPoints);
540+
polygonsPaths.add(getMap().addPolygon(pathOptions));
541+
}
542+
543+
}
519544

520545
/**
521546
* Save the map camera state on a preference file

Android/src/org/droidplanner/android/maps/providers/mapbox/MapBoxFragment.java

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -603,4 +603,10 @@ public void skipMarkerClickEvents(boolean skip) {
603603
// TODO Auto-generated method stub
604604

605605
}
606+
607+
@Override
608+
public void updatePolygonsPaths(List<List<Coord2D>> paths) {
609+
// TODO Auto-generated method stub
610+
611+
}
606612
}

0 commit comments

Comments
 (0)