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
00031
00032
00033
00034
00035
00036
00037 #ifndef PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_
00038 #define PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_
00039
00040 #if defined __GNUC__
00041 #pragma GCC system_header
00042 #endif
00043
00044
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/common/io.h>
00047
00048 #include <vtkSmartPointer.h>
00049 #include <vtkPoints.h>
00050 #include <vtkFloatArray.h>
00051
00052 namespace pcl
00053 {
00054 namespace visualization
00055 {
00060 template <typename PointT>
00061 class PointCloudGeometryHandler
00062 {
00063 public:
00064 typedef pcl::PointCloud<PointT> PointCloud;
00065 typedef typename PointCloud::Ptr PointCloudPtr;
00066 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00067
00068 typedef typename boost::shared_ptr<PointCloudGeometryHandler<PointT> > Ptr;
00069 typedef typename boost::shared_ptr<const PointCloudGeometryHandler<PointT> > ConstPtr;
00070
00072 PointCloudGeometryHandler (const PointCloudConstPtr &cloud) :
00073 cloud_ (cloud), capable_ (false),
00074 field_x_idx_ (-1), field_y_idx_ (-1), field_z_idx_ (-1),
00075 fields_ ()
00076 {}
00077
00079 virtual ~PointCloudGeometryHandler () {}
00080
00084 virtual std::string
00085 getName () const = 0;
00086
00088 virtual std::string
00089 getFieldName () const = 0;
00090
00092 inline bool
00093 isCapable () const { return (capable_); }
00094
00098 virtual void
00099 getGeometry (vtkSmartPointer<vtkPoints> &points) const = 0;
00100
00104 void
00105 setInputCloud (const PointCloudConstPtr &cloud)
00106 {
00107 cloud_ = cloud;
00108 }
00109
00110 protected:
00112 PointCloudConstPtr cloud_;
00113
00117 bool capable_;
00118
00120 int field_x_idx_;
00121
00123 int field_y_idx_;
00124
00126 int field_z_idx_;
00127
00129 std::vector<pcl::PCLPointField> fields_;
00130 };
00131
00133
00138 template <typename PointT>
00139 class PointCloudGeometryHandlerXYZ : public PointCloudGeometryHandler<PointT>
00140 {
00141 public:
00142 typedef typename PointCloudGeometryHandler<PointT>::PointCloud PointCloud;
00143 typedef typename PointCloud::Ptr PointCloudPtr;
00144 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00145
00146 typedef typename boost::shared_ptr<PointCloudGeometryHandlerXYZ<PointT> > Ptr;
00147 typedef typename boost::shared_ptr<const PointCloudGeometryHandlerXYZ<PointT> > ConstPtr;
00148
00150 PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud);
00151
00153 virtual ~PointCloudGeometryHandlerXYZ () {};
00154
00156 virtual std::string
00157 getName () const { return ("PointCloudGeometryHandlerXYZ"); }
00158
00160 virtual std::string
00161 getFieldName () const { return ("xyz"); }
00162
00166 virtual void
00167 getGeometry (vtkSmartPointer<vtkPoints> &points) const;
00168
00169 private:
00170
00171 using PointCloudGeometryHandler<PointT>::cloud_;
00172 using PointCloudGeometryHandler<PointT>::capable_;
00173 using PointCloudGeometryHandler<PointT>::field_x_idx_;
00174 using PointCloudGeometryHandler<PointT>::field_y_idx_;
00175 using PointCloudGeometryHandler<PointT>::field_z_idx_;
00176 using PointCloudGeometryHandler<PointT>::fields_;
00177 };
00178
00180
00186 template <typename PointT>
00187 class PointCloudGeometryHandlerSurfaceNormal : public PointCloudGeometryHandler<PointT>
00188 {
00189 public:
00190 typedef typename PointCloudGeometryHandler<PointT>::PointCloud PointCloud;
00191 typedef typename PointCloud::Ptr PointCloudPtr;
00192 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00193
00194 typedef typename boost::shared_ptr<PointCloudGeometryHandlerSurfaceNormal<PointT> > Ptr;
00195 typedef typename boost::shared_ptr<const PointCloudGeometryHandlerSurfaceNormal<PointT> > ConstPtr;
00196
00198 PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud);
00199
00201 virtual std::string
00202 getName () const { return ("PointCloudGeometryHandlerSurfaceNormal"); }
00203
00205 virtual std::string
00206 getFieldName () const { return ("normal_xyz"); }
00207
00211 virtual void
00212 getGeometry (vtkSmartPointer<vtkPoints> &points) const;
00213
00214 private:
00215
00216 using PointCloudGeometryHandler<PointT>::cloud_;
00217 using PointCloudGeometryHandler<PointT>::capable_;
00218 using PointCloudGeometryHandler<PointT>::field_x_idx_;
00219 using PointCloudGeometryHandler<PointT>::field_y_idx_;
00220 using PointCloudGeometryHandler<PointT>::field_z_idx_;
00221 using PointCloudGeometryHandler<PointT>::fields_;
00222 };
00223
00225
00231 template <typename PointT>
00232 class PointCloudGeometryHandlerCustom : public PointCloudGeometryHandler<PointT>
00233 {
00234 public:
00235 typedef typename PointCloudGeometryHandler<PointT>::PointCloud PointCloud;
00236 typedef typename PointCloud::Ptr PointCloudPtr;
00237 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00238
00239 typedef typename boost::shared_ptr<PointCloudGeometryHandlerCustom<PointT> > Ptr;
00240 typedef typename boost::shared_ptr<const PointCloudGeometryHandlerCustom<PointT> > ConstPtr;
00241
00243 PointCloudGeometryHandlerCustom (const PointCloudConstPtr &cloud,
00244 const std::string &x_field_name,
00245 const std::string &y_field_name,
00246 const std::string &z_field_name)
00247 {
00248 field_x_idx_ = pcl::getFieldIndex (*cloud, x_field_name, fields_);
00249 if (field_x_idx_ == -1)
00250 return;
00251 field_y_idx_ = pcl::getFieldIndex (*cloud, y_field_name, fields_);
00252 if (field_y_idx_ == -1)
00253 return;
00254 field_z_idx_ = pcl::getFieldIndex (*cloud, z_field_name, fields_);
00255 if (field_z_idx_ == -1)
00256 return;
00257 field_name_ = x_field_name + y_field_name + z_field_name;
00258 capable_ = true;
00259 }
00260
00262 virtual std::string
00263 getName () const { return ("PointCloudGeometryHandlerCustom"); }
00264
00266 virtual std::string
00267 getFieldName () const { return (field_name_); }
00268
00272 virtual void
00273 getGeometry (vtkSmartPointer<vtkPoints> &points) const
00274 {
00275 if (!capable_)
00276 return;
00277
00278 if (!points)
00279 points = vtkSmartPointer<vtkPoints>::New ();
00280 points->SetDataTypeToFloat ();
00281 points->SetNumberOfPoints (cloud_->points.size ());
00282
00283 float data;
00284
00285 double p[3];
00286 for (vtkIdType i = 0; i < static_cast<vtkIdType> (cloud_->points.size ()); ++i)
00287 {
00288
00289 const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&cloud_->points[i]);
00290 memcpy (&data, pt_data + fields_[field_x_idx_].offset, sizeof (float));
00291 p[0] = data;
00292
00293 memcpy (&data, pt_data + fields_[field_y_idx_].offset, sizeof (float));
00294 p[1] = data;
00295
00296 memcpy (&data, pt_data + fields_[field_z_idx_].offset, sizeof (float));
00297 p[2] = data;
00298
00299 points->SetPoint (i, p);
00300 }
00301 }
00302
00303 private:
00304
00305 using PointCloudGeometryHandler<PointT>::cloud_;
00306 using PointCloudGeometryHandler<PointT>::capable_;
00307 using PointCloudGeometryHandler<PointT>::field_x_idx_;
00308 using PointCloudGeometryHandler<PointT>::field_y_idx_;
00309 using PointCloudGeometryHandler<PointT>::field_z_idx_;
00310 using PointCloudGeometryHandler<PointT>::fields_;
00311
00313 std::string field_name_;
00314 };
00315
00317
00321 template <>
00322 class PCL_EXPORTS PointCloudGeometryHandler<pcl::PCLPointCloud2>
00323 {
00324 public:
00325 typedef pcl::PCLPointCloud2 PointCloud;
00326 typedef PointCloud::Ptr PointCloudPtr;
00327 typedef PointCloud::ConstPtr PointCloudConstPtr;
00328
00329 typedef boost::shared_ptr<PointCloudGeometryHandler<PointCloud> > Ptr;
00330 typedef boost::shared_ptr<const PointCloudGeometryHandler<PointCloud> > ConstPtr;
00331
00333 PointCloudGeometryHandler (const PointCloudConstPtr &cloud, const Eigen::Vector4f & = Eigen::Vector4f::Zero ())
00334 : cloud_ (cloud)
00335 , capable_ (false)
00336 , field_x_idx_ (-1)
00337 , field_y_idx_ (-1)
00338 , field_z_idx_ (-1)
00339 , fields_ (cloud_->fields)
00340 {
00341 }
00342
00344 virtual ~PointCloudGeometryHandler () {}
00345
00347 virtual std::string
00348 getName () const = 0;
00349
00351 virtual std::string
00352 getFieldName () const = 0;
00353
00355 inline bool
00356 isCapable () const { return (capable_); }
00357
00361 virtual void
00362 getGeometry (vtkSmartPointer<vtkPoints> &points) const;
00363
00367 void
00368 setInputCloud (const PointCloudConstPtr &cloud)
00369 {
00370 cloud_ = cloud;
00371 }
00372
00373 protected:
00375 PointCloudConstPtr cloud_;
00376
00380 bool capable_;
00381
00383 int field_x_idx_;
00384
00386 int field_y_idx_;
00387
00389 int field_z_idx_;
00390
00392 std::vector<pcl::PCLPointField> fields_;
00393 };
00394
00396
00401 template <>
00402 class PCL_EXPORTS PointCloudGeometryHandlerXYZ<pcl::PCLPointCloud2> : public PointCloudGeometryHandler<pcl::PCLPointCloud2>
00403 {
00404 public:
00405 typedef PointCloudGeometryHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00406 typedef PointCloud::Ptr PointCloudPtr;
00407 typedef PointCloud::ConstPtr PointCloudConstPtr;
00408
00409 typedef boost::shared_ptr<PointCloudGeometryHandlerXYZ<PointCloud> > Ptr;
00410 typedef boost::shared_ptr<const PointCloudGeometryHandlerXYZ<PointCloud> > ConstPtr;
00411
00413 PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud);
00414
00416 virtual ~PointCloudGeometryHandlerXYZ () {}
00417
00419 virtual std::string
00420 getName () const { return ("PointCloudGeometryHandlerXYZ"); }
00421
00423 virtual std::string
00424 getFieldName () const { return ("xyz"); }
00425 };
00426
00428
00434 template <>
00435 class PCL_EXPORTS PointCloudGeometryHandlerSurfaceNormal<pcl::PCLPointCloud2> : public PointCloudGeometryHandler<pcl::PCLPointCloud2>
00436 {
00437 public:
00438 typedef PointCloudGeometryHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00439 typedef PointCloud::Ptr PointCloudPtr;
00440 typedef PointCloud::ConstPtr PointCloudConstPtr;
00441
00442 typedef boost::shared_ptr<PointCloudGeometryHandlerSurfaceNormal<PointCloud> > Ptr;
00443 typedef boost::shared_ptr<const PointCloudGeometryHandlerSurfaceNormal<PointCloud> > ConstPtr;
00444
00446 PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud);
00447
00449 virtual std::string
00450 getName () const { return ("PointCloudGeometryHandlerSurfaceNormal"); }
00451
00453 virtual std::string
00454 getFieldName () const { return ("normal_xyz"); }
00455 };
00456
00458
00464 template <>
00465 class PCL_EXPORTS PointCloudGeometryHandlerCustom<pcl::PCLPointCloud2> : public PointCloudGeometryHandler<pcl::PCLPointCloud2>
00466 {
00467 public:
00468 typedef PointCloudGeometryHandler<pcl::PCLPointCloud2>::PointCloud PointCloud;
00469 typedef PointCloud::Ptr PointCloudPtr;
00470 typedef PointCloud::ConstPtr PointCloudConstPtr;
00471
00473 PointCloudGeometryHandlerCustom (const PointCloudConstPtr &cloud,
00474 const std::string &x_field_name,
00475 const std::string &y_field_name,
00476 const std::string &z_field_name);
00477
00479 virtual ~PointCloudGeometryHandlerCustom () {}
00480
00482 virtual std::string
00483 getName () const { return ("PointCloudGeometryHandlerCustom"); }
00484
00486 virtual std::string
00487 getFieldName () const { return (field_name_); }
00488
00489 private:
00491 std::string field_name_;
00492 };
00493 }
00494 }
00495
00496 #ifdef PCL_NO_PRECOMPILE
00497 #include <pcl/visualization/impl/point_cloud_geometry_handlers.hpp>
00498 #endif
00499
00500 #endif // PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_
00501