30 #include <OgreSceneNode.h> 31 #include <OgreSceneManager.h> 52 "Advanced: set the size of the incoming PointCloud message queue. " 53 " Increasing this is useful if your incoming TF data is delayed significantly " 54 "from your PointCloud data, but it can greatly increase memory usage if the messages are big.",
virtual void onInitialize()
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
virtual int getInt() const
Return the internal property value as an integer.
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
ros::CallbackQueueInterface * getCallbackQueue()
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
tf::MessageFilter< sensor_msgs::PointCloud > * tf_filter_
Property specialized to provide max/min enforcement for integers.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Displays a point cloud of type sensor_msgs::PointCloud.
virtual void setQueueSize(uint32_t new_queue_size)
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
void setCallbackQueue(CallbackQueueInterface *queue)
virtual void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager.
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
virtual void processMessage(const sensor_msgs::PointCloudConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
Displays a point cloud of type sensor_msgs::PointCloud.
IntProperty * queue_size_property_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void reset()
Called to tell the display to clear its state.
PointCloudCommon * point_cloud_common_
void update(float wall_dt, float ros_dt)