30 #ifndef RVIZ_CAMERA_DISPLAY_H 31 #define RVIZ_CAMERA_DISPLAY_H 36 #include <OgreMaterial.h> 37 #include <OgreRenderTargetListener.h> 38 #include <OgreSharedPtr.h> 40 # include <sensor_msgs/CameraInfo.h> 65 class RosTopicProperty;
66 class DisplayGroupVisibilityProperty;
80 virtual void onInitialize();
81 virtual void fixedFrameChanged();
82 virtual void update(
float wall_dt,
float ros_dt );
86 virtual void preRenderTargetUpdate(
const Ogre::RenderTargetEvent& evt );
87 virtual void postRenderTargetUpdate(
const Ogre::RenderTargetEvent& evt );
95 virtual void onEnable();
96 virtual void onDisable();
105 virtual void updateQueueSize();
111 virtual void processMessage(
const sensor_msgs::Image::ConstPtr& msg);
112 void caminfoCallback(
const sensor_msgs::CameraInfo::ConstPtr& msg );
FloatProperty * alpha_property_
sensor_msgs::CameraInfo::ConstPtr current_caminfo_
Ogre::SceneNode * bg_scene_node_
static const QString OVERLAY
static const QString BOTH
RenderPanel * render_panel_
tf::MessageFilter< sensor_msgs::CameraInfo > * caminfo_tf_filter_
Ogre::SceneNode * fg_scene_node_
Property specialized to enforce floating point max/min.
boost::mutex caminfo_mutex_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
EnumProperty * image_position_property_
Display subclass for subscribing and displaying to image messages.
Ogre::Rectangle2D * fg_screen_rect_
DisplayGroupVisibilityProperty * visibility_property_
FloatProperty * zoom_property_
Ogre::MaterialPtr fg_material_
static const QString BACKGROUND
Ogre::Rectangle2D * bg_screen_rect_
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
Ogre::MaterialPtr bg_material_