11package com .o3dr .android .client .apis ;
22
33import android .os .Bundle ;
4+ import android .os .Handler ;
5+ import android .text .TextUtils ;
6+ import android .util .Log ;
47
58import com .o3dr .android .client .Drone ;
9+ import com .o3dr .android .client .utils .connection .IpConnectionListener ;
10+ import com .o3dr .android .client .utils .connection .UdpConnection ;
611import com .o3dr .services .android .lib .coordinate .LatLongAlt ;
12+ import com .o3dr .services .android .lib .drone .action .ExperimentalActions ;
13+ import com .o3dr .services .android .lib .drone .attribute .error .CommandExecutionError ;
714import com .o3dr .services .android .lib .mavlink .MavlinkMessageWrapper ;
815import com .o3dr .services .android .lib .model .AbstractCommandListener ;
916import com .o3dr .services .android .lib .model .action .Action ;
1017
18+ import java .nio .ByteBuffer ;
1119import java .util .concurrent .ConcurrentHashMap ;
1220
21+ import static com .o3dr .services .android .lib .drone .action .CameraActions .EXTRA_VIDEO_TAG ;
1322import static com .o3dr .services .android .lib .drone .action .ExperimentalActions .ACTION_SEND_MAVLINK_MESSAGE ;
1423import static com .o3dr .services .android .lib .drone .action .ExperimentalActions .ACTION_SET_RELAY ;
1524import static com .o3dr .services .android .lib .drone .action .ExperimentalActions .ACTION_SET_ROI ;
2231import static com .o3dr .services .android .lib .drone .action .ExperimentalActions .EXTRA_SERVO_PWM ;
2332import static com .o3dr .services .android .lib .drone .action .ExperimentalActions .EXTRA_SET_ROI_LAT_LONG_ALT ;
2433
25-
2634/**
2735 * Contains drone commands with no defined interaction model yet.
2836 */
2937public class ExperimentalApi extends Api {
30-
3138 private static final ConcurrentHashMap <Drone , ExperimentalApi > experimentalApiCache = new ConcurrentHashMap <>();
3239 private static final Builder <ExperimentalApi > apiBuilder = new Builder <ExperimentalApi >() {
3340 @ Override
@@ -36,6 +43,10 @@ public ExperimentalApi build(Drone drone) {
3643 }
3744 };
3845
46+ private final CapabilityApi capabilityChecker ;
47+
48+ private final VideoStreamObserver videoStreamObserver ;
49+
3950 /**
4051 * Retrieves an ExperimentalApi instance.
4152 *
@@ -50,6 +61,9 @@ public static ExperimentalApi getApi(final Drone drone) {
5061
5162 private ExperimentalApi (Drone drone ) {
5263 this .drone = drone ;
64+ this .capabilityChecker = CapabilityApi .getApi (drone );
65+
66+ videoStreamObserver = new VideoStreamObserver (drone .getHandler ());
5367 }
5468
5569 /**
@@ -149,4 +163,275 @@ public void setServo(int channel, int pwm, AbstractCommandListener listener) {
149163 params .putInt (EXTRA_SERVO_PWM , pwm );
150164 drone .performAsyncActionOnDroneThread (new Action (ACTION_SET_SERVO , params ), listener );
151165 }
166+
167+ /**
168+ * Attempt to grab ownership and get a lock for the video stream. Can fail if
169+ * the video stream is already owned by another client.
170+ *
171+ * @param tag Video tag.
172+ * @param callback Video stream observer callback.
173+ *
174+ * @since 2.8.1
175+ */
176+ public void startVideoStream (final String tag , final IVideoStreamCallback callback ) {
177+ if (callback == null ) {
178+ throw new NullPointerException ("Video stream callback can't be null" );
179+ }
180+
181+ capabilityChecker .checkFeatureSupport (CapabilityApi .FeatureIds .SOLO_VIDEO_STREAMING ,
182+ new CapabilityApi .FeatureSupportListener () {
183+ @ Override
184+ public void onFeatureSupportResult (String featureId , int result , Bundle resultInfo ) {
185+ final AbstractCommandListener listener = new AbstractCommandListener () {
186+ @ Override
187+ public void onSuccess () {
188+ // Start VideoStreamObserver to connect to vehicle video stream and receive
189+ // video stream packets.
190+ videoStreamObserver .setCallback (callback );
191+ videoStreamObserver .start ();
192+
193+ videoStreamObserver .getCallback ().onVideoStreamConnecting ();
194+ }
195+
196+ @ Override
197+ public void onError (int executionError ) {
198+ videoStreamObserver .getCallback ().onError (executionError );
199+ }
200+
201+ @ Override
202+ public void onTimeout () {
203+ videoStreamObserver .getCallback ().onTimeout ();
204+ }
205+ };
206+
207+ switch (result ) {
208+ case CapabilityApi .FEATURE_SUPPORTED :
209+ startVideoStreamForObserver (tag , listener );
210+ break ;
211+
212+ case CapabilityApi .FEATURE_UNSUPPORTED :
213+ postErrorEvent (CommandExecutionError .COMMAND_UNSUPPORTED , listener );
214+ break ;
215+
216+ default :
217+ postErrorEvent (CommandExecutionError .COMMAND_FAILED , listener );
218+ break ;
219+ }
220+ }
221+ });
222+ }
223+
224+ /**
225+ * Release ownership of the video stream.
226+ *
227+ * @param tag Video tag.
228+ *
229+ * @since 2.8.1
230+ */
231+ public void stopVideoStream (final String tag ) {
232+ capabilityChecker .checkFeatureSupport (CapabilityApi .FeatureIds .SOLO_VIDEO_STREAMING ,
233+ new CapabilityApi .FeatureSupportListener () {
234+ @ Override
235+ public void onFeatureSupportResult (String featureId , int result , Bundle resultInfo ) {
236+ final AbstractCommandListener listener = new AbstractCommandListener () {
237+ @ Override
238+ public void onSuccess () {
239+ videoStreamObserver .getCallback ().onVideoStreamDisconnecting ();
240+
241+ videoStreamObserver .stop ();
242+ }
243+
244+ @ Override
245+ public void onError (int executionError ) {
246+ videoStreamObserver .getCallback ().onError (executionError );
247+ }
248+
249+ @ Override
250+ public void onTimeout () {
251+ videoStreamObserver .getCallback ().onTimeout ();
252+ }
253+ };
254+
255+ switch (result ) {
256+ case CapabilityApi .FEATURE_SUPPORTED :
257+ stopVideoStreamForObserver (tag , listener );
258+ break ;
259+
260+ case CapabilityApi .FEATURE_UNSUPPORTED :
261+ postErrorEvent (CommandExecutionError .COMMAND_UNSUPPORTED , listener );
262+ break ;
263+
264+ default :
265+ postErrorEvent (CommandExecutionError .COMMAND_FAILED , listener );
266+ break ;
267+ }
268+ }
269+ });
270+ }
271+
272+ /**
273+ * Prepending 'observer' to the tag for differentiation
274+ * @param tag
275+ * @return
276+ */
277+ private String getObserverTag (String tag ){
278+ return "observer" + (TextUtils .isEmpty (tag ) ? "" : "." + tag );
279+ }
280+
281+ /**
282+ * Attempt to grab ownership and start the video stream from the connected drone. Can fail if
283+ * the video stream is already owned by another client.
284+ *
285+ * @param tag Video tag.
286+ * @param listener Register a listener to receive update of the command execution status.
287+ * @since 2.8.1
288+ */
289+ private void startVideoStreamForObserver (final String tag , AbstractCommandListener listener ) {
290+ final Bundle params = new Bundle ();
291+ params .putString (EXTRA_VIDEO_TAG , getObserverTag (tag ));
292+
293+ drone .performAsyncActionOnDroneThread (new Action (ExperimentalActions .ACTION_START_VIDEO_STREAM_FOR_OBSERVER ,
294+ params ), listener );
295+ }
296+
297+ /**
298+ * Stop the video stream from the connected drone, and release ownership.
299+ *
300+ * @param tag Video tag.
301+ * @param listener Register a listener to receive update of the command execution status.
302+ * @since 2.8.1
303+ */
304+ private void stopVideoStreamForObserver (final String tag , AbstractCommandListener listener ) {
305+ final Bundle params = new Bundle ();
306+ params .putString (EXTRA_VIDEO_TAG , getObserverTag (tag ));
307+
308+ drone .performAsyncActionOnDroneThread (new Action (ExperimentalActions .ACTION_STOP_VIDEO_STREAM_FOR_OBSERVER , params ),
309+ listener );
310+ }
311+
312+ /**
313+ * Observer for vehicle video stream.
314+ */
315+ private static class VideoStreamObserver implements IpConnectionListener {
316+ private final String TAG = VideoStreamObserver .class .getSimpleName ();
317+
318+ private static final int UDP_BUFFER_SIZE = 1500 ;
319+ private static final long RECONNECT_COUNTDOWN_IN_MILLIS = 1000l ;
320+ private static final int SOLO_STREAM_UDP_PORT = 5600 ;
321+
322+ private UdpConnection linkConn ;
323+ private final Handler handler ;
324+
325+ private final Runnable onVideoStreamConnected = new Runnable () {
326+ @ Override
327+ public void run () {
328+ handler .removeCallbacks (this );
329+ if (callback != null )
330+ callback .onVideoStreamConnected ();
331+ }
332+ };
333+
334+ private final Runnable onVideoStreamDisconnected = new Runnable () {
335+ @ Override
336+ public void run () {
337+ handler .removeCallbacks (this );
338+ if (callback != null ){
339+ callback .onVideoStreamDisconnected ();
340+ }
341+ }
342+ };
343+
344+ private IVideoStreamCallback callback ;
345+
346+ public VideoStreamObserver (Handler handler ) {
347+ this .handler = handler ;
348+ }
349+
350+ public void setCallback (IVideoStreamCallback callback ) {
351+ this .callback = callback ;
352+ }
353+
354+ private IVideoStreamCallback getCallback () {
355+ return callback ;
356+ }
357+
358+ private final Runnable reconnectTask = new Runnable () {
359+ @ Override
360+ public void run () {
361+ handler .removeCallbacks (reconnectTask );
362+ if (linkConn != null )
363+ linkConn .connect ();
364+ }
365+ };
366+
367+ public void start () {
368+ if (this .linkConn == null ) {
369+ this .linkConn = new UdpConnection (handler , SOLO_STREAM_UDP_PORT ,
370+ UDP_BUFFER_SIZE , true , 42 );
371+ this .linkConn .setIpConnectionListener (this );
372+ }
373+
374+ handler .removeCallbacks (reconnectTask );
375+
376+ Log .d (TAG , "Connecting to video stream..." );
377+ this .linkConn .connect ();
378+ }
379+
380+ public void stop () {
381+ Log .d (TAG , "Stopping video manager" );
382+
383+ handler .removeCallbacks (reconnectTask );
384+
385+ if (this .linkConn != null ) {
386+ // Break the link.
387+ this .linkConn .disconnect ();
388+ this .linkConn = null ;
389+ }
390+ }
391+
392+ @ Override
393+ public void onIpConnected () {
394+ Log .d (TAG , "Connected to video stream" );
395+
396+ handler .post (onVideoStreamConnected );
397+ handler .removeCallbacks (reconnectTask );
398+ }
399+
400+ @ Override
401+ public void onIpDisconnected () {
402+ Log .d (TAG , "Video stream disconnected" );
403+
404+ handler .post (onVideoStreamDisconnected );
405+ handler .postDelayed (reconnectTask , RECONNECT_COUNTDOWN_IN_MILLIS );
406+ }
407+
408+ @ Override
409+ public void onPacketReceived (final ByteBuffer packetBuffer ) {
410+ handler .post (new Runnable () {
411+ @ Override
412+ public void run () {
413+ callback .onVideoStreamPacketReceived (packetBuffer .array (), packetBuffer .limit ());
414+ }
415+ });
416+ }
417+ }
418+
419+ /**
420+ * Callback for directly observing video stream.
421+ */
422+ public interface IVideoStreamCallback {
423+ void onVideoStreamConnecting ();
424+
425+ void onVideoStreamConnected ();
426+
427+ void onVideoStreamDisconnecting ();
428+
429+ void onVideoStreamDisconnected ();
430+
431+ void onError (int executionError );
432+
433+ void onTimeout ();
434+
435+ void onVideoStreamPacketReceived (byte [] data , int dataSize );
436+ }
152437}
0 commit comments