Skip to content

Commit 6f94de0

Browse files
committed
Added ability to modify the GUIDED SCAN follow mode roi altitude.
1 parent 217b46b commit 6f94de0

File tree

5 files changed

+105
-46
lines changed

5 files changed

+105
-46
lines changed

Android/res/layout/fragment_mode_follow.xml

+9
Original file line numberDiff line numberDiff line change
@@ -35,4 +35,13 @@
3535
style="@style/missionItemDetailCard"
3636
android:text="@string/radius_label"/>
3737

38+
<org.droidplanner.android.widgets.spinnerWheel.CardWheelHorizontalView
39+
android:id="@+id/roi_height_spinner"
40+
android:orientation="horizontal"
41+
android:layout_width="match_parent"
42+
android:layout_height="wrap_content"
43+
android:visibility="gone"
44+
style="@style/missionItemDetailCard"
45+
android:text="@string/roi_height_label"/>
46+
3847
</LinearLayout>

Android/res/values/strings.xml

+1
Original file line numberDiff line numberDiff line change
@@ -337,6 +337,7 @@
337337
<string name="telemetry_default_value">0.0</string>
338338
<string name="climb_rate_label">Climb Rate</string>
339339
<string name="altitude_label">Altitude</string>
340+
<string name="roi_height_label">ROI Height</string>
340341
<string name="meter_unit">m</string>
341342
<string name="speed_unit">m/s</string>
342343
<string name="speed_label">Speed</string>

Android/src/org/droidplanner/android/fragments/mode/ModeFollowFragment.java

+80-42
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
import com.o3dr.android.client.Drone;
1919
import com.o3dr.android.client.apis.gcs.FollowApi;
2020
import com.o3dr.services.android.lib.coordinate.LatLong;
21+
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
2122
import com.o3dr.services.android.lib.drone.attribute.AttributeEvent;
2223
import com.o3dr.services.android.lib.drone.attribute.AttributeType;
2324
import com.o3dr.services.android.lib.gcs.follow.FollowState;
@@ -34,6 +35,8 @@
3435

3536
public class ModeFollowFragment extends ModeGuidedFragment implements OnItemSelectedListener, DroneMap.MapMarkerProvider {
3637

38+
private static final double DEFAULT_MIN_RADIUS = 2; //meters
39+
3740
private static final int ROI_TARGET_MARKER_INDEX = 0;
3841

3942
private static final IntentFilter eventFilter = new IntentFilter(AttributeEvent.FOLLOW_UPDATE);
@@ -51,17 +54,21 @@ public void onReceive(Context context, Intent intent) {
5154
}
5255
};
5356

57+
private final GuidedScanROIMarkerInfo roiMarkerInfo = new GuidedScanROIMarkerInfo();
58+
59+
private final MarkerInfo[] emptyMarkers = {};
5460
private final MarkerInfo[] markers = new MarkerInfo[1];
5561

5662
{
57-
markers[ROI_TARGET_MARKER_INDEX] = new GuidedScanROIMarkerInfo();
63+
markers[ROI_TARGET_MARKER_INDEX] = roiMarkerInfo;
5864
}
5965

6066
private TextView modeDescription;
6167
private Spinner spinner;
6268
private ArrayAdapter<FollowType> adapter;
6369

6470
private CardWheelHorizontalView<LengthUnit> mRadiusWheel;
71+
private CardWheelHorizontalView<LengthUnit> roiHeightWheel;
6572

