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

Circle simplify #1171

Merged
merged 2 commits into from
Oct 14, 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
33 changes: 2 additions & 31 deletions Android/res/layout/fragment_editor_detail_circle.xml
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@
android:layout_height="wrap_content"
android:layout_below="@id/title_rect">

<LinearLayout
<LinearLayout
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:orientation="vertical"
Expand Down Expand Up @@ -122,37 +122,8 @@
android:id="@+id/loiterTurnPicker"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="@string/Orbits"
android:text="@string/circle_turns"
style="@style/missionItemDetailCard"/>

<CheckBox
android:id="@+id/checkBoxAdvanced"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_marginLeft="8dp"
android:fontFamily="sans-serif-light"
android:textSize="20sp"
android:padding="5dp"
android:text="@string/label_advaned" />

<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
android:id="@+id/numberStepsPicker"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="@string/label_steps_count"
android:visibility="gone"
tools:visibility="visible"
style="@style/missionItemDetailCard"/>

<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
android:id="@+id/altitudeStepPicker"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:text="@string/label_altitude_step"
android:visibility="gone"
tools:visibility="visible"
style="@style/missionItemDetailCard"/>

</LinearLayout>
</ScrollView>

Expand Down
2 changes: 1 addition & 1 deletion Android/res/values-de/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@
<string name="waypoint_coordsrc">Quelldaten:</string>
<string name="waypoint_jumpto">Springe zu Wegpunkt:</string>
<string name="waypoint_repeat">Wegpunkt wiederholen</string>
<string name="Orbits">Umlaufbahnen</string>
<string name="circle_turns">Umlaufbahnen</string>

<!-- Selection of map style -->
<string name="menu_map_type">Kartentyp</string>
Expand Down
2 changes: 1 addition & 1 deletion Android/res/values-it/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -189,7 +189,7 @@
<string name="waypoint_coordsrc">Fonte dati:</string>
<string name="waypoint_jumpto">Vai a Waypoint:</string>
<string name="waypoint_repeat">Ripetere Waypoint</string>
<string name="Orbits">Orbite</string>
<string name="circle_turns">Orbite</string>
<string name="dlg_clear_mission_title">Elimina missione</string>
<string name="dlg_clear_mission_confirm">Eliminare tutti i waypoints dalla mappa?</string>

Expand Down
2 changes: 1 addition & 1 deletion Android/res/values-zh-rCN/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@
<string name="waypoint_coordsrc">源数据</string>
<string name="waypoint_jumpto">跳至航点:</string>
<string name="waypoint_repeat">重复航点</string>
<string name="Orbits">轨道</string>
<string name="circle_turns">轨道</string>

<string name="dlg_clear_mission_title">清除任务</string>
<string name="dlg_clear_mission_confirm">从地图上清除所有航点?</string>
Expand Down
2 changes: 1 addition & 1 deletion Android/res/values-zh-rTW/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@
<string name="waypoint_coordsrc">來源數據:</string>
<string name="waypoint_jumpto">跳至航點:</string>
<string name="waypoint_repeat">重覆航點</string>
<string name="Orbits">軌跡</string>
<string name="circle_turns">軌跡</string>

<string name="dlg_clear_mission_title">清除任務</string>
<string name="dlg_clear_mission_confirm">是否從清除地圖上的所有航點?</string>
Expand Down
2 changes: 1 addition & 1 deletion Android/res/values/strings.xml
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@
<string name="waypoint_coordsrc">Source data:</string>
<string name="waypoint_jumpto">Jump to waypoint:</string>
<string name="waypoint_repeat">Repeat waypoint</string>
<string name="Orbits">Orbits</string>
<string name="circle_turns">Number of turns</string>

<string name="dlg_clear_mission_title">Clear Mission</string>
<string name="dlg_clear_mission_confirm">Clear all waypoints from the map?</string>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
package org.droidplanner.android.proxy.mission.item.fragments;

import java.util.List;

import org.droidplanner.R;
import org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView;
import org.droidplanner.android.widgets.spinnerWheel.adapters.NumericWheelAdapter;
Expand All @@ -10,24 +12,12 @@
import android.content.Context;
import android.os.Bundle;
import android.view.View;
import android.widget.CheckBox;
import android.widget.CompoundButton;

import java.util.List;

