Go to the documentation of this file.
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
74 "Laser scan time, computed from time_increment * len(ranges), is rather large: %1s.\n"
75 "The display of any message will be delayed by this amount of time!")
81 sensor_msgs::PointCloud2Ptr cloud(
new sensor_msgs::PointCloud2);
84 ros::Duration tolerance(scan->time_increment * scan->ranges.size());
101 ROS_DEBUG(
"LaserScan [%s]: failed to transform scan: %s. This message should not repeat (tolerance "
102 "should now be set on our tf2::MessageFilter).",
103 qPrintable(
getName()), e.what());
virtual void unsubscribe()
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
void processMessage(const sensor_msgs::LaserScanConstPtr &scan) override
Process a single message. Overridden from MessageFilterDisplay.
void update(float wall_dt, float ros_dt)
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
void update(float wall_dt, float ros_dt) override
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)
virtual ros::CallbackQueueInterface * getThreadedQueue()=0
Return a CallbackQueue using a different thread than the main GUI one.
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void checkTolerance(int tolerance)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void reset() override
Called to tell the display to clear its state.
Visualizes a laser scan, received as a sensor_msgs::LaserScan.
void setTolerance(const ros::Duration &tolerance)
Displays a point cloud of type sensor_msgs::PointCloud.
void setCallbackQueue(CallbackQueueInterface *queue)
void onInitialize() override
~LaserScanDisplay() override
virtual QString getName() const
Return the name of this Property as a QString.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
ros::Duration filter_tolerance_
PointCloudCommon * point_cloud_common_
tf2_ros::MessageFilter< sensor_msgs::LaserScan > * tf_filter_
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const
Convenience function: returns getFrameManager()->getTF2BufferPtr().
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
laser_geometry::LaserProjection * projector_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09