Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
vpRobotBebop2.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for Parrot Bebop 2 drone.
33  *
34  * Authors:
35  * Gatien Gaumerais
36  *
37 *****************************************************************************/
38 
39 #include <visp3/core/vpConfig.h>
40 
41 #ifdef VISP_HAVE_ARSDK
42 
43 #include <visp3/robot/vpRobotBebop2.h>
44 
45 #include <visp3/core/vpExponentialMap.h> // For velocity computation
46 
47 #ifdef VISP_HAVE_FFMPEG
48 extern "C" {
49 #include <libavcodec/avcodec.h>
50 #include <libavformat/avformat.h>
51 #include <libavutil/imgutils.h>
52 }
53 #include <visp3/core/vpImageConvert.h>
54 #endif
55 
56 #include <iostream>
57 #include <math.h>
58 
59 #define TAG "vpRobotBebop2" // For error messages of ARSDK
60 
75 BEGIN_VISP_NAMESPACE
76 bool vpRobotBebop2::m_running = false;
77 ARCONTROLLER_Device_t *vpRobotBebop2::m_deviceController = nullptr;
78 
114 vpRobotBebop2::vpRobotBebop2(bool verbose, bool setDefaultSettings, std::string ipAddress, int discoveryPort)
115  : m_ipAddress(ipAddress), m_discoveryPort(discoveryPort)
116 {
117  // Setting up signal handling
118  memset(&m_sigAct, 0, sizeof(m_sigAct));
119  m_sigAct.sa_handler = vpRobotBebop2::sighandler;
120  sigaction(SIGINT, &m_sigAct, 0);
121  sigaction(SIGBUS, &m_sigAct, 0);
122  sigaction(SIGSEGV, &m_sigAct, 0);
123  sigaction(SIGKILL, &m_sigAct, 0);
124  sigaction(SIGQUIT, &m_sigAct, 0);
125 
126 #ifdef VISP_HAVE_FFMPEG
127  m_codecContext = nullptr;
128  m_packet = AVPacket();
129  m_picture = nullptr;
130  m_bgr_picture = nullptr;
131  m_img_convert_ctx = nullptr;
132  m_buffer = nullptr;
133  m_videoDecodingStarted = false;
134 #endif
135 
136  m_batteryLevel = 100;
137 
138  m_exposureSet = true;
139  m_flatTrimFinished = true;
140  m_relativeMoveEnded = true;
141  m_videoResolutionSet = true;
142  m_streamingStarted = false;
143  m_streamingModeSet = false;
144  m_settingsReset = false;
145 
146  m_update_codec_params = false;
147  m_codec_params_data = std::vector<uint8_t>();
148 
149  m_maxTilt = -1;
150 
151  m_cameraHorizontalFOV = -1;
152  m_currentCameraTilt = -1;
153  m_minCameraTilt = -1;
154  m_maxCameraTilt = -1;
155  m_currentCameraPan = -1;
156  m_minCameraPan = -1;
157  m_maxCameraPan = -1;
158 
159  setVerbose(verbose);
160 
161  m_errorController = ARCONTROLLER_OK;
162  m_deviceState = ARCONTROLLER_DEVICE_STATE_MAX;
163 
164  // Initialises a semaphore
165  ARSAL_Sem_Init(&(m_stateSem), 0, 0);
166 
167  // Creates a discovery device to find the drone on the wifi network
168  ARDISCOVERY_Device_t *discoverDevice = discoverDrone();
169 
170  // Creates a drone controller with the discovery device
171  createDroneController(discoverDevice);
172 
173  // Sets up callbacks
174  setupCallbacks();
175 
176  // Start the drone controller, connects to the drone. If an error occurs, it will set m_errorController to the error.
177  startController();
178 
179  // We check if the drone was actually found and connected to the controller
180  if ((m_errorController != ARCONTROLLER_OK) || (m_deviceState != ARCONTROLLER_DEVICE_STATE_RUNNING)) {
181  cleanUp();
182  m_running = false;
183 
185  "Failed to connect to bebop2 with ip %s and port %d. Make sure that the ip address is correct "
186  "and that your computer is connected to the drone Wifi spot before starting",
187  ipAddress.c_str(), discoveryPort));
188  }
189  else {
190  m_running = true;
191 
192 #ifdef VISP_HAVE_FFMPEG
194 #endif
195  if (setDefaultSettings) {
197 
198  setMaxTilt(10);
199 
200 #ifdef VISP_HAVE_FFMPEG
202  setExposure(0);
203  setStreamingMode(0);
204 #endif
205  setCameraOrientation(0, 0, true);
206  }
207  }
208 }
209 
216 
224 {
225  if (isRunning() && m_deviceController != nullptr && isLanded()) {
226 
227  m_flatTrimFinished = false;
228 
229  m_deviceController->aRDrone3->sendPilotingFlatTrim(m_deviceController->aRDrone3);
230 
231  // m_flatTrimFinished is set back to true when the drone has finished the calibration, via a callback
232  while (!m_flatTrimFinished) {
233  vpTime::sleepMs(1);
234  }
235  }
236  else {
237  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't do a flat trim : drone isn't landed.");
238  }
239 }
240 
245 std::string vpRobotBebop2::getIpAddress() { return m_ipAddress; }
246 
251 int vpRobotBebop2::getDiscoveryPort() { return m_discoveryPort; }
252 
257 double vpRobotBebop2::getMaxTilt() { return m_maxTilt; }
258 
265 unsigned int vpRobotBebop2::getBatteryLevel() { return m_batteryLevel; }
266 
271 double vpRobotBebop2::getCameraHorizontalFOV() const { return m_cameraHorizontalFOV; }
272 
277 double vpRobotBebop2::getCurrentCameraTilt() const { return m_currentCameraTilt; }
278 
283 double vpRobotBebop2::getMinCameraTilt() const { return m_minCameraTilt; }
284 
289 double vpRobotBebop2::getMaxCameraTilt() const { return m_maxCameraTilt; }
290 
295 double vpRobotBebop2::getCurrentCameraPan() const { return m_currentCameraPan; }
296 
301 double vpRobotBebop2::getMinCameraPan() const { return m_minCameraPan; }
302 
307 double vpRobotBebop2::getMaxCameraPan() const { return m_maxCameraPan; }
308 
321 void vpRobotBebop2::setCameraOrientation(double tilt, double pan, bool blocking)
322 {
323  if (isRunning() && m_deviceController != nullptr) {
324 
325  m_deviceController->aRDrone3->sendCameraOrientationV2(m_deviceController->aRDrone3, static_cast<float>(tilt),
326  static_cast<float>(pan));
327 
328  if (blocking) {
329  while (std::abs(tilt - m_currentCameraTilt) > 0.01 || std::abs(pan - m_currentCameraPan) > 0.01) {
330  vpTime::sleepMs(1);
331  }
332  }
333 
334  }
335  else {
336  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set camera orientation : drone isn't running.");
337  }
338 }
339 
351 void vpRobotBebop2::setCameraTilt(double tilt, bool blocking)
352 {
353  if (isRunning() && m_deviceController != nullptr) {
354 
355  m_deviceController->aRDrone3->sendCameraOrientationV2(m_deviceController->aRDrone3, static_cast<float>(tilt),
356  static_cast<float>(getCurrentCameraPan()));
357 
358  if (blocking) {
359  while (std::abs(tilt - m_currentCameraTilt) > 0.01) {
360  vpTime::sleepMs(1);
361  }
362  }
363 
364  }
365  else {
366  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set camera tilt value : drone isn't running.");
367  }
368 }
369 
381 void vpRobotBebop2::setCameraPan(double pan, bool blocking)
382 {
383  if (isRunning() && m_deviceController != nullptr) {
384 
385  m_deviceController->aRDrone3->sendCameraOrientationV2(
386  m_deviceController->aRDrone3, static_cast<float>(getCurrentCameraTilt()), static_cast<float>(pan));
387 
388  if (blocking) {
389  while (std::abs(pan - m_currentCameraPan) > 0.01) {
390  vpTime::sleepMs(1);
391  }
392  }
393 
394  }
395  else {
396  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set camera pan value : drone isn't running.");
397  }
398 }
399 
405 {
406  if (m_deviceController == nullptr) {
407  return false;
408  }
409  else {
410  return m_running;
411  }
412 }
413 
419 {
420 #ifdef VISP_HAVE_FFMPEG
421  return m_videoDecodingStarted;
422 #else
423  return false;
424 #endif
425 }
426 
432 {
433  return getFlyingState() == ARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE_HOVERING;
434 }
435 
441 {
442  return getFlyingState() == ARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE_FLYING;
443 }
444 
450 {
451  return getFlyingState() == ARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE_LANDED;
452 }
453 
461 void vpRobotBebop2::takeOff(bool blocking)
462 {
463  if (isRunning() && isLanded() && m_deviceController != nullptr) {
464 
465  m_deviceController->aRDrone3->sendPilotingTakeOff(m_deviceController->aRDrone3);
466 
467  if (blocking) {
468  while (!isHovering()) {
469  vpTime::sleepMs(1);
470  }
471  }
472 
473  }
474  else {
475  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't take off : drone isn't landed.");
476  }
477 }
478 
486 {
487  if (m_deviceController != nullptr) {
488  m_deviceController->aRDrone3->sendPilotingLanding(m_deviceController->aRDrone3);
489  }
490 }
491 
503 {
504  if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) {
505  m_errorController =
506  m_deviceController->aRDrone3->setPilotingPCMDGaz(m_deviceController->aRDrone3, static_cast<char>(value));
507 
508  if (m_errorController != ARCONTROLLER_OK) {
509  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error when sending move command : %s",
510  ARCONTROLLER_Error_ToString(m_errorController));
511  }
512 
513  }
514  else {
515  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set vertical speed : drone isn't flying or hovering.");
516  }
517 }
518 
530 {
531  if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) {
532 
533  m_errorController =
534  m_deviceController->aRDrone3->setPilotingPCMDYaw(m_deviceController->aRDrone3, static_cast<char>(value));
535 
536  if (m_errorController != ARCONTROLLER_OK) {
537  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error when sending move command : %s",
538  ARCONTROLLER_Error_ToString(m_errorController));
539  }
540 
541  }
542  else {
543  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set yaw speed : drone isn't flying or hovering.");
544  }
545 }
546 
557 void vpRobotBebop2::setPitch(int value)
558 {
559  if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) {
560 
561  m_errorController =
562  m_deviceController->aRDrone3->setPilotingPCMDPitch(m_deviceController->aRDrone3, static_cast<char>(value));
563  m_errorController = m_deviceController->aRDrone3->setPilotingPCMDFlag(m_deviceController->aRDrone3, 1);
564 
565  if (m_errorController != ARCONTROLLER_OK) {
566  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error when sending move command : %s",
567  ARCONTROLLER_Error_ToString(m_errorController));
568  }
569 
570  }
571  else {
572  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set pitch value : drone isn't flying or hovering.");
573  }
574 }
575 
586 void vpRobotBebop2::setRoll(int value)
587 {
588  if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) {
589 
590  m_errorController =
591  m_deviceController->aRDrone3->setPilotingPCMDRoll(m_deviceController->aRDrone3, static_cast<char>(value));
592  m_errorController = m_deviceController->aRDrone3->setPilotingPCMDFlag(m_deviceController->aRDrone3, 1);
593 
594  if (m_errorController != ARCONTROLLER_OK) {
595  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error when sending move command : %s",
596  ARCONTROLLER_Error_ToString(m_errorController));
597  }
598 
599  }
600  else {
601  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set roll value : drone isn't flying or hovering.");
602  }
603 }
604 
612 {
613  if (m_deviceController != nullptr) {
614  m_errorController = m_deviceController->aRDrone3->sendPilotingEmergency(m_deviceController->aRDrone3);
615  }
616 }
617 
633 void vpRobotBebop2::setPosition(float dX, float dY, float dZ, float dPsi, bool blocking)
634 {
635  if (isRunning() && m_deviceController != nullptr && (isFlying() || isHovering())) {
636 
637  m_relativeMoveEnded = false;
638  m_deviceController->aRDrone3->sendPilotingMoveBy(m_deviceController->aRDrone3, dX, dY, dZ, dPsi);
639 
640  if (blocking) {
641 
642  // m_relativeMoveEnded is set back to true when the drone has finished his move, via a callback
643  while (!m_relativeMoveEnded) {
644  vpTime::sleepMs(1);
645  }
646  }
647  }
648  else {
649  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't move : drone isn't flying or hovering.");
650  }
651 }
652 
666 void vpRobotBebop2::setPosition(const vpHomogeneousMatrix &M, bool blocking)
667 {
668  double epsilon = (std::numeric_limits<double>::epsilon());
669  if (std::abs(M.getRotationMatrix().getThetaUVector()[0]) >= epsilon) {
670  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't move : rotation around X axis should be 0.");
671  return;
672  }
673  if (std::abs(M.getRotationMatrix().getThetaUVector()[1]) >= epsilon) {
674  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't move : rotation around Y axis should be 0.");
675  return;
676  }
677  float dThetaZ = static_cast<float>(M.getRotationMatrix().getThetaUVector()[2]);
679  setPosition(static_cast<float>(t[0]), static_cast<float>(t[1]), static_cast<float>(t[2]), dThetaZ, blocking);
680 }
681 
693 void vpRobotBebop2::setVelocity(const vpColVector &vel_cmd, double delta_t)
694 {
695 
696  if (vel_cmd.size() != 4) {
697  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR",
698  "Can't set velocity : dimension of the velocity vector should be equal to 4.");
699  stopMoving();
700  return;
701  }
702 
703  vpColVector ve(6);
704 
705  ve[0] = vel_cmd[0];
706  ve[1] = vel_cmd[1];
707  ve[2] = vel_cmd[2];
708  ve[5] = vel_cmd[3];
709 
711  setPosition(M, false);
712 }
713 
722 void vpRobotBebop2::setVerbose(bool verbose)
723 {
724  if (verbose) {
725  ARSAL_Print_SetMinimumLevel(ARSAL_PRINT_INFO);
726  }
727  else {
728  ARSAL_Print_SetMinimumLevel(ARSAL_PRINT_WARNING);
729  }
730 }
731 
737 {
738  if (isRunning() && m_deviceController != nullptr) {
739 
740  m_settingsReset = false;
741  m_deviceController->common->sendSettingsReset(m_deviceController->common);
742 
743  while (!m_settingsReset) {
744  vpTime::sleepMs(1);
745  }
746 
747  }
748  else {
749  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't reset drone settings : drone isn't running.");
750  }
751 }
752 
764 void vpRobotBebop2::setMaxTilt(double maxTilt)
765 {
766  if (isRunning() && m_deviceController != nullptr) {
767  m_deviceController->aRDrone3->sendPilotingSettingsMaxTilt(m_deviceController->aRDrone3,
768  static_cast<float>(maxTilt));
769  }
770  else {
771  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set tilt value : drone isn't running.");
772  }
773 }
774 
783 {
784  if (isRunning() && !isLanded() && m_deviceController != nullptr) {
785  m_errorController = m_deviceController->aRDrone3->setPilotingPCMD(m_deviceController->aRDrone3, 0, 0, 0, 0, 0, 0);
786  }
787 }
788 
789 //*** ***//
790 //*** Streaming functions ***//
791 //*** ***//
792 
793 #ifdef VISP_HAVE_FFMPEG // Functions related to video streaming and decoding requiers FFmpeg
794 
804 {
805  if (m_videoDecodingStarted) {
806 
807  if (m_bgr_picture->data[0] != nullptr) {
808  I.resize(static_cast<unsigned int>(m_videoHeight), static_cast<unsigned int>(m_videoWidth));
809 
810  m_bgr_picture_mutex.lock();
811  vpImageConvert::BGRToGrey(m_bgr_picture->data[0], reinterpret_cast<unsigned char *>(I.bitmap), I.getWidth(),
812  I.getHeight());
813  m_bgr_picture_mutex.unlock();
814  }
815  else {
816  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Error while getting current grayscale image : image data is nullptr");
817  }
818 
819  }
820  else {
821  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't get current image : video streaming isn't started.");
822  }
823 }
824 
834 {
835  if (m_videoDecodingStarted) {
836 
837  if (m_bgr_picture->data[0] != nullptr) {
838  I.resize(static_cast<unsigned int>(m_videoHeight), static_cast<unsigned int>(m_videoWidth));
839 
840  m_bgr_picture_mutex.lock();
841  vpImageConvert::BGRToRGBa(m_bgr_picture->data[0], reinterpret_cast<unsigned char *>(I.bitmap), I.getWidth(),
842  I.getHeight());
843  m_bgr_picture_mutex.unlock();
844  }
845  else {
846  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Error while getting current RGBa image : image data is nullptr");
847  }
848 
849  }
850  else {
851  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't get current image : video streaming isn't started.");
852  }
853 }
854 
860 int vpRobotBebop2::getVideoHeight() { return m_videoHeight; }
861 
867 int vpRobotBebop2::getVideoWidth() { return m_videoWidth; }
868 
877 {
878  if (isRunning() && m_deviceController != nullptr) {
879  expo = std::min<float>(1.5f, std::max<float>(-1.5f, expo));
880 
881  m_exposureSet = false;
882  m_deviceController->aRDrone3->sendPictureSettingsExpositionSelection(m_deviceController->aRDrone3, expo);
883 
884  // m_exposureSet is set back to true when the drone has finished his move, via a callback
885  while (!m_exposureSet) {
886  vpTime::sleepMs(1);
887  }
888  }
889  else {
890  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set exposure : drone isn't running.");
891  }
892 }
893 
909 {
910  if (isRunning() && m_deviceController != nullptr) {
911 
912  if (!isStreaming() && isLanded()) {
913  eARCOMMANDS_ARDRONE3_MEDIASTREAMING_VIDEOSTREAMMODE_MODE cmd_mode =
914  ARCOMMANDS_ARDRONE3_MEDIASTREAMING_VIDEOSTREAMMODE_MODE_LOW_LATENCY;
915  switch (mode) {
916  case 0:
917  cmd_mode = ARCOMMANDS_ARDRONE3_MEDIASTREAMING_VIDEOSTREAMMODE_MODE_LOW_LATENCY;
918  break;
919  case 1:
920  cmd_mode = ARCOMMANDS_ARDRONE3_MEDIASTREAMING_VIDEOSTREAMMODE_MODE_HIGH_RELIABILITY;
921  break;
922  case 2:
923  cmd_mode = ARCOMMANDS_ARDRONE3_MEDIASTREAMING_VIDEOSTREAMMODE_MODE_HIGH_RELIABILITY_LOW_FRAMERATE;
924  break;
925  default:
926  break;
927  }
928  m_streamingModeSet = false;
929  m_deviceController->aRDrone3->sendMediaStreamingVideoStreamMode(m_deviceController->aRDrone3, cmd_mode);
930 
931  // m_streamingModeSet is set back to true when the drone has finished setting the stream mode, via a callback
932  while (!m_streamingModeSet) {
933  vpTime::sleepMs(1);
934  }
935 
936  }
937  else {
938  ARSAL_PRINT(
939  ARSAL_PRINT_ERROR, "ERROR",
940  "Can't set streaming mode : drone has to be landed and not streaming in order to set streaming mode.");
941  }
942  }
943  else {
944  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set streaming mode : drone isn't running.");
945  }
946 }
947 
960 {
961  if (isRunning() && m_deviceController != nullptr) {
962 
963  if (!isStreaming() && isLanded()) {
964 
965  eARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEORESOLUTIONS_TYPE cmd_mode;
966 
967  switch (mode) {
968 
969  case 0:
970  default:
971  cmd_mode = ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEORESOLUTIONS_TYPE_REC1080_STREAM480;
972  m_videoWidth = 856;
973  m_videoHeight = 480;
974  break;
975 
976  case 1:
977  cmd_mode = ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEORESOLUTIONS_TYPE_REC720_STREAM720;
978  m_videoWidth = 1280;
979  m_videoHeight = 720;
980  break;
981  }
982 
983  m_videoResolutionSet = false;
984  m_deviceController->aRDrone3->sendPictureSettingsVideoResolutions(m_deviceController->aRDrone3, cmd_mode);
985 
986  // m_videoResolutionSet is set back to true when the drone has finished setting the resolution, via a callback
987  while (!m_videoResolutionSet) {
988  vpTime::sleepMs(1);
989  }
990 
991  }
992  else {
993  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR",
994  "Can't set video resolution : drone has to be landed and not streaming in order to set streaming "
995  "parameters.");
996  }
997  }
998  else {
999  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set video resolution : drone isn't running.");
1000  }
1001 }
1002 
1015 {
1016  if (isRunning() && m_deviceController != nullptr) {
1017 
1018  eARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE cmd_mode =
1019  ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE_NONE;
1020  switch (mode) {
1021 
1022  case 0:
1023  cmd_mode = ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE_NONE;
1024  break;
1025  case 1:
1026  cmd_mode = ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE_ROLL;
1027  break;
1028  case 2:
1029  cmd_mode = ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE_PITCH;
1030  break;
1031  case 3:
1032  cmd_mode = ARCOMMANDS_ARDRONE3_PICTURESETTINGS_VIDEOSTABILIZATIONMODE_MODE_ROLL_PITCH;
1033  break;
1034 
1035  default:
1036  break;
1037  }
1038  m_deviceController->aRDrone3->sendPictureSettingsVideoStabilizationMode(m_deviceController->aRDrone3, cmd_mode);
1039 
1040  }
1041  else {
1042  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't set video stabilisation mode : drone isn't running.");
1043  }
1044 }
1045 
1055 {
1056  if (isRunning() && m_deviceController != nullptr) {
1057  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Starting video streaming ... ");
1058 
1059  // Sending command to the drone to start the video stream
1060  m_errorController = m_deviceController->aRDrone3->sendMediaStreamingVideoEnable(m_deviceController->aRDrone3, 1);
1061 
1062  if (m_errorController == ARCONTROLLER_OK) {
1063  m_streamingStarted = false;
1064  // Blocking until streaming is started
1065  while (!m_streamingStarted) {
1066  vpTime::sleepMs(1);
1067  }
1068  startVideoDecoding();
1069 
1070  /* We wait for the streaming to actually start (it has a delay before actually
1071  sending frames, even if it is indicated as started by the drone), or else the
1072  decoder is doesn't have time to synchronize with the stream */
1073  vpTime::sleepMs(4000);
1074 
1075  }
1076  else {
1077  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error :%s", ARCONTROLLER_Error_ToString(m_errorController));
1078  }
1079 
1080  }
1081  else {
1082  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't start streaming : drone isn't running.");
1083  }
1084 }
1085 
1092 {
1093  if (m_videoDecodingStarted && m_deviceController != nullptr) {
1094  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Stopping video streaming ... ");
1095 
1096  // Sending command to the drone to stop the video stream
1097  m_errorController = m_deviceController->aRDrone3->sendMediaStreamingVideoEnable(m_deviceController->aRDrone3, 0);
1098 
1099  if (m_errorController == ARCONTROLLER_OK) {
1100 
1101  // Blocking until streaming is stopped
1102  while (getStreamingState() != ARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED_DISABLED) {
1103  vpTime::sleepMs(1);
1104  }
1105  vpTime::sleepMs(500); // We wait for the streaming to actually stops or else it causes segmentation fault.
1106  stopVideoDecoding();
1107 
1108  }
1109  else {
1110  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error :%s", ARCONTROLLER_Error_ToString(m_errorController));
1111  }
1112 
1113  }
1114  else {
1115  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Can't stop streaming : streaming already stopped.");
1116  }
1117 }
1118 
1119 #endif // #ifdef VISP_HAVE_FFMPEG
1120 
1121 //*** ***//
1122 //*** Private Functions ***//
1123 //*** ***//
1124 
1129 void vpRobotBebop2::sighandler(int signo)
1130 {
1131  std::cout << "Stopping Bebop2 because of detected signal (" << signo << "): " << static_cast<char>(7);
1132  switch (signo) {
1133  case SIGINT:
1134  std::cout << "SIGINT (stopped by ^C) " << std::endl;
1135  break;
1136  case SIGBUS:
1137  std::cout << "SIGBUS (stopped due to a bus error) " << std::endl;
1138  break;
1139  case SIGSEGV:
1140  std::cout << "SIGSEGV (stopped due to a segmentation fault) " << std::endl;
1141  break;
1142  case SIGKILL:
1143  std::cout << "SIGKILL (stopped by CTRL \\) " << std::endl;
1144  break;
1145  case SIGQUIT:
1146  std::cout << "SIGQUIT " << std::endl;
1147  break;
1148  default:
1149  std::cout << signo << std::endl;
1150  }
1151 
1152  vpRobotBebop2::m_running = false;
1153 
1154  // Landing the drone
1155  if (m_deviceController != nullptr) {
1156  m_deviceController->aRDrone3->sendPilotingLanding(m_deviceController->aRDrone3);
1157  }
1158  std::exit(EXIT_FAILURE);
1159 }
1160 
1165 eARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE vpRobotBebop2::getFlyingState()
1166 {
1167  if (m_deviceController != nullptr) {
1168  eARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE flyingState =
1169  ARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE_MAX;
1170  eARCONTROLLER_ERROR error;
1171 
1172  ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary = ARCONTROLLER_ARDrone3_GetCommandElements(
1173  m_deviceController->aRDrone3, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED, &error);
1174 
1175  if (error == ARCONTROLLER_OK && elementDictionary != nullptr) {
1176  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1177  ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr;
1178 
1179  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element);
1180 
1181  if (element != nullptr) {
1182  // Suppress warnings
1183  // Get the value
1184  HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE,
1185  arg);
1186 
1187  if (arg != nullptr) {
1188  // Enums are stored as I32
1189  flyingState = static_cast<eARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE>(arg->value.I32);
1190  }
1191  }
1192  }
1193  return flyingState;
1194  }
1195  else {
1196  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Error when checking flying state : drone isn't connected.");
1197  return ARCOMMANDS_ARDRONE3_PILOTINGSTATE_FLYINGSTATECHANGED_STATE_MAX;
1198  }
1199 }
1200 
1205 eARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED vpRobotBebop2::getStreamingState()
1206 {
1207  if (m_deviceController != nullptr) {
1208  eARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED streamingState =
1209  ARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED_MAX;
1210  eARCONTROLLER_ERROR error;
1211 
1212  ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary = ARCONTROLLER_ARDrone3_GetCommandElements(
1213  m_deviceController->aRDrone3, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED,
1214  &error);
1215 
1216  if (error == ARCONTROLLER_OK && elementDictionary != nullptr) {
1217  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1218  ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr;
1219 
1220  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element);
1221 
1222  if (element != nullptr) {
1223  // Get the value
1224  HASH_FIND_STR(element->arguments,
1225  ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED, arg);
1226 
1227  if (arg != nullptr) {
1228  // Enums are stored as I32
1229  streamingState =
1230  static_cast<eARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED>(arg->value.I32);
1231  }
1232  }
1233  }
1234  return streamingState;
1235  }
1236  else {
1237  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Error when checking streaming state : drone isn't connected.");
1238  return ARCOMMANDS_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED_ENABLED_MAX;
1239  }
1240 }
1241 
1246 ARDISCOVERY_Device_t *vpRobotBebop2::discoverDrone()
1247 {
1248  eARDISCOVERY_ERROR errorDiscovery = ARDISCOVERY_OK;
1249 
1250  ARDISCOVERY_Device_t *device = ARDISCOVERY_Device_New(&errorDiscovery);
1251 
1252  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Starting drone Wifi discovery ...");
1253  const char *charIpAddress = m_ipAddress.c_str();
1254  errorDiscovery =
1255  ARDISCOVERY_Device_InitWifi(device, ARDISCOVERY_PRODUCT_BEBOP_2, "bebop2", charIpAddress, m_discoveryPort);
1256 
1257  if (errorDiscovery != ARDISCOVERY_OK) {
1258  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Discovery error :%s", ARDISCOVERY_Error_ToString(errorDiscovery));
1259  }
1260  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Drone controller created.");
1261  return device;
1262 }
1263 
1270 void vpRobotBebop2::createDroneController(ARDISCOVERY_Device_t *discoveredDrone)
1271 {
1272  m_deviceController = ARCONTROLLER_Device_New(discoveredDrone, &m_errorController);
1273  if (m_errorController != ARCONTROLLER_OK) {
1274  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Creation of deviceController failed.");
1275  }
1276  ARDISCOVERY_Device_Delete(&discoveredDrone);
1277  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Device created.");
1278 }
1279 
1284 void vpRobotBebop2::setupCallbacks()
1285 {
1286  // Adding stateChanged callback, called when the state of the controller has changed
1287  m_errorController = ARCONTROLLER_Device_AddStateChangedCallback(m_deviceController, stateChangedCallback, this);
1288  if (m_errorController != ARCONTROLLER_OK) {
1289  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "add State callback failed.");
1290  }
1291 
1292  // Adding commendReceived callback, called when the a command has been received from the device
1293  m_errorController = ARCONTROLLER_Device_AddCommandReceivedCallback(m_deviceController, commandReceivedCallback, this);
1294 
1295  if (m_errorController != ARCONTROLLER_OK) {
1296  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "add Command callback failed.");
1297  }
1298 
1299 #ifdef VISP_HAVE_FFMPEG
1300  // Adding frame received callback, called when a streaming frame has been received from the device
1301  m_errorController = ARCONTROLLER_Device_SetVideoStreamCallbacks(m_deviceController, decoderConfigCallback,
1302  didReceiveFrameCallback, nullptr, this);
1303 
1304  if (m_errorController != ARCONTROLLER_OK) {
1305  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error: %s", ARCONTROLLER_Error_ToString(m_errorController));
1306  }
1307 #endif
1308  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Callbacks set up.");
1309 }
1310 
1315 void vpRobotBebop2::startController()
1316 {
1317  // Starts the controller
1318  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "Connecting ...");
1319  m_errorController = ARCONTROLLER_Device_Start(m_deviceController);
1320 
1321  if (m_errorController != ARCONTROLLER_OK) {
1322  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error :%s", ARCONTROLLER_Error_ToString(m_errorController));
1323  }
1324 
1325  // Waits for the stateChangedCallback to unclock the semaphore
1326  ARSAL_Sem_Wait(&(m_stateSem));
1327 
1328  // Checks the device state
1329  m_deviceState = ARCONTROLLER_Device_GetState(m_deviceController, &m_errorController);
1330 
1331  if ((m_errorController != ARCONTROLLER_OK) || (m_deviceState != ARCONTROLLER_DEVICE_STATE_RUNNING)) {
1332  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- deviceState :%d", m_deviceState);
1333  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "- error :%s", ARCONTROLLER_Error_ToString(m_errorController));
1334  }
1335  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Controller started.");
1336 }
1337 
1338 #ifdef VISP_HAVE_FFMPEG
1344 void vpRobotBebop2::initCodec()
1345 {
1346  av_register_all();
1347  avcodec_register_all();
1348  avformat_network_init();
1349 
1350  // Finds the correct codec
1351  AVCodec *codec = avcodec_find_decoder(AV_CODEC_ID_H264);
1352  if (!codec) {
1353  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Codec not found.");
1354  return;
1355  }
1356 
1357  // Allocates memory for codec
1358  m_codecContext = avcodec_alloc_context3(codec);
1359 
1360  if (!m_codecContext) {
1361  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Failed to allocate codec context.");
1362  return;
1363  }
1364 
1365  // Sets codec parameters (TODO : should be done automaticaly by drone callback decoderConfigCallback)
1366  m_codecContext->pix_fmt = AV_PIX_FMT_YUV420P;
1367  m_codecContext->skip_frame = AVDISCARD_DEFAULT;
1368  m_codecContext->error_concealment = FF_EC_GUESS_MVS | FF_EC_DEBLOCK;
1369  m_codecContext->skip_loop_filter = AVDISCARD_DEFAULT;
1370  m_codecContext->workaround_bugs = AVMEDIA_TYPE_VIDEO;
1371  m_codecContext->codec_id = AV_CODEC_ID_H264;
1372  m_codecContext->skip_idct = AVDISCARD_DEFAULT;
1373 
1374  m_codecContext->width = m_videoWidth;
1375  m_codecContext->height = m_videoHeight;
1376 
1377  if (codec->capabilities & AV_CODEC_CAP_TRUNCATED) {
1378  m_codecContext->flags |= AV_CODEC_FLAG_TRUNCATED;
1379  }
1380  m_codecContext->flags2 |= AV_CODEC_FLAG2_CHUNKS;
1381 
1382  // Opens the codec
1383  if (avcodec_open2(m_codecContext, codec, nullptr) < 0) {
1384  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Failed to open codec.");
1385  return;
1386  }
1387 
1388  AVPixelFormat pFormat = AV_PIX_FMT_BGR24;
1389  int numBytes = av_image_get_buffer_size(pFormat, m_codecContext->width, m_codecContext->height, 1);
1390  m_buffer = static_cast<uint8_t *>(av_malloc(static_cast<unsigned long>(numBytes) * sizeof(uint8_t)));
1391 
1392  av_init_packet(&m_packet); // Packed used to send data to the decoder
1393  m_picture = av_frame_alloc(); // Frame used to receive data from the decoder
1394 
1395  m_bgr_picture_mutex.lock();
1396  m_bgr_picture = av_frame_alloc(); // Frame used to store rescaled frame received from the decoder
1397  m_bgr_picture_mutex.unlock();
1398 
1399  m_img_convert_ctx = sws_getContext(m_codecContext->width, m_codecContext->height, m_codecContext->pix_fmt,
1400  m_codecContext->width, m_codecContext->height, pFormat, SWS_BICUBIC, nullptr, nullptr,
1401  nullptr); // Used to rescale frame received from the decoder
1402 }
1403 
1409 void vpRobotBebop2::cleanUpCodec()
1410 {
1411  m_videoDecodingStarted = false;
1412  av_packet_unref(&m_packet);
1413 
1414  if (m_codecContext) {
1415  avcodec_flush_buffers(m_codecContext);
1416  avcodec_free_context(&m_codecContext);
1417  }
1418 
1419  if (m_picture) {
1420  av_frame_free(&m_picture);
1421  }
1422 
1423  if (m_bgr_picture) {
1424  m_bgr_picture_mutex.lock();
1425  av_frame_free(&m_bgr_picture);
1426  m_bgr_picture_mutex.unlock();
1427  }
1428 
1429  if (m_img_convert_ctx) {
1430  sws_freeContext(m_img_convert_ctx);
1431  }
1432  if (m_buffer) {
1433  av_free(m_buffer);
1434  }
1435 }
1436 
1442 void vpRobotBebop2::startVideoDecoding()
1443 {
1444  if (!m_videoDecodingStarted) {
1445  initCodec();
1446  m_videoDecodingStarted = true;
1447  }
1448  else {
1449  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Video decoding is already started.");
1450  }
1451 }
1452 
1458 void vpRobotBebop2::stopVideoDecoding()
1459 {
1460  if (m_videoDecodingStarted) {
1461  cleanUpCodec();
1462  }
1463  else {
1464  ARSAL_PRINT(ARSAL_PRINT_ERROR, "ERROR", "Video decoding is already stopped.");
1465  }
1466 }
1467 
1475 void vpRobotBebop2::computeFrame(ARCONTROLLER_Frame_t *frame)
1476 {
1477 
1478  // Updating codec parameters from SPS and PPS buffers received from the drone in decoderConfigCallback
1479  if (m_update_codec_params && m_codec_params_data.size()) {
1480  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "Updating H264 codec parameters (Buffer Size: %lu) ...",
1481  m_codec_params_data.size());
1482 
1483  m_packet.data = &m_codec_params_data[0];
1484  m_packet.size = static_cast<int>(m_codec_params_data.size());
1485 
1486  int ret = avcodec_send_packet(m_codecContext, &m_packet);
1487 
1488  if (ret == 0) {
1489 
1490  ret = avcodec_receive_frame(m_codecContext, m_picture);
1491 
1492  if (ret == 0 || ret == AVERROR(EAGAIN)) {
1493  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "H264 codec parameters updated.");
1494  }
1495  else {
1496  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Unexpected error while updating H264 parameters.");
1497  }
1498  }
1499  else {
1500  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Unexpected error while sending H264 parameters.");
1501  }
1502  m_update_codec_params = false;
1503  av_packet_unref(&m_packet);
1504  av_frame_unref(m_picture);
1505  }
1506 
1507  // Decoding frame coming from the drone
1508  m_packet.data = frame->data;
1509  m_packet.size = static_cast<int>(frame->used);
1510 
1511  int ret = avcodec_send_packet(m_codecContext, &m_packet);
1512  if (ret < 0) {
1513 
1514  char *errbuff = new char[AV_ERROR_MAX_STRING_SIZE];
1515  av_strerror(ret, errbuff, AV_ERROR_MAX_STRING_SIZE);
1516  std::string err(errbuff);
1517  delete[] errbuff;
1518  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Error sending a packet for decoding : %d, %s", ret, err.c_str());
1519 
1520  }
1521  else {
1522 
1523  ret = avcodec_receive_frame(m_codecContext, m_picture);
1524 
1525  if (ret < 0) {
1526 
1527  if (ret == AVERROR(EAGAIN)) {
1528  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "AVERROR(EAGAIN)"); // Not an error, need to send data again
1529  }
1530  else if (ret == AVERROR_EOF) {
1531  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "AVERROR_EOF"); // End of file reached, should not happen with drone footage
1532  }
1533  else {
1534 
1535  char *errbuff = new char[AV_ERROR_MAX_STRING_SIZE];
1536  av_strerror(ret, errbuff, AV_ERROR_MAX_STRING_SIZE);
1537  std::string err(errbuff);
1538  delete[] errbuff;
1539  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Error receiving a decoded frame : %d, %s", ret, err.c_str());
1540  }
1541  }
1542  else {
1543  m_bgr_picture_mutex.lock();
1544  av_frame_unref(m_bgr_picture);
1545  av_image_fill_arrays(m_bgr_picture->data, m_bgr_picture->linesize, m_buffer, AV_PIX_FMT_BGR24,
1546  m_codecContext->width, m_codecContext->height, 1);
1547 
1548  sws_scale(m_img_convert_ctx, (m_picture)->data, (m_picture)->linesize, 0, m_codecContext->height,
1549  (m_bgr_picture)->data, (m_bgr_picture)->linesize);
1550 
1551  m_bgr_picture_mutex.unlock();
1552  }
1553  }
1554 
1555  av_packet_unref(&m_packet);
1556 
1557  av_frame_unref(m_picture);
1558 }
1559 #endif // #ifdef VISP_HAVE_FFMPEG
1565 void vpRobotBebop2::cleanUp()
1566 {
1567  if (m_deviceController != nullptr) {
1568  // Lands the drone if not landed
1569  land();
1570 
1571 #ifdef VISP_HAVE_FFMPEG
1572  // Stops the streaming if not stopped
1573  stopStreaming();
1574 #endif
1575 
1576  // Deletes the controller
1577  m_deviceState = ARCONTROLLER_Device_GetState(m_deviceController, &m_errorController);
1578  if ((m_errorController == ARCONTROLLER_OK) && (m_deviceState != ARCONTROLLER_DEVICE_STATE_STOPPED)) {
1579 
1580  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "Disconnecting ...");
1581  m_errorController = ARCONTROLLER_Device_Stop(m_deviceController);
1582 
1583  if (m_errorController == ARCONTROLLER_OK) {
1584  // Wait for the semaphore to increment, it will when the controller changes its state to 'stopped'
1585  ARSAL_Sem_Wait(&(m_stateSem));
1586  }
1587  }
1588  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "Deleting device controller ...");
1589  ARCONTROLLER_Device_Delete(&m_deviceController);
1590 
1591  // Destroys the semaphore
1592  ARSAL_Sem_Destroy(&(m_stateSem));
1593 
1594  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "- Cleanup done.");
1595  }
1596  else {
1597 
1598  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Error while cleaning up memory.");
1599  }
1600  m_running = false;
1601 }
1602 
1603 //*** ***//
1604 //*** Callbacks ***//
1605 //*** ***//
1606 
1615 void vpRobotBebop2::stateChangedCallback(eARCONTROLLER_DEVICE_STATE newState, eARCONTROLLER_ERROR error,
1616  void *customData)
1617 {
1618  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Controller state changed, new state: %d.", newState);
1619  (void)error;
1620 
1621  vpRobotBebop2 *drone = static_cast<vpRobotBebop2 *>(customData);
1622  switch (newState) {
1623  case ARCONTROLLER_DEVICE_STATE_STOPPED:
1624  // Stopping the programm
1625  drone->m_running = false;
1626  // Incrementing semaphore
1627  ARSAL_Sem_Post(&(drone->m_stateSem));
1628  break;
1629 
1630  case ARCONTROLLER_DEVICE_STATE_RUNNING:
1631  // Incrementing semaphore
1632  ARSAL_Sem_Post(&(drone->m_stateSem));
1633  break;
1634 
1635  default:
1636  break;
1637  }
1638 }
1639 
1640 #ifdef VISP_HAVE_FFMPEG
1650 eARCONTROLLER_ERROR vpRobotBebop2::decoderConfigCallback(ARCONTROLLER_Stream_Codec_t codec, void *customData)
1651 {
1652  vpRobotBebop2 *drone = static_cast<vpRobotBebop2 *>(customData);
1653 
1654  uint8_t *sps_buffer_ptr = codec.parameters.h264parameters.spsBuffer;
1655  uint32_t sps_buffer_size = static_cast<uint32_t>(codec.parameters.h264parameters.spsSize);
1656  uint8_t *pps_buffer_ptr = codec.parameters.h264parameters.ppsBuffer;
1657  uint32_t pps_buffer_size = static_cast<uint32_t>(codec.parameters.h264parameters.ppsSize);
1658 
1659  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "H264 configuration packet received: #SPS: %d #PPS: %d", sps_buffer_size,
1660  pps_buffer_size);
1661 
1662  drone->m_update_codec_params = (sps_buffer_ptr && pps_buffer_ptr && sps_buffer_size && pps_buffer_size &&
1663  (pps_buffer_size < 32) && (sps_buffer_size < 32));
1664 
1665  if (drone->m_update_codec_params) {
1666  // If codec parameters where received from the drone, we store them to pass them to the decoder in the next call of
1667  // computeFrame
1668  drone->m_codec_params_data.resize(sps_buffer_size + pps_buffer_size);
1669  std::copy(sps_buffer_ptr, sps_buffer_ptr + sps_buffer_size, drone->m_codec_params_data.begin());
1670  std::copy(pps_buffer_ptr, pps_buffer_ptr + pps_buffer_size, drone->m_codec_params_data.begin() + sps_buffer_size);
1671  }
1672  else {
1673  // If data is invalid, we clear the vector
1674  drone->m_codec_params_data.clear();
1675  }
1676  return ARCONTROLLER_OK;
1677 }
1678 
1687 eARCONTROLLER_ERROR vpRobotBebop2::didReceiveFrameCallback(ARCONTROLLER_Frame_t *frame, void *customData)
1688 {
1689  vpRobotBebop2 *drone = static_cast<vpRobotBebop2 *>(customData);
1690 
1691  if (frame != nullptr) {
1692 
1693  if (drone->m_videoDecodingStarted) {
1694  drone->computeFrame(frame);
1695  }
1696 
1697  }
1698  else {
1699  ARSAL_PRINT(ARSAL_PRINT_WARNING, TAG, "frame is nullptr.");
1700  }
1701 
1702  return ARCONTROLLER_OK;
1703 }
1704 #endif // #ifdef VISP_HAVE_FFMPEG
1705 
1715 void vpRobotBebop2::cmdBatteryStateChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary,
1716  vpRobotBebop2 *drone)
1717 {
1718  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1719  ARCONTROLLER_DICTIONARY_ELEMENT_t *singleElement = nullptr;
1720 
1721  if (elementDictionary == nullptr) {
1722  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "elements is nullptr");
1723  return;
1724  }
1725 
1726  // Get the command received in the device controller
1727  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, singleElement);
1728 
1729  if (singleElement == nullptr) {
1730  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "singleElement is nullptr");
1731  return;
1732  }
1733 
1734  // Get the value
1735  HASH_FIND_STR(singleElement->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_BATTERYSTATECHANGED_PERCENT,
1736  arg);
1737 
1738  if (arg == nullptr) {
1739  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "arg is nullptr");
1740  return;
1741  }
1742  drone->m_batteryLevel = arg->value.U8;
1743  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Battery level changed : %u percent remaining.", drone->m_batteryLevel);
1744 
1745  if (drone->m_batteryLevel <= 5) {
1746  ARSAL_PRINT(ARSAL_PRINT_WARNING, TAG, " - WARNING, very low battery level, drone will stop soon !");
1747  }
1748  else if (drone->m_batteryLevel <= 10) {
1749  ARSAL_PRINT(ARSAL_PRINT_WARNING, TAG, " - Warning, low battery level !");
1750  }
1751 }
1752 
1763 void vpRobotBebop2::cmdCameraOrientationChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary,
1764  vpRobotBebop2 *drone)
1765 {
1766  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1767  ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr;
1768  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element);
1769  if (element != nullptr) {
1770  HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_CAMERASTATE_ORIENTATIONV2_TILT, arg);
1771 
1772  if (arg != nullptr) {
1773  drone->m_currentCameraTilt = static_cast<double>(arg->value.Float);
1774  }
1775 
1776  HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_CAMERASTATE_ORIENTATIONV2_PAN, arg);
1777  if (arg != nullptr) {
1778  drone->m_currentCameraPan = static_cast<double>(arg->value.Float);
1779  }
1780  }
1781 }
1782 
1794 void vpRobotBebop2::cmdCameraSettingsRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone)
1795 {
1796  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1797  ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr;
1798  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element);
1799  if (element != nullptr) {
1800  HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_FOV,
1801  arg);
1802  if (arg != nullptr) {
1803  drone->m_cameraHorizontalFOV = static_cast<double>(arg->value.Float);
1804  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Camera horizontal FOV : %f degrees.",
1805  static_cast<double>(drone->m_cameraHorizontalFOV));
1806  }
1807  HASH_FIND_STR(element->arguments,
1808  ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_PANMAX, arg);
1809  if (arg != nullptr) {
1810  drone->m_maxCameraPan = static_cast<double>(arg->value.Float);
1811  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Max camera pan : %f degrees.",
1812  static_cast<double>(drone->m_maxCameraPan));
1813  }
1814  HASH_FIND_STR(element->arguments,
1815  ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_PANMIN, arg);
1816  if (arg != nullptr) {
1817  drone->m_minCameraPan = static_cast<double>(arg->value.Float);
1818  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Min camera pan : %f degrees.",
1819  static_cast<double>(drone->m_minCameraPan));
1820  }
1821  HASH_FIND_STR(element->arguments,
1822  ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_TILTMAX, arg);
1823  if (arg != nullptr) {
1824  drone->m_maxCameraTilt = static_cast<double>(arg->value.Float);
1825  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Max camera tilt : %f degrees.",
1826  static_cast<double>(drone->m_maxCameraTilt));
1827  }
1828  HASH_FIND_STR(element->arguments,
1829  ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED_TILTMIN, arg);
1830  if (arg != nullptr) {
1831  drone->m_minCameraTilt = static_cast<double>(arg->value.Float);
1832  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, " - Min camera tilt : %f degrees.",
1833  static_cast<double>(drone->m_minCameraTilt));
1834  }
1835  }
1836 }
1837 
1848 void vpRobotBebop2::cmdMaxPitchRollChangedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary,
1849  vpRobotBebop2 *drone)
1850 {
1851  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1852  ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr;
1853 
1854  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element);
1855  if (element != nullptr) {
1856  HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSETTINGSSTATE_MAXTILTCHANGED_CURRENT,
1857  arg);
1858  if (arg != nullptr) {
1859  drone->m_maxTilt = static_cast<double>(arg->value.Float);
1860  }
1861  }
1862 }
1863 
1874 void vpRobotBebop2::cmdRelativeMoveEndedRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone)
1875 {
1876  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1877  ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr;
1878 
1879  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element);
1880 
1881  if (element != nullptr) {
1882  HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR, arg);
1883 
1884  if (arg != nullptr) {
1885  eARCOMMANDS_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR error =
1886  static_cast<eARCOMMANDS_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR>(arg->value.I32);
1887  if ((error != ARCOMMANDS_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR_OK) &&
1888  (error != ARCOMMANDS_ARDRONE3_PILOTINGEVENT_MOVEBYEND_ERROR_INTERRUPTED)) {
1889  ARSAL_PRINT(ARSAL_PRINT_ERROR, TAG, "Relative move ended with error %d", error);
1890  }
1891  drone->m_relativeMoveEnded = true;
1892  }
1893  }
1894 }
1895 
1906 void vpRobotBebop2::cmdExposureSetRcv(ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, vpRobotBebop2 *drone)
1907 {
1908  ARCONTROLLER_DICTIONARY_ARG_t *arg = nullptr;
1909  ARCONTROLLER_DICTIONARY_ELEMENT_t *element = nullptr;
1910 
1911  HASH_FIND_STR(elementDictionary, ARCONTROLLER_DICTIONARY_SINGLE_KEY, element);
1912 
1913  if (element != nullptr) {
1914 
1915  HASH_FIND_STR(element->arguments, ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PICTURESETTINGSSTATE_EXPOSITIONCHANGED_VALUE,
1916  arg);
1917 
1918  if (arg != nullptr) {
1919  drone->m_exposureSet = true;
1920  }
1921  }
1922 }
1923 
1933 void vpRobotBebop2::commandReceivedCallback(eARCONTROLLER_DICTIONARY_KEY commandKey,
1934  ARCONTROLLER_DICTIONARY_ELEMENT_t *elementDictionary, void *customData)
1935 {
1936  vpRobotBebop2 *drone = static_cast<vpRobotBebop2 *>(customData);
1937 
1938  if (drone == nullptr)
1939  return;
1940 
1941  switch (commandKey) {
1942  case ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_BATTERYSTATECHANGED:
1943  // If the command received is a battery state changed
1944  cmdBatteryStateChangedRcv(elementDictionary, drone);
1945  break;
1946 
1947  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSETTINGSSTATE_MAXTILTCHANGED:
1948  // If the command receivend is a max pitch/roll changed
1949  cmdMaxPitchRollChangedRcv(elementDictionary, drone);
1950  break;
1951 
1952  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGEVENT_MOVEBYEND:
1953  // If the command received is a relative move ended
1954  cmdRelativeMoveEndedRcv(elementDictionary, drone);
1955  break;
1956 
1957  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PILOTINGSTATE_FLATTRIMCHANGED:
1958  // If the command received is a flat trim finished
1959  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "Flat trim finished ...");
1960  drone->m_flatTrimFinished = true;
1961  break;
1962 
1963  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PICTURESETTINGSSTATE_EXPOSITIONCHANGED:
1964  // If the command received is a exposition changed
1965  cmdExposureSetRcv(elementDictionary, drone);
1966  break;
1967 
1968  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_PICTURESETTINGSSTATE_VIDEORESOLUTIONSCHANGED:
1969  // If the command received is a resolution changed
1970  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "Video resolution set ...");
1971  drone->m_videoResolutionSet = true;
1972  break;
1973 
1974  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOENABLECHANGED:
1975  // If the command received is a streaming started
1976  drone->m_streamingStarted = true;
1977  break;
1978 
1979  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_MEDIASTREAMINGSTATE_VIDEOSTREAMMODECHANGED:
1980  // If the command received is a streaming mode changed
1981  drone->m_streamingModeSet = true;
1982  break;
1983 
1984  case ARCONTROLLER_DICTIONARY_KEY_COMMON_SETTINGSSTATE_RESETCHANGED:
1985  // If the command received is a settings reset
1986  ARSAL_PRINT(ARSAL_PRINT_INFO, TAG, "Settings reset ...");
1987  drone->m_settingsReset = true;
1988  break;
1989 
1990  case ARCONTROLLER_DICTIONARY_KEY_ARDRONE3_CAMERASTATE_ORIENTATIONV2:
1991  // If the command received is a camera orientation changed
1992  cmdCameraOrientationChangedRcv(elementDictionary, drone);
1993  break;
1994 
1995  case ARCONTROLLER_DICTIONARY_KEY_COMMON_CAMERASETTINGSSTATE_CAMERASETTINGSCHANGED:
1996  // If the command received is a camera information sent
1997  cmdCameraSettingsRcv(elementDictionary, drone);
1998  break;
1999 
2000  default:
2001  break;
2002  }
2003 }
2004 
2005 #undef TAG
2006 END_VISP_NAMESPACE
2007 #elif !defined(VISP_BUILD_SHARED_LIBS)
2008 // Work around to avoid warning: libvisp_robot.a(vpRobotBebop2.cpp.o) has
2009 // no symbols
2010 void dummy_vpRobotBebop2() { };
2011 #endif // VISP_HAVE_ARSDK
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:349
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ fatalError
Fatal error.
Definition: vpException.h:72
static vpHomogeneousMatrix direct(const vpColVector &v)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpRotationMatrix getRotationMatrix() const
vpTranslationVector getTranslationVector() const
static void BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
static void BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
unsigned int getWidth() const
Definition: vpImage.h:242
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:542
Type * bitmap
points toward the bitmap
Definition: vpImage.h:135
unsigned int getHeight() const
Definition: vpImage.h:181
void setPitch(int value)
std::string getIpAddress()
double getMinCameraPan() const
void resetAllSettings()
void setMaxTilt(double maxTilt)
void setPosition(float dX, float dY, float dZ, float dPsi, bool blocking)
void setVelocity(const vpColVector &vel, double delta_t)
void setExposure(float expo)
double getCurrentCameraPan() const
void setVideoStabilisationMode(int mode)
void setRoll(int value)
double getMinCameraTilt() const
double getMaxCameraTilt() const
void setVerbose(bool verbose)
void setVerticalSpeed(int value)
void getGrayscaleImage(vpImage< unsigned char > &I)
void setStreamingMode(int mode)
static void land()
double getMaxTilt()
unsigned int getBatteryLevel()
void getRGBaImage(vpImage< vpRGBa > &I)
void setYawSpeed(int value)
void setCameraPan(double pan, bool blocking=false)
void takeOff(bool blocking=true)
virtual ~vpRobotBebop2()
double getCurrentCameraTilt() const
double getCameraHorizontalFOV() const
void setVideoResolution(int mode)
void setCameraTilt(double tilt, bool blocking=false)
vpRobotBebop2(bool verbose=false, bool setDefaultSettings=true, std::string ipAddress="192.168.42.1", int discoveryPort=44444)
void setCameraOrientation(double tilt, double pan, bool blocking=false)
double getMaxCameraPan() const
vpThetaUVector getThetaUVector()
Class that consider the case of a translation vector.
VISP_EXPORT void sleepMs(double t)