$search
#include <ros_image_texture.h>
Definition at line 67 of file ros_image_texture.h.
rviz::ROSImageTexture::ROSImageTexture | ( | const ros::NodeHandle & | nh | ) |
Definition at line 33 of file ros_image_texture.cpp.
rviz::ROSImageTexture::~ROSImageTexture | ( | ) |
Definition at line 51 of file ros_image_texture.cpp.
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 56 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 74 of file ros_image_texture.cpp.
void rviz::ROSImageTexture::setTopic | ( | const std::string & | topic | ) |
Definition at line 81 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.
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.
uint32_t rviz::ROSImageTexture::image_count_ [private] |
Definition at line 115 of file ros_image_texture.h.
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.
bool rviz::ROSImageTexture::new_image_ [private] |
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.
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.
std::string rviz::ROSImageTexture::transport_type_ [private] |
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.