RGBDCameraPlugin Class Reference

#include <RGBDCameraPlugin.hh>

Public Member Functions

 RGBDCameraPlugin ()
 Constructs the object. More...
 
virtual ~RGBDCameraPlugin ()
 Destroys the object. More...
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Loads the plugin. More...
 
void onNewRGBFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Callback function for handling RGB frame updates. More...
 
void onNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Callback function for handling depth frame updates. More...
 

Private Member Functions

void onUpdate ()
 Callback function for handling world update event. More...
 
void onRequest (CameraRequestPtr &_msg)
 Callback function for handling incoming requests. More...
 
void saveRenderRGB ()
 TODO. More...
 
void saveRenderDepth ()
 TODO. More...
 
void saveDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format, const std::string &_filename)
 TODO. More...
 
void clearQueues ()
 TODO. More...
 

Static Private Member Functions

static int OgrePixelFormat (const std::string &_format)
 Get the OGRE image pixel format As seen in gazebo/rendering/Camera.cc. More...
 

Private Attributes

std::unique_ptr< RGBDCameraPluginPrivatedata_ptr
 Class with private attributes. More...
 
physics::ModelPtr model
 Camera model. More...
 
physics::WorldPtr world
 World. More...
 
rendering::DepthCameraPtr camera
 Pointer to depth camera renderer. More...
 
event::ConnectionPtr updateConn
 Pointer to world update callback connection. More...
 
event::ConnectionPtr newRGBFrameConn
 Pointer to RGB camera callback connection. More...
 
event::ConnectionPtr newDepthFrameConn
 Pointer to depth camera callback connection. More...
 
std::thread thread_rgb
 Auxiliar thread for saving RGB frames to disk. More...
 
std::thread thread_depth
 Auxiliar thread for saving depth frames to disk. More...
 
bool stop_thread {false}
 Flag to stop thread execution. More...
 
ConcurrentQueue< unsigned char * > * rgb_queue
 Multithread safe queue for RGB data. More...
 
ConcurrentQueue< float * > * depth_queue
 Multithread safe queue for depth data. More...
 
std::string output_dir
 Render output directory. More...
 
std::string output_prefix {""}
 Rendered output filename prefix. More...
 
std::string output_ext
 Rendered output format. More...
 
bool capture {false}
 Flag for capture request. More...
 
bool update_pose {false}
 Flag for pose update request. More...
 
ignition::math::Pose3d new_pose
 New desired pose. More...
 
bool rgb_captured {false}
 Flag for RGB successfully captured. More...
 
bool depth_captured {false}
 Flag for depth successfully captured. More...
 

Constructor & Destructor Documentation

Constructs the object.

~RGBDCameraPlugin ( )
virtual

Destroys the object.

Member Function Documentation

void clearQueues ( )
private

TODO.

void Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
virtual

Loads the plugin.

Parameters
_modelThe model pointer
_sdfThe sdf element pointer
int OgrePixelFormat ( const std::string &  _format)
staticprivate

Get the OGRE image pixel format As seen in gazebo/rendering/Camera.cc.

Parameters
[in]_formatThe Gazebo image format
Returns
Integer representation of the Ogre image format
void onNewDepthFrame ( const float *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)

Callback function for handling depth frame updates.

Parameters
_imageImage data
_widthImage width
_heightImage height
_depthImage depth
_formatImage format
void onNewRGBFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)

Callback function for handling RGB frame updates.

Parameters
_imageImage data
_widthImage width
_heightImage height
_depthImage depth
_formatImage format
void onRequest ( CameraRequestPtr _msg)
private

Callback function for handling incoming requests.

Parameters
_msgThe message
void onUpdate ( )
private

Callback function for handling world update event.

void saveDepthFrame ( const float *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format,
const std::string &  _filename 
)
private

TODO.

void saveRenderDepth ( )
private

TODO.

void saveRenderRGB ( )
private

TODO.

Member Data Documentation

rendering::DepthCameraPtr camera
private

Pointer to depth camera renderer.

bool capture {false}
private

Flag for capture request.

std::unique_ptr<RGBDCameraPluginPrivate> data_ptr
private

Class with private attributes.

bool depth_captured {false}
private

Flag for depth successfully captured.

ConcurrentQueue<float*>* depth_queue
private

Multithread safe queue for depth data.

physics::ModelPtr model
private

Camera model.

ignition::math::Pose3d new_pose
private

New desired pose.

event::ConnectionPtr newDepthFrameConn
private

Pointer to depth camera callback connection.

event::ConnectionPtr newRGBFrameConn
private

Pointer to RGB camera callback connection.

std::string output_dir
private

Render output directory.

std::string output_ext
private

Rendered output format.

std::string output_prefix {""}
private

Rendered output filename prefix.

bool rgb_captured {false}
private

Flag for RGB successfully captured.

ConcurrentQueue<unsigned char*>* rgb_queue
private

Multithread safe queue for RGB data.

bool stop_thread {false}
private

Flag to stop thread execution.

std::thread thread_depth
private

Auxiliar thread for saving depth frames to disk.

std::thread thread_rgb
private

Auxiliar thread for saving RGB frames to disk.

bool update_pose {false}
private

Flag for pose update request.

event::ConnectionPtr updateConn
private

Pointer to world update callback connection.

physics::WorldPtr world
private

World.


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