#include <bebop.h>
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< VideoDecoder > | video_decoder_ptr_ |
Static Private Attributes | |
static const char * | LOG_TAG = "BebopSDK" |
typedef std::pair<eARCONTROLLER_DICTIONARY_KEY, boost::shared_ptr<cb::AbstractCommand> > bebop_driver::Bebop::callback_map_pair_t [private] |
typedef std::map<eARCONTROLLER_DICTIONARY_KEY, boost::shared_ptr<cb::AbstractCommand> > bebop_driver::Bebop::callback_map_t [private] |
bebop_driver::Bebop::Bebop | ( | ARSAL_Print_Callback_t | custom_print_callback = 0 | ) | [explicit] |
void bebop_driver::Bebop::AnimationFlip | ( | const uint8_t & | anim_id | ) |
void bebop_driver::Bebop::Cleanup | ( | ) | [private] |
void bebop_driver::Bebop::CommandReceivedCallback | ( | eARCONTROLLER_DICTIONARY_KEY | cmd_key, |
ARCONTROLLER_DICTIONARY_ELEMENT_t * | element_dict_ptr, | ||
void * | bebop_void_ptr | ||
) | [static, private] |
void bebop_driver::Bebop::Connect | ( | ros::NodeHandle & | nh, |
ros::NodeHandle & | priv_nh, | ||
const std::string & | bebop_ip = "192.168.42.1" |
||
) |
eARCONTROLLER_ERROR bebop_driver::Bebop::DecoderConfigCallback | ( | ARCONTROLLER_Stream_Codec_t | codec, |
void * | bebop_void_ptr | ||
) | [static, private] |
void bebop_driver::Bebop::Disconnect | ( | ) |
void bebop_driver::Bebop::Emergency | ( | ) |
void bebop_driver::Bebop::FlatTrim | ( | ) |
eARCONTROLLER_ERROR bebop_driver::Bebop::FrameReceivedCallback | ( | ARCONTROLLER_Frame_t * | frame, |
void * | bebop_void_ptr | ||
) | [static, private] |
const ARCONTROLLER_Device_t* bebop_driver::Bebop::GetControllerCstPtr | ( | ) | const [inline] |
bool bebop_driver::Bebop::GetFrontCameraFrame | ( | std::vector< uint8_t > & | buffer, |
uint32_t & | width, | ||
uint32_t & | height | ||
) | const |
uint32_t bebop_driver::Bebop::GetFrontCameraFrameHeight | ( | ) | const |
uint32_t bebop_driver::Bebop::GetFrontCameraFrameWidth | ( | ) | const |
ARSAL_Sem_t* bebop_driver::Bebop::GetStateSemPtr | ( | ) | [inline] |
bool bebop_driver::Bebop::IsConnected | ( | ) | const [inline] |
bool bebop_driver::Bebop::IsStreamingStarted | ( | ) | const [inline] |
void bebop_driver::Bebop::Land | ( | ) |
void bebop_driver::Bebop::Move | ( | const double & | roll, |
const double & | pitch, | ||
const double & | gaz_speed, | ||
const double & | yaw_speed | ||
) |
void bebop_driver::Bebop::MoveCamera | ( | const double & | tilt, |
const double & | pan | ||
) |
void bebop_driver::Bebop::NavigateHome | ( | const bool & | start_stop | ) |
void bebop_driver::Bebop::SetDate | ( | const std::string & | date | ) |
void bebop_driver::Bebop::SetExposure | ( | const float & | exposure | ) |
void bebop_driver::Bebop::StartAutonomousFlight | ( | const std::string & | filepath | ) |
void bebop_driver::Bebop::StartStreaming | ( | ) |
void bebop_driver::Bebop::StateChangedCallback | ( | eARCONTROLLER_DEVICE_STATE | new_state, |
eARCONTROLLER_ERROR | error, | ||
void * | bebop_void_ptr | ||
) | [static, private] |
void bebop_driver::Bebop::StopStreaming | ( | ) |
void bebop_driver::Bebop::Takeoff | ( | ) |
void bebop_driver::Bebop::TakeSnapshot | ( | ) |
void bebop_driver::Bebop::ThrowOnCtrlError | ( | const eARCONTROLLER_ERROR & | error, |
const std::string & | message = std::string() |
||
) | [private] |
void bebop_driver::Bebop::ThrowOnInternalError | ( | const std::string & | message = std::string() | ) | [private] |
void bebop_driver::Bebop::ToggleVideoRecording | ( | const bool | start | ) |
void bebop_driver::Bebop::UpdateSettings | ( | const bebop_driver::BebopArdrone3Config & | config | ) |
std::string bebop_driver::Bebop::bebop_ip_ [private] |
ARCONTROLLER_Device_t* bebop_driver::Bebop::device_controller_ptr_ [private] |
ARDISCOVERY_Device_t* bebop_driver::Bebop::device_ptr_ [private] |
eARCONTROLLER_DEVICE_STATE bebop_driver::Bebop::device_state_ [private] |
eARCONTROLLER_ERROR bebop_driver::Bebop::error_ [private] |
boost::condition_variable bebop_driver::Bebop::frame_avail_cond_ [mutable, private] |
boost::mutex bebop_driver::Bebop::frame_avail_mutex_ [mutable, private] |
boost::atomic<bool> bebop_driver::Bebop::is_connected_ [private] |
bool bebop_driver::Bebop::is_frame_avail_ [mutable, private] |
boost::atomic<bool> bebop_driver::Bebop::is_streaming_started_ [private] |
const char * bebop_driver::Bebop::LOG_TAG = "BebopSDK" [static, private] |
ARSAL_Sem_t bebop_driver::Bebop::state_sem_ [private] |
boost::shared_ptr<VideoDecoder> bebop_driver::Bebop::video_decoder_ptr_ [private] |