Skip to content

Commit

Permalink
Merge branch 'master' into beta
Browse files Browse the repository at this point in the history
  • Loading branch information
arthurbenemann committed Nov 6, 2014
2 parents c6c6c54 + 458a776 commit 8d65045
Show file tree
Hide file tree
Showing 23 changed files with 429 additions and 88 deletions.
2 changes: 1 addition & 1 deletion Android/AndroidManifest.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
xmlns:tools="http://schemas.android.com/tools"
package="org.droidplanner"
android:versionCode="108"
android:versionCode="109"
android:versionName="please run version.sh to get the version name">

<uses-sdk
Expand Down
72 changes: 0 additions & 72 deletions Android/res/layout/fragment_editor_detail_cond_yaw.xml

This file was deleted.

108 changes: 108 additions & 0 deletions Android/res/layout/fragment_editor_detail_condition_yaw.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
<?xml version="1.0" encoding="utf-8"?>
<RelativeLayout xmlns:android="http://schemas.android.com/apk/res/android"
xmlns:tools="http://schemas.android.com/tools"
style="@style/missionItemDetailLayout" >

<org.droidplanner.android.widgets.spinners.SpinnerSelfSelect
android:id="@+id/spinnerWaypointType"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_alignParentTop="true"
android:layout_margin="5dp"
android:entries="@array/ExampleWaypointType" />

<RelativeLayout
android:id="@+id/title_rect"
android:layout_width="match_parent"
android:layout_height="64dp"
android:layout_alignParentTop="true"
android:background="@drawable/wp_title_rectangle" >

<TextView
android:id="@+id/WaypointIndex"
style="@style/largeMissionDetailText"
android:layout_width="64dp"
android:layout_height="wrap_content"
android:layout_centerVertical="true"
tools:text="22" />

<View
android:id="@+id/title_div"
android:layout_width="1dp"
android:layout_height="54dp"
android:layout_alignParentTop="true"
android:layout_marginTop="5dp"
android:layout_toRightOf="@id/WaypointIndex"
android:background="@drawable/wp_title_div" />

<RelativeLayout
android:id="@+id/title_content"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_centerVertical="true"
android:layout_toRightOf="@id/title_div"
android:orientation="vertical" >

<TextView
android:id="@+id/WaypointType"
style="@style/missionHeaderTitle"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_marginLeft="12dp"
android:text="@string/waypointType_Condition_Yaw" />

<TextView
android:id="@+id/DistanceLabel"
style="@style/missionHeaderlabel"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_alignLeft="@id/WaypointType"
android:layout_below="@id/WaypointType" />
</RelativeLayout>
</RelativeLayout>

<ImageView
android:id="@+id/menuHint"
android:layout_width="wrap_content"
android:layout_height="wrap_content"
android:layout_alignBottom="@id/title_rect"
android:layout_alignParentRight="true"
android:layout_margin="10dp"
android:src="@drawable/ic_menu_hint"
tools:ignore="ContentDescription" />

<LinearLayout
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_below="@id/title_rect"
android:orientation="vertical"
android:paddingBottom="5dp" >

<TextView
style="@style/ModeDetailText"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:background="@drawable/mode_desc_rectangle"
android:padding="12dp"
android:text="@string/waypointInfo_CondYaw" />

<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
android:id="@+id/picker1"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:orientation="vertical"
android:text="@string/mission_control_condition_yaw_angle" >

</org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView>

<CheckBox
android:id="@+id/checkBox1"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="@string/mission_control_condition_yaw_relative" />

</LinearLayout>

</RelativeLayout>
3 changes: 3 additions & 0 deletions Android/res/values/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,7 @@
<string name="waypointType_RTL">Return To Launch</string>
<string name="waypointType_Land">Land</string>
<string name="waypointType_Change_Speed">Change Speed</string>
<string name="waypointType_Condition_Yaw">Set Yaw</string>
<string name="waypointType_Camera_Trigger">Camera Trigger</string>
<string name="waypointType_Set_Servo">Set Servo</string>
<string name="waypointType_EPM">EPM</string>
Expand Down Expand Up @@ -367,6 +368,8 @@
<string name="mission_control_follow">Follow</string>
<string name="mission_control_dronie">Dronie</string>
<string name="mission_control_change_speed">Change Speed</string>
<string name="mission_control_condition_yaw_angle">Target angle</string>
<string name="mission_control_condition_yaw_relative">Relative Angle</string>
<string name="telemetry_label">Telemetry</string>
<string name="flight_modes_label">Flight modes</string>
<string name="menu_info_bar">Info Bar</string>
Expand Down
2 changes: 2 additions & 0 deletions Android/src/org/droidplanner/android/fragments/DroneMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,8 @@ public void run() {
}

mMapFragment.updateMissionPath(missionProxy);

mMapFragment.updatePolygonsPaths(missionProxy.getPolygonsPath());

mHandler.removeCallbacks(this);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import org.droidplanner.android.maps.DPMap;
import org.droidplanner.android.maps.MarkerInfo;
import org.droidplanner.android.proxy.mission.item.markers.MissionItemMarkerInfo;
import org.droidplanner.android.proxy.mission.item.markers.PolygonMarkerInfo;
import org.droidplanner.android.proxy.mission.item.markers.SurveyMarkerInfoProvider;
import org.droidplanner.android.utils.prefs.AutoPanMode;
import org.droidplanner.core.helpers.coordinates.Coord2D;
Expand Down Expand Up @@ -70,10 +71,12 @@ public void onMarkerDragEnd(MarkerInfo markerInfo) {
}

