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
00038 #ifndef CLOUD_ITEM_H_
00039 #define CLOUD_ITEM_H_
00040
00041 #include <pcl/apps/cloud_composer/items/cloud_composer_item.h>
00042 #include <pcl/visualization/pcl_visualizer.h>
00043 #include <pcl/search/kdtree.h>
00044
00045
00046 typedef pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2> GeometryHandler;
00047 typedef pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2> ColorHandler;
00048
00049 namespace pcl
00050 {
00051 namespace cloud_composer
00052 {
00053 namespace PointTypeFlags
00054 {
00055 enum PointType
00056 {
00057 NONE = 0,
00058 XYZ = (1 << 0),
00059 RGB = (1 << 1),
00060 RGBA = (1 << 2),
00061 NORMAL = (1 << 3),
00062 HSV = (1 << 4),
00063 AXIS = (1 << 5),
00064 };
00065 }
00066 class PCL_EXPORTS CloudItem : public CloudComposerItem
00067 {
00068 public:
00069
00070
00071 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00072
00073 CloudItem (const QString name,
00074 const pcl::PCLPointCloud2::Ptr cloud_ptr,
00075 const Eigen::Vector4f& origin = Eigen::Vector4f (),
00076 const Eigen::Quaternionf& orientation = Eigen::Quaternionf (),
00077 bool make_templated_cloud = true);
00078
00079 CloudItem (const CloudItem& to_copy);
00080 virtual ~CloudItem ();
00081
00083 template <typename PointT>
00084 static CloudItem*
00085 createCloudItemFromTemplate (const QString name, typename PointCloud<PointT>::Ptr cloud_ptr);
00086
00091 virtual QVariant
00092 data (int role = Qt::UserRole +1) const;
00093
00096 virtual void
00097 setData ( const QVariant & value, int role = Qt::UserRole + 1 );
00098
00099 inline virtual int
00100 type () const { return CLOUD_ITEM; }
00101
00102 virtual CloudItem*
00103 clone () const;
00104
00106 virtual void
00107 paintView (boost::shared_ptr<pcl::visualization::PCLVisualizer> vis) const;
00108
00110 virtual void
00111 removeFromView (boost::shared_ptr<pcl::visualization::PCLVisualizer> vis) const;
00112
00114 void
00115 setTemplateCloudFromBlob ();
00116
00117 int
00118 getPointType () const { return point_type_; }
00119
00120 template <typename PointT> void
00121 printNumPoints () const;
00122
00123 virtual bool
00124 isSanitized () const { return is_sanitized_; }
00125 private:
00126
00127
00128 pcl::PCLPointCloud2::Ptr cloud_blob_ptr_;
00129 ColorHandler::ConstPtr color_handler_;
00130 GeometryHandler::ConstPtr geometry_handler_;
00131
00132
00133
00134
00135 Eigen::Vector4f origin_;
00136 Eigen::Quaternionf orientation_;
00137
00138
00139 int point_type_;
00140 bool template_cloud_set_;
00141
00142 bool
00143 checkIfFinite ();
00144
00145 bool is_sanitized_;
00146
00147
00148 template <typename PointT> inline void
00149 setPointType ()
00150 {
00151 qCritical () << "CloudItem::setPointType for type with no specialization";
00152 point_type_ = PointTypeFlags::NONE;
00153 }
00154
00155
00156 };
00157
00158 template <> inline void
00159 CloudItem::setPointType <PointXYZ> ()
00160 {
00161 point_type_ = PointTypeFlags::XYZ;
00162 }
00163 template <> inline void
00164 CloudItem::setPointType <PointXYZRGB> ()
00165 {
00166 point_type_ = PointTypeFlags::XYZ | PointTypeFlags::RGB;
00167 }
00168 template <> inline void
00169 CloudItem::setPointType <PointXYZRGBA> ()
00170 {
00171 point_type_ = PointTypeFlags::XYZ | PointTypeFlags::RGBA;
00172 }
00173
00174
00175 }
00176 }
00177
00178
00179 Q_DECLARE_METATYPE (pcl::PCLPointCloud2::ConstPtr);
00180 Q_DECLARE_METATYPE (GeometryHandler::ConstPtr);
00181 Q_DECLARE_METATYPE (ColorHandler::ConstPtr);
00182 Q_DECLARE_METATYPE (Eigen::Vector4f);
00183 Q_DECLARE_METATYPE (Eigen::Quaternionf);
00184
00185 Q_DECLARE_METATYPE (pcl::search::KdTree<pcl::PointXYZ>::Ptr);
00186 Q_DECLARE_METATYPE (pcl::search::KdTree<pcl::PointXYZRGB>::Ptr);
00187 Q_DECLARE_METATYPE (pcl::search::KdTree<pcl::PointXYZRGBA>::Ptr);
00188
00189 Q_DECLARE_METATYPE (pcl::PointCloud <pcl::PointXYZ>::Ptr);
00190 Q_DECLARE_METATYPE (pcl::PointCloud <pcl::PointXYZRGB>::Ptr);
00191 Q_DECLARE_METATYPE (pcl::PointCloud <pcl::PointXYZRGBA>::Ptr);
00192
00193 #endif //CLOUD_ITEM_H_