18
18
import com .o3dr .android .client .Drone ;
19
19
import com .o3dr .android .client .apis .gcs .FollowApi ;
20
20
import com .o3dr .services .android .lib .coordinate .LatLong ;
21
+ import com .o3dr .services .android .lib .coordinate .LatLongAlt ;
21
22
import com .o3dr .services .android .lib .drone .attribute .AttributeEvent ;
22
23
import com .o3dr .services .android .lib .drone .attribute .AttributeType ;
23
24
import com .o3dr .services .android .lib .gcs .follow .FollowState ;
34
35
35
36
public class ModeFollowFragment extends ModeGuidedFragment implements OnItemSelectedListener , DroneMap .MapMarkerProvider {
36
37
38
+ private static final double DEFAULT_MIN_RADIUS = 2 ; //meters
39
+
37
40
private static final int ROI_TARGET_MARKER_INDEX = 0 ;
38
41
39
42
private static final IntentFilter eventFilter = new IntentFilter (AttributeEvent .FOLLOW_UPDATE );
@@ -51,17 +54,21 @@ public void onReceive(Context context, Intent intent) {
51
54
}
52
55
};
53
56
57
+ private final GuidedScanROIMarkerInfo roiMarkerInfo = new GuidedScanROIMarkerInfo ();
58
+
59
+ private final MarkerInfo [] emptyMarkers = {};
54
60
private final MarkerInfo [] markers = new MarkerInfo [1 ];
55
61
56
62
{
57
- markers [ROI_TARGET_MARKER_INDEX ] = new GuidedScanROIMarkerInfo () ;
63
+ markers [ROI_TARGET_MARKER_INDEX ] = roiMarkerInfo ;
58
64
}
59
65
60
66
private TextView modeDescription ;
61
67
private Spinner spinner ;
62
68
private ArrayAdapter <FollowType > adapter ;
63
69
64
70
private CardWheelHorizontalView <LengthUnit > mRadiusWheel ;
71
+ private CardWheelHorizontalView <LengthUnit > roiHeightWheel ;
65
72
66
73
@ Override
67
74
public View onCreateView (LayoutInflater inflater , ViewGroup container , Bundle savedInstanceState ) {
@@ -72,17 +79,25 @@ public View onCreateView(LayoutInflater inflater, ViewGroup container, Bundle sa
72
79
public void onViewCreated (View parentView , Bundle savedInstanceState ) {
73
80
super .onViewCreated (parentView , savedInstanceState );
74
81
82
+ modeDescription = (TextView ) parentView .findViewById (R .id .ModeDetail );
83
+
75
84
final Context context = getContext ();
76
85
final LengthUnitProvider lengthUP = getLengthUnitProvider ();
86
+
77
87
final LengthWheelAdapter radiusAdapter = new LengthWheelAdapter (context , R .layout .wheel_text_centered ,
78
88
lengthUP .boxBaseValueToTarget (2 ), lengthUP .boxBaseValueToTarget (200 ));
79
89
80
- modeDescription = (TextView ) parentView .findViewById (R .id .ModeDetail );
81
-
82
90
mRadiusWheel = (CardWheelHorizontalView <LengthUnit >) parentView .findViewById (R .id .radius_spinner );
83
91
mRadiusWheel .setViewAdapter (radiusAdapter );
84
92
mRadiusWheel .addScrollListener (this );
85
93
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
+
86
101
spinner = (Spinner ) parentView .findViewById (R .id .follow_type_spinner );
87
102
adapter = new FollowTypesAdapter (context , getAppPrefs ().isAdvancedMenuEnabled ());
88
103
spinner .setAdapter (adapter );
@@ -103,7 +118,7 @@ public void onApiConnected() {
103
118
super .onApiConnected ();
104
119
105
120
final FollowState followState = getDrone ().getAttribute (AttributeType .FOLLOW_STATE );
106
- if (followState != null ){
121
+ if (followState != null ) {
107
122
final FollowType followType = followState .getMode ();
108
123
spinner .setSelection (adapter .getPosition (followType ));
109
124
onFollowTypeUpdate (followType , followState .getParams ());
@@ -113,29 +128,41 @@ public void onApiConnected() {
113
128
getBroadcastManager ().registerReceiver (eventReceiver , eventFilter );
114
129
}
115
130
116
- private void onFollowTypeUpdate (FollowType followType , Bundle params ){
131
+ private void onFollowTypeUpdate (FollowType followType , Bundle params ) {
117
132
updateModeDescription (followType );
118
133
119
134
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 )));
122
142
} else {
123
- hideRadiusPicker ( );
143
+ mRadiusWheel . setVisibility ( View . GONE );
124
144
}
125
145
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 );
133
154
}
155
+
156
+ if (roiTarget instanceof LatLongAlt )
157
+ roiHeight = ((LatLongAlt ) roiTarget ).getAltitude ();
134
158
}
159
+
160
+ roiHeightWheel .setCurrentValue (getLengthUnitProvider ().boxBaseValueToTarget (roiHeight ));
161
+ updateROITargetMarker (roiTarget );
135
162
}
136
163
137
- private void updateModeDescription (FollowType followType ){
138
- switch (followType ){
164
+ private void updateModeDescription (FollowType followType ) {
165
+ switch (followType ) {
139
166
case GUIDED_SCAN :
140
167
modeDescription .setText (R .string .mode_follow_guided_scan );
141
168
break ;
@@ -155,32 +182,32 @@ public void onApiDisconnected() {
155
182
156
183
@ Override
157
184
public void onScrollingEnded (CardWheelHorizontalView cardWheel , LengthUnit oldValue , LengthUnit newValue ) {
185
+ final Drone drone = getDrone ();
158
186
switch (cardWheel .getId ()) {
159
187
case R .id .radius_spinner :
160
- final Drone drone = getDrone ();
161
188
if (drone .isConnected ()) {
162
189
Bundle params = new Bundle ();
163
190
params .putDouble (FollowType .EXTRA_FOLLOW_RADIUS , newValue .toBase ().getValue ());
164
191
FollowApi .updateFollowParams (drone , params );
165
192
}
166
193
break ;
167
194
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
+
168
205
default :
169
206
super .onScrollingEnded (cardWheel , oldValue , newValue );
170
207
break ;
171
208
}
172
209
}
173
210
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
-
184
211
@ Override
185
212
public void onItemSelected (AdapterView <?> parent , View view , int position , long id ) {
186
213
final FollowType type = adapter .getItem (position );
@@ -193,14 +220,6 @@ public void onItemSelected(AdapterView<?> parent, View view, int position, long
193
220
onFollowTypeUpdate (type , null );
194
221
}
195
222
196
- private void hideRadiusPicker () {
197
- mRadiusWheel .setVisibility (View .GONE );
198
- }
199
-
200
- private void showRadiusPicker () {
201
- mRadiusWheel .setVisibility (View .VISIBLE );
202
- }
203
-
204
223
@ Override
205
224
public void onNothingSelected (AdapterView <?> arg0 ) {
206
225
}
@@ -212,23 +231,42 @@ public void onGuidedClick(LatLong coord) {
212
231
if (followState != null && followState .isEnabled () && followState .getMode ().hasParam (FollowType .EXTRA_FOLLOW_ROI_TARGET )) {
213
232
Toast .makeText (getContext (), R .string .guided_scan_roi_set_message , Toast .LENGTH_LONG ).show ();
214
233
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 );
218
238
updateROITargetMarker (coord );
219
239
} else {
220
240
super .onGuidedClick (coord );
221
241
}
222
242
}
223
243
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 );
226
255
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
+ }
227
262
}
228
263
229
264
@ Override
230
265
public MarkerInfo [] getMapMarkers () {
231
- return markers ;
266
+ if (roiMarkerInfo .isVisible ())
267
+ return markers ;
268
+ else
269
+ return emptyMarkers ;
232
270
}
233
271
234
272
private static class FollowTypesAdapter extends ArrayAdapter <FollowType > {
0 commit comments