6673
@Override
6774
public View onCreateView(LayoutInflater inflater, ViewGroup container, Bundle savedInstanceState) {
@@ -72,17 +79,25 @@ public View onCreateView(LayoutInflater inflater, ViewGroup container, Bundle sa
7279
public void onViewCreated(View parentView, Bundle savedInstanceState) {
7380
super.onViewCreated(parentView, savedInstanceState);
7481

82+
modeDescription = (TextView) parentView.findViewById(R.id.ModeDetail);
83+
7584
final Context context = getContext();
7685
final LengthUnitProvider lengthUP = getLengthUnitProvider();
86+
7787
final LengthWheelAdapter radiusAdapter = new LengthWheelAdapter(context, R.layout.wheel_text_centered,
7888
lengthUP.boxBaseValueToTarget(2), lengthUP.boxBaseValueToTarget(200));
7989

80-
modeDescription = (TextView) parentView.findViewById(R.id.ModeDetail);
81-
8290
mRadiusWheel = (CardWheelHorizontalView<LengthUnit>) parentView.findViewById(R.id.radius_spinner);
8391
mRadiusWheel.setViewAdapter(radiusAdapter);
8492
mRadiusWheel.addScrollListener(this);
8593

94+
final LengthWheelAdapter roiHeightAdapter = new LengthWheelAdapter(context, R.layout.wheel_text_centered,
95+
lengthUP.boxBaseValueToTarget(0), lengthUP.boxBaseValueToTarget(200));
96+
97+
roiHeightWheel = (CardWheelHorizontalView<LengthUnit>) parentView.findViewById(R.id.roi_height_spinner);
98+
roiHeightWheel.setViewAdapter(roiHeightAdapter);
99+
roiHeightWheel.addScrollListener(this);
100+
86101
spinner = (Spinner) parentView.findViewById(R.id.follow_type_spinner);
87102
adapter = new FollowTypesAdapter(context, getAppPrefs().isAdvancedMenuEnabled());
88103
spinner.setAdapter(adapter);
@@ -103,7 +118,7 @@ public void onApiConnected() {
103118
super.onApiConnected();
104119

105120
final FollowState followState = getDrone().getAttribute(AttributeType.FOLLOW_STATE);
106-
if(followState != null){
121+
if (followState != null) {
107122
final FollowType followType = followState.getMode();
108123
spinner.setSelection(adapter.getPosition(followType));
109124
onFollowTypeUpdate(followType, followState.getParams());
@@ -113,29 +128,41 @@ public void onApiConnected() {
113128
getBroadcastManager().registerReceiver(eventReceiver, eventFilter);
114129
}
115130

116-
private void onFollowTypeUpdate(FollowType followType, Bundle params){
131+
private void onFollowTypeUpdate(FollowType followType, Bundle params) {
117132
updateModeDescription(followType);
118133

119134
if (followType.hasParam(FollowType.EXTRA_FOLLOW_RADIUS)) {
120-
showRadiusPicker();
121-
updateCurrentRadius();
135+
double radius = DEFAULT_MIN_RADIUS;
136+
if (params != null) {
137+
radius = params.getDouble(FollowType.EXTRA_FOLLOW_RADIUS, DEFAULT_MIN_RADIUS);
138+
}
139+
140+
mRadiusWheel.setVisibility(View.VISIBLE);
141+
mRadiusWheel.setCurrentValue((getLengthUnitProvider().boxBaseValueToTarget(radius)));
122142
} else {
123-
hideRadiusPicker();
143+
mRadiusWheel.setVisibility(View.GONE);
124144
}
125145

126-
if(!followType.hasParam(FollowType.EXTRA_FOLLOW_ROI_TARGET))
127-
markers[ROI_TARGET_MARKER_INDEX].setPosition(null);
128-
else if(params != null){
129-
params.setClassLoader(LatLong.class.getClassLoader());
130-
LatLong roiTarget = params.getParcelable(FollowType.EXTRA_FOLLOW_ROI_TARGET);
131-
if(roiTarget != null){
132-
updateROITargetMarker(roiTarget);
146+
double roiHeight = GuidedScanROIMarkerInfo.DEFAULT_FOLLOW_ROI_ALTITUDE;
147+
LatLong roiTarget = null;
148+
if (followType.hasParam(FollowType.EXTRA_FOLLOW_ROI_TARGET)) {
149+
roiTarget = roiMarkerInfo.getPosition();
150+
151+
if (params != null) {
152+
params.setClassLoader(LatLong.class.getClassLoader());
153+
roiTarget = params.getParcelable(FollowType.EXTRA_FOLLOW_ROI_TARGET);
133154
}
155+
156+
if (roiTarget instanceof LatLongAlt)
157+
roiHeight = ((LatLongAlt) roiTarget).getAltitude();
134158
}
159+
160+
roiHeightWheel.setCurrentValue(getLengthUnitProvider().boxBaseValueToTarget(roiHeight));
161+
updateROITargetMarker(roiTarget);
135162
}
136163

137-
private void updateModeDescription(FollowType followType){
138-
switch(followType){
164+
private void updateModeDescription(FollowType followType) {
165+
switch (followType) {
139166
case GUIDED_SCAN:
140167
modeDescription.setText(R.string.mode_follow_guided_scan);
141168
break;
@@ -155,32 +182,32 @@ public void onApiDisconnected() {
155182

156183
@Override
157184
public void onScrollingEnded(CardWheelHorizontalView cardWheel, LengthUnit oldValue, LengthUnit newValue) {
185+
final Drone drone = getDrone();
158186
switch (cardWheel.getId()) {
159187
case R.id.radius_spinner:
160-
final Drone drone = getDrone();
161188
if (drone.isConnected()) {
162189
Bundle params = new Bundle();
163190
params.putDouble(FollowType.EXTRA_FOLLOW_RADIUS, newValue.toBase().getValue());
164191
FollowApi.updateFollowParams(drone, params);
165192
}
166193
break;
167194

195+
case R.id.roi_height_spinner:
196+
if (drone.isConnected()) {
197+
final LatLongAlt roiCoord = roiMarkerInfo.getPosition();
198+
if (roiCoord != null) {
199+
roiCoord.setAltitude(newValue.toBase().getValue());
200+
pushROITargetToVehicle(drone, roiCoord);
201+
}
202+
}
203+
break;
204+
168205
default:
169206
super.onScrollingEnded(cardWheel, oldValue, newValue);
170207
break;
171208
}
172209
}
173210

174-
private void updateCurrentRadius() {
175-
final Drone drone = getDrone();
176-
if (mRadiusWheel != null && drone.isConnected()) {
177-
final FollowState followState = getDrone().getAttribute(AttributeType.FOLLOW_STATE);
178-
Bundle params = followState.getParams();
179-
double radius = params.getDouble(FollowType.EXTRA_FOLLOW_RADIUS, 2);
180-
mRadiusWheel.setCurrentValue((getLengthUnitProvider().boxBaseValueToTarget(radius)));
181-
}
182-
}
183-
184211
@Override
185212
public void onItemSelected(AdapterView<?> parent, View view, int position, long id) {
186213
final FollowType type = adapter.getItem(position);
@@ -193,14 +220,6 @@ public void onItemSelected(AdapterView<?> parent, View view, int position, long
193220
onFollowTypeUpdate(type, null);
194221
}
195222

196-
private void hideRadiusPicker() {
197-
mRadiusWheel.setVisibility(View.GONE);
198-
}
199-
200-
private void showRadiusPicker() {
201-
mRadiusWheel.setVisibility(View.VISIBLE);
202-
}
203-
204223
@Override
205224
public void onNothingSelected(AdapterView<?> arg0) {
206225
}
@@ -212,23 +231,42 @@ public void onGuidedClick(LatLong coord) {
212231
if (followState != null && followState.isEnabled() && followState.getMode().hasParam(FollowType.EXTRA_FOLLOW_ROI_TARGET)) {
213232
Toast.makeText(getContext(), R.string.guided_scan_roi_set_message, Toast.LENGTH_LONG).show();
214233

215-
Bundle params = new Bundle();
216-
params.putParcelable(FollowType.EXTRA_FOLLOW_ROI_TARGET, coord);
217-
FollowApi.updateFollowParams(drone, params);
234+
final double roiHeight = roiHeightWheel.getCurrentValue().toBase().getValue();
235+
final LatLongAlt roiCoord = new LatLongAlt(coord.getLatitude(), coord.getLongitude(), roiHeight);
236+
237+
pushROITargetToVehicle(drone, roiCoord);
218238
updateROITargetMarker(coord);
219239
} else {
220240
super.onGuidedClick(coord);
221241
}
222242
}
223243

224-
private void updateROITargetMarker(LatLong target){
225-
markers[ROI_TARGET_MARKER_INDEX].setPosition(target);
244+
private void pushROITargetToVehicle(Drone drone, LatLongAlt roiCoord) {
245+
if (roiCoord == null)
246+
return;
247+
248+
Bundle params = new Bundle();
249+
params.putParcelable(FollowType.EXTRA_FOLLOW_ROI_TARGET, roiCoord);
250+
FollowApi.updateFollowParams(drone, params);
251+
}
252+
253+
private void updateROITargetMarker(LatLong target) {
254+
roiMarkerInfo.setPosition(target);
226255
getBroadcastManager().sendBroadcast(new Intent(DroneMap.ACTION_UPDATE_MAP));
256+
257+
if (target == null) {
258+
roiHeightWheel.setVisibility(View.GONE);
259+
} else {
260+
roiHeightWheel.setVisibility(View.VISIBLE);
261+
}
227262
}
228263

229264
@Override
230265
public MarkerInfo[] getMapMarkers() {
231-
return markers;
266+
if (roiMarkerInfo.isVisible())
267+
return markers;
268+
else
269+
return emptyMarkers;
232270
}
233271

234272
private static class FollowTypesAdapter extends ArrayAdapter<FollowType> {

Android/src/org/droidplanner/android/graphic/map/GuidedScanROIMarkerInfo.java

+15-3
Original file line numberDiff line numberDiff line change
@@ -5,24 +5,36 @@
55
import android.graphics.BitmapFactory;
66

77
import com.o3dr.services.android.lib.coordinate.LatLong;
8+
import com.o3dr.services.android.lib.coordinate.LatLongAlt;
89

910
import org.droidplanner.android.R;
11+
import org.droidplanner.android.fragments.mode.ModeFollowFragment;
1012
import org.droidplanner.android.maps.MarkerInfo;
1113

1214
/**
1315
* Created by Fredia Huya-Kouadio on 1/27/15.
1416
*/
1517
public class GuidedScanROIMarkerInfo extends MarkerInfo.SimpleMarkerInfo {
1618

17-
private LatLong roiCoord;
19+
public static final double DEFAULT_FOLLOW_ROI_ALTITUDE = 10; //meters
20+
private LatLongAlt roiCoord;
1821

1922
@Override
2023
public void setPosition(LatLong coord){
21-
this.roiCoord = coord;
24+
if(coord == null || coord instanceof LatLongAlt){
25+
roiCoord = (LatLongAlt) coord;
26+
}
27+
else {
28+
double defaultHeight = DEFAULT_FOLLOW_ROI_ALTITUDE;
29+
if(roiCoord != null)
30+
defaultHeight = roiCoord.getAltitude();
31+
32+
this.roiCoord = new LatLongAlt(coord.getLatitude(), coord.getLongitude(), defaultHeight);
33+
}
2234
}
2335

2436
@Override
25-
public LatLong getPosition(){
37+
public LatLongAlt getPosition(){
2638
return roiCoord;
2739
}
2840

Android/src/org/droidplanner/android/utils/prefs/DroidPlannerPrefs.java

-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,6 @@ public class DroidPlannerPrefs {
3737
private static final boolean DEFAULT_OFFLINE_MAP_ENABLED = false;
3838
private static final String DEFAULT_MAP_TYPE = "";
3939
private static final AutoPanMode DEFAULT_AUTO_PAN_MODE = AutoPanMode.DISABLED;
40-
private static final boolean DEFAULT_GUIDED_MODE_ON_LONG_PRESS = true;
4140
public static final boolean DEFAULT_PREF_UI_LANGUAGE = false;
4241
public static final String DEFAULT_SPEECH_PERIOD = "0";
4342
public static final boolean DEFAULT_TTS_CEILING_EXCEEDED = true;

0 commit comments

Comments
 (0)