Skip to content

Commit

Permalink
Merge pull request #1792 from DroidPlanner/misc_bug_fixes
Browse files Browse the repository at this point in the history
Misc bug fixes
  • Loading branch information
m4gr3d authored Aug 20, 2016
2 parents 76c6d48 + a947a74 commit e006bdb
Show file tree
Hide file tree
Showing 15 changed files with 261 additions and 69 deletions.
16 changes: 16 additions & 0 deletions Android/res/layout/fragment_editor_detail_survey.xml
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,22 @@
</GridLayout>
</HorizontalScrollView>

<CheckBox
android:id="@+id/check_start_camera_before_first_waypoint"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:minHeight="48dp"
android:text="@string/start_camera_before_first_waypoint"/>

<CheckBox
android:id="@+id/check_lock_copter_yaw"
style="@style/missionItemDetailCard"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:minHeight="48dp"
android:text="@string/lock_copter_orientation"/>

<org.droidplanner.android.view.spinnerWheel.CardWheelHorizontalView
android:id="@+id/anglePicker"
style="@style/missionItemDetailCard"
Expand Down
5 changes: 5 additions & 0 deletions Android/res/menu/menu_flight_map.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
<?xml version="1.0" encoding="utf-8"?>
<menu xmlns:android="http://schemas.android.com/apk/res/android"
xmlns:app="http://schemas.android.com/apk/res-auto">

<item android:id="@+id/menu_export_flight_path_as_mission"
android:title="@string/menu_export_flight_path_as_mission"
app:showAsAction="never"/>

