Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 #include "laser_scan_display.h"
00031 #include "rviz/visualization_manager.h"
00032 #include "rviz/properties/property.h"
00033 #include "rviz/properties/property_manager.h"
00034 #include "rviz/frame_manager.h"
00035 
00036 #include "ogre_tools/point_cloud.h"
00037 
00038 #include <tf/transform_listener.h>
00039 #include <sensor_msgs/PointCloud.h>
00040 #include <laser_geometry/laser_geometry.h>
00041 
00042 #include <OGRE/OgreSceneNode.h>
00043 #include <OGRE/OgreSceneManager.h>
00044 
00045 namespace rviz
00046 {
00047 
00048 LaserScanDisplay::LaserScanDisplay()
00049   : PointCloudBase()
00050 {
00051 }
00052 
00053 LaserScanDisplay::~LaserScanDisplay()
00054 {
00055   unsubscribe();
00056   tf_filter_->clear();
00057   delete projector_;
00058   delete tf_filter_;
00059 }
00060 
00061 void LaserScanDisplay::onInitialize()
00062 {
00063   PointCloudBase::onInitialize();
00064   tf_filter_ = new tf::MessageFilter<sensor_msgs::LaserScan>(*vis_manager_->getTFClient(), "", 10, threaded_nh_);
00065   projector_ = new laser_geometry::LaserProjection();
00066 
00067   tf_filter_->connectInput(sub_);
00068   tf_filter_->registerCallback(boost::bind(&LaserScanDisplay::incomingScanCallback, this, _1));
00069   vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00070 }
00071 
00072 void LaserScanDisplay::setTopic( const std::string& topic )
00073 {
00074   unsubscribe();
00075 
00076   topic_ = topic;
00077   reset();
00078 
00079   subscribe();
00080 
00081   propertyChanged(topic_property_);
00082 
00083   causeRender();
00084 }
00085 
00086 
00087 void LaserScanDisplay::onEnable()
00088 {
00089   PointCloudBase::onEnable();
00090 
00091   subscribe();
00092 }
00093 
00094 void LaserScanDisplay::onDisable()
00095 {
00096   unsubscribe();
00097 
00098   PointCloudBase::onDisable();
00099 }
00100 
00101 void LaserScanDisplay::subscribe()
00102 {
00103   if ( !isEnabled() )
00104   {
00105     return;
00106   }
00107 
00108   sub_.subscribe(threaded_nh_, topic_, 2);
00109 }
00110 
00111 void LaserScanDisplay::unsubscribe()
00112 {
00113   sub_.unsubscribe();
00114   tf_filter_->clear();
00115 }
00116 
00117 
00118 void LaserScanDisplay::incomingScanCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
00119 {
00120   sensor_msgs::PointCloudPtr cloud(new sensor_msgs::PointCloud);
00121 
00122   std::string frame_id = scan->header.frame_id;
00123 
00124   
00125   ros::Duration tolerance(scan->time_increment * scan->ranges.size());
00126   if (tolerance > filter_tolerance_)
00127   {
00128     filter_tolerance_ = tolerance;
00129     tf_filter_->setTolerance(filter_tolerance_);
00130   }
00131 
00132   try
00133   {
00134     projector_->transformLaserScanToPointCloud(fixed_frame_, *scan, *cloud , *vis_manager_->getTFClient(), laser_geometry::channel_option::Intensity);
00135   }
00136   catch (tf::TransformException& e)
00137   {
00138     ROS_DEBUG("LaserScan [%s]: failed to transform scan: %s.  This message should not repeat (tolerance should now be set on our tf::MessageFilter).", name_.c_str(), e.what());
00139     return;
00140   }
00141   addMessage(cloud);
00142 }
00143 
00144 void LaserScanDisplay::targetFrameChanged()
00145 {
00146 }
00147 
00148 void LaserScanDisplay::fixedFrameChanged()
00149 {
00150   tf_filter_->setTargetFrame(fixed_frame_);
00151 
00152   PointCloudBase::fixedFrameChanged();
00153 }
00154 
00155 void LaserScanDisplay::createProperties()
00156 {
00157   topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &LaserScanDisplay::getTopic, this ),
00158                                                                             boost::bind( &LaserScanDisplay::setTopic, this, _1 ), parent_category_, this );
00159   setPropertyHelpText(topic_property_, "sensor_msgs::LaserScan topic to subscribe to.");
00160   ROSTopicStringPropertyPtr str_prop = topic_property_.lock();
00161   str_prop->addLegacyName("Scan Topic");
00162   str_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::LaserScan>());
00163 
00164   PointCloudBase::createProperties();
00165 }
00166 
00167 }