30 #include <OgreSceneNode.h> 31 #include <OgreSceneManager.h> 54 "Advanced: set the size of the incoming LaserScan message queue. " 55 " Increasing this is useful if your incoming TF data is delayed significantly " 56 "from your LaserScan data, but it can greatly increase memory usage if the messages are big.",
83 sensor_msgs::PointCloudPtr cloud(
new sensor_msgs::PointCloud );
85 std::string frame_id = scan->header.frame_id;
88 ros::Duration tolerance(scan->time_increment * scan->ranges.size());
102 ROS_DEBUG(
"LaserScan [%s]: failed to transform scan: %s. This message should not repeat (tolerance should now be set on our tf::MessageFilter).",
103 qPrintable(
getName() ), e.what() );
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
virtual void onInitialize()
virtual tf::TransformListener * getTFClient() const =0
Convenience function: returns getFrameManager()->getTFClient().
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.
laser_geometry::LaserProjection * projector_
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::LaserScan > * 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.
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
virtual void setQueueSize(uint32_t new_queue_size)
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
void setCallbackQueue(CallbackQueueInterface *queue)
virtual void reset()
Called to tell the display to clear its state.
IntProperty * queue_size_property_
Visualizes a laser scan, received as a sensor_msgs::LaserScan.
virtual void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager.
void transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
ros::Duration filter_tolerance_
virtual void processMessage(const sensor_msgs::LaserScanConstPtr &scan)
Process a single message. Overridden from MessageFilterDisplay.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setTolerance(const ros::Duration &tolerance)
virtual QString getName() const
Return the name of this Property as a QString.
PointCloudCommon * point_cloud_common_
void update(float wall_dt, float ros_dt)