bebop.h
Go to the documentation of this file.
00001 
00025 #ifndef BEBOP_AUTONOMY_BEBOP_H
00026 #define BEBOP_AUTONOMY_BEBOP_H
00027 
00028 #define BEBOP_ERR_STR_SZ  150
00029 
00030 #include <sys/syscall.h>
00031 #include <sys/types.h>
00032 
00033 #include <string>
00034 #include <vector>
00035 #include <utility>
00036 #include <map>
00037 
00038 #include <boost/shared_ptr.hpp>
00039 #include <boost/atomic.hpp>
00040 #include <boost/thread/mutex.hpp>
00041 #include <boost/thread/condition_variable.hpp>
00042 
00043 extern "C"
00044 {
00045   #include "libARSAL/ARSAL.h"
00046   #include "libARController/ARController.h"
00047 }
00048 
00049 // Forward declarations
00050 extern "C"
00051 {
00052   struct ARDISCOVERY_Device_t;
00053 }
00054 namespace ros
00055 {
00056   class NodeHandle;
00057 }
00058 
00059 namespace bebop_driver
00060 {
00061 
00062 namespace util
00063 {
00064 inline long int GetLWPId()
00065 {
00066   return (syscall(SYS_gettid));
00067 }
00068 
00069 }  // namespace util
00070 
00071 // Forward declarations
00072 class BebopArdrone3Config;
00073 class VideoDecoder;
00074 namespace cb
00075 {
00076   class AbstractCommand;
00077 }  // namespace cb
00078 #define FORWARD_DECLARATIONS
00079 #include "bebop_driver/autogenerated/common_state_callback_includes.h"
00080 #include "bebop_driver/autogenerated/ardrone3_state_callback_includes.h"
00081 #include "bebop_driver/autogenerated/ardrone3_setting_callback_includes.h"
00082 #undef FORWARD_DECLARATIONS
00083 
00084 class Bebop
00085 {
00086 private:
00087   static const char* LOG_TAG;
00088   boost::atomic<bool> is_connected_;
00089   boost::atomic<bool> is_streaming_started_;
00090   ARDISCOVERY_Device_t* device_ptr_;
00091   ARCONTROLLER_Device_t* device_controller_ptr_;
00092   eARCONTROLLER_ERROR error_;
00093   eARCONTROLLER_DEVICE_STATE device_state_;
00094   ARSAL_Sem_t state_sem_;
00095   boost::shared_ptr<VideoDecoder> video_decoder_ptr_;
00096   std::string bebop_ip_;
00097 
00098 //  boost::mutex callback_map_mutex_;
00099   typedef std::map<eARCONTROLLER_DICTIONARY_KEY, boost::shared_ptr<cb::AbstractCommand> > callback_map_t;
00100   typedef std::pair<eARCONTROLLER_DICTIONARY_KEY, boost::shared_ptr<cb::AbstractCommand> > callback_map_pair_t;
00101   callback_map_t callback_map_;
00102 
00103   // sync
00104   mutable boost::condition_variable frame_avail_cond_;
00105   mutable boost::mutex frame_avail_mutex_;
00106   mutable bool is_frame_avail_;
00107 
00108   static void StateChangedCallback(
00109       eARCONTROLLER_DEVICE_STATE new_state,
00110       eARCONTROLLER_ERROR error,
00111       void *bebop_void_ptr);
00112 
00113   static void CommandReceivedCallback(
00114       eARCONTROLLER_DICTIONARY_KEY cmd_key,
00115       ARCONTROLLER_DICTIONARY_ELEMENT_t* element_dict_ptr,
00116       void* bebop_void_ptr);
00117 
00118   static eARCONTROLLER_ERROR FrameReceivedCallback(ARCONTROLLER_Frame_t *frame,
00119       void *bebop_void_ptr);
00120 
00121   static eARCONTROLLER_ERROR DecoderConfigCallback(ARCONTROLLER_Stream_Codec_t codec,
00122       void *bebop_void_ptr);
00123 
00124   // nothrow
00125   void Cleanup();
00126 
00127   void ThrowOnInternalError(const std::string& message = std::string());
00128   void ThrowOnCtrlError(const eARCONTROLLER_ERROR& error, const std::string& message = std::string());
00129 
00130 public:
00131   // Navdata Callbacks
00132 #define DEFINE_SHARED_PTRS
00133 #include "bebop_driver/autogenerated/common_state_callback_includes.h"
00134 #include "bebop_driver/autogenerated/ardrone3_state_callback_includes.h"
00135 #include "bebop_driver/autogenerated/ardrone3_setting_callback_includes.h"
00136 #undef DEFINE_SHARED_PTRS
00137 
00138   inline ARSAL_Sem_t* GetStateSemPtr() {return &state_sem_;}
00139   inline const ARCONTROLLER_Device_t* GetControllerCstPtr() const {return device_controller_ptr_;}
00140 
00141   inline bool IsConnected() const {return is_connected_;}
00142   inline bool IsStreamingStarted() const {return is_streaming_started_;}
00143 
00144   explicit Bebop(ARSAL_Print_Callback_t custom_print_callback = 0);
00145   ~Bebop();
00146 
00147   void Connect(ros::NodeHandle& nh, ros::NodeHandle& priv_nh, const std::string& bebop_ip = "192.168.42.1");
00148   void StartStreaming();
00149 
00150   // Disable all data callback and streaming (nothrow)
00151   void StopStreaming();
00152   // nothrow
00153   void Disconnect();
00154 
00155   void SetDate(const std::string &date);
00156   void RequestAllSettings();
00157   void ResetAllSettings();
00158   void UpdateSettings(const bebop_driver::BebopArdrone3Config& config);
00159 
00160   void Takeoff();
00161   void Land();
00162   void Emergency();
00163   void FlatTrim();
00164   // false: Stop, true: Start
00165   void NavigateHome(const bool& start_stop);
00166   void StartAutonomousFlight(const std::string &filepath);
00167   void PauseAutonomousFlight();
00168   void StopAutonomousFlight();
00169   void AnimationFlip(const uint8_t& anim_id);
00170 
00171   // -1..1
00172   void Move(const double& roll, const double& pitch, const double& gaz_speed, const double& yaw_speed);
00173   void MoveCamera(const double& tilt, const double& pan);
00174 
00175   void TakeSnapshot();
00176   // exposure should be between -3.0 and +3.0
00177   void SetExposure(const float& exposure);
00178   // true: start, false: stop
00179   void ToggleVideoRecording(const bool start);
00180 
00181   // This function is blocking and runs in the caller's thread's context
00182   // which is different from FrameReceivedCallback's context
00183   bool GetFrontCameraFrame(std::vector<uint8_t>& buffer, uint32_t &width, uint32_t &height) const;
00184   uint32_t GetFrontCameraFrameWidth() const;
00185   uint32_t GetFrontCameraFrameHeight() const;
00186 };
00187 
00188 }  // namespace bebop_driver
00189 
00190 
00191 #endif  // BEBOP_AUTONOMY_BEBOP_H


bebop_driver
Author(s): Mani Monajjemi
autogenerated on Sat Jun 8 2019 20:37:45