private void checkForWaypointMarker(MarkerInfo markerInfo) {
if (!(markerInfo instanceof SurveyMarkerInfoProvider)
&& (markerInfo instanceof MissionItemMarkerInfo)) {
if ((markerInfo instanceof MissionItemMarkerInfo)) {
missionProxy.move(((MissionItemMarkerInfo) markerInfo).getMarkerOrigin(),
markerInfo.getPosition());
}else if ((markerInfo instanceof PolygonMarkerInfo)) {
PolygonMarkerInfo marker = (PolygonMarkerInfo) markerInfo;
missionProxy.movePolygonPoint(marker.getSurvey(), marker.getIndex(), markerInfo.getPosition());
}
}

Expand Down
9 changes: 9 additions & 0 deletions Android/src/org/droidplanner/android/maps/DPMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@ public interface DPMap extends DroneInterfaces.OnDroneListener {
public static final int DRONE_LEASH_DEFAULT_COLOR = Color.WHITE;
public static final int DRONE_LEASH_DEFAULT_WIDTH = 2;

public static final int POLYGONS_PATH_DEFAULT_COLOR = Color.RED;
public static final int POLYGONS_PATH_DEFAULT_WIDTH = 4;

public static final String PREF_LAT = "pref_map_lat";
public static final float DEFAULT_LATITUDE = 37.8575523f;

Expand Down Expand Up @@ -343,6 +346,12 @@ interface OnMarkerDragListener {
* source to use to draw the mission path
*/
public void updateMissionPath(PathSource pathSource);

/**
* Updates the polygons on the map.
*
*/
public void updatePolygonsPaths(List<List<Coord2D>> paths);

/**
* Zoom to fit coordinates on map
Expand Down
1 change: 1 addition & 0 deletions Android/src/org/droidplanner/android/maps/MarkerInfo.java
Original file line number Diff line number Diff line change
Expand Up @@ -163,4 +163,5 @@ public boolean isVisible() {
}
}


}
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@
import com.google.android.gms.maps.model.LatLngBounds;
import com.google.android.gms.maps.model.Marker;
import com.google.android.gms.maps.model.MarkerOptions;
import com.google.android.gms.maps.model.Polygon;
import com.google.android.gms.maps.model.PolygonOptions;
import com.google.android.gms.maps.model.Polyline;
import com.google.android.gms.maps.model.PolylineOptions;
import com.google.android.gms.maps.model.TileOverlay;
Expand Down Expand Up @@ -110,6 +112,8 @@ public class GoogleMapFragment extends SupportMapFragment implements DPMap, Loca
protected boolean useMarkerClickAsMapClick = false;
private boolean isMapLayoutFinished = false;

private List<Polygon> polygonsPaths = new ArrayList<Polygon>();

@Override
public View onCreateView(LayoutInflater inflater, ViewGroup viewGroup,
Bundle bundle) {
Expand Down Expand Up @@ -516,6 +520,27 @@ public void updateMissionPath(PathSource pathSource) {

missionPath.setPoints(pathPoints);
}


@Override
public void updatePolygonsPaths(List<List<Coord2D>> paths){
for (Polygon poly : polygonsPaths) {
poly.remove();
}

for (List<Coord2D> contour : paths) {
PolygonOptions pathOptions = new PolygonOptions();
pathOptions.strokeColor(POLYGONS_PATH_DEFAULT_COLOR).strokeWidth(
POLYGONS_PATH_DEFAULT_WIDTH);
final List<LatLng> pathPoints = new ArrayList<LatLng>(contour.size());
for (Coord2D coord : contour) {
pathPoints.add(DroneHelper.CoordToLatLang(coord));
}
pathOptions.addAll(pathPoints);
polygonsPaths.add(getMap().addPolygon(pathOptions));
}

}

/**
* Save the map camera state on a preference file
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -603,4 +603,10 @@ public void skipMarkerClickEvents(boolean skip) {
// TODO Auto-generated method stub

}

@Override
public void updatePolygonsPaths(List<List<Coord2D>> paths) {
// TODO Auto-generated method stub

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -510,6 +510,16 @@ public void move(MissionItemProxy item, Coord2D position) {
mMission.notifyMissionUpdate();
}

public void movePolygonPoint(Survey survey, int index, Coord2D position) {
survey.polygon.movePoint(position, index);
try {
survey.build();
} catch (Exception e) {
e.printStackTrace();
}
mMission.notifyMissionUpdate();
}

public List<Coord2D> getVisibleCoords() {
final List<Coord2D> coords = new ArrayList<Coord2D>();

Expand Down Expand Up @@ -599,4 +609,14 @@ public float makeAndUploadDronie() {
refresh();
return (float) bearing;
}

public List<List<Coord2D>> getPolygonsPath() {
ArrayList<List<Coord2D>> polygonPaths = new ArrayList<List<Coord2D>>();
for (MissionItem item : mMission.getItems()) {
if (item instanceof Survey) {
polygonPaths.add(((Survey)item).polygon.getPoints());
}
}
return polygonPaths;
}
}
Loading

0 comments on commit 8d65045

Please sign in to comment.