Skip to content

Commit 5d2f3e6

Browse files
Merge branch 'master' into beta
2 parents 8d65045 + 98e14a2 commit 5d2f3e6

File tree

31 files changed

+384
-64
lines changed

31 files changed

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

88
<uses-sdk

Android/res/values/preferences_keys.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ This file is used to store the preferences keys so that it's accessible and modi
3535
<string name="pref_permanent_notification_key">pref_permanent_notification</string>
3636
<string name="pref_ui_gps_hdop_key">pref_ui_gps_hdop</string>
3737
<string name="pref_ui_language_english_key">pref_ui_language_english</string>
38+
<string name="pref_ui_realtime_footprints_key">pref_ui_realtime_footprints_key</string>
3839
<string name="pref_dshare_username_key">dshare_username</string>
3940
<string name="pref_dshare_password_key">dshare_password</string>
4041
<string name="pref_dshare_enabled_key">dshare_enabled</string>

Android/res/values/strings.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -459,6 +459,8 @@
459459
<string name="pref_title_osm">Open Street Map Preferences</string>
460460
<string name="pref_title_mapbox">MapBox Preferences</string>
461461
<string name="activity_title_map_provider_preferences">Map Provider Preferences</string>
462+
<string name="pref_ui_realtime_footprints_title">Realtime camera footprint</string>
463+
<string name="pref_ui_realtime_footprints_summary">Display the camera projection on the ground in realtime</string>
462464

463465
<!-- Others (when possible move to a grouping above) -->
464466
<string name="tune_roll">Manual adjustment of roll and pitch tuning. Rate_P is the primary value to adjust.</string>

Android/res/xml/preferences.xml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,12 @@
4848
android:key="@string/pref_map_provider_settings_key"
4949
android:summary="@string/pref_map_provider_settings_summary"
5050
android:title="@string/pref_map_provider_settings_title" />
51+
52+
<CheckBoxPreference
53+
android:defaultValue="false"
54+
android:key="@string/pref_ui_realtime_footprints_key"
55+
android:summary="@string/pref_ui_realtime_footprints_summary"
56+
android:title="@string/pref_ui_realtime_footprints_title" />
5157
</PreferenceCategory>
5258
<PreferenceCategory android:title="@string/pref_title_notifications" >
5359
<CheckBoxPreference

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

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,14 +17,21 @@
1717
import org.droidplanner.core.drone.DroneInterfaces.DroneEventsType;
1818
import org.droidplanner.core.drone.DroneInterfaces.OnDroneListener;
1919
import org.droidplanner.core.helpers.coordinates.Coord2D;
20+
import org.droidplanner.core.helpers.units.Altitude;
2021
import org.droidplanner.core.model.Drone;
22+
import org.droidplanner.core.survey.CameraInfo;
23+
import org.droidplanner.core.survey.Footprint;
24+
25+
import com.MAVLink.Messages.ardupilotmega.msg_camera_feedback;
26+
import com.google.android.gms.internal.ln;
2127

