30 #ifndef RVIZ_CAMERA_DISPLAY_H 31 #define RVIZ_CAMERA_DISPLAY_H 38 #include <OgreMaterial.h> 39 #include <OgreRenderTargetListener.h> 40 #include <OgreSharedPtr.h> 42 #include <sensor_msgs/CameraInfo.h> 66 class RosTopicProperty;
67 class DisplayGroupVisibilityProperty;
81 void onInitialize()
override;
82 void fixedFrameChanged()
override;
83 void update(
float wall_dt,
float ros_dt)
override;
84 void reset()
override;
87 void preRenderTargetUpdate(
const Ogre::RenderTargetEvent& evt)
override;
88 void postRenderTargetUpdate(
const Ogre::RenderTargetEvent& evt)
override;
96 void onEnable()
override;
97 void onDisable()
override;
106 void updateQueueSize()
override;
112 void processMessage(
const sensor_msgs::Image::ConstPtr& msg)
override;
113 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_
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_
std::unique_ptr< tf2_ros::MessageFilter< sensor_msgs::CameraInfo > > caminfo_tf_filter_
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
Ogre::MaterialPtr bg_material_