00001 #include <pcl/apps/cloud_composer/qt.h>
00002 #include <pcl/apps/cloud_composer/items/cloud_item.h>
00003 #include <pcl/filters/passthrough.h>
00004
00005
00006 #include <pcl/point_types.h>
00007 #include <pcl/impl/instantiate.hpp>
00008 #include <pcl/apps/cloud_composer/impl/cloud_item.hpp>
00009
00010 pcl::cloud_composer::CloudItem::CloudItem (QString name,
00011 pcl::PCLPointCloud2::Ptr cloud_ptr,
00012 const Eigen::Vector4f& origin,
00013 const Eigen::Quaternionf& orientation,
00014 bool make_templated_cloud)
00015 : CloudComposerItem (name)
00016 , origin_ (origin)
00017 , orientation_ (orientation)
00018 , template_cloud_set_ (false)
00019 , point_type_ (PointTypeFlags::NONE)
00020 , is_sanitized_ (false)
00021 {
00022
00023
00024
00025
00026
00027 cloud_blob_ptr_ = cloud_ptr;
00028 pcl::PCLPointCloud2::ConstPtr const_cloud_ptr = cloud_ptr;
00029 this->setData (QVariant::fromValue (const_cloud_ptr), ItemDataRole::CLOUD_BLOB);
00030 this->setData (QVariant::fromValue (origin_), ItemDataRole::ORIGIN);
00031 this->setData (QVariant::fromValue (orientation_), ItemDataRole::ORIENTATION);
00032
00033
00034 color_handler_.reset (new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2> (cloud_ptr));
00035 this->setData (QVariant::fromValue (color_handler_), ItemDataRole::COLOR_HANDLER);
00036 geometry_handler_.reset (new pcl::visualization::PointCloudGeometryHandlerXYZ<pcl::PCLPointCloud2> (cloud_ptr));
00037 this->setData (QVariant::fromValue (geometry_handler_), ItemDataRole::GEOMETRY_HANDLER);
00038
00039 properties_->addCategory ("Core Properties");
00040 properties_->addProperty ("Name", QVariant (this->text ()), Qt::NoItemFlags, "Core Properties");
00041 properties_->addProperty ("Height", QVariant (cloud_blob_ptr_->height), Qt::NoItemFlags, "Core Properties");
00042 properties_->addProperty ("Width", QVariant (cloud_blob_ptr_->width), Qt::NoItemFlags,"Core Properties");
00043 properties_->addCategory ("Display Variables");
00044 properties_->addProperty ("Point Size", QVariant (1.0), Qt::ItemIsEditable | Qt::ItemIsEnabled, "Display Variables");
00045 properties_->addProperty ("Opacity", QVariant (1.0), Qt::ItemIsEditable | Qt::ItemIsEnabled, "Display Variables");
00046
00047 if (make_templated_cloud)
00048 setTemplateCloudFromBlob ();
00049
00050 if (checkIfFinite ())
00051 is_sanitized_ = true;
00052
00053 }
00054
00055
00056 pcl::cloud_composer::CloudItem*
00057 pcl::cloud_composer::CloudItem::clone () const
00058 {
00059 pcl::PCLPointCloud2::Ptr cloud_copy (new pcl::PCLPointCloud2 (*cloud_blob_ptr_));
00060
00061 CloudItem* new_item = new CloudItem (this->text (), cloud_copy, origin_,orientation_);
00062
00063 PropertiesModel* new_item_properties = new_item->getPropertiesModel ();
00064 new_item_properties->copyProperties (properties_);
00065
00066 return new_item;
00067 }
00068
00069 pcl::cloud_composer::CloudItem::~CloudItem ()
00070 {
00071 qDebug () << "Cloud item destructor";
00072 }
00073
00074
00075 void
00076 pcl::cloud_composer::CloudItem::paintView (boost::shared_ptr<pcl::visualization::PCLVisualizer> vis) const
00077 {
00078 vis->addPointCloud (cloud_blob_ptr_, geometry_handler_, color_handler_, origin_, orientation_, getId ().toStdString ());
00079 vis->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, properties_->getProperty ("Point Size").toDouble (), getId ().toStdString ());
00080 vis->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_OPACITY, properties_->getProperty ("Opacity").toDouble (), getId ().toStdString ());
00081
00082 }
00083
00084 void
00085 pcl::cloud_composer::CloudItem::removeFromView (boost::shared_ptr<pcl::visualization::PCLVisualizer> vis) const
00086 {
00087 vis->removePointCloud (getId ().toStdString ());
00088 }
00089
00090 QVariant
00091 pcl::cloud_composer::CloudItem::data (int role) const
00092 {
00093
00094 if ( (role == ItemDataRole::CLOUD_TEMPLATED || role == ItemDataRole::KD_TREE_SEARCH) && !template_cloud_set_)
00095 {
00096 qCritical () << "Attempted to access templated types which are not set!!";
00097 }
00098
00099 return CloudComposerItem::data (role);
00100 }
00101
00102 void
00103 pcl::cloud_composer::CloudItem::setData ( const QVariant & value, int role)
00104 {
00105 if ( role == ItemDataRole::CLOUD_TEMPLATED )
00106 template_cloud_set_ = true;
00107
00108 CloudComposerItem::setData (value, role);
00109 }
00110
00111 void
00112 pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
00113 {
00114 if (! template_cloud_set_ )
00115 {
00116 int num_fields = cloud_blob_ptr_->fields.size ();
00117 std::vector<pcl::PCLPointField>::iterator end = cloud_blob_ptr_->fields.end ();
00118 std::vector<pcl::PCLPointField>::iterator itr = cloud_blob_ptr_->fields.begin ();
00119 QStringList field_names;
00120 for ( itr = cloud_blob_ptr_->fields.begin () ; itr != end; ++itr)
00121 {
00122 field_names.append (QString::fromStdString ( itr->name ));
00123 }
00124 point_type_ = PointTypeFlags::NONE;
00125 if (field_names.contains ("x") && field_names.contains ("y") && field_names.contains ("z"))
00126 point_type_ = (point_type_ | PointTypeFlags::XYZ);
00127 if (field_names.contains ("rgb"))
00128 point_type_ = point_type_ | PointTypeFlags::RGB;
00129 if (field_names.contains ("rgba"))
00130 point_type_ = point_type_ | PointTypeFlags::RGBA;
00131 if (field_names.contains ("normal_x") && field_names.contains ("normal_y") && field_names.contains ("normal_z"))
00132 {
00133 if (field_names.contains ("curvature"))
00134 point_type_ = point_type_ | PointTypeFlags::NORMAL;
00135 else
00136 point_type_ = point_type_ | PointTypeFlags::AXIS;
00137 }
00138 if (field_names.contains ("h") && field_names.contains ("s") && field_names.contains ("v"))
00139 point_type_ = point_type_ | PointTypeFlags::HSV;
00140
00141 QVariant cloud_pointer_variant;
00142 QVariant kd_tree_variant;
00143 switch (point_type_)
00144 {
00145 case (PointTypeFlags::XYZ):
00146 {
00147 pcl::PointCloud <PointXYZ>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZ> >();
00148 pcl::fromPCLPointCloud2 (*cloud_blob_ptr_, *cloud_ptr);
00149 cloud_pointer_variant = QVariant::fromValue (cloud_ptr);
00150
00151 pcl::search::KdTree<PointXYZ>::Ptr kd_search = boost::make_shared<search::KdTree<PointXYZ> >();
00152 kd_search->setInputCloud (cloud_ptr);
00153 kd_tree_variant = QVariant::fromValue (kd_search);
00154 break;
00155 }
00156 case (PointTypeFlags::XYZ | PointTypeFlags::RGB):
00157 {
00158 pcl::PointCloud <PointXYZRGB>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZRGB> >();
00159 pcl::fromPCLPointCloud2 (*cloud_blob_ptr_, *cloud_ptr);
00160 cloud_pointer_variant = QVariant::fromValue (cloud_ptr);
00161 pcl::search::KdTree<PointXYZRGB>::Ptr kd_search = boost::make_shared<search::KdTree<PointXYZRGB> >();
00162 kd_search->setInputCloud (cloud_ptr);
00163 kd_tree_variant = QVariant::fromValue (kd_search);
00164 break;
00165 }
00166 case (PointTypeFlags::XYZ | PointTypeFlags::RGBA):
00167 {
00168 pcl::PointCloud <PointXYZRGBA>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZRGBA> >();
00169 pcl::fromPCLPointCloud2 (*cloud_blob_ptr_, *cloud_ptr);
00170 cloud_pointer_variant = QVariant::fromValue (cloud_ptr);
00171 pcl::search::KdTree<PointXYZRGBA>::Ptr kd_search = boost::make_shared<search::KdTree<PointXYZRGBA> >();
00172 kd_search->setInputCloud (cloud_ptr);
00173 kd_tree_variant = QVariant::fromValue (kd_search);
00174 break;
00175 }
00176
00177 case (PointTypeFlags::NONE):
00178 QMessageBox::warning (0,"Unknown blob type!", "Could not find appropriate template type for this cloud blob! Only blob functionality enabled!");
00179 }
00180
00181 this->setData (cloud_pointer_variant, ItemDataRole::CLOUD_TEMPLATED);
00182 this->setData (kd_tree_variant, ItemDataRole::KD_TREE_SEARCH);
00183 template_cloud_set_ = true;
00184 }
00185 else
00186 qDebug () << "Trying to set cloud from blob, but template cloud already set!";
00187
00188 }
00189
00190
00191 bool
00192 pcl::cloud_composer::CloudItem::checkIfFinite ()
00193 {
00194 if (! cloud_blob_ptr_)
00195 return false;
00196
00197 pcl::PCLPointCloud2::Ptr cloud_filtered = boost::make_shared<pcl::PCLPointCloud2> ();
00198 pcl::PassThrough<pcl::PCLPointCloud2> pass_filter;
00199 pass_filter.setInputCloud (cloud_blob_ptr_);
00200 pass_filter.setKeepOrganized (false);
00201 pass_filter.filter (*cloud_filtered);
00202
00203 if (cloud_filtered->data.size() == cloud_blob_ptr_->data.size ())
00204 return true;
00205
00206 return false;
00207
00208 }