Skip to content

Commit

Permalink
Merge pull request #970 from arthurbenemann/circle_fix
Browse files Browse the repository at this point in the history
Circle Item fix
  • Loading branch information
arthurbenemann committed Aug 12, 2014
2 parents 64d3c6f + 8cefd92 commit 2d81187
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 13 deletions.
8 changes: 4 additions & 4 deletions Android/res/layout/fragment_editor_detail_circle.xml
Original file line number Diff line number Diff line change
Expand Up @@ -125,19 +125,19 @@
custom:min="0"
custom:title="@string/waypoint_altitude"
custom:unit="m" >

</org.droidplanner.android.widgets.SeekBarWithText.SeekBarWithText>

<org.droidplanner.android.widgets.SeekBarWithText.SeekBarWithText
android:id="@+id/loiterRadius"
android:layout_width="match_parent"
android:layout_height="wrap_content"
android:layout_margin="2dp"
custom:inc="0.1"
custom:max="20"
custom:inc="1"
custom:max="50"
custom:min="0"
custom:title="@string/loiter_radius"
custom:unit="m"
android:visibility="gone" >
custom:unit="m">
</org.droidplanner.android.widgets.SeekBarWithText.SeekBarWithText>

<FrameLayout
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.droidplanner.android.mission.item.fragments;
package org.droidplanner.android.proxy.mission.item.fragments;

import org.droidplanner.R;
import org.droidplanner.android.proxy.mission.item.fragments.MissionDetailFragment;
import org.droidplanner.android.widgets.SeekBarWithText.SeekBarWithText;
import org.droidplanner.core.mission.MissionItemType;
import org.droidplanner.core.mission.waypoints.Circle;
Expand All @@ -21,6 +20,7 @@ public class MissionCircleFragment extends MissionDetailFragment implements
private CheckBox checkBoxAdvanced;
private SeekBarWithText altitudeStepSeekBar;
private SeekBarWithText numberStepSeekBar;
private SeekBarWithText loiterRadiusSeekBar;

@Override
protected int getResource() {
Expand Down Expand Up @@ -57,9 +57,8 @@ public void onViewCreated(View view, Bundle savedInstanceState) {
loiterTurnSeekBar.setOnChangedListener(this);
loiterTurnSeekBar.setValue(item.getNumeberOfTurns());

SeekBarWithText loiterRadiusSeekBar = (SeekBarWithText) view
.findViewById(R.id.loiterRadius);
// loiterRadiusSeekBar.setAbsValue(item.getRadius());
loiterRadiusSeekBar = (SeekBarWithText) view.findViewById(R.id.loiterRadius);
loiterRadiusSeekBar.setAbsValue(item.getRadius());
loiterRadiusSeekBar.setOnChangedListener(this);
}

Expand All @@ -78,8 +77,7 @@ public void onSeekBarChanged() {

item.getCoordinate().getAltitude().set(altitudeSeekBar.getValue());
item.setTurns((int) loiterTurnSeekBar.getValue());
// item.setOrbitalRadius(loiterRadiusSeekBar.getValue());
// item.setYawAngle(yawSeekBar.getValue());
item.setRadius(loiterRadiusSeekBar.getValue());

if (checkBoxAdvanced.isChecked()) {
item.setMultiCircle((int) numberStepSeekBar.getValue(), altitudeStepSeekBar.getValue());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@

import org.droidplanner.R;
import org.droidplanner.android.DroidPlannerApp;
import org.droidplanner.android.mission.item.fragments.MissionCircleFragment;
import org.droidplanner.android.proxy.mission.MissionProxy;
import org.droidplanner.android.proxy.mission.item.MissionItemProxy;
import org.droidplanner.android.proxy.mission.item.adapters.AdapterMissionItems;
Expand Down
7 changes: 6 additions & 1 deletion Core/src/org/droidplanner/core/mission/waypoints/Circle.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,11 @@ public Circle(msg_mission_item msg, Mission mission) {
public void setTurns(int turns) {
this.turns = Math.abs(turns);
}


public void setRadius(double radius) {
this.radius = Math.abs(radius);
}

public int getNumeberOfTurns() {
return turns;
Expand Down Expand Up @@ -90,7 +95,7 @@ private void packSingleCircle(List<msg_mission_item> list, Length extraHeight) {
mavMsg.z = (float) (coordinate.getAltitude().valueInMeters() + extraHeight.valueInMeters());
mavMsg.command = MAV_CMD.MAV_CMD_NAV_LOITER_TURNS;
mavMsg.param1 = Math.abs(turns);
mavMsg.param3 = (turns > 0) ? 1 : -1;
mavMsg.param3 = (float) radius;
}

@Override
Expand Down

0 comments on commit 2d81187

Please sign in to comment.