#include <image_overlay.h>
Public Member Functions | |
void | clear () |
int | getHeight () |
Ogre::MaterialPtr | getMaterial () |
int | getWidth () |
ImageOverlay (Ogre::SceneNode *scene_root, unsigned char render_queue_group) | |
bool | setImage (const sensor_msgs::Image &image, const stereo_msgs::DisparityImage &disparity_image) |
bool | setImage (const sensor_msgs::Image &image) |
bool | setImage (unsigned char *rgb_data, int width, int height) |
copy RGB data to texture | |
bool | update () |
virtual | ~ImageOverlay () |
Private Member Functions | |
bool | setImageNoLock (const sensor_msgs::Image &image) |
Private Attributes | |
int | count_ |
Ogre::Image | empty_image_ |
int | height_ |
std::vector< unsigned char > | image_buffer_ |
Ogre::Rectangle2D * | image_rect_ |
boost::mutex | mutex_ |
bool | new_image_ |
std::string | resource_group_name_ |
Ogre::SceneNode * | scene_root_ |
Ogre::TexturePtr | texture_ |
Ogre::MaterialPtr | texture_material_ |
int | width_ |
paints an image, filling the whole viewport performs locking so it can used in a thread-safe way
Definition at line 54 of file image_overlay.h.
rviz_interaction_tools::ImageOverlay::ImageOverlay | ( | Ogre::SceneNode * | scene_root, |
unsigned char | render_queue_group | ||
) |
Definition at line 49 of file image_overlay.cpp.
rviz_interaction_tools::ImageOverlay::~ImageOverlay | ( | ) | [virtual] |
Definition at line 117 of file image_overlay.cpp.
void rviz_interaction_tools::ImageOverlay::clear | ( | void | ) |
Definition at line 282 of file image_overlay.cpp.
Definition at line 298 of file image_overlay.cpp.
Ogre::MaterialPtr rviz_interaction_tools::ImageOverlay::getMaterial | ( | ) | [inline] |
Definition at line 83 of file image_overlay.h.
Definition at line 291 of file image_overlay.cpp.
bool rviz_interaction_tools::ImageOverlay::setImage | ( | const sensor_msgs::Image & | image, |
const stereo_msgs::DisparityImage & | disparity_image | ||
) |
copy mono or RGB image to texture, color areas with missing disparity in red (if present)
Definition at line 124 of file image_overlay.cpp.
bool rviz_interaction_tools::ImageOverlay::setImage | ( | const sensor_msgs::Image & | image | ) |
Definition at line 167 of file image_overlay.cpp.
bool rviz_interaction_tools::ImageOverlay::setImage | ( | unsigned char * | rgb_data, |
int | width, | ||
int | height | ||
) |
copy RGB data to texture
Definition at line 228 of file image_overlay.cpp.
bool rviz_interaction_tools::ImageOverlay::setImageNoLock | ( | const sensor_msgs::Image & | image | ) | [private] |
Definition at line 180 of file image_overlay.cpp.
Definition at line 247 of file image_overlay.cpp.
int rviz_interaction_tools::ImageOverlay::count_ [private] |
Definition at line 92 of file image_overlay.h.
Ogre::Image rviz_interaction_tools::ImageOverlay::empty_image_ [private] |
Definition at line 96 of file image_overlay.h.
int rviz_interaction_tools::ImageOverlay::height_ [private] |
Definition at line 105 of file image_overlay.h.
std::vector<unsigned char> rviz_interaction_tools::ImageOverlay::image_buffer_ [private] |
Definition at line 103 of file image_overlay.h.
Ogre::Rectangle2D* rviz_interaction_tools::ImageOverlay::image_rect_ [private] |
Definition at line 97 of file image_overlay.h.
boost::mutex rviz_interaction_tools::ImageOverlay::mutex_ [private] |
Definition at line 90 of file image_overlay.h.
Definition at line 102 of file image_overlay.h.
std::string rviz_interaction_tools::ImageOverlay::resource_group_name_ [private] |
Definition at line 107 of file image_overlay.h.
Ogre::SceneNode* rviz_interaction_tools::ImageOverlay::scene_root_ [private] |
Definition at line 99 of file image_overlay.h.
Ogre::TexturePtr rviz_interaction_tools::ImageOverlay::texture_ [private] |
Definition at line 95 of file image_overlay.h.
Ogre::MaterialPtr rviz_interaction_tools::ImageOverlay::texture_material_ [private] |
Definition at line 94 of file image_overlay.h.
int rviz_interaction_tools::ImageOverlay::width_ [private] |
Definition at line 104 of file image_overlay.h.