$search
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 "point_cloud2_display.h" 00031 #include "point_cloud_transformers.h" 00032 #include "rviz/visualization_manager.h" 00033 #include "rviz/properties/property.h" 00034 #include "rviz/properties/property_manager.h" 00035 #include "rviz/frame_manager.h" 00036 #include "rviz/validate_floats.h" 00037 00038 #include <ros/time.h> 00039 #include "ogre_tools/point_cloud.h" 00040 00041 #include <tf/transform_listener.h> 00042 00043 #include <OGRE/OgreSceneNode.h> 00044 #include <OGRE/OgreSceneManager.h> 00045 00046 namespace rviz 00047 { 00048 00049 PointCloud2Display::PointCloud2Display() 00050 : PointCloudBase() 00051 , queue_size_( 10 ) 00052 , tf_filter_( 0 ) 00053 { 00054 } 00055 00056 PointCloud2Display::~PointCloud2Display() 00057 { 00058 unsubscribe(); 00059 tf_filter_->clear(); 00060 delete tf_filter_; 00061 } 00062 00063 void PointCloud2Display::onInitialize() 00064 { 00065 PointCloudBase::onInitialize(); 00066 tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(*vis_manager_->getTFClient(), "", queue_size_, threaded_nh_); 00067 tf_filter_->connectInput(sub_); 00068 tf_filter_->registerCallback(&PointCloud2Display::incomingCloudCallback, this); 00069 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this); 00070 } 00071 00072 void PointCloud2Display::setQueueSize( int size ) 00073 { 00074 if( size != queue_size_ ) 00075 { 00076 queue_size_ = size; 00077 00078 unsubscribe(); 00079 reset(); 00080 00081 if( tf_filter_ ) 00082 { 00083 tf_filter_->clear(); 00084 delete tf_filter_; 00085 } 00086 00087 tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(*vis_manager_->getTFClient(), "", queue_size_, threaded_nh_); 00088 tf_filter_->connectInput(sub_); 00089 tf_filter_->registerCallback(&PointCloud2Display::incomingCloudCallback, this); 00090 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this); 00091 00092 subscribe(); 00093 00094 fixedFrameChanged(); 00095 propertyChanged( queue_size_property_ ); 00096 } 00097 } 00098 00099 int PointCloud2Display::getQueueSize() 00100 { 00101 return queue_size_; 00102 } 00103 00104 void PointCloud2Display::setTopic( const std::string& topic ) 00105 { 00106 unsubscribe(); 00107 topic_ = topic; 00108 reset(); 00109 subscribe(); 00110 00111 propertyChanged(topic_property_); 00112 00113 causeRender(); 00114 } 00115 00116 void PointCloud2Display::onEnable() 00117 { 00118 PointCloudBase::onEnable(); 00119 00120 subscribe(); 00121 } 00122 00123 void PointCloud2Display::onDisable() 00124 { 00125 unsubscribe(); 00126 tf_filter_->clear(); 00127 00128 PointCloudBase::onDisable(); 00129 } 00130 00131 void PointCloud2Display::subscribe() 00132 { 00133 if ( !isEnabled() ) 00134 { 00135 return; 00136 } 00137 00138 sub_.subscribe(threaded_nh_, topic_, 2); 00139 } 00140 00141 void PointCloud2Display::unsubscribe() 00142 { 00143 sub_.unsubscribe(); 00144 } 00145 00146 void PointCloud2Display::incomingCloudCallback(const sensor_msgs::PointCloud2ConstPtr& cloud) 00147 { 00148 // Filter any nan values out of the cloud. Any nan values that make it through to PointCloudBase 00149 // will get their points put off in lala land, but it means they still do get processed/rendered 00150 // which can be a big performance hit 00151 sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2); 00152 int32_t xi = findChannelIndex(cloud, "x"); 00153 int32_t yi = findChannelIndex(cloud, "y"); 00154 int32_t zi = findChannelIndex(cloud, "z"); 00155 00156 if (xi == -1 || yi == -1 || zi == -1) 00157 { 00158 return; 00159 } 00160 00161 const uint32_t xoff = cloud->fields[xi].offset; 00162 const uint32_t yoff = cloud->fields[yi].offset; 00163 const uint32_t zoff = cloud->fields[zi].offset; 00164 const uint32_t point_step = cloud->point_step; 00165 const size_t point_count = cloud->width * cloud->height; 00166 filtered->data.resize(cloud->data.size()); 00167 if (point_count == 0) 00168 { 00169 return; 00170 } 00171 00172 uint32_t output_count = 0; 00173 const uint8_t* ptr = &cloud->data.front(); 00174 for (size_t i = 0; i < point_count; ++i) 00175 { 00176 float x = *reinterpret_cast<const float*>(ptr + xoff); 00177 float y = *reinterpret_cast<const float*>(ptr + yoff); 00178 float z = *reinterpret_cast<const float*>(ptr + zoff); 00179 if (validateFloats(Ogre::Vector3(x, y, z))) 00180 { 00181 memcpy(&filtered->data.front() + (output_count * point_step), ptr, point_step); 00182 ++output_count; 00183 } 00184 00185 ptr += point_step; 00186 } 00187 00188 filtered->header = cloud->header; 00189 filtered->fields = cloud->fields; 00190 filtered->data.resize(output_count * point_step); 00191 filtered->height = 1; 00192 filtered->width = output_count; 00193 filtered->is_bigendian = cloud->is_bigendian; 00194 filtered->point_step = point_step; 00195 filtered->row_step = output_count; 00196 00197 addMessage(filtered); 00198 } 00199 00200 void PointCloud2Display::targetFrameChanged() 00201 { 00202 } 00203 00204 void PointCloud2Display::fixedFrameChanged() 00205 { 00206 tf_filter_->setTargetFrame( fixed_frame_ ); 00207 00208 PointCloudBase::fixedFrameChanged(); 00209 } 00210 00211 void PointCloud2Display::createProperties() 00212 { 00213 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, 00214 boost::bind( &PointCloud2Display::getTopic, this ), 00215 boost::bind( &PointCloud2Display::setTopic, this, _1 ), 00216 parent_category_, this ); 00217 setPropertyHelpText(topic_property_, "sensor_msgs::PointCloud2 topic to subscribe to."); 00218 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock(); 00219 topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::PointCloud2>()); 00220 00221 queue_size_property_ = property_manager_->createProperty<IntProperty>( "Queue Size", property_prefix_, 00222 boost::bind( &PointCloud2Display::getQueueSize, this ), 00223 boost::bind( &PointCloud2Display::setQueueSize, this, _1 ), 00224 parent_category_, this ); 00225 setPropertyHelpText( queue_size_property_, "Advanced: set the size of the incoming PointCloud2 message queue. Increasing this is useful if your incoming TF data is delayed significantly from your PointCloud2 data, but it can greatly increase memory usage if the messages are big." ); 00226 00227 PointCloudBase::createProperties(); 00228 } 00229 00230 } // namespace rviz