point_cloud2_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 "rviz/default_plugin/point_cloud_common.h"
00036 #include "rviz/default_plugin/point_cloud_transformers.h"
00037 #include "rviz/display_context.h"
00038 #include "rviz/frame_manager.h"
00039 #include "rviz/ogre_helpers/point_cloud.h"
00040 #include "rviz/properties/int_property.h"
00041 #include "rviz/validate_floats.h"
00042 
00043 #include "point_cloud2_display.h"
00044 
00045 namespace rviz
00046 {
00047 
00048 PointCloud2Display::PointCloud2Display()
00049   : point_cloud_common_( new PointCloudCommon( this ))
00050 {
00051   queue_size_property_ = new IntProperty( "Queue Size", 10,
00052                                           "Advanced: set the size of the incoming PointCloud2 message queue. "
00053                                           " Increasing this is useful if your incoming TF data is delayed significantly "
00054                                           "from your PointCloud2 data, but it can greatly increase memory usage if the messages are big.",
00055                                           this, SLOT( updateQueueSize() ));
00056 
00057   // PointCloudCommon sets up a callback queue with a thread for each
00058   // instance.  Use that for processing incoming messages.
00059   update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
00060 }
00061 
00062 PointCloud2Display::~PointCloud2Display()
00063 {
00064   delete point_cloud_common_;
00065 }
00066 
00067 void PointCloud2Display::onInitialize()
00068 {
00069   MFDClass::onInitialize();
00070   point_cloud_common_->initialize( context_, scene_node_ );
00071 }
00072 
00073 void PointCloud2Display::updateQueueSize()
00074 {
00075   tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
00076 }
00077 
00078 void PointCloud2Display::processMessage( const sensor_msgs::PointCloud2ConstPtr& cloud )
00079 {
00080   // Filter any nan values out of the cloud.  Any nan values that make it through to PointCloudBase
00081   // will get their points put off in lala land, but it means they still do get processed/rendered
00082   // which can be a big performance hit
00083   sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
00084   int32_t xi = findChannelIndex(cloud, "x");
00085   int32_t yi = findChannelIndex(cloud, "y");
00086   int32_t zi = findChannelIndex(cloud, "z");
00087 
00088   if (xi == -1 || yi == -1 || zi == -1)
00089   {
00090     return;
00091   }
00092 
00093   const uint32_t xoff = cloud->fields[xi].offset;
00094   const uint32_t yoff = cloud->fields[yi].offset;
00095   const uint32_t zoff = cloud->fields[zi].offset;
00096   const uint32_t point_step = cloud->point_step;
00097   const size_t point_count = cloud->width * cloud->height;
00098   filtered->data.resize(cloud->data.size());
00099   if (point_count == 0)
00100   {
00101     return;
00102   }
00103 
00104   uint32_t output_count = 0;
00105   const uint8_t* ptr = &cloud->data.front();
00106   for (size_t i = 0; i < point_count; ++i)
00107   {
00108     float x = *reinterpret_cast<const float*>(ptr + xoff);
00109     float y = *reinterpret_cast<const float*>(ptr + yoff);
00110     float z = *reinterpret_cast<const float*>(ptr + zoff);
00111     if (validateFloats(Ogre::Vector3(x, y, z)))
00112     {
00113       memcpy(&filtered->data.front() + (output_count * point_step), ptr, point_step);
00114       ++output_count;
00115     }
00116 
00117     ptr += point_step;
00118   }
00119 
00120   filtered->header = cloud->header;
00121   filtered->fields = cloud->fields;
00122   filtered->data.resize(output_count * point_step);
00123   filtered->height = 1;
00124   filtered->width = output_count;
00125   filtered->is_bigendian = cloud->is_bigendian;
00126   filtered->point_step = point_step;
00127   filtered->row_step = output_count;
00128 
00129   point_cloud_common_->addMessage( filtered );
00130 }
00131 
00132 
00133 void PointCloud2Display::update( float wall_dt, float ros_dt )
00134 {
00135   point_cloud_common_->update( wall_dt, ros_dt );
00136 }
00137 
00138 void PointCloud2Display::reset()
00139 {
00140   MFDClass::reset();
00141   point_cloud_common_->reset();
00142 }
00143 
00144 } // namespace rviz
00145 
00146 #include <pluginlib/class_list_macros.h>
00147 PLUGINLIB_EXPORT_CLASS( rviz::PointCloud2Display, rviz::Display )


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