$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: point_cloud_handlers.h 36637 2011-04-20 01:33:25Z michael.s.dixon $ 00035 * 00036 */ 00037 #ifndef PCL_POINT_CLOUD_HANDLERS_H_ 00038 #define PCL_POINT_CLOUD_HANDLERS_H_ 00039 00040 #include <pcl_visualization/common/common.h> 00041 // PCL includes 00042 #include <pcl/point_types.h> 00043 #include <pcl/point_cloud.h> 00044 #include <pcl/io/io.h> 00045 // VTK includes 00046 #include <vtkSmartPointer.h> 00047 #include <vtkDataArray.h> 00048 #include <vtkUnsignedCharArray.h> 00049 #include <vtkFloatArray.h> 00050 #include <vtkPoints.h> 00051 // Boost includes 00052 #include <boost/make_shared.hpp> 00053 00054 namespace pcl_visualization 00055 { 00059 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 00071 inline Ptr makeShared () const { return (boost::make_shared<PointCloudGeometryHandler<PointT> >) (*this); } 00072 00074 PointCloudGeometryHandler (const PointCloud &cloud) : cloud_ (), capable_ (false) 00075 { 00076 cloud_.reset (new PointCloud (cloud)); 00077 } 00078 00080 virtual std::string getName () const = 0; 00081 00083 virtual std::string getFieldName () const = 0; 00084 00086 inline bool isCapable () const { return (capable_); } 00087 00091 virtual void getGeometry (vtkSmartPointer<vtkPoints> &points) const = 0; 00092 00093 protected: 00095 PointCloudPtr cloud_; 00096 00098 bool capable_; 00099 00101 int field_x_idx_; 00102 00104 int field_y_idx_; 00105 00107 int field_z_idx_; 00108 00111 std::vector<sensor_msgs::PointField> fields_; 00112 }; 00113 00115 00116 template <typename PointT> 00117 class PointCloudGeometryHandlerXYZ : public PointCloudGeometryHandler<PointT> 00118 { 00119 public: 00120 typedef typename PointCloudGeometryHandler<PointT>::PointCloud PointCloud; 00121 typedef typename PointCloud::Ptr PointCloudPtr; 00122 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00123 00124 typedef typename boost::shared_ptr<PointCloudGeometryHandlerXYZ<PointT> > Ptr; 00125 typedef typename boost::shared_ptr<const PointCloudGeometryHandlerXYZ<PointT> > ConstPtr; 00126 00128 PointCloudGeometryHandlerXYZ (const PointCloud &cloud); 00129 00131 virtual inline std::string getName () const { return ("PointCloudGeometryHandlerXYZ"); } 00132 00134 virtual std::string getFieldName () const { return ("xyz"); } 00135 00139 virtual void getGeometry (vtkSmartPointer<vtkPoints> &points) const; 00140 00141 private: 00142 // Members derived from the base class 00143 using PointCloudGeometryHandler<PointT>::cloud_; 00144 using PointCloudGeometryHandler<PointT>::capable_; 00145 using PointCloudGeometryHandler<PointT>::field_x_idx_; 00146 using PointCloudGeometryHandler<PointT>::field_y_idx_; 00147 using PointCloudGeometryHandler<PointT>::field_z_idx_; 00148 using PointCloudGeometryHandler<PointT>::fields_; 00149 }; 00150 00152 00153 template <typename PointT> 00154 class PointCloudGeometryHandlerSurfaceNormal : public PointCloudGeometryHandler<PointT> 00155 { 00156 public: 00157 typedef typename PointCloudGeometryHandler<PointT>::PointCloud PointCloud; 00158 typedef typename PointCloud::Ptr PointCloudPtr; 00159 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00160 00161 typedef typename boost::shared_ptr<PointCloudGeometryHandlerSurfaceNormal<PointT> > Ptr; 00162 typedef typename boost::shared_ptr<const PointCloudGeometryHandlerSurfaceNormal<PointT> > ConstPtr; 00163 00165 PointCloudGeometryHandlerSurfaceNormal (const PointCloud &cloud); 00166 00168 virtual inline std::string getName () const { return ("PointCloudGeometryHandlerSurfaceNormal"); } 00169 00171 virtual std::string getFieldName () const { return ("normal_xyz"); } 00172 00176 virtual void getGeometry (vtkSmartPointer<vtkPoints> &points) const; 00177 00178 private: 00179 // Members derived from the base class 00180 using PointCloudGeometryHandler<PointT>::cloud_; 00181 using PointCloudGeometryHandler<PointT>::capable_; 00182 using PointCloudGeometryHandler<PointT>::field_x_idx_; 00183 using PointCloudGeometryHandler<PointT>::field_y_idx_; 00184 using PointCloudGeometryHandler<PointT>::field_z_idx_; 00185 using PointCloudGeometryHandler<PointT>::fields_; 00186 }; 00187 00189 00190 template <typename PointT> 00191 class PointCloudGeometryHandlerCustom : public PointCloudGeometryHandler<PointT> 00192 { 00193 public: 00194 typedef typename PointCloudGeometryHandler<PointT>::PointCloud PointCloud; 00195 typedef typename PointCloud::Ptr PointCloudPtr; 00196 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00197 00198 typedef typename boost::shared_ptr<PointCloudGeometryHandlerCustom<PointT> > Ptr; 00199 typedef typename boost::shared_ptr<const PointCloudGeometryHandlerCustom<PointT> > ConstPtr; 00200 00202 PointCloudGeometryHandlerCustom (const PointCloud &cloud, const std::string &x_field_name, const std::string &y_field_name, const std::string &z_field_name); 00203 00205 virtual inline std::string getName () const { return ("PointCloudGeometryHandlerCustom"); } 00206 00208 virtual std::string getFieldName () const { return (field_name_); } 00209 00213 virtual void getGeometry (vtkSmartPointer<vtkPoints> &points) const; 00214 00215 private: 00216 // Members derived from the base class 00217 using PointCloudGeometryHandler<PointT>::cloud_; 00218 using PointCloudGeometryHandler<PointT>::capable_; 00219 using PointCloudGeometryHandler<PointT>::field_x_idx_; 00220 using PointCloudGeometryHandler<PointT>::field_y_idx_; 00221 using PointCloudGeometryHandler<PointT>::field_z_idx_; 00222 using PointCloudGeometryHandler<PointT>::fields_; 00223 00225 std::string field_name_; 00226 }; 00227 00231 00232 template <> 00233 class PointCloudGeometryHandler<sensor_msgs::PointCloud2> 00234 { 00235 public: 00236 typedef sensor_msgs::PointCloud2 PointCloud; 00237 typedef PointCloud::Ptr PointCloudPtr; 00238 typedef PointCloud::ConstPtr PointCloudConstPtr; 00239 00240 typedef boost::shared_ptr<PointCloudGeometryHandler<PointCloud> > Ptr; 00241 typedef boost::shared_ptr<const PointCloudGeometryHandler<PointCloud> > ConstPtr; 00242 00244 PointCloudGeometryHandler (const PointCloud &cloud) : cloud_ (), capable_ (false) 00245 { 00246 cloud_.reset (new PointCloud (cloud)); 00247 fields_ = cloud_->fields; 00248 } 00249 00251 virtual std::string getName () const = 0; 00252 00254 virtual std::string getFieldName () const = 0; 00255 00257 inline bool isCapable () const { return (capable_); } 00258 00262 virtual void getGeometry (vtkSmartPointer<vtkPoints> &points) const; 00263 00264 protected: 00266 PointCloudPtr cloud_; 00267 00269 bool capable_; 00270 00272 int field_x_idx_; 00273 00275 int field_y_idx_; 00276 00278 int field_z_idx_; 00279 00281 std::vector<sensor_msgs::PointField> fields_; 00282 }; 00283 00285 00286 template <> 00287 class PointCloudGeometryHandlerXYZ<sensor_msgs::PointCloud2> : public PointCloudGeometryHandler<sensor_msgs::PointCloud2> 00288 { 00289 public: 00290 typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2>::PointCloud PointCloud; 00291 typedef PointCloud::Ptr PointCloudPtr; 00292 typedef PointCloud::ConstPtr PointCloudConstPtr; 00293 00294 typedef boost::shared_ptr<PointCloudGeometryHandlerXYZ<PointCloud> > Ptr; 00295 typedef boost::shared_ptr<const PointCloudGeometryHandlerXYZ<PointCloud> > ConstPtr; 00296 00298 PointCloudGeometryHandlerXYZ (const PointCloud &cloud); 00299 00301 virtual inline std::string getName () const { return ("PointCloudGeometryHandlerXYZ"); } 00302 00304 virtual std::string getFieldName () const { return ("xyz"); } 00305 }; 00306 00308 00309 template <> 00310 class PointCloudGeometryHandlerSurfaceNormal<sensor_msgs::PointCloud2> : public PointCloudGeometryHandler<sensor_msgs::PointCloud2> 00311 { 00312 public: 00313 typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2>::PointCloud PointCloud; 00314 typedef PointCloud::Ptr PointCloudPtr; 00315 typedef PointCloud::ConstPtr PointCloudConstPtr; 00316 00317 typedef boost::shared_ptr<PointCloudGeometryHandlerSurfaceNormal<PointCloud> > Ptr; 00318 typedef boost::shared_ptr<const PointCloudGeometryHandlerSurfaceNormal<PointCloud> > ConstPtr; 00319 00321 PointCloudGeometryHandlerSurfaceNormal (const PointCloud &cloud); 00322 00324 virtual inline std::string getName () const { return ("PointCloudGeometryHandlerSurfaceNormal"); } 00325 00327 virtual std::string getFieldName () const { return ("normal_xyz"); } 00328 }; 00329 00331 00332 template <> 00333 class PointCloudGeometryHandlerCustom<sensor_msgs::PointCloud2> : public PointCloudGeometryHandler<sensor_msgs::PointCloud2> 00334 { 00335 public: 00336 typedef PointCloudGeometryHandler<sensor_msgs::PointCloud2>::PointCloud PointCloud; 00337 typedef PointCloud::Ptr PointCloudPtr; 00338 typedef PointCloud::ConstPtr PointCloudConstPtr; 00339 00341 PointCloudGeometryHandlerCustom (const PointCloud &cloud, const std::string &x_field_name, const std::string &y_field_name, const std::string &z_field_name); 00342 00344 virtual inline std::string getName () const { return ("PointCloudGeometryHandlerCustom"); } 00345 00347 virtual std::string getFieldName () const { return (field_name_); } 00348 private: 00350 std::string field_name_; 00351 }; 00352 00356 00357 template <typename PointT> 00358 class PointCloudColorHandler 00359 { 00360 public: 00361 typedef pcl::PointCloud<PointT> PointCloud; 00362 typedef typename PointCloud::Ptr PointCloudPtr; 00363 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00364 00365 typedef boost::shared_ptr<PointCloudColorHandler<PointT> > Ptr; 00366 typedef boost::shared_ptr<const PointCloudColorHandler<PointT> > ConstPtr; 00367 00368 inline Ptr makeShared () const { return (boost::make_shared<PointCloudColorHandler<PointT> >) (*this); } 00369 00371 PointCloudColorHandler (const PointCloud &cloud) : cloud_ (), capable_ (false) 00372 { 00373 cloud_.reset (new PointCloud (cloud)); 00374 } 00375 00376 00378 inline bool isCapable () const { return (capable_); } 00379 00380 00382 virtual std::string getName () const = 0; 00383 00384 00386 virtual std::string getFieldName () const = 0; 00387 00388 00392 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const = 0; 00393 00394 protected: 00396 PointCloudPtr cloud_; 00397 00399 bool capable_; 00400 00402 int field_idx_; 00403 00406 std::vector<sensor_msgs::PointField> fields_; 00407 }; 00408 00410 00411 template <typename PointT> 00412 class PointCloudColorHandlerRandom : public PointCloudColorHandler<PointT> 00413 { 00414 typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud; 00415 typedef typename PointCloud::Ptr PointCloudPtr; 00416 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00417 00418 public: 00419 typedef boost::shared_ptr<PointCloudColorHandlerRandom<PointT> > Ptr; 00420 typedef boost::shared_ptr<const PointCloudColorHandlerRandom<PointT> > ConstPtr; 00421 00423 PointCloudColorHandlerRandom (const PointCloud &cloud) : PointCloudColorHandler<PointT> (cloud) { capable_ = true; } 00424 00426 virtual inline std::string getName () const { return ("PointCloudColorHandlerRandom"); } 00427 00429 virtual std::string getFieldName () const { return ("[random]"); } 00430 00434 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00435 00436 protected: 00437 // Members derived from the base class 00438 using PointCloudColorHandler<PointT>::cloud_; 00439 using PointCloudColorHandler<PointT>::capable_; 00440 }; 00441 00443 00444 template <typename PointT> 00445 class PointCloudColorHandlerCustom : public PointCloudColorHandler<PointT> 00446 { 00447 typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud; 00448 typedef typename PointCloud::Ptr PointCloudPtr; 00449 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00450 00451 public: 00452 typedef boost::shared_ptr<PointCloudColorHandlerCustom<PointT> > Ptr; 00453 typedef boost::shared_ptr<const PointCloudColorHandlerCustom<PointT> > ConstPtr; 00454 00456 PointCloudColorHandlerCustom (const PointCloud &cloud, double r, double g, double b) : PointCloudColorHandler<PointT> (cloud) 00457 { 00458 capable_ = true; 00459 r_ = r; 00460 g_ = g; 00461 b_ = b; 00462 } 00463 00465 virtual inline std::string getName () const { return ("PointCloudColorHandlerCustom"); } 00466 00468 virtual std::string getFieldName () const { return (""); } 00469 00473 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00474 00475 protected: 00476 // Members derived from the base class 00477 using PointCloudColorHandler<PointT>::cloud_; 00478 using PointCloudColorHandler<PointT>::capable_; 00479 00481 double r_, g_, b_; 00482 }; 00483 00485 00486 template <typename PointT> 00487 class PointCloudColorHandlerRGBField : public PointCloudColorHandler<PointT> 00488 { 00489 typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud; 00490 typedef typename PointCloud::Ptr PointCloudPtr; 00491 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00492 00493 public: 00494 typedef boost::shared_ptr<PointCloudColorHandlerRGBField<PointT> > Ptr; 00495 typedef boost::shared_ptr<const PointCloudColorHandlerRGBField<PointT> > ConstPtr; 00496 00498 PointCloudColorHandlerRGBField (const PointCloud &cloud); 00499 00501 virtual std::string getFieldName () const { return ("rgb"); } 00502 00503 protected: 00505 virtual inline std::string getName () const { return ("PointCloudColorHandlerRGBField"); } 00506 00510 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00511 00512 private: 00513 // Members derived from the base class 00514 using PointCloudColorHandler<PointT>::cloud_; 00515 using PointCloudColorHandler<PointT>::capable_; 00516 using PointCloudColorHandler<PointT>::field_idx_; 00517 using PointCloudColorHandler<PointT>::fields_; 00518 }; 00519 00521 00522 template <typename PointT> 00523 class PointCloudColorHandlerGenericField : public PointCloudColorHandler<PointT> 00524 { 00525 typedef typename PointCloudColorHandler<PointT>::PointCloud PointCloud; 00526 typedef typename PointCloud::Ptr PointCloudPtr; 00527 typedef typename PointCloud::ConstPtr PointCloudConstPtr; 00528 00529 public: 00530 typedef boost::shared_ptr<PointCloudColorHandlerGenericField<PointT> > Ptr; 00531 typedef boost::shared_ptr<const PointCloudColorHandlerGenericField<PointT> > ConstPtr; 00532 00534 PointCloudColorHandlerGenericField (const PointCloud &cloud, const std::string &field_name); 00535 00537 virtual std::string getFieldName () const { return (field_name_); } 00538 00539 protected: 00541 virtual inline std::string getName () const { return ("PointCloudColorHandlerGenericField"); } 00542 00546 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00547 00548 private: 00549 using PointCloudColorHandler<PointT>::cloud_; 00550 using PointCloudColorHandler<PointT>::capable_; 00551 using PointCloudColorHandler<PointT>::field_idx_; 00552 using PointCloudColorHandler<PointT>::fields_; 00553 00555 std::string field_name_; 00556 }; 00557 00561 00562 template <> 00563 class PointCloudColorHandler<sensor_msgs::PointCloud2> 00564 { 00565 public: 00566 typedef sensor_msgs::PointCloud2 PointCloud; 00567 typedef PointCloud::Ptr PointCloudPtr; 00568 typedef PointCloud::ConstPtr PointCloudConstPtr; 00569 00570 typedef boost::shared_ptr<PointCloudColorHandler<PointCloud> > Ptr; 00571 typedef boost::shared_ptr<const PointCloudColorHandler<PointCloud> > ConstPtr; 00572 00574 PointCloudColorHandler (const PointCloud &cloud) : cloud_ (), capable_ (false) 00575 { 00576 cloud_.reset (new PointCloud (cloud)); 00577 } 00578 00580 inline bool isCapable () const { return (capable_); } 00581 00583 virtual std::string getName () const = 0; 00584 00586 virtual std::string getFieldName () const = 0; 00587 00591 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const = 0; 00592 00593 protected: 00595 PointCloudPtr cloud_; 00596 00598 bool capable_; 00599 00601 int field_idx_; 00602 }; 00603 00605 00606 template <> 00607 class PointCloudColorHandlerRandom<sensor_msgs::PointCloud2> : public PointCloudColorHandler<sensor_msgs::PointCloud2> 00608 { 00609 typedef PointCloudColorHandler<sensor_msgs::PointCloud2>::PointCloud PointCloud; 00610 typedef PointCloud::Ptr PointCloudPtr; 00611 typedef PointCloud::ConstPtr PointCloudConstPtr; 00612 00613 public: 00614 typedef boost::shared_ptr<PointCloudColorHandlerRandom<PointCloud> > Ptr; 00615 typedef boost::shared_ptr<const PointCloudColorHandlerRandom<PointCloud> > ConstPtr; 00616 00618 PointCloudColorHandlerRandom (const PointCloud &cloud) : PointCloudColorHandler<sensor_msgs::PointCloud2> (cloud) { capable_ = true; } 00619 00621 virtual inline std::string getName () const { return ("PointCloudColorHandlerRandom"); } 00622 00624 virtual std::string getFieldName () const { return ("[random]"); } 00625 00629 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00630 }; 00631 00633 00634 template <> 00635 class PointCloudColorHandlerCustom<sensor_msgs::PointCloud2> : public PointCloudColorHandler<sensor_msgs::PointCloud2> 00636 { 00637 typedef PointCloudColorHandler<sensor_msgs::PointCloud2>::PointCloud PointCloud; 00638 typedef PointCloud::Ptr PointCloudPtr; 00639 typedef PointCloud::ConstPtr PointCloudConstPtr; 00640 00641 public: 00643 PointCloudColorHandlerCustom (const PointCloud &cloud, double r, double g, double b) : PointCloudColorHandler<sensor_msgs::PointCloud2> (cloud) 00644 { 00645 capable_ = true; 00646 r_ = r; 00647 g_ = g; 00648 b_ = b; 00649 } 00650 00652 virtual inline std::string getName () const { return ("PointCloudColorHandlerCustom"); } 00653 00655 virtual std::string getFieldName () const { return (""); } 00656 00660 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00661 00662 protected: 00664 double r_, g_, b_; 00665 }; 00666 00668 00669 template <> 00670 class PointCloudColorHandlerRGBField<sensor_msgs::PointCloud2> : public PointCloudColorHandler<sensor_msgs::PointCloud2> 00671 { 00672 typedef PointCloudColorHandler<sensor_msgs::PointCloud2>::PointCloud PointCloud; 00673 typedef PointCloud::Ptr PointCloudPtr; 00674 typedef PointCloud::ConstPtr PointCloudConstPtr; 00675 00676 public: 00677 typedef boost::shared_ptr<PointCloudColorHandlerRGBField<PointCloud> > Ptr; 00678 typedef boost::shared_ptr<const PointCloudColorHandlerRGBField<PointCloud> > ConstPtr; 00679 00681 PointCloudColorHandlerRGBField (const PointCloud &cloud); 00682 00683 protected: 00685 virtual inline std::string getName () const { return ("PointCloudColorHandlerRGBField"); } 00686 00688 virtual std::string getFieldName () const { return ("rgb"); } 00689 00693 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00694 }; 00695 00697 00698 template <> 00699 class PointCloudColorHandlerGenericField<sensor_msgs::PointCloud2> : public PointCloudColorHandler<sensor_msgs::PointCloud2> 00700 { 00701 typedef PointCloudColorHandler<sensor_msgs::PointCloud2>::PointCloud PointCloud; 00702 typedef PointCloud::Ptr PointCloudPtr; 00703 typedef PointCloud::ConstPtr PointCloudConstPtr; 00704 00705 public: 00706 typedef boost::shared_ptr<PointCloudColorHandlerGenericField<PointCloud> > Ptr; 00707 typedef boost::shared_ptr<const PointCloudColorHandlerGenericField<PointCloud> > ConstPtr; 00708 00710 PointCloudColorHandlerGenericField (const PointCloud &cloud, const std::string &field_name); 00711 00712 protected: 00714 virtual inline std::string getName () const { return ("PointCloudColorHandlerGenericField"); } 00715 00717 virtual std::string getFieldName () const { return (field_name_); } 00718 00722 virtual void getColor (vtkSmartPointer<vtkDataArray> &scalars) const; 00723 00724 private: 00726 std::string field_name_; 00727 }; 00728 00729 } 00730 00731 #include "libpcl_visualization/point_cloud_handlers.hpp" 00732 00733 #endif