Public Member Functions | Protected Member Functions | Protected Attributes
srs_ui_but::CRosTopicTexture Class Reference

#include <but_rostexture.h>

List of all members.

Public Member Functions

void clear ()
 Clear.
 CRosTopicTexture (const ros::NodeHandle &nh, const std::string &texture_name, const std::string &encoding)
 Constructor - encoding in OpenCV format.
const Ogre::TexturePtr & getTexture ()
 Get current texture pointer.
std::string getTopic ()
 Get current topic.
void setTopic (const std::string &topic)
 Set topic to subscribe to.
bool update ()
 Update content of texture from message.
 ~CRosTopicTexture ()
 Constructor - encoding in Ogre format.

Protected Member Functions

void callback (const sensor_msgs::Image::ConstPtr &image)
 On new image callback function.

Protected Attributes

sensor_msgs::Image::ConstPtr m_current_image
std::string m_frame
image_transport::ImageTransport m_it
boost::mutex m_mutex
std::string m_name
 Texture name.
bool m_new_image
ros::NodeHandle m_nh
 Node handle.
boost::shared_ptr
< image_transport::SubscriberFilter
m_sub
CRosTextureConverter m_texture_converter
 Texture.
tf::TransformListenerm_tf_client
boost::shared_ptr
< tf::MessageFilter
< sensor_msgs::Image > > 
m_tf_filter
std::string m_topic
 Current topic.
std::string m_transport_type

Detailed Description

Definition at line 143 of file but_rostexture.h.


Constructor & Destructor Documentation

srs_ui_but::CRosTopicTexture::CRosTopicTexture ( const ros::NodeHandle nh,
const std::string &  texture_name,
const std::string &  encoding 
)

Constructor - encoding in OpenCV format.

Constructor

Definition at line 328 of file but_rostexture.cpp.

Constructor - encoding in Ogre format.

Destructor

Definition at line 343 of file but_rostexture.cpp.


Member Function Documentation

void srs_ui_but::CRosTopicTexture::callback ( const sensor_msgs::Image::ConstPtr &  image) [protected]

On new image callback function.

On new image data callback

Definition at line 447 of file but_rostexture.cpp.

Clear.

Clear data

Definition at line 428 of file but_rostexture.cpp.

const Ogre::TexturePtr& srs_ui_but::CRosTopicTexture::getTexture ( ) [inline]

Get current texture pointer.

Definition at line 162 of file but_rostexture.h.

std::string srs_ui_but::CRosTopicTexture::getTopic ( ) [inline]

Get current topic.

Definition at line 159 of file but_rostexture.h.

void srs_ui_but::CRosTopicTexture::setTopic ( const std::string &  topic)

Set topic to subscribe to.

Set topic to subscribe to

Definition at line 352 of file but_rostexture.cpp.

Update content of texture from message.

Update texture data

Definition at line 391 of file but_rostexture.cpp.


Member Data Documentation

sensor_msgs::Image::ConstPtr srs_ui_but::CRosTopicTexture::m_current_image [protected]

Definition at line 187 of file but_rostexture.h.

std::string srs_ui_but::CRosTopicTexture::m_frame [protected]

Definition at line 194 of file but_rostexture.h.

Definition at line 188 of file but_rostexture.h.

boost::mutex srs_ui_but::CRosTopicTexture::m_mutex [protected]

Definition at line 192 of file but_rostexture.h.

std::string srs_ui_but::CRosTopicTexture::m_name [protected]

Texture name.

Definition at line 182 of file but_rostexture.h.

Definition at line 193 of file but_rostexture.h.

Node handle.

Definition at line 176 of file but_rostexture.h.

Definition at line 189 of file but_rostexture.h.

Texture.

Definition at line 179 of file but_rostexture.h.

Definition at line 195 of file but_rostexture.h.

boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > srs_ui_but::CRosTopicTexture::m_tf_filter [protected]

Definition at line 190 of file but_rostexture.h.

std::string srs_ui_but::CRosTopicTexture::m_topic [protected]

Current topic.

Definition at line 185 of file but_rostexture.h.

Definition at line 191 of file but_rostexture.h.


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


srs_ui_but
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Michal Spanel (spanel@fit.vutbr.cz), Tomas Lokaj
autogenerated on Mon Oct 6 2014 08:49:31