laser_scan_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
32 
33 #include <ros/time.h>
34 
36 
38 #include <rviz/display_context.h>
39 #include <rviz/frame_manager.h>
42 #include <rviz/validate_floats.h>
43 
44 #include "laser_scan_display.h"
45 
46 namespace rviz
47 {
49  : point_cloud_common_(new PointCloudCommon(this)), projector_(new laser_geometry::LaserProjection())
50 {
51 }
52 
54 {
56  delete point_cloud_common_;
57  delete projector_;
58 }
59 
61 {
62  // Use the threaded queue for processing of incoming messages
64 
67 }
68 
70 {
71  if (tolerance > 1)
72  setStatus(StatusProperty::Warn, "Scan Time",
73  QString(
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!")
76  .arg(tolerance));
77 }
78 
79 void LaserScanDisplay::processMessage(const sensor_msgs::LaserScanConstPtr& scan)
80 {
81  sensor_msgs::PointCloud2Ptr cloud(new sensor_msgs::PointCloud2);
82 
83  // Compute tolerance necessary for this scan
84  ros::Duration tolerance(scan->time_increment * scan->ranges.size());
85  if (tolerance > filter_tolerance_)
86  {
87  filter_tolerance_ = tolerance;
90  }
91 
92  try
93  {
94  auto tf = context_->getTF2BufferPtr();
95 
96  projector_->transformLaserScanToPointCloud(fixed_frame_.toStdString(), *scan, *cloud, *tf, -1.0,
98  }
99  catch (tf2::TransformException& e)
100  {
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());
104  return;
105  }
106 
108 }
109 
110 void LaserScanDisplay::update(float wall_dt, float ros_dt)
111 {
112  point_cloud_common_->update(wall_dt, ros_dt);
113 }
114 
116 {
117  MFDClass::reset();
120 }
121 
122 } // namespace rviz
123 
rviz::MessageFilterDisplay< sensor_msgs::LaserScan >::reset
void reset() override
Definition: message_filter_display.h:125
validate_floats.h
frame_manager.h
rviz::MessageFilterDisplay< sensor_msgs::LaserScan >::unsubscribe
virtual void unsubscribe()
Definition: message_filter_display.h:177
rviz::PointCloudCommon::initialize
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
Definition: point_cloud_common.cpp:366
rviz::LaserScanDisplay::processMessage
void processMessage(const sensor_msgs::LaserScanConstPtr &scan) override
Process a single message. Overridden from MessageFilterDisplay.
Definition: laser_scan_display.cpp:79
rviz::PointCloudCommon::update
void update(float wall_dt, float ros_dt)
Definition: point_cloud_common.cpp:520
rviz::LaserScanDisplay::onInitialize
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
Definition: laser_scan_display.cpp:60
time.h
point_cloud_common.h
int_property.h
rviz::LaserScanDisplay::LaserScanDisplay
LaserScanDisplay()
Definition: laser_scan_display.cpp:48
rviz::LaserScanDisplay::update
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Definition: laser_scan_display.cpp:110
laser_geometry::LaserProjection::transformLaserScanToPointCloud
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)
point_cloud.h
rviz::DisplayContext::getThreadedQueue
virtual ros::CallbackQueueInterface * getThreadedQueue()=0
Return a CallbackQueue using a different thread than the main GUI one.
rviz::PointCloudCommon::addMessage
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
Definition: point_cloud_common.cpp:939
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
laser_scan_display.h
rviz::LaserScanDisplay::checkTolerance
void checkTolerance(int tolerance)
Definition: laser_scan_display.cpp:69
rviz::Display
Definition: display.h:63
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:176
laser_geometry.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ROS_DEBUG
#define ROS_DEBUG(...)
rviz
Definition: add_display_dialog.cpp:54
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
rviz::LaserScanDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: laser_scan_display.cpp:115
rviz::StatusProperty::Warn
@ Warn
Definition: status_property.h:45
rviz::LaserScanDisplay
Visualizes a laser scan, received as a sensor_msgs::LaserScan.
Definition: laser_scan_display.h:48
tf2_ros::MessageFilter::setTolerance
void setTolerance(const ros::Duration &tolerance)
laser_geometry
rviz::PointCloudCommon
Displays a point cloud of type sensor_msgs::PointCloud.
Definition: point_cloud_common.h:84
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
rviz::MessageFilterDisplay< sensor_msgs::LaserScan >::onInitialize
void onInitialize() override
Definition: message_filter_display.h:105
rviz::LaserScanDisplay::~LaserScanDisplay
~LaserScanDisplay() override
Definition: laser_scan_display.cpp:53
rviz::Property::getName
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:164
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
rviz::LaserScanDisplay::filter_tolerance_
ros::Duration filter_tolerance_
Definition: laser_scan_display.h:72
rviz::LaserScanDisplay::point_cloud_common_
PointCloudCommon * point_cloud_common_
Definition: laser_scan_display.h:69
rviz::MessageFilterDisplay< sensor_msgs::LaserScan >::tf_filter_
tf2_ros::MessageFilter< sensor_msgs::LaserScan > * tf_filter_
Definition: message_filter_display.h:232
class_list_macros.hpp
rviz::PointCloudCommon::reset
void reset()
Definition: point_cloud_common.cpp:508
tf
display_context.h
DurationBase< Duration >::toSec
double toSec() const
tf2::TransformException
laser_geometry::channel_option::Intensity
Intensity
ros::Duration
rviz::DisplayContext::getTF2BufferPtr
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const
Convenience function: returns getFrameManager()->getTF2BufferPtr().
Definition: display_context.h:98
rviz::Display::update_nh_
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Definition: display.h:300
rviz::LaserScanDisplay::projector_
laser_geometry::LaserProjection * projector_
Definition: laser_scan_display.h:71


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09