laser_scan_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <OGRE/OgreSceneNode.h>
00031 #include <OGRE/OgreSceneManager.h>
00032 
00033 #include <ros/time.h>
00034 
00035 #include <laser_geometry/laser_geometry.h>
00036 
00037 #include "rviz/default_plugin/point_cloud_common.h"
00038 #include "rviz/display_context.h"
00039 #include "rviz/frame_manager.h"
00040 #include "rviz/ogre_helpers/point_cloud.h"
00041 #include "rviz/properties/int_property.h"
00042 #include "rviz/validate_floats.h"
00043 
00044 #include "laser_scan_display.h"
00045 
00046 namespace rviz
00047 {
00048 
00049 LaserScanDisplay::LaserScanDisplay()
00050   : point_cloud_common_( new PointCloudCommon( this ))
00051   , projector_( new laser_geometry::LaserProjection() )
00052 {
00053   queue_size_property_ = new IntProperty( "Queue Size", 10,
00054                                           "Advanced: set the size of the incoming LaserScan message queue. "
00055                                           " Increasing this is useful if your incoming TF data is delayed significantly "
00056                                           "from your LaserScan data, but it can greatly increase memory usage if the messages are big.",
00057                                           this, SLOT( updateQueueSize() ));
00058 
00059   // PointCloudCommon sets up a callback queue with a thread for each
00060   // instance.  Use that for processing incoming messages.
00061   update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
00062 }
00063 
00064 LaserScanDisplay::~LaserScanDisplay()
00065 {
00066   delete point_cloud_common_;
00067   delete projector_;
00068 }
00069 
00070 void LaserScanDisplay::onInitialize()
00071 {
00072   MFDClass::onInitialize();
00073   point_cloud_common_->initialize( context_, scene_node_ );
00074 }
00075 
00076 void LaserScanDisplay::updateQueueSize()
00077 {
00078   tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
00079 }
00080 
00081 void LaserScanDisplay::processMessage( const sensor_msgs::LaserScanConstPtr& scan )
00082 {
00083   sensor_msgs::PointCloudPtr cloud( new sensor_msgs::PointCloud );
00084 
00085   std::string frame_id = scan->header.frame_id;
00086 
00087   // Compute tolerance necessary for this scan
00088   ros::Duration tolerance(scan->time_increment * scan->ranges.size());
00089   if (tolerance > filter_tolerance_)
00090   {
00091     filter_tolerance_ = tolerance;
00092     tf_filter_->setTolerance(filter_tolerance_);
00093   }
00094 
00095   try
00096   {
00097     projector_->transformLaserScanToPointCloud( fixed_frame_.toStdString(), *scan, *cloud, *context_->getTFClient(),
00098                                                 laser_geometry::channel_option::Intensity );
00099   }
00100   catch (tf::TransformException& e)
00101   {
00102     ROS_DEBUG( "LaserScan [%s]: failed to transform scan: %s.  This message should not repeat (tolerance should now be set on our tf::MessageFilter).",
00103                qPrintable( getName() ), e.what() );
00104     return;
00105   }
00106 
00107   point_cloud_common_->addMessage( cloud );
00108 }
00109 
00110 void LaserScanDisplay::update( float wall_dt, float ros_dt )
00111 {
00112   point_cloud_common_->update( wall_dt, ros_dt );
00113 }
00114 
00115 void LaserScanDisplay::reset()
00116 {
00117   MFDClass::reset();
00118   point_cloud_common_->reset();
00119 }
00120 
00121 } // namespace rviz
00122 
00123 #include <pluginlib/class_list_macros.h>
00124 PLUGINLIB_EXPORT_CLASS( rviz::LaserScanDisplay, rviz::Display )


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35