#include <overlay_camera_display.h>

| Public Member Functions | |
| virtual void | fixedFrameChanged () | 
| virtual void | onInitialize () | 
| OverlayCameraDisplay () | |
| virtual void | postRenderTargetUpdate (const Ogre::RenderTargetEvent &evt) | 
| virtual void | preRenderTargetUpdate (const Ogre::RenderTargetEvent &evt) | 
| virtual void | reset () | 
| virtual void | update (float wall_dt, float ros_dt) | 
| virtual | ~OverlayCameraDisplay () | 
| Static Public Attributes | |
| static const QString | BACKGROUND | 
| static const QString | BOTH | 
| static const QString | OVERLAY | 
| Protected Member Functions | |
| virtual void | onDisable () | 
| virtual void | onEnable () | 
| void | redraw () | 
| Protected Attributes | |
| int | height_ | 
| rviz::IntProperty * | height_property_ | 
| bool | initializedp_ | 
| int | left_ | 
| rviz::IntProperty * | left_property_ | 
| OverlayObject::Ptr | overlay_ | 
| RenderPanel * | render_panel_ | 
| ROSImageTexture | texture_ | 
| float | texture_alpha_ | 
| rviz::FloatProperty * | texture_alpha_property_ | 
| int | top_ | 
| rviz::IntProperty * | top_property_ | 
| int | width_ | 
| rviz::IntProperty * | width_property_ | 
| Private Slots | |
| void | forceRender () | 
| void | updateAlpha () | 
| void | updateHeight () | 
| void | updateLeft () | 
| virtual void | updateQueueSize () | 
| void | updateTextureAlpha () | 
| void | updateTop () | 
| void | updateWidth () | 
| Private Member Functions | |
| void | caminfoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg) | 
| void | clear () | 
| virtual void | processMessage (const sensor_msgs::Image::ConstPtr &msg) | 
| void | subscribe () | 
| void | unsubscribe () | 
| bool | updateCamera () | 
| void | updateStatus () | 
| Private Attributes | |
| FloatProperty * | alpha_property_ | 
| Ogre::MaterialPtr | bg_material_ | 
| Ogre::SceneNode * | bg_scene_node_ | 
| Ogre::Rectangle2D * | bg_screen_rect_ | 
| boost::mutex | caminfo_mutex_ | 
| bool | caminfo_ok_ | 
| message_filters::Subscriber < sensor_msgs::CameraInfo > | caminfo_sub_ | 
| tf::MessageFilter < sensor_msgs::CameraInfo > * | caminfo_tf_filter_ | 
| sensor_msgs::CameraInfo::ConstPtr | current_caminfo_ | 
| Ogre::MaterialPtr | fg_material_ | 
| Ogre::SceneNode * | fg_scene_node_ | 
| Ogre::Rectangle2D * | fg_screen_rect_ | 
| bool | force_render_ | 
| EnumProperty * | image_position_property_ | 
| bool | new_caminfo_ | 
| uint32_t | vis_bit_ | 
| DisplayGroupVisibilityProperty * | visibility_property_ | 
| FloatProperty * | zoom_property_ | 
Definition at line 85 of file overlay_camera_display.h.
Definition at line 88 of file overlay_camera_display.cpp.
Definition at line 136 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::caminfoCallback | ( | const sensor_msgs::CameraInfo::ConstPtr & | msg | ) |  [private] | 
Definition at line 586 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::clear | ( | void | ) |  [private] | 
Definition at line 360 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::fixedFrameChanged | ( | ) |  [virtual] | 
Reimplemented from rviz::ImageDisplayBase.
Definition at line 593 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::forceRender | ( | ) |  [private, slot] | 
Definition at line 348 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::onDisable | ( | ) |  [protected, virtual] | 
Reimplemented from rviz::Display.
Definition at line 286 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::onEnable | ( | ) |  [protected, virtual] | 
Reimplemented from rviz::Display.
Definition at line 277 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::onInitialize | ( | ) |  [virtual] | 
Reimplemented from rviz::ImageDisplayBase.
Definition at line 162 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::postRenderTargetUpdate | ( | const Ogre::RenderTargetEvent & | evt | ) |  [virtual] | 
Definition at line 271 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::preRenderTargetUpdate | ( | const Ogre::RenderTargetEvent & | evt | ) |  [virtual] | 
Definition at line 261 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::processMessage | ( | const sensor_msgs::Image::ConstPtr & | msg | ) |  [private, virtual] | 
Implements rviz::ImageDisplayBase.
Definition at line 581 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::redraw | ( | ) |  [protected] | 
Definition at line 406 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::reset | ( | ) |  [virtual] | 
Reimplemented from rviz::ImageDisplayBase.
Definition at line 600 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::subscribe | ( | ) |  [private, virtual] | 
Reimplemented from rviz::ImageDisplayBase.
Definition at line 296 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::unsubscribe | ( | ) |  [private, virtual] | 
Reimplemented from rviz::ImageDisplayBase.
Definition at line 322 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::update | ( | float | wall_dt, | 
| float | ros_dt | ||
| ) |  [virtual] | 
Reimplemented from rviz::Display.
Definition at line 376 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::updateAlpha | ( | ) |  [private, slot] | 
Definition at line 328 of file overlay_camera_display.cpp.
| bool jsk_rviz_plugins::OverlayCameraDisplay::updateCamera | ( | ) |  [private] | 
Definition at line 428 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::updateHeight | ( | ) |  [private, slot] | 
Definition at line 611 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::updateLeft | ( | ) |  [private, slot] | 
Definition at line 616 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::updateQueueSize | ( | ) |  [private, virtual, slot] | 
Reimplemented from rviz::ImageDisplayBase.
Definition at line 354 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::updateStatus | ( | ) |  [private] | 
| void jsk_rviz_plugins::OverlayCameraDisplay::updateTextureAlpha | ( | ) |  [private, slot] | 
Definition at line 626 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::updateTop | ( | ) |  [private, slot] | 
Definition at line 621 of file overlay_camera_display.cpp.
| void jsk_rviz_plugins::OverlayCameraDisplay::updateWidth | ( | ) |  [private, slot] | 
Definition at line 606 of file overlay_camera_display.cpp.
Definition at line 144 of file overlay_camera_display.h.
| const QString jsk_rviz_plugins::OverlayCameraDisplay::BACKGROUND  [static] | 
Definition at line 102 of file overlay_camera_display.h.
| Ogre::MaterialPtr jsk_rviz_plugins::OverlayCameraDisplay::bg_material_  [private] | 
Definition at line 136 of file overlay_camera_display.h.
| Ogre::SceneNode* jsk_rviz_plugins::OverlayCameraDisplay::bg_scene_node_  [private] | 
Definition at line 132 of file overlay_camera_display.h.
| Ogre::Rectangle2D* jsk_rviz_plugins::OverlayCameraDisplay::bg_screen_rect_  [private] | 
Definition at line 135 of file overlay_camera_display.h.
| const QString jsk_rviz_plugins::OverlayCameraDisplay::BOTH  [static] | 
Definition at line 104 of file overlay_camera_display.h.
Definition at line 150 of file overlay_camera_display.h.
| bool jsk_rviz_plugins::OverlayCameraDisplay::caminfo_ok_  [private] | 
Definition at line 154 of file overlay_camera_display.h.
| message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_rviz_plugins::OverlayCameraDisplay::caminfo_sub_  [private] | 
Definition at line 141 of file overlay_camera_display.h.
| tf::MessageFilter<sensor_msgs::CameraInfo>* jsk_rviz_plugins::OverlayCameraDisplay::caminfo_tf_filter_  [private] | 
Definition at line 142 of file overlay_camera_display.h.
| sensor_msgs::CameraInfo::ConstPtr jsk_rviz_plugins::OverlayCameraDisplay::current_caminfo_  [private] | 
Definition at line 149 of file overlay_camera_display.h.
| Ogre::MaterialPtr jsk_rviz_plugins::OverlayCameraDisplay::fg_material_  [private] | 
Definition at line 139 of file overlay_camera_display.h.
| Ogre::SceneNode* jsk_rviz_plugins::OverlayCameraDisplay::fg_scene_node_  [private] | 
Definition at line 133 of file overlay_camera_display.h.
| Ogre::Rectangle2D* jsk_rviz_plugins::OverlayCameraDisplay::fg_screen_rect_  [private] | 
Definition at line 138 of file overlay_camera_display.h.
| bool jsk_rviz_plugins::OverlayCameraDisplay::force_render_  [private] | 
Definition at line 156 of file overlay_camera_display.h.
| int jsk_rviz_plugins::OverlayCameraDisplay::height_  [protected] | 
Definition at line 167 of file overlay_camera_display.h.
Definition at line 163 of file overlay_camera_display.h.
Definition at line 145 of file overlay_camera_display.h.
| bool jsk_rviz_plugins::OverlayCameraDisplay::initializedp_  [protected] | 
Definition at line 170 of file overlay_camera_display.h.
| int jsk_rviz_plugins::OverlayCameraDisplay::left_  [protected] | 
Definition at line 168 of file overlay_camera_display.h.
Definition at line 164 of file overlay_camera_display.h.
| bool jsk_rviz_plugins::OverlayCameraDisplay::new_caminfo_  [private] | 
Definition at line 152 of file overlay_camera_display.h.
| const QString jsk_rviz_plugins::OverlayCameraDisplay::OVERLAY  [static] | 
Definition at line 103 of file overlay_camera_display.h.
Definition at line 160 of file overlay_camera_display.h.
Definition at line 112 of file overlay_camera_display.h.
Definition at line 111 of file overlay_camera_display.h.
| float jsk_rviz_plugins::OverlayCameraDisplay::texture_alpha_  [protected] | 
Definition at line 169 of file overlay_camera_display.h.
Definition at line 166 of file overlay_camera_display.h.
| int jsk_rviz_plugins::OverlayCameraDisplay::top_  [protected] | 
Definition at line 168 of file overlay_camera_display.h.
Definition at line 165 of file overlay_camera_display.h.
| uint32_t jsk_rviz_plugins::OverlayCameraDisplay::vis_bit_  [private] | 
Definition at line 158 of file overlay_camera_display.h.
| DisplayGroupVisibilityProperty* jsk_rviz_plugins::OverlayCameraDisplay::visibility_property_  [private] | 
Definition at line 147 of file overlay_camera_display.h.
| int jsk_rviz_plugins::OverlayCameraDisplay::width_  [protected] | 
Definition at line 167 of file overlay_camera_display.h.
Definition at line 162 of file overlay_camera_display.h.
Definition at line 146 of file overlay_camera_display.h.