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 <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
00058
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
00081
00082
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 }
00145
00146 #include <pluginlib/class_list_macros.h>
00147 PLUGINLIB_EXPORT_CLASS( rviz::PointCloud2Display, rviz::Display )