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/common.h"
00035 #include "rviz/frame_manager.h"
00036
00037 #include "ogre_tools/point_cloud.h"
00038
00039 #include <tf/transform_listener.h>
00040 #include <sensor_msgs/PointCloud.h>
00041 #include <laser_geometry/laser_geometry.h>
00042
00043 #include <OGRE/OgreSceneNode.h>
00044 #include <OGRE/OgreSceneManager.h>
00045
00046 namespace rviz
00047 {
00048
00049 LaserScanDisplay::LaserScanDisplay( const std::string& name, VisualizationManager* manager )
00050 : PointCloudBase( name, manager )
00051 , tf_filter_(*manager->getTFClient(), "", 10, threaded_nh_)
00052 {
00053 projector_ = new laser_geometry::LaserProjection();
00054
00055 tf_filter_.connectInput(sub_);
00056 tf_filter_.registerCallback(boost::bind(&LaserScanDisplay::incomingScanCallback, this, _1));
00057 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00058 }
00059
00060 LaserScanDisplay::~LaserScanDisplay()
00061 {
00062 unsubscribe();
00063 tf_filter_.clear();
00064 delete projector_;
00065 }
00066
00067 void LaserScanDisplay::setTopic( const std::string& topic )
00068 {
00069 unsubscribe();
00070
00071 topic_ = topic;
00072 reset();
00073
00074 subscribe();
00075
00076 propertyChanged(topic_property_);
00077
00078 causeRender();
00079 }
00080
00081
00082 void LaserScanDisplay::onEnable()
00083 {
00084 PointCloudBase::onEnable();
00085
00086 subscribe();
00087 }
00088
00089 void LaserScanDisplay::onDisable()
00090 {
00091 unsubscribe();
00092
00093 PointCloudBase::onDisable();
00094 }
00095
00096 void LaserScanDisplay::subscribe()
00097 {
00098 if ( !isEnabled() )
00099 {
00100 return;
00101 }
00102
00103 sub_.subscribe(threaded_nh_, topic_, 2);
00104 }
00105
00106 void LaserScanDisplay::unsubscribe()
00107 {
00108 sub_.unsubscribe();
00109 tf_filter_.clear();
00110 }
00111
00112
00113 void LaserScanDisplay::incomingScanCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
00114 {
00115 sensor_msgs::PointCloudPtr cloud(new sensor_msgs::PointCloud);
00116
00117 std::string frame_id = scan->header.frame_id;
00118
00119
00120 ros::Duration tolerance(scan->time_increment * scan->ranges.size());
00121 if (tolerance > filter_tolerance_)
00122 {
00123 filter_tolerance_ = tolerance;
00124 tf_filter_.setTolerance(filter_tolerance_);
00125 }
00126
00127 try
00128 {
00129 projector_->transformLaserScanToPointCloud(fixed_frame_, *scan, *cloud , *vis_manager_->getTFClient(), laser_geometry::channel_option::Intensity);
00130 }
00131 catch (tf::TransformException& e)
00132 {
00133 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());
00134 return;
00135 }
00136 addMessage(cloud);
00137 }
00138
00139 void LaserScanDisplay::targetFrameChanged()
00140 {
00141 }
00142
00143 void LaserScanDisplay::fixedFrameChanged()
00144 {
00145 tf_filter_.setTargetFrame(fixed_frame_);
00146
00147 PointCloudBase::fixedFrameChanged();
00148 }
00149
00150 void LaserScanDisplay::createProperties()
00151 {
00152 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &LaserScanDisplay::getTopic, this ),
00153 boost::bind( &LaserScanDisplay::setTopic, this, _1 ), parent_category_, this );
00154 setPropertyHelpText(topic_property_, "sensor_msgs::LaserScan topic to subscribe to.");
00155 ROSTopicStringPropertyPtr str_prop = topic_property_.lock();
00156 str_prop->addLegacyName("Scan Topic");
00157 str_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::LaserScan>());
00158
00159 PointCloudBase::createProperties();
00160 }
00161
00162 }