Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes
bebop_driver::Bebop Class Reference

#include <bebop.h>

List of all members.

Public Member Functions

void AnimationFlip (const uint8_t &anim_id)
 Bebop (ARSAL_Print_Callback_t custom_print_callback=0)
void Connect (ros::NodeHandle &nh, ros::NodeHandle &priv_nh, const std::string &bebop_ip="192.168.42.1")
void Disconnect ()
void Emergency ()
void FlatTrim ()
const ARCONTROLLER_Device_t * GetControllerCstPtr () const
bool GetFrontCameraFrame (std::vector< uint8_t > &buffer, uint32_t &width, uint32_t &height) const
uint32_t GetFrontCameraFrameHeight () const
uint32_t GetFrontCameraFrameWidth () const
ARSAL_Sem_t * GetStateSemPtr ()
bool IsConnected () const
bool IsStreamingStarted () const
void Land ()
void Move (const double &roll, const double &pitch, const double &gaz_speed, const double &yaw_speed)
void MoveCamera (const double &tilt, const double &pan)
void NavigateHome (const bool &start_stop)
void PauseAutonomousFlight ()
void RequestAllSettings ()
void ResetAllSettings ()
void SetDate (const std::string &date)
void SetExposure (const float &exposure)
void StartAutonomousFlight (const std::string &filepath)
void StartStreaming ()
void StopAutonomousFlight ()
void StopStreaming ()
void Takeoff ()
void TakeSnapshot ()
void ToggleVideoRecording (const bool start)
void UpdateSettings (const bebop_driver::BebopArdrone3Config &config)
 ~Bebop ()

Private Types

typedef std::pair
< eARCONTROLLER_DICTIONARY_KEY,
boost::shared_ptr
< cb::AbstractCommand > > 
callback_map_pair_t
typedef std::map
< eARCONTROLLER_DICTIONARY_KEY,
boost::shared_ptr
< cb::AbstractCommand > > 
callback_map_t

Private Member Functions

void Cleanup ()
void ThrowOnCtrlError (const eARCONTROLLER_ERROR &error, const std::string &message=std::string())
void ThrowOnInternalError (const std::string &message=std::string())

Static Private Member Functions

static void CommandReceivedCallback (eARCONTROLLER_DICTIONARY_KEY cmd_key, ARCONTROLLER_DICTIONARY_ELEMENT_t *element_dict_ptr, void *bebop_void_ptr)
static eARCONTROLLER_ERROR DecoderConfigCallback (ARCONTROLLER_Stream_Codec_t codec, void *bebop_void_ptr)
static eARCONTROLLER_ERROR FrameReceivedCallback (ARCONTROLLER_Frame_t *frame, void *bebop_void_ptr)
static void StateChangedCallback (eARCONTROLLER_DEVICE_STATE new_state, eARCONTROLLER_ERROR error, void *bebop_void_ptr)

Private Attributes

std::string bebop_ip_
callback_map_t callback_map_
ARCONTROLLER_Device_t * device_controller_ptr_
ARDISCOVERY_Device_t * device_ptr_
eARCONTROLLER_DEVICE_STATE device_state_
eARCONTROLLER_ERROR error_
boost::condition_variable frame_avail_cond_
boost::mutex frame_avail_mutex_
boost::atomic< bool > is_connected_
bool is_frame_avail_
boost::atomic< bool > is_streaming_started_
ARSAL_Sem_t state_sem_
boost::shared_ptr< VideoDecodervideo_decoder_ptr_

Static Private Attributes

static const char * LOG_TAG = "BebopSDK"

Detailed Description

Definition at line 84 of file bebop.h.


Member Typedef Documentation

typedef std::pair<eARCONTROLLER_DICTIONARY_KEY, boost::shared_ptr<cb::AbstractCommand> > bebop_driver::Bebop::callback_map_pair_t [private]

Definition at line 100 of file bebop.h.

typedef std::map<eARCONTROLLER_DICTIONARY_KEY, boost::shared_ptr<cb::AbstractCommand> > bebop_driver::Bebop::callback_map_t [private]

Definition at line 99 of file bebop.h.


Constructor & Destructor Documentation

bebop_driver::Bebop::Bebop ( ARSAL_Print_Callback_t  custom_print_callback = 0) [explicit]

Definition at line 210 of file bebop.cpp.

Definition at line 228 of file bebop.cpp.


Member Function Documentation

void bebop_driver::Bebop::AnimationFlip ( const uint8_t &  anim_id)

Definition at line 505 of file bebop.cpp.

void bebop_driver::Bebop::Cleanup ( ) [private]

Definition at line 324 of file bebop.cpp.

void bebop_driver::Bebop::CommandReceivedCallback ( eARCONTROLLER_DICTIONARY_KEY  cmd_key,
ARCONTROLLER_DICTIONARY_ELEMENT_t *  element_dict_ptr,
void *  bebop_void_ptr 
) [static, private]

Definition at line 104 of file bebop.cpp.

void bebop_driver::Bebop::Connect ( ros::NodeHandle nh,
ros::NodeHandle priv_nh,
const std::string &  bebop_ip = "192.168.42.1" 
)

Definition at line 236 of file bebop.cpp.

eARCONTROLLER_ERROR bebop_driver::Bebop::DecoderConfigCallback ( ARCONTROLLER_Stream_Codec_t  codec,
void *  bebop_void_ptr 
) [static, private]