<item
android:id="@+id/menu_map_clear_flight_path"
android:title="@string/menu_clear_flight_path"
Expand Down
4 changes: 4 additions & 0 deletions Android/res/values/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -632,4 +632,8 @@
<string name="no_tlog_position_data">No tlog position data</string>
<string name="menu_clear_flight_path">Clear flight path</string>
<string name="menu_export_as_mission">Export as mission</string>
<string name="menu_export_flight_path_as_mission">Export flight path as mission</string>
<string name="error_empty_flight_path">Try flying a bit first :)</string>
<string name="start_camera_before_first_waypoint">Start camera before first waypoint</string>
<string name="lock_copter_orientation">Lock copter orientation</string>
</resources>
Original file line number Diff line number Diff line change
Expand Up @@ -350,10 +350,6 @@ private void openMissionFile() {
@Override
public void onFileSelected(String filepath) {
File missionFile = new File(filepath);
if(missionFile.equals(openedMissionFile)){
// Nothing to do.
return;
}
openedMissionFile = missionFile;
openMissionFile(Uri.fromFile(missionFile));
}
Expand Down
49 changes: 34 additions & 15 deletions Android/src/org/droidplanner/android/fragments/DroneMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,10 @@

import com.o3dr.android.client.Drone;
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
import com.o3dr.services.android.lib.drone.property.Altitude;
import com.o3dr.services.android.lib.drone.property.CameraProxy;
import com.o3dr.services.android.lib.drone.property.Gps;

Expand Down Expand Up @@ -86,10 +88,7 @@ public void onReceive(Context context, Intent intent) {
case AttributeEvent.GPS_POSITION: {
graphicDrone.updateMarker(DroneMap.this);
mMapFragment.updateDroneLeashPath(guided);
final Gps droneGps = drone.getAttribute(AttributeType.GPS);
if (droneGps != null && droneGps.isValid()) {
mMapFragment.addFlightPathPoint(droneGps.getPosition());
}
updateFlightPath();
break;
}

Expand Down Expand Up @@ -137,6 +136,8 @@ public void onReceive(Context context, Intent intent) {
}
};

protected final LinkedList<LatLongAlt> flightPathPoints = new LinkedList<>();

private final Map<MissionItemProxy, List<MarkerInfo>> missionMarkers = new HashMap<>();
private final LinkedList<MarkerInfo> externalMarkersToAdd = new LinkedList<>();
private final LinkedList<PolylineInfo> externalPolylinesToAdd = new LinkedList<>();
Expand Down Expand Up @@ -189,6 +190,18 @@ public void onApiConnected() {
onMissionUpdate();
}

private void updateFlightPath(){
if(showFlightPath()) {
final Gps droneGps = drone.getAttribute(AttributeType.GPS);
if (droneGps != null && droneGps.isValid()) {
Altitude droneAltitude = drone.getAttribute(AttributeType.ALTITUDE);
LatLongAlt flightPoint = new LatLongAlt(droneGps.getPosition(),
droneAltitude.getAltitude());
addFlightPathPoint(flightPoint);
}
}
}

protected final void onMissionUpdate(){
mMapFragment.updateMissionPath(missionProxy);

Expand Down Expand Up @@ -251,7 +264,7 @@ private void updateMapFragment(Bundle savedInstanceState) {
mMapFragment = (DPMap) fm.findFragmentById(R.id.map_fragment_container);
if (mMapFragment == null || mMapFragment.getProvider() != mapProvider) {
final Bundle mapArgs = new Bundle();
mapArgs.putInt(DPMap.EXTRA_MAX_FLIGHT_PATH_SIZE, getMaxFlightPathSize());
mapArgs.putBoolean(DPMap.EXTRA_SHOW_FLIGHT_PATH, showFlightPath());

mMapFragment = mapProvider.getMapFragment();
((Fragment) mMapFragment).setArguments(mapArgs);
Expand All @@ -275,22 +288,27 @@ private void updateMapFragment(Bundle savedInstanceState) {
}

if(savedInstanceState != null){
LatLong[] flightPathPoints = (LatLong[]) savedInstanceState.getParcelableArray(EXTRA_DRONE_FLIGHT_PATH);
if(flightPathPoints != null && flightPathPoints.length > 0){
for(LatLong point : flightPathPoints) {
mMapFragment.addFlightPathPoint(point);
flightPathPoints.clear();
LatLongAlt[] flightPoints = (LatLongAlt[]) savedInstanceState.getParcelableArray(EXTRA_DRONE_FLIGHT_PATH);
if(flightPoints != null && flightPoints.length > 0){
for(LatLongAlt point : flightPoints) {
addFlightPathPoint(point);
}
}
}
}

private void addFlightPathPoint(LatLongAlt point) {
mMapFragment.addFlightPathPoint(point);
flightPathPoints.add(point);
}

@Override
public void onSaveInstanceState(Bundle outState){
super.onSaveInstanceState(outState);
if(mMapFragment != null) {
List<LatLong> flightPath = mMapFragment.getFlightPath();
if(flightPath != null && !flightPath.isEmpty()){
outState.putParcelableArray(EXTRA_DRONE_FLIGHT_PATH, flightPath.toArray(new LatLong[flightPath.size()]));
if(!flightPathPoints.isEmpty()){
outState.putParcelableArray(EXTRA_DRONE_FLIGHT_PATH, flightPathPoints.toArray(new LatLongAlt[flightPathPoints.size()]));
}
}
}
Expand Down Expand Up @@ -320,14 +338,15 @@ public void onAttach(Activity activity) {
mAppPrefs = DroidPlannerPrefs.getInstance(context);
}

protected int getMaxFlightPathSize() {
return 0;
}
protected boolean showFlightPath(){
return false;
}

protected void clearFlightPath(){
if (mMapFragment != null) {
mMapFragment.clearFlightPath();
}
flightPathPoints.clear();
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,13 @@
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
import com.o3dr.services.android.lib.drone.mission.Mission;
import com.o3dr.services.android.lib.drone.property.Gps;
import com.o3dr.services.android.lib.drone.property.GuidedState;
import com.o3dr.services.android.lib.drone.property.State;

import org.droidplanner.android.R;
import org.droidplanner.android.activities.EditorActivity;
import org.droidplanner.android.dialogs.GuidedDialog;
import org.droidplanner.android.dialogs.GuidedDialog.GuidedDialogListener;
import org.droidplanner.android.graphic.map.GraphicHome;
Expand Down Expand Up @@ -103,8 +105,8 @@ public void onPause() {
}

@Override
protected int getMaxFlightPathSize() {
return 1000;
protected boolean showFlightPath(){
return true;
}

@Override
Expand Down Expand Up @@ -143,6 +145,18 @@ public boolean onOptionsItemSelected(MenuItem item) {
clearFlightPath();
return true;

case R.id.menu_export_flight_path_as_mission:
if (flightPathPoints.isEmpty()) {
Toast.makeText(getContext(), R.string.error_empty_flight_path, Toast.LENGTH_LONG).show();
return true;
}

Mission exportedMission = DroneHelper.exportPathAsMission(getContext(), flightPathPoints);
startActivity(new Intent(getActivity(), EditorActivity.class)
.setAction(EditorActivity.ACTION_VIEW_MISSION)
.putExtra(EditorActivity.EXTRA_MISSION, exportedMission));
return true;

default:
return super.onOptionsItemSelected(item);
}
Expand Down
9 changes: 4 additions & 5 deletions Android/src/org/droidplanner/android/maps/DPMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import android.os.Parcelable;

import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
import com.o3dr.services.android.lib.drone.property.FootPrint;

import org.droidplanner.android.maps.providers.DPMapProvider;
Expand All @@ -22,8 +23,8 @@ public interface DPMap {

String PACKAGE_NAME = DPMap.class.getPackage().getName();

String EXTRA_MAX_FLIGHT_PATH_SIZE = PACKAGE_NAME + ""
+ ".EXTRA_MAX_FLIGHT_PATH_SIZE";
String EXTRA_SHOW_FLIGHT_PATH = PACKAGE_NAME + ""
+ ".EXTRA_SHOW_FLIGHT_PATH";

int FLIGHT_PATH_DEFAULT_COLOR = 0xfffd693f;
int FLIGHT_PATH_DEFAULT_WIDTH = 6;
Expand Down Expand Up @@ -62,7 +63,7 @@ public interface DPMap {
* @param coord
* drone's coordinate
*/
void addFlightPathPoint(LatLong coord);
void addFlightPathPoint(LatLongAlt coord);

/**
* Draw the footprint of the camera in the ground
Expand Down Expand Up @@ -120,8 +121,6 @@ public interface DPMap {
*/
void downloadMapTiles(MapDownloader mapDownloader, DPMap.VisibleMapArea mapRegion, int minimumZ, int maximumZ);

List<LatLong> getFlightPath();

/**
* @return the map center coordinates.
*/
Expand Down
25 changes: 5 additions & 20 deletions Android/src/org/droidplanner/android/maps/GoogleMapFragment.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@
import com.google.android.gms.maps.model.VisibleRegion;
import com.o3dr.android.client.Drone;
import com.o3dr.services.android.lib.coordinate.LatLong;
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
import com.o3dr.services.android.lib.drone.property.FootPrint;
Expand Down Expand Up @@ -253,7 +254,7 @@ protected void doRun() {
private Polyline flightPath;
private Polyline missionPath;
private Polyline mDroneLeashPath;
private int maxFlightPathSize;
private boolean showFlightPath;

/*
* DP Map listeners
Expand Down Expand Up @@ -330,7 +331,7 @@ public View onCreateView(LayoutInflater inflater, ViewGroup viewGroup, Bundle bu

final Bundle args = getArguments();
if (args != null) {
maxFlightPathSize = args.getInt(EXTRA_MAX_FLIGHT_PATH_SIZE);
showFlightPath = args.getBoolean(EXTRA_SHOW_FLIGHT_PATH);
}

return view;
Expand Down Expand Up @@ -452,13 +453,13 @@ public DPMapProvider getProvider() {
}

@Override
public void addFlightPathPoint(final LatLong coord) {
public void addFlightPathPoint(final LatLongAlt coord) {
final LatLng position = DroneHelper.coordToLatLng(coord);

getMapAsync(new OnMapReadyCallback() {
@Override
public void onMapReady(GoogleMap googleMap) {
if (maxFlightPathSize > 0) {
if (showFlightPath) {
if (flightPath == null) {
PolylineOptions flightPathOptions = new PolylineOptions();
flightPathOptions.color(FLIGHT_PATH_DEFAULT_COLOR)
Expand All @@ -467,29 +468,13 @@ public void onMapReady(GoogleMap googleMap) {
}

List<LatLng> oldFlightPath = flightPath.getPoints();
while (oldFlightPath.size() > maxFlightPathSize) {
oldFlightPath.remove(0);
}
oldFlightPath.add(position);
flightPath.setPoints(oldFlightPath);
}
}
});
}

@Override
public List<LatLong> getFlightPath(){
if(flightPath == null)
return null;

List<LatLng> flightPathPoints = flightPath.getPoints();
List<LatLong> flightPath = new ArrayList<>(flightPathPoints.size());
for(LatLng point : flightPathPoints){
flightPath.add(DroneHelper.latLngToCoord(point));
}
return flightPath;
}

@Override
public void clearMarkers() {
for(MarkerInfo markerInfo : markersMap.values()){
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,10 @@ public void addSurveyPolygon(List<LatLong> points, boolean spline) {
survey = new Survey();
}
survey.setPolygonPoints(points);

// Load the last survey preferences.
dpPrefs.loadSurveyPreferences(drone, survey);

addMissionItem(survey);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,14 @@ public void onApiConnected() {
final Context context = getContext();

typeSpinner.setSelection(commandAdapter.getPosition(MissionItemType.SPLINE_WAYPOINT));
SplineWaypoint item = (SplineWaypoint) getMissionItems().get(0);

final NumericWheelAdapter delayAdapter = new NumericWheelAdapter(context, R.layout.wheel_text_centered, 0,
60, "%d s");
CardWheelHorizontalView<Integer> delayPicker = (CardWheelHorizontalView<Integer>) view.findViewById(R.id
.waypointDelayPicker);
delayPicker.setViewAdapter(delayAdapter);
delayPicker.setCurrentValue((int) item.getDelay());
delayPicker.addScrollListener(this);

final LengthUnitProvider lengthUP = getLengthUnitProvider();
Expand All @@ -47,11 +49,8 @@ public void onApiConnected() {
CardWheelHorizontalView<LengthUnit> altitudePicker = (CardWheelHorizontalView<LengthUnit>) view.findViewById
(R.id.altitudePicker);
altitudePicker.setViewAdapter(altitudeAdapter);
altitudePicker.addScrollListener(this);

SplineWaypoint item = (SplineWaypoint) getMissionItems().get(0);
delayPicker.setCurrentValue((int) item.getDelay());
altitudePicker.setCurrentValue(lengthUP.boxBaseValueToTarget(item.getCoordinate().getAltitude()));
altitudePicker.addScrollListener(this);
}

@Override
Expand Down
Loading

0 comments on commit e006bdb

Please sign in to comment.