2228
import android.app.Activity;
2329
import android.content.Context;
2430
import android.os.Bundle;
2531
import android.os.Handler;
2632
import android.support.v4.app.Fragment;
2733
import android.support.v4.app.FragmentManager;
34+
import android.util.Log;
2835
import android.view.LayoutInflater;
2936
import android.view.View;
3037
import android.view.ViewGroup;
@@ -94,6 +101,8 @@ public void run() {
94101

95102
protected Context context;
96103

104+
private CameraInfo camera = new CameraInfo();
105+
97106
protected abstract boolean isMissionDraggable();
98107

99108
@Override
@@ -181,6 +190,15 @@ public void onDroneEvent(DroneEventsType event, Drone drone) {
181190
}
182191
break;
183192

193+
case ATTITUDE:
194+
if (((DroidPlannerApp) getActivity().getApplication()).getPreferences()
195+
.isRealtimeFootprintsEnabled()) {
196+
if (drone.getGps().isPositionValid()) {
197+
mMapFragment.updateRealTimeFootprint(drone.getCamera().getCurrentFieldOfView());
198+
}
199+
200+
}
201+
break;
184202
case GUIDEDPOINT:
185203
mMapFragment.updateMarker(guided);
186204
mMapFragment.updateDroneLeashPath(guided);
@@ -195,6 +213,9 @@ public void onDroneEvent(DroneEventsType event, Drone drone) {
195213
case HEARTBEAT_TIMEOUT:
196214
mMapFragment.updateMarker(graphicDrone);
197215
break;
216+
case FOOTPRINT:
217+
mMapFragment.addCameraFootprint(drone.getCamera().getLastFootprint());
218+
break;
198219
default:
199220
break;
200221
}

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

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import org.droidplanner.core.drone.DroneInterfaces;
1010
import org.droidplanner.core.gcs.location.Location;
1111
import org.droidplanner.core.helpers.coordinates.Coord2D;
12+
import org.droidplanner.core.survey.Footprint;
1213

1314
import android.graphics.Color;
1415
import android.location.LocationListener;
@@ -35,6 +36,10 @@ public interface DPMap extends DroneInterfaces.OnDroneListener {
3536
public static final int POLYGONS_PATH_DEFAULT_COLOR = Color.RED;
3637
public static final int POLYGONS_PATH_DEFAULT_WIDTH = 4;
3738

39+
public static final int FOOTPRINT_DEFAULT_COLOR = 0;
40+
public static final int FOOTPRINT_DEFAULT_WIDTH = 2;
41+
public static final int FOOTPRINT_FILL_COLOR = Color.argb(80, 0, 0, 200);
42+
3843
public static final String PREF_LAT = "pref_map_lat";
3944
public static final float DEFAULT_LATITUDE = 37.8575523f;
4045

@@ -137,6 +142,12 @@ interface OnMarkerDragListener {
137142
*/
138143
public void addFlightPathPoint(Coord2D coord);
139144

145+
/**
146+
* Draw the footprint of the camera in the ground
147+
* @param footprintToBeDraw
148+
*/
149+
public void addCameraFootprint(Footprint footprintToBeDraw);
150+
140151
/**
141152
* Remove all markers from the map.
142153
*/
@@ -372,5 +383,7 @@ interface OnMarkerDragListener {
372383
* @param skip if it should skip further events
373384
*/
374385
public void skipMarkerClickEvents(boolean skip);
386+
387+
public void updateRealTimeFootprint(Footprint footprint);
375388

376389
}

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

Lines changed: 38 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
import org.droidplanner.android.utils.prefs.AutoPanMode;
2222
import org.droidplanner.android.utils.prefs.DroidPlannerPrefs;
2323
import org.droidplanner.core.model.Drone;
24+
import org.droidplanner.core.survey.Footprint;
2425
import org.droidplanner.core.drone.DroneInterfaces;
2526
import org.droidplanner.core.helpers.coordinates.Coord2D;
2627

@@ -79,6 +80,7 @@ public class GoogleMapFragment extends SupportMapFragment implements DPMap, Loca
7980

8081
private static final float GO_TO_MY_LOCATION_ZOOM = 19f;
8182

83+
8284
private final HashBiMap<MarkerInfo, Marker> mBiMarkersMap = new HashBiMap<MarkerInfo, Marker>();
8385

8486
private Drone mDrone;
@@ -114,6 +116,8 @@ public class GoogleMapFragment extends SupportMapFragment implements DPMap, Loca
114116

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

119+
private Polygon footprintPoly;
120+
117121
@Override
118122
public View onCreateView(LayoutInflater inflater, ViewGroup viewGroup,
119123
Bundle bundle) {
@@ -523,6 +527,26 @@ public void updateMissionPath(PathSource pathSource) {
523527

524528

525529
@Override
530+
public void updateRealTimeFootprint(Footprint footprint) {
531+
if (footprintPoly == null) {
532+
PolygonOptions pathOptions = new PolygonOptions();
533+
pathOptions.strokeColor(FOOTPRINT_DEFAULT_COLOR).strokeWidth(FOOTPRINT_DEFAULT_WIDTH);
534+
pathOptions.fillColor(FOOTPRINT_FILL_COLOR);
535+
536+
for (Coord2D vertex : footprint.getVertexInGlobalFrame()) {
537+
pathOptions.add(DroneHelper.CoordToLatLang(vertex));
538+
}
539+
footprintPoly = getMap().addPolygon(pathOptions);
540+
}else{
541+
List<LatLng> list = new ArrayList<LatLng>();
542+
for (Coord2D vertex : footprint.getVertexInGlobalFrame()) {
543+
list.add(DroneHelper.CoordToLatLang(vertex));
544+
}
545+
footprintPoly.setPoints(list);
546+
}
547+
}
548+
549+
@Override
526550
public void updatePolygonsPaths(List<List<Coord2D>> paths){
527551
for (Polygon poly : polygonsPaths) {
528552
poly.remove();
@@ -542,7 +566,20 @@ public void updatePolygonsPaths(List<List<Coord2D>> paths){
542566

543567
}
544568

545-
/**
569+
@Override
570+
public void addCameraFootprint(Footprint footprintToBeDraw) {
571+
PolygonOptions pathOptions = new PolygonOptions();
572+
pathOptions.strokeColor(FOOTPRINT_DEFAULT_COLOR).strokeWidth(FOOTPRINT_DEFAULT_WIDTH);
573+
pathOptions.fillColor(FOOTPRINT_FILL_COLOR);
574+
575+
for (Coord2D vertex : footprintToBeDraw.getVertexInGlobalFrame()) {
576+
pathOptions.add(DroneHelper.CoordToLatLang(vertex));
577+
}
578+
getMap().addPolygon(pathOptions);
579+
580+
}
581+
582+
/**
546583
* Save the map camera state on a preference file
547584
* http://stackoverflow.com/questions
548585
* /16697891/google-maps-android-api-v2-restoring

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

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
import org.droidplanner.core.drone.DroneInterfaces;
2020
import org.droidplanner.core.helpers.coordinates.Coord2D;
2121
import org.droidplanner.core.model.Drone;
22+
import org.droidplanner.core.survey.Footprint;
2223

2324
import android.app.Activity;
2425
import android.content.SharedPreferences;
@@ -609,4 +610,16 @@ public void updatePolygonsPaths(List<List<Coord2D>> paths) {
609610
// TODO Auto-generated method stub
610611

611612
}
613+
614+
@Override
615+
public void addCameraFootprint(Footprint footprintToBeDraw) {
616+
// TODO Auto-generated method stub
617+
618+
}
619+
620+
@Override
621+
public void updateRealTimeFootprint(Footprint footprint) {
622+
// TODO Auto-generated method stub
623+
624+
}
612625
}

Android/src/org/droidplanner/android/proxy/mission/item/adapters/CamerasAdapter.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
import org.droidplanner.R;
44
import org.droidplanner.android.utils.file.help.CameraInfoLoader;
5-
import org.droidplanner.core.mission.survey.CameraInfo;
5+
import org.droidplanner.core.survey.CameraInfo;
66

77
import android.content.Context;
88
import android.view.View;

Android/src/org/droidplanner/android/proxy/mission/item/fragments/MissionStructureScannerFragment.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,8 @@
1010
import org.droidplanner.android.widgets.spinners.SpinnerSelfSelect;
1111
import org.droidplanner.core.helpers.units.Altitude;
1212
import org.droidplanner.core.mission.MissionItemType;
13-
import org.droidplanner.core.mission.survey.CameraInfo;
1413
import org.droidplanner.core.mission.waypoints.StructureScanner;
14+
import org.droidplanner.core.survey.CameraInfo;
1515

1616
import android.content.Context;
1717
import android.os.Bundle;

0 commit comments

Comments
 (0)