rviz::ROSImageTexture Class Reference

#include <ros_image_texture.h>

List of all members.

Public Member Functions

void clear ()
void getAvailableTransportTypes (V_string &types)
uint32_t getHeight ()
const
sensor_msgs::Image::ConstPtr & 
getImage ()
uint32_t getImageCount ()
image_transport::ImageTransport & getImageTransport ()
const Ogre::TexturePtr & getTexture ()
const std::string & getTransportType ()
uint32_t getWidth ()
 ROSImageTexture (const ros::NodeHandle &nh)
void setFrame (const std::string &frame, tf::TransformListener *tf_client)
void setTopic (const std::string &topic)
void setTransportType (const std::string &transport_type)
bool update ()
 ~ROSImageTexture ()

Private Member Functions

void callback (const sensor_msgs::Image::ConstPtr &image)

Private Attributes

sensor_msgs::Image::ConstPtr current_image_
Ogre::Image empty_image_
std::string frame_
uint32_t height_
uint32_t image_count_
image_transport::ImageTransport it_
boost::mutex mutex_
bool new_image_
ros::NodeHandle nh_
boost::shared_ptr
< image_transport::SubscriberFilter > 
sub_
Ogre::TexturePtr texture_
tf::TransformListener * tf_client_
boost::shared_ptr
< tf::MessageFilter
< sensor_msgs::Image > > 
tf_filter_
std::string topic_
std::string transport_type_
uint32_t width_

Detailed Description

Definition at line 67 of file ros_image_texture.h.


Constructor & Destructor Documentation

rviz::ROSImageTexture::ROSImageTexture ( const ros::NodeHandle &  nh  ) 

Definition at line 34 of file ros_image_texture.cpp.

rviz::ROSImageTexture::~ROSImageTexture (  ) 

Definition at line 52 of file ros_image_texture.cpp.


Member Function Documentation

void rviz::ROSImageTexture::callback ( const sensor_msgs::Image::ConstPtr &  image  )  [private]

Definition at line 254 of file ros_image_texture.cpp.

void rviz::ROSImageTexture::clear (  ) 

Definition at line 57 of file ros_image_texture.cpp.

void rviz::ROSImageTexture::getAvailableTransportTypes ( V_string types  ) 

Definition at line 120 of file ros_image_texture.cpp.

uint32_t rviz::ROSImageTexture::getHeight (  )  [inline]

Definition at line 82 of file ros_image_texture.h.

const sensor_msgs::Image::ConstPtr & rviz::ROSImageTexture::getImage (  ) 

Definition at line 142 of file ros_image_texture.cpp.

uint32_t rviz::ROSImageTexture::getImageCount (  )  [inline]

Definition at line 83 of file ros_image_texture.h.

image_transport::ImageTransport& rviz::ROSImageTexture::getImageTransport (  )  [inline]

Definition at line 85 of file ros_image_texture.h.

const Ogre::TexturePtr& rviz::ROSImageTexture::getTexture (  )  [inline]

Definition at line 78 of file ros_image_texture.h.

const std::string& rviz::ROSImageTexture::getTransportType (  )  [inline]

Definition at line 88 of file ros_image_texture.h.

uint32_t rviz::ROSImageTexture::getWidth (  )  [inline]

Definition at line 81 of file ros_image_texture.h.

void rviz::ROSImageTexture::setFrame ( const std::string &  frame,
tf::TransformListener *  tf_client 
)

Definition at line 75 of file ros_image_texture.cpp.

void rviz::ROSImageTexture::setTopic ( const std::string &  topic  ) 

Definition at line 82 of file ros_image_texture.cpp.

void rviz::ROSImageTexture::setTransportType ( const std::string &  transport_type  ) 

Definition at line 114 of file ros_image_texture.cpp.

bool rviz::ROSImageTexture::update (  ) 

Definition at line 149 of file ros_image_texture.cpp.


Member Data Documentation

sensor_msgs::Image::ConstPtr rviz::ROSImageTexture::current_image_ [private]

Definition at line 101 of file ros_image_texture.h.

Ogre::Image rviz::ROSImageTexture::empty_image_ [private]

Definition at line 106 of file ros_image_texture.h.

std::string rviz::ROSImageTexture::frame_ [private]

Definition at line 112 of file ros_image_texture.h.

uint32_t rviz::ROSImageTexture::height_ [private]

Definition at line 109 of file ros_image_texture.h.

Definition at line 115 of file ros_image_texture.h.

image_transport::ImageTransport rviz::ROSImageTexture::it_ [private]

Definition at line 95 of file ros_image_texture.h.

boost::mutex rviz::ROSImageTexture::mutex_ [private]

Definition at line 102 of file ros_image_texture.h.

Definition at line 103 of file ros_image_texture.h.

ros::NodeHandle rviz::ROSImageTexture::nh_ [private]

Definition at line 94 of file ros_image_texture.h.

boost::shared_ptr<image_transport::SubscriberFilter> rviz::ROSImageTexture::sub_ [private]

Definition at line 96 of file ros_image_texture.h.

Ogre::TexturePtr rviz::ROSImageTexture::texture_ [private]

Definition at line 105 of file ros_image_texture.h.

tf::TransformListener* rviz::ROSImageTexture::tf_client_ [private]

Definition at line 113 of file ros_image_texture.h.

boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > rviz::ROSImageTexture::tf_filter_ [private]

Definition at line 97 of file ros_image_texture.h.

std::string rviz::ROSImageTexture::topic_ [private]

Definition at line 111 of file ros_image_texture.h.

Definition at line 99 of file ros_image_texture.h.

uint32_t rviz::ROSImageTexture::width_ [private]

Definition at line 108 of file ros_image_texture.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Josh Faust
autogenerated on Fri Jan 11 09:36:34 2013