public class MissionCircleFragment extends MissionDetailFragment implements
CardWheelHorizontalView.OnCardWheelChangedListener, CompoundButton.OnCheckedChangeListener {

private static final String EXTRA_IS_ADVANCED_ON = "is_advanced_on";
private static final boolean DEFAULT_IS_ADVANCED_ON = false;

private CheckBox checkBoxAdvanced;
CardWheelHorizontalView.OnCardWheelChangedListener{

private List<Circle> mItemsList;

private CardWheelHorizontalView mNumberStepsPicker;
private CardWheelHorizontalView mAltitudeStepPicker;

@Override
protected int getResource() {
return R.layout.fragment_editor_detail_circle;
Expand All @@ -45,29 +35,6 @@ public void onViewCreated(View view, Bundle savedInstanceState) {
//Use the first one as reference.
final Circle firstItem = mItemsList.get(0);

boolean isAdvanced = DEFAULT_IS_ADVANCED_ON;
if (savedInstanceState != null) {
isAdvanced = savedInstanceState
.getBoolean(EXTRA_IS_ADVANCED_ON, DEFAULT_IS_ADVANCED_ON);
}
checkBoxAdvanced = (CheckBox) view.findViewById(R.id.checkBoxAdvanced);
checkBoxAdvanced.setOnCheckedChangeListener(this);
checkBoxAdvanced.setChecked(isAdvanced);

final NumericWheelAdapter altitudeStepAdapter = new NumericWheelAdapter(context,
R.layout.wheel_text_centered, 1, 10, "%d m");
mAltitudeStepPicker = (CardWheelHorizontalView) view.findViewById(R.id.altitudeStepPicker);
mAltitudeStepPicker.setViewAdapter(altitudeStepAdapter);
mAltitudeStepPicker.addChangingListener(this);
mAltitudeStepPicker.setCurrentValue((int) firstItem.getAltitudeStep());

final NumericWheelAdapter numberStepsAdapter = new NumericWheelAdapter(context,
R.layout.wheel_text_centered, 1, 10, "%d");
mNumberStepsPicker = (CardWheelHorizontalView) view.findViewById(R.id.numberStepsPicker);
mNumberStepsPicker.setViewAdapter(numberStepsAdapter);
mNumberStepsPicker.addChangingListener(this);
mNumberStepsPicker.setCurrentValue(firstItem.getNumberOfSteps());

final NumericWheelAdapter altitudeAdapter = new NumericWheelAdapter(context, MIN_ALTITUDE,
MAX_ALTITUDE, "%d m");
altitudeAdapter.setItemResource(R.layout.wheel_text_centered);
Expand Down Expand Up @@ -96,35 +63,6 @@ public void onViewCreated(View view, Bundle savedInstanceState) {
loiterRadiusPicker.setCurrentValue((int) firstItem.getRadius());
}

@Override
public void onSaveInstanceState(Bundle outState) {
super.onSaveInstanceState(outState);
outState.putBoolean(EXTRA_IS_ADVANCED_ON,
checkBoxAdvanced != null && checkBoxAdvanced.isChecked());
}

@Override
public void onCheckedChanged(CompoundButton buttonView, boolean isChecked) {
if (buttonView == checkBoxAdvanced) {
int visibility;
if (isChecked) {
visibility = View.VISIBLE;
for(Circle item: mItemsList) {
item.setNumberOfSteps(mNumberStepsPicker.getCurrentValue());
item.setAltitudeStep(mAltitudeStepPicker.getCurrentValue());
}
} else {
visibility = View.GONE;
for(Circle item: mItemsList) {
item.setNumberOfSteps(1);
}
}

mAltitudeStepPicker.setVisibility(visibility);
mNumberStepsPicker.setVisibility(visibility);
}
}

@Override
public void onChanged(CardWheelHorizontalView cardWheel, int oldValue, int newValue) {
switch (cardWheel.getId()) {
Expand All @@ -146,22 +84,6 @@ public void onChanged(CardWheelHorizontalView cardWheel, int oldValue, int newVa
item.setTurns(newValue);
}
break;

case R.id.numberStepsPicker:
if (checkBoxAdvanced.isChecked()) {
for(Circle item: mItemsList) {
item.setNumberOfSteps(newValue);
}
}
break;

case R.id.altitudeStepPicker:
if (checkBoxAdvanced.isChecked()) {
for(Circle item: mItemsList) {
item.setAltitudeStep(newValue);
}
}
break;
}
}
}
41 changes: 3 additions & 38 deletions Core/src/org/droidplanner/core/mission/waypoints/Circle.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
import java.util.List;

import org.droidplanner.core.helpers.coordinates.Coord3D;
import org.droidplanner.core.helpers.units.Length;
import org.droidplanner.core.mission.Mission;
import org.droidplanner.core.mission.MissionItem;
import org.droidplanner.core.mission.MissionItemType;
Expand All @@ -17,8 +16,6 @@ public class Circle extends SpatialCoordItem {

private double radius = 10.0;
private int turns = 1;
private int numberOfSteps = 1;
private double altitudeStep = 2;

public Circle(MissionItem item) {
super(item);
Expand Down Expand Up @@ -49,46 +46,14 @@ public double getRadius() {
return radius;
}

public double getAltitudeStep() {
return altitudeStep;
}

public void setAltitudeStep(double altitudeStep) {
this.altitudeStep = altitudeStep;
}

public int getNumberOfSteps() {
return numberOfSteps;
}

public void setNumberOfSteps(int numberOfSteps) {
this.numberOfSteps = numberOfSteps;
}

public void setMultiCircle(int number, double stepHeight) {
this.numberOfSteps = number;
this.altitudeStep = stepHeight;
}

public void setSingleCircle() {
numberOfSteps = 1;
}

@Override
public List<msg_mission_item> packMissionItem() {

List<msg_mission_item> list = new ArrayList<msg_mission_item>();

for (int i = 0; i < getNumberOfSteps(); i++) {
Length extraHeight = new Length(getAltitudeStep() * i);
packSingleCircle(list, extraHeight);
}

System.out.println(list.toString());
packSingleCircle(list);
return list;
}

private void packSingleCircle(List<msg_mission_item> list, Length extraHeight) {
private void packSingleCircle(List<msg_mission_item> list) {
msg_mission_item mavMsg = new msg_mission_item();
list.add(mavMsg);
mavMsg.autocontinue = 1;
Expand All @@ -97,7 +62,7 @@ private void packSingleCircle(List<msg_mission_item> list, Length extraHeight) {
mavMsg.frame = MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
mavMsg.x = (float) coordinate.getLat();
mavMsg.y = (float) coordinate.getLng();
mavMsg.z = (float) (coordinate.getAltitude().valueInMeters() + extraHeight.valueInMeters());
mavMsg.z = (float) (coordinate.getAltitude().valueInMeters());
mavMsg.command = MAV_CMD.MAV_CMD_NAV_LOITER_TURNS;
mavMsg.param1 = Math.abs(turns);
mavMsg.param3 = (float) radius;
Expand Down