Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Dronie update #1203

Merged
merged 6 commits into from
Oct 24, 2014
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions Android/res/values/preferences_keys.xml
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ This file is used to store the preferences keys so that it's accessible and modi
<string name="pref_warn_on_arm_key">pref_warn_on_arm</string>
<string name="pref_auto_insert_mission_takeoff_rtl_land_key">pref_auto_insert_mission_takeoff_rtl_land</string>
<string name="pref_warn_on_takeoff_in_auto_key">pref_warn_on_takeoff_in_auto</string>
<string name="pref_warn_on_dronie_creation_key">pref_warn_on_dronie_creation</string>

<string name="pref_enable_tts_key">pref_enable_tts</string>
<string name="pref_tts_periodic_key">tts_periodic</string>
Expand Down
5 changes: 4 additions & 1 deletion Android/res/values/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -498,7 +498,7 @@
<!-- Drone locator strings -->
<string name="locator">Locator</string>
<string name="open_tlog_file">Open Log File</string>
<string name="status_waiting_for_gps">Waiting for GPS...</string>
<string name="status_waiting_for_gps">Waiting for GPS</string>

<!-- Preference dialogs -->
<string name="pref_misc_title">Miscellaneous</string>
Expand All @@ -512,5 +512,8 @@
<string name="pref_dialog_selection_reset_desc"><![CDATA[Reset selection through: Settings -> User Interface -> Preference Dialogs]]></string>
<string name="dialog_confirm_take_off_in_auto_title">Take off in Auto?</string>
<string name="dialog_confirm_take_off_in_auto_msg">Warning! The drone will now take off and start the mission.</string>
<string name="pref_dronie_creation_title">Create dronie?</string>
<string name="pref_dronie_creation_message">Please stand back 8m before starting the
dronie.</string>

</resources>
8 changes: 8 additions & 0 deletions Android/res/xml/preferences.xml
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,14 @@
android:defaultValue="@string/pref_dialog_entry_ask"
android:entryValues="@array/preference_dialog_entry"/>

<ListPreference
android:key="@string/pref_warn_on_dronie_creation_key"
android:title="@string/pref_dronie_creation_title"
android:entries="@array/preference_dialog_entry"
android:entryValues="@array/preference_dialog_entry"
android:defaultValue="@string/pref_dialog_entry_ask"
/>

</PreferenceScreen>
</PreferenceCategory>
</PreferenceScreen>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,9 +119,7 @@ public void onDrawerOpened() {
resetMapBearing.setOnClickListener(new View.OnClickListener() {
@Override
public void onClick(View v) {
if(mapFragment != null) {
mapFragment.updateMapBearing(0);
}
updateMapBearing(0);
}
});

Expand Down Expand Up @@ -237,6 +235,11 @@ private void updateMapLocationButtons(AutoPanMode mode) {
}
}

public void updateMapBearing(float bearing){
if(mapFragment != null)
mapFragment.updateMapBearing(bearing);
}

/**
* Ensures that the device has the correct version of the Google Play
* Services.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package org.droidplanner.android.fragments;

import android.app.Activity;
import android.graphics.Color;
import android.os.Bundle;
import android.support.v4.app.Fragment;
Expand All @@ -14,9 +15,11 @@

import org.droidplanner.R;
import org.droidplanner.android.DroidPlannerApp;
import org.droidplanner.android.activities.FlightActivity;
import org.droidplanner.android.activities.helpers.SuperUI;
import org.droidplanner.android.dialogs.YesNoDialog;
import org.droidplanner.android.dialogs.YesNoWithPrefsDialog;
import org.droidplanner.android.proxy.mission.MissionProxy;
import org.droidplanner.android.utils.analytics.GAUtils;
import org.droidplanner.core.MAVLink.MavLinkArm;
import org.droidplanner.core.drone.DroneInterfaces;
Expand All @@ -35,7 +38,7 @@ public class CopterFlightActionsFragment extends Fragment implements View.OnClic
private static final double TAKEOFF_ALTITUDE = 10.0;

private Drone drone;

private MissionProxy missionProxy;
private Follow followMe;

private View mDisconnectedButtons;
Expand All @@ -49,13 +52,23 @@ public class CopterFlightActionsFragment extends Fragment implements View.OnClic
private Button pauseBtn;
private Button autoBtn;

@Override
public void onAttach(Activity activity){
super.onAttach(activity);
if(!(activity instanceof FlightActivity)){
throw new IllegalStateException("Parent activity must be an instance of " +
FlightActivity.class.getName());
}
}

@Override
public View onCreateView(LayoutInflater inflater, ViewGroup container, Bundle savedInstanceState) {
View view = inflater.inflate(R.layout.fragment_copter_mission_control, container, false);

DroidPlannerApp droidPlannerApp = (DroidPlannerApp) getActivity().getApplication();
drone = droidPlannerApp.getDrone();
followMe = droidPlannerApp.getFollowMe();
missionProxy = droidPlannerApp.getMissionProxy();
return view;
}

Expand Down Expand Up @@ -208,7 +221,7 @@ public void onClick(View v) {
break;

case R.id.mc_dronieBtn:
drone.getMission().makeAndUploadDronie();
getDronieConfirmation();
eventBuilder.setAction(ACTION_FLIGHT_ACTION_BUTTON).setLabel("Dronie uploaded");
break;

Expand All @@ -223,6 +236,31 @@ public void onClick(View v) {

}

private void getDronieConfirmation() {
YesNoWithPrefsDialog ynd = YesNoWithPrefsDialog.newInstance(getActivity()
.getApplicationContext(), getString(R.string.pref_dronie_creation_title),
getString(R.string.pref_dronie_creation_message), new YesNoDialog.Listener() {
@Override
public void onYes() {
final float bearing = missionProxy.makeAndUploadDronie();
if(bearing >= 0){
final FlightActivity flightActivity = (FlightActivity) getActivity();
if(flightActivity != null){
flightActivity.updateMapBearing(bearing);
}
}
}

@Override
public void onNo() {
}
}, getString(R.string.pref_warn_on_dronie_creation_key));

if(ynd != null){
ynd.show(getChildFragmentManager(), "Confirm dronie creation");
}
}

private void getTakeOffInAutoConfirmation() {
YesNoWithPrefsDialog ynd = YesNoWithPrefsDialog.newInstance(getActivity()
.getApplicationContext(), getString(R.string.dialog_confirm_take_off_in_auto_title),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
import org.droidplanner.core.mission.waypoints.SpatialCoordItem;
import org.droidplanner.core.mission.waypoints.SplineWaypoint;
import org.droidplanner.core.mission.waypoints.Waypoint;
import org.droidplanner.core.model.Drone;
import org.droidplanner.core.util.Pair;

/**
Expand Down Expand Up @@ -223,16 +224,6 @@ public void addTakeoff() {
mMission.addMissionItem(takeoff);
}

public void addDronie(Coord2D start, Coord2D end) {
clear();

List<MissionItem> dronieItems = Mission.createDronie(mMission,start, end);

addMissionItems(dronieItems);
}



public void addTakeOffAndRTL(){
if(!mMission.isFirstItemTakeoff()){
final Takeoff takeOff = new Takeoff(mMission, new Altitude(Takeoff.DEFAULT_TAKEOFF_ALTITUDE));
Expand Down Expand Up @@ -569,4 +560,10 @@ public Length getMissionLength() {
return new Length(0);
}
}

public float makeAndUploadDronie() {
final double bearing = mMission.makeAndUploadDronie();
refresh();
return (float) bearing;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public void onViewCreated(View view, Bundle savedInstanceState) {

final NumericWheelAdapter adapter = new NumericWheelAdapter(getActivity()
.getApplicationContext(), R.layout.wheel_text_centered, 1,
20, "%d m");
20, "%d m/s");
final CardWheelHorizontalView cardAltitudePicker = (CardWheelHorizontalView) view
.findViewById(R.id.picker1);
cardAltitudePicker.setViewAdapter(adapter);
Expand Down
115 changes: 69 additions & 46 deletions Core/src/org/droidplanner/core/mission/Mission.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package org.droidplanner.core.mission;

import java.util.ArrayList;
import java.util.Collections;
import java.util.List;
import com.MAVLink.Messages.ardupilotmega.msg_mission_ack;
import com.MAVLink.Messages.ardupilotmega.msg_mission_item;
import com.MAVLink.Messages.enums.MAV_CMD;

import org.droidplanner.core.drone.DroneInterfaces.DroneEventsType;
import org.droidplanner.core.drone.DroneVariable;
Expand All @@ -11,6 +11,7 @@
import org.droidplanner.core.helpers.geoTools.GeoTools;
import org.droidplanner.core.helpers.units.Altitude;
import org.droidplanner.core.helpers.units.Length;
import org.droidplanner.core.helpers.units.Speed;
import org.droidplanner.core.mission.commands.ChangeSpeed;
import org.droidplanner.core.mission.commands.ReturnToHome;
import org.droidplanner.core.mission.commands.Takeoff;
Expand All @@ -23,9 +24,9 @@
import org.droidplanner.core.model.Drone;
import org.droidplanner.core.util.Pair;

import com.MAVLink.Messages.ardupilotmega.msg_mission_ack;
import com.MAVLink.Messages.ardupilotmega.msg_mission_item;
import com.MAVLink.Messages.enums.MAV_CMD;
import java.util.ArrayList;
import java.util.Collections;
import java.util.List;

/**
* This implements a mavlink mission. A mavlink mission is a set of
Expand Down Expand Up @@ -105,10 +106,10 @@ public void addMissionItem(MissionItem missionItem) {
notifyMissionUpdate();
}

public void addMissionItem(int index, MissionItem missionItem){
items.add(index, missionItem);
notifyMissionUpdate();
}
public void addMissionItem(int index, MissionItem missionItem) {
items.add(index, missionItem);
notifyMissionUpdate();
}

/**
* Signals that this mission object was updated. //TODO: maybe move outside
Expand Down Expand Up @@ -142,39 +143,39 @@ public Altitude getLastAltitude() {
*/
public void replace(MissionItem oldItem, MissionItem newItem) {
final int index = items.indexOf(oldItem);
if(index == -1){
return;
}
if (index == -1) {
return;
}

items.remove(index);
items.add(index, newItem);
notifyMissionUpdate();
}

public void replaceAll(List<Pair<MissionItem, MissionItem>> updatesList){
if(updatesList == null || updatesList.isEmpty()){
return;
}
public void replaceAll(List<Pair<MissionItem, MissionItem>> updatesList) {
if (updatesList == null || updatesList.isEmpty()) {
return;
}

boolean wasUpdated = false;
for(Pair<MissionItem, MissionItem> updatePair : updatesList){
final MissionItem oldItem = updatePair.first;
final int index = items.indexOf(oldItem);
if(index == -1){
continue;
}
boolean wasUpdated = false;
for (Pair<MissionItem, MissionItem> updatePair : updatesList) {
final MissionItem oldItem = updatePair.first;
final int index = items.indexOf(oldItem);
if (index == -1) {
continue;
}

final MissionItem newItem = updatePair.second;
items.remove(index);
items.add(index, newItem);
final MissionItem newItem = updatePair.second;
items.remove(index);
items.add(index, newItem);

wasUpdated = true;
}
wasUpdated = true;
}

if(wasUpdated) {
notifyMissionUpdate();
}
}
if (wasUpdated) {
notifyMissionUpdate();
}
}

/**
* Reverse the order of the mission items.
Expand Down Expand Up @@ -302,28 +303,50 @@ public List<msg_mission_item> getMsgMissionItems() {
return data;
}

public void makeAndUploadDronie() {
/**
* Create and upload a dronie mission to the drone
*
* @return the bearing in degrees the drone trajectory will take.
*/
public double makeAndUploadDronie() {
Coord2D currentPosition = myDrone.getGps().getPosition();
if(currentPosition == null || myDrone.getGps().getSatCount()<=5){
if (currentPosition == null || myDrone.getGps().getSatCount() <= 5) {
myDrone.notifyDroneEvent(DroneEventsType.WARNING_NO_GPS);
return;
return -1;
}

final double bearing = 180 + myDrone.getOrientation().getYaw();
items.clear();
items.addAll(createDronie(this, currentPosition, GeoTools.newCoordFromBearingAndDistance(
currentPosition, 180 + myDrone.getOrientation().getYaw(), 50.0)));
items.addAll(createDronie(currentPosition,
GeoTools.newCoordFromBearingAndDistance(currentPosition, bearing, 50.0)));
sendMissionToAPM();
notifyMissionUpdate();

return bearing;
}

public static List<MissionItem> createDronie(Mission mMission,Coord2D start, Coord2D end) {
public List<MissionItem> createDronie(Coord2D start, Coord2D end) {
final int startAltitude = 4;

final int roiDistance = -8;
Coord2D slowDownPoint = GeoTools.pointAlongTheLine(start, end, 5);

Speed defaultSpeed = myDrone.getSpeed().getSpeedParameter();
if (defaultSpeed == null) {
defaultSpeed = new Speed(5);
}

List<MissionItem> dronieItems = new ArrayList<MissionItem>();
dronieItems.add(new Takeoff(mMission, new Altitude(startAltitude)));
dronieItems.add(new RegionOfInterest(mMission,new Coord3D(GeoTools.pointAlongTheLine(start, end, -8), new Altitude(1.0))));
dronieItems.add(new Waypoint(mMission, new Coord3D(end, new Altitude(startAltitude+GeoTools.getDistance(start, end).valueInMeters()/2.0))));
dronieItems.add(new Waypoint(mMission, new Coord3D(start, new Altitude(startAltitude))));
dronieItems.add(new Land(mMission,start));
dronieItems.add(new Takeoff(this, new Altitude(startAltitude)));
dronieItems.add(new RegionOfInterest(this, new Coord3D(GeoTools.pointAlongTheLine(start,
end, roiDistance), new Altitude(1.0))));
dronieItems.add(new Waypoint(this, new Coord3D(end, new Altitude(startAltitude
+ GeoTools.getDistance(start, end).valueInMeters() / 2.0))));
dronieItems.add(new Waypoint(this, new Coord3D(slowDownPoint, new Altitude(startAltitude
+ GeoTools.getDistance(start, slowDownPoint).valueInMeters() / 2.0))));
dronieItems.add(new ChangeSpeed(this, new Speed(1.0)));
dronieItems.add(new Waypoint(this, new Coord3D(start, new Altitude(startAltitude))));
dronieItems.add(new ChangeSpeed(this, defaultSpeed));
dronieItems.add(new Land(this, start));
return dronieItems;
}

Expand All @@ -341,7 +364,7 @@ public boolean isFirstItemTakeoff() {
}

public boolean isLastItemLandOrRTL() {
MissionItem last = items.get(items.size()-1);
MissionItem last = items.get(items.size() - 1);
return (last instanceof ReturnToHome) || (last instanceof Land);
}
}