-
Notifications
You must be signed in to change notification settings - Fork 582
/
WaypointMissionOperatorView.java
398 lines (361 loc) · 18.2 KB
/
WaypointMissionOperatorView.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
package com.dji.sdk.sample.demo.missionoperator;
import android.content.Context;
import android.util.Log;
import android.view.View;
import com.dji.sdk.sample.R;
import com.dji.sdk.sample.demo.missionmanager.MissionBaseView;
import com.dji.sdk.sample.internal.controller.DJISampleApplication;
import com.dji.sdk.sample.internal.utils.ToastUtils;
import java.util.ArrayList;
import java.util.List;
import androidx.annotation.NonNull;
import androidx.annotation.Nullable;
import dji.common.error.DJIError;
import dji.common.flightcontroller.FlightControllerState;
import dji.common.flightcontroller.simulator.InitializationData;
import dji.common.mission.waypoint.Waypoint;
import dji.common.mission.waypoint.WaypointAction;
import dji.common.mission.waypoint.WaypointActionType;
import dji.common.mission.waypoint.WaypointMission;
import dji.common.mission.waypoint.WaypointMissionDownloadEvent;
import dji.common.mission.waypoint.WaypointMissionExecutionEvent;
import dji.common.mission.waypoint.WaypointMissionFinishedAction;
import dji.common.mission.waypoint.WaypointMissionFlightPathMode;
import dji.common.mission.waypoint.WaypointMissionGotoWaypointMode;
import dji.common.mission.waypoint.WaypointMissionHeadingMode;
import dji.common.mission.waypoint.WaypointMissionState;
import dji.common.mission.waypoint.WaypointMissionUploadEvent;
import dji.common.mission.waypoint.WaypointTurnMode;
import dji.common.model.LocationCoordinate2D;
import dji.common.util.CommonCallbacks;
import dji.keysdk.FlightControllerKey;
import dji.keysdk.KeyManager;
import dji.sdk.base.BaseProduct;
import dji.sdk.flightcontroller.FlightController;
import dji.sdk.mission.MissionControl;
import dji.sdk.mission.waypoint.WaypointMissionOperator;
import dji.sdk.mission.waypoint.WaypointMissionOperatorListener;
import dji.sdk.products.Aircraft;
import static dji.keysdk.FlightControllerKey.HOME_LOCATION_LATITUDE;
import static dji.keysdk.FlightControllerKey.HOME_LOCATION_LONGITUDE;
public class WaypointMissionOperatorView extends MissionBaseView {
private static final double BASE_LATITUDE = 22;
private static final double BASE_LONGITUDE = 113;
private static final int REFRESH_FREQ = 10;
private static final int SATELLITE_COUNT = 10;
private static final int MAX_HEIGHT = 500;
private static final int MAX_RADIUS = 500;
private static final double ONE_METER_OFFSET = 0.00000899322;
private static final double HORIZONTAL_DISTANCE = 30;
private static final double VERTICAL_DISTANCE = 30;
private WaypointMissionOperator waypointMissionOperator = null;
private FlightController flightController = null;
private WaypointMission mission = null;
private WaypointMissionOperatorListener listener;
private static final int WAYPOINT_COUNT = 4;
public WaypointMissionOperatorView(Context context) {
super(context);
}
@Override
public void onClick(View view) {
waypointMissionOperator = getWaypointMissionOperator();
switch(view.getId()) {
case R.id.btn_simulator:
startSimulator();
break;
case R.id.btn_set_maximum_altitude:
if (null != getFlightController()) {
flightController.setMaxFlightHeight(MAX_HEIGHT, new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError == null ? "The maximum height is set to 500m!" : djiError.getDescription());
}
});
}
break;
case R.id.btn_set_maximum_radius:
if (null != getFlightController()) {
flightController.setMaxFlightRadius(MAX_RADIUS, new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError == null ? "The maximum radius is set to 500m!" : djiError.getDescription());
}
});
}
break;
case R.id.btn_load:
mission = createRectangleWaypointMission();
DJIError djiError = waypointMissionOperator.loadMission(mission);
if (djiError == null) {
ToastUtils.setResultToToast("Mission is loaded successfully");
} else {
ToastUtils.setResultToToast(djiError.getDescription());
}
break;
case R.id.btn_upload:
if (WaypointMissionState.READY_TO_RETRY_UPLOAD.equals(waypointMissionOperator.getCurrentState()) || WaypointMissionState.READY_TO_UPLOAD.equals(waypointMissionOperator.getCurrentState())) {
waypointMissionOperator.uploadMission(new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError != null ? "" : djiError.getDescription());
}
});
} else {
ToastUtils.setResultToToast("Wait for mission to be loaded");
}
break;
case R.id.btn_start:
if (null != mission) {
waypointMissionOperator.startMission(new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError != null ? "" : djiError.getDescription());
}
});
} else {
ToastUtils.setResultToToast("Wait for mission to be uploaded");
}
break;
case R.id.btn_stop:
waypointMissionOperator.stopMission(new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError != null ? "" : djiError.getDescription());
}
});
break;
case R.id.btn_pause:
waypointMissionOperator.pauseMission(new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError == null ? "The mission has been paused" : djiError.getDescription());
}
});
break;
case R.id.btn_resume:
waypointMissionOperator.resumeMission(new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError == null ? "The mission has been resumed" : djiError.getDescription());
}
});
break;
case R.id.btn_download:
if (WaypointMissionState.EXECUTING.equals(waypointMissionOperator.getCurrentState()) || WaypointMissionState.EXECUTION_PAUSED.equals(waypointMissionOperator.getCurrentState())) {
waypointMissionOperator.downloadMission(new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError != null ? "" : djiError.getDescription());
}
});
} else {
ToastUtils.setResultToToast("Mission can be downloaded when the mission state is EXECUTING or EXECUTION_PAUSED!");
}
break;
default:
break;
}
}
@Override
protected void onAttachedToWindow() {
super.onAttachedToWindow();
BaseProduct product = DJISampleApplication.getProductInstance();
if (product == null || !product.isConnected()) {
ToastUtils.setResultToToast("Disconnect");
return;
} else {
if (product instanceof Aircraft) {
flightController = ((Aircraft) product).getFlightController();
}
if (flightController != null) {
flightController.setStateCallback(new FlightControllerState.Callback() {
@Override
public void onUpdate(@NonNull FlightControllerState flightControllerState) {
homeLatitude = flightControllerState.getHomeLocation().getLatitude();
homeLongitude = flightControllerState.getHomeLocation().getLongitude();
flightState = flightControllerState.getFlightMode();
updateWaypointMissionState();
}
});
}
}
waypointMissionOperator = MissionControl.getInstance().getWaypointMissionOperator();
setUpListener();
}
@Override
protected void onDetachedFromWindow() {
tearDownListener();
if (flightController != null) {
flightController.getSimulator().stop(null);
flightController.setStateCallback(null);
}
super.onDetachedFromWindow();
}
/**
* Pre-define a square, co-ordination (0,0),(0,30),(30,30),(30,0). So the drone heading needs to turn 45 degrees every turn.
*/
private WaypointMission createRectangleWaypointMission() {
WaypointMission.Builder builder = new WaypointMission.Builder();
double baseLatitude = 22;
double baseLongitude = 113;
Object latitudeValue = KeyManager.getInstance().getValue((FlightControllerKey.create(HOME_LOCATION_LATITUDE)));
Object longitudeValue = KeyManager.getInstance().getValue((FlightControllerKey.create(HOME_LOCATION_LONGITUDE)));
if (latitudeValue != null && latitudeValue instanceof Double) {
baseLatitude = (double) latitudeValue;
}
if (longitudeValue != null && longitudeValue instanceof Double) {
baseLongitude = (double) longitudeValue;
}
final float baseAltitude = 30.0f;
builder.autoFlightSpeed(5f);
builder.maxFlightSpeed(10f);
builder.setExitMissionOnRCSignalLostEnabled(false);
builder.finishedAction(WaypointMissionFinishedAction.GO_HOME);
builder.flightPathMode(WaypointMissionFlightPathMode.NORMAL);
builder.gotoFirstWaypointMode(WaypointMissionGotoWaypointMode.SAFELY);
builder.setPointOfInterest(new LocationCoordinate2D(15, 15));
builder.headingMode(WaypointMissionHeadingMode.TOWARD_POINT_OF_INTEREST);
builder.repeatTimes(1);
List<Waypoint> waypointList = new ArrayList<>();
// Waypoint 0: (0,10)
Waypoint waypoint0 = new Waypoint(baseLatitude, baseLongitude, baseAltitude);
waypoint0.turnMode = WaypointTurnMode.CLOCKWISE;
waypoint0.addAction(new WaypointAction(WaypointActionType.ROTATE_AIRCRAFT,0 + calculateTurnAngle()));
waypoint0.addAction(new WaypointAction(WaypointActionType.START_TAKE_PHOTO, 1000));
waypointList.add(waypoint0);
// Waypoint 1: (0,30)
Waypoint waypoint1 = new Waypoint(baseLatitude, baseLongitude + HORIZONTAL_DISTANCE * ONE_METER_OFFSET, baseAltitude);
waypoint0.turnMode = WaypointTurnMode.COUNTER_CLOCKWISE;
waypoint1.addAction(new WaypointAction(WaypointActionType.ROTATE_AIRCRAFT, 0 - calculateTurnAngle()));
waypoint1.addAction(new WaypointAction(WaypointActionType.START_TAKE_PHOTO, 0));
waypointList.add(waypoint1);
// Waypoint 2: (30,30)
Waypoint waypoint2 = new Waypoint(baseLatitude + VERTICAL_DISTANCE * ONE_METER_OFFSET, baseLongitude + HORIZONTAL_DISTANCE * ONE_METER_OFFSET, baseAltitude);
waypoint0.turnMode = WaypointTurnMode.COUNTER_CLOCKWISE;
waypoint2.addAction(new WaypointAction(WaypointActionType.ROTATE_AIRCRAFT, -180 + calculateTurnAngle()));
waypoint2.addAction(new WaypointAction(WaypointActionType.START_TAKE_PHOTO, 0));
waypointList.add(waypoint2);
// Waypoint 3: (30,0)
Waypoint waypoint3 = new Waypoint(baseLatitude + VERTICAL_DISTANCE * ONE_METER_OFFSET, baseLongitude, baseAltitude);
waypoint0.turnMode = WaypointTurnMode.COUNTER_CLOCKWISE;
waypoint3.addAction(new WaypointAction(WaypointActionType.ROTATE_AIRCRAFT, 180 - calculateTurnAngle()));
waypoint3.addAction(new WaypointAction(WaypointActionType.START_TAKE_PHOTO, 0));
waypointList.add(waypoint3);
builder.waypointList(waypointList).waypointCount(waypointList.size());
return builder.build();
}
private void updateWaypointMissionState(){
if (waypointMissionOperator != null && waypointMissionOperator.getCurrentState() != null) {
ToastUtils.setResultToText(FCPushInfoTV,
"home point latitude: "
+ homeLatitude
+ "\nhome point longitude: "
+ homeLongitude
+ "\nFlight state: "
+ flightState.name()
+ "\nCurrent Waypointmission state : "
+ waypointMissionOperator.getCurrentState().getName());
} else {
ToastUtils.setResultToText(FCPushInfoTV,
"home point latitude: "
+ homeLatitude
+ "\nhome point longitude: "
+ homeLongitude
+ "\nFlight state: "
+ flightState.name());
}
}
private void setUpListener() {
// Example of Listener
listener = new WaypointMissionOperatorListener() {
@Override
public void onDownloadUpdate(@NonNull WaypointMissionDownloadEvent waypointMissionDownloadEvent) {
// Example of Download Listener
if (waypointMissionDownloadEvent.getProgress() != null
&& waypointMissionDownloadEvent.getProgress().isSummaryDownloaded
&& waypointMissionDownloadEvent.getProgress().downloadedWaypointIndex == (WAYPOINT_COUNT - 1)) {
ToastUtils.setResultToToast("Mission is downloaded successfully");
}
updateWaypointMissionState();
}
@Override
public void onUploadUpdate(@NonNull WaypointMissionUploadEvent waypointMissionUploadEvent) {
// Example of Upload Listener
if (waypointMissionUploadEvent.getProgress() != null
&& waypointMissionUploadEvent.getProgress().isSummaryUploaded
&& waypointMissionUploadEvent.getProgress().uploadedWaypointIndex == (WAYPOINT_COUNT - 1)) {
ToastUtils.setResultToToast("Mission is uploaded successfully");
}
updateWaypointMissionState();
}
@Override
public void onExecutionUpdate(@NonNull WaypointMissionExecutionEvent waypointMissionExecutionEvent) {
// Example of Execution Listener
Log.d("TAG",
(waypointMissionExecutionEvent.getPreviousState() == null
? ""
: waypointMissionExecutionEvent.getPreviousState().getName())
+ ", "
+ waypointMissionExecutionEvent.getCurrentState().getName()
+ (waypointMissionExecutionEvent.getProgress() == null
? ""
: waypointMissionExecutionEvent.getProgress().targetWaypointIndex));
updateWaypointMissionState();
}
@Override
public void onExecutionStart() {
ToastUtils.setResultToToast("Mission started");
updateWaypointMissionState();
}
@Override
public void onExecutionFinish(@Nullable DJIError djiError) {
ToastUtils.setResultToToast("Mission finished");
updateWaypointMissionState();
}
};
if (waypointMissionOperator != null && listener != null) {
// Example of adding listeners
waypointMissionOperator.addListener(listener);
}
}
private void tearDownListener() {
if (waypointMissionOperator != null && listener != null) {
// Example of removing listeners
waypointMissionOperator.removeListener(listener);
}
}
private int calculateTurnAngle() {
return Math.round((float)Math.toDegrees(Math.atan(VERTICAL_DISTANCE/ HORIZONTAL_DISTANCE)));
}
private WaypointMissionOperator getWaypointMissionOperator() {
if (null == waypointMissionOperator) {
if (null != MissionControl.getInstance()) {
return MissionControl.getInstance().getWaypointMissionOperator();
}
}
return waypointMissionOperator;
}
private FlightController getFlightController() {
if (null == flightController) {
if (null != DJISampleApplication.getAircraftInstance()) {
return DJISampleApplication.getAircraftInstance().getFlightController();
}
ToastUtils.setResultToToast("Product is disconnected!");
}
return flightController;
}
private void startSimulator() {
if (null != getFlightController()) {
flightController.getSimulator().start(InitializationData.createInstance(new LocationCoordinate2D(BASE_LATITUDE, BASE_LONGITUDE),REFRESH_FREQ, SATELLITE_COUNT), new CommonCallbacks.CompletionCallback() {
@Override
public void onResult(DJIError djiError) {
ToastUtils.setResultToToast(djiError != null ? "Simulator started" : djiError.getDescription());
}
});
}
}
@Override
public int getDescription() {
return R.string.component_listview_waypoint_mission_operator;
}
}