Definition at line 139 of file bebop.cpp.

Definition at line 386 of file bebop.cpp.

Definition at line 456 of file bebop.cpp.

Definition at line 464 of file bebop.cpp.

eARCONTROLLER_ERROR bebop_driver::Bebop::FrameReceivedCallback ( ARCONTROLLER_Frame_t *  frame,
void *  bebop_void_ptr 
) [static, private]

Definition at line 168 of file bebop.cpp.

const ARCONTROLLER_Device_t* bebop_driver::Bebop::GetControllerCstPtr ( ) const [inline]

Definition at line 139 of file bebop.h.

bool bebop_driver::Bebop::GetFrontCameraFrame ( std::vector< uint8_t > &  buffer,
uint32_t &  width,
uint32_t &  height 
) const

Definition at line 572 of file bebop.cpp.

Definition at line 567 of file bebop.cpp.

Definition at line 562 of file bebop.cpp.

ARSAL_Sem_t* bebop_driver::Bebop::GetStateSemPtr ( ) [inline]

Definition at line 138 of file bebop.h.

bool bebop_driver::Bebop::IsConnected ( ) const [inline]

Definition at line 141 of file bebop.h.

bool bebop_driver::Bebop::IsStreamingStarted ( ) const [inline]

Definition at line 142 of file bebop.h.

Definition at line 448 of file bebop.cpp.

void bebop_driver::Bebop::Move ( const double &  roll,
const double &  pitch,
const double &  gaz_speed,
const double &  yaw_speed 
)

Definition at line 519 of file bebop.cpp.

void bebop_driver::Bebop::MoveCamera ( const double &  tilt,
const double &  pan 
)

Definition at line 553 of file bebop.cpp.

void bebop_driver::Bebop::NavigateHome ( const bool &  start_stop)

Definition at line 472 of file bebop.cpp.

Definition at line 489 of file bebop.cpp.

Definition at line 402 of file bebop.cpp.

Definition at line 410 of file bebop.cpp.

void bebop_driver::Bebop::SetDate ( const std::string &  date)

Definition at line 394 of file bebop.cpp.

void bebop_driver::Bebop::SetExposure ( const float &  exposure)

Definition at line 610 of file bebop.cpp.

void bebop_driver::Bebop::StartAutonomousFlight ( const std::string &  filepath)

Definition at line 481 of file bebop.cpp.

Definition at line 345 of file bebop.cpp.

void bebop_driver::Bebop::StateChangedCallback ( eARCONTROLLER_DEVICE_STATE  new_state,
eARCONTROLLER_ERROR  error,
void *  bebop_void_ptr 
) [static, private]

Definition at line 88 of file bebop.cpp.

Definition at line 497 of file bebop.cpp.

Definition at line 369 of file bebop.cpp.

Definition at line 440 of file bebop.cpp.

Definition at line 602 of file bebop.cpp.

void bebop_driver::Bebop::ThrowOnCtrlError ( const eARCONTROLLER_ERROR &  error,
const std::string &  message = std::string() 
) [private]

Definition at line 636 of file bebop.cpp.

void bebop_driver::Bebop::ThrowOnInternalError ( const std::string &  message = std::string()) [private]

Definition at line 628 of file bebop.cpp.

void bebop_driver::Bebop::ToggleVideoRecording ( const bool  start)

Definition at line 619 of file bebop.cpp.

void bebop_driver::Bebop::UpdateSettings ( const bebop_driver::BebopArdrone3Config &  config)

Definition at line 420 of file bebop.cpp.


Member Data Documentation

std::string bebop_driver::Bebop::bebop_ip_ [private]

Definition at line 96 of file bebop.h.

Definition at line 101 of file bebop.h.

ARCONTROLLER_Device_t* bebop_driver::Bebop::device_controller_ptr_ [private]

Definition at line 91 of file bebop.h.

ARDISCOVERY_Device_t* bebop_driver::Bebop::device_ptr_ [private]

Definition at line 90 of file bebop.h.

eARCONTROLLER_DEVICE_STATE bebop_driver::Bebop::device_state_ [private]

Definition at line 93 of file bebop.h.

eARCONTROLLER_ERROR bebop_driver::Bebop::error_ [private]

Definition at line 92 of file bebop.h.

boost::condition_variable bebop_driver::Bebop::frame_avail_cond_ [mutable, private]

Definition at line 104 of file bebop.h.

boost::mutex bebop_driver::Bebop::frame_avail_mutex_ [mutable, private]

Definition at line 105 of file bebop.h.

boost::atomic<bool> bebop_driver::Bebop::is_connected_ [private]

Definition at line 88 of file bebop.h.

bool bebop_driver::Bebop::is_frame_avail_ [mutable, private]

Definition at line 106 of file bebop.h.

boost::atomic<bool> bebop_driver::Bebop::is_streaming_started_ [private]

Definition at line 89 of file bebop.h.

const char * bebop_driver::Bebop::LOG_TAG = "BebopSDK" [static, private]

Definition at line 87 of file bebop.h.

ARSAL_Sem_t bebop_driver::Bebop::state_sem_ [private]

Definition at line 94 of file bebop.h.

Definition at line 95 of file bebop.h.


The documentation for this class was generated from the following files:


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