Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 0 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -276,8 +276,6 @@ find_package(Qhull)
# Cuda
include(${PCL_SOURCE_DIR}/cmake/pcl_find_cuda.cmake)

# Find ROS
include(${PCL_SOURCE_DIR}/cmake/pcl_find_ros.cmake)
# Find QT4
find_package(Qt4)
if (QT4_FOUND)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ pcl::cloud_composer::CloudItem::printNumPoints () const
template <typename PointT> pcl::cloud_composer::CloudItem*
pcl::cloud_composer::CloudItem::createCloudItemFromTemplate (const QString name, typename PointCloud<PointT>::Ptr cloud_ptr)
{
sensor_msgs::PointCloud2::Ptr cloud_blob = boost::make_shared <sensor_msgs::PointCloud2> ();
toROSMsg (*cloud_ptr, *cloud_blob);
pcl::PCLPointCloud2::Ptr cloud_blob = boost::make_shared <pcl::PCLPointCloud2> ();
toPCLPointCloud2 (*cloud_ptr, *cloud_blob);
CloudItem* cloud_item = new CloudItem ( name, cloud_blob, Eigen::Vector4f (), Eigen::Quaternionf (), false);
cloud_item->setData (QVariant::fromValue(cloud_ptr), ItemDataRole::CLOUD_TEMPLATED);
cloud_item->setPointType<PointT> ();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,8 @@ pcl::cloud_composer::MergeSelection::performTemplatedAction (QList <const CloudC

//Eigen::Vector4f source_origin = input_cloud_item->data (ItemDataRole::ORIGIN).value<Eigen::Vector4f> ();
//Eigen::Quaternionf source_orientation = input_cloud_item->data (ItemDataRole::ORIENTATION).value<Eigen::Quaternionf> ();
//sensor_msgs::PointCloud2::Ptr cloud_blob = boost::make_shared <sensor_msgs::PointCloud2> ();;
//toROSMsg (*original_minus_indices, *cloud_blob);
//pcl::PCLPointCloud2::Ptr cloud_blob = boost::make_shared <pcl::PCLPointCloud2> ();;
//toPCLPointCloud2 (*original_minus_indices, *cloud_blob);
//CloudItem* new_cloud_item = new CloudItem (input_cloud_item->text ()
//, cloud_blob
// , source_origin
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@
#include <pcl/search/kdtree.h>

//Typedefs to make things sane
typedef pcl::visualization::PointCloudGeometryHandler<sensor_msgs::PointCloud2> GeometryHandler;
typedef pcl::visualization::PointCloudColorHandler<sensor_msgs::PointCloud2> ColorHandler;
typedef pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2> GeometryHandler;
typedef pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2> ColorHandler;

namespace pcl
{
Expand All @@ -71,7 +71,7 @@ namespace pcl
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

CloudItem (const QString name,
const sensor_msgs::PointCloud2::Ptr cloud_ptr,
const pcl::PCLPointCloud2::Ptr cloud_ptr,
const Eigen::Vector4f& origin = Eigen::Vector4f (),
const Eigen::Quaternionf& orientation = Eigen::Quaternionf (),
bool make_templated_cloud = true);
Expand Down Expand Up @@ -125,7 +125,7 @@ namespace pcl
private:

//These are just stored for convenience
sensor_msgs::PointCloud2::Ptr cloud_blob_ptr_;
pcl::PCLPointCloud2::Ptr cloud_blob_ptr_;
ColorHandler::ConstPtr color_handler_;
GeometryHandler::ConstPtr geometry_handler_;

Expand Down Expand Up @@ -176,7 +176,7 @@ namespace pcl
}

//Add PointCloud types to QT MetaType System
Q_DECLARE_METATYPE (sensor_msgs::PointCloud2::ConstPtr);
Q_DECLARE_METATYPE (pcl::PCLPointCloud2::ConstPtr);
Q_DECLARE_METATYPE (GeometryHandler::ConstPtr);
Q_DECLARE_METATYPE (ColorHandler::ConstPtr);
Q_DECLARE_METATYPE (Eigen::Vector4f);
Expand All @@ -190,4 +190,4 @@ Q_DECLARE_METATYPE (pcl::PointCloud <pcl::PointXYZ>::Ptr);
Q_DECLARE_METATYPE (pcl::PointCloud <pcl::PointXYZRGB>::Ptr);
Q_DECLARE_METATYPE (pcl::PointCloud <pcl::PointXYZRGBA>::Ptr);

#endif //CLOUD_ITEM_H_
#endif //CLOUD_ITEM_H_
2 changes: 1 addition & 1 deletion apps/cloud_composer/src/cloud_composer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ pcl::cloud_composer::ComposerMainWindow::ComposerMainWindow (QWidget *parent)
this->setCorner (Qt::BottomRightCorner, Qt::RightDockWidgetArea);

//Register types in Qt
qRegisterMetaType<sensor_msgs::PointCloud2::Ptr> ("PointCloud2Ptr");
qRegisterMetaType<pcl::PCLPointCloud2::Ptr> ("PCLPointCloud2Ptr");
qRegisterMetaType<GeometryHandler::ConstPtr> ("GeometryHandlerConstPtr");
qRegisterMetaType<ColorHandler::ConstPtr> ("ColorHandlerConstPtr");
qRegisterMetaType<Eigen::Vector4f> ("EigenVector4f");
Expand Down
24 changes: 12 additions & 12 deletions apps/cloud_composer/src/items/cloud_item.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include <pcl/apps/cloud_composer/impl/cloud_item.hpp>

pcl::cloud_composer::CloudItem::CloudItem (QString name,
sensor_msgs::PointCloud2::Ptr cloud_ptr,
pcl::PCLPointCloud2::Ptr cloud_ptr,
const Eigen::Vector4f& origin,
const Eigen::Quaternionf& orientation,
bool make_templated_cloud)
Expand All @@ -25,15 +25,15 @@ pcl::cloud_composer::CloudItem::CloudItem (QString name,

// qDebug () << "Cloud size after passthrough : "<<cloud_filtered->width<<"x"<<cloud_filtered->height;
cloud_blob_ptr_ = cloud_ptr;
sensor_msgs::PointCloud2::ConstPtr const_cloud_ptr = cloud_ptr;
pcl::PCLPointCloud2::ConstPtr const_cloud_ptr = cloud_ptr;
this->setData (QVariant::fromValue (const_cloud_ptr), ItemDataRole::CLOUD_BLOB);
this->setData (QVariant::fromValue (origin_), ItemDataRole::ORIGIN);
this->setData (QVariant::fromValue (orientation_), ItemDataRole::ORIENTATION);

//Create a color and geometry handler for this cloud
color_handler_.reset (new pcl::visualization::PointCloudColorHandlerRGBField<sensor_msgs::PointCloud2> (cloud_ptr));
color_handler_.reset (new pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2> (cloud_ptr));
this->setData (QVariant::fromValue (color_handler_), ItemDataRole::COLOR_HANDLER);
geometry_handler_.reset (new pcl::visualization::PointCloudGeometryHandlerXYZ<sensor_msgs::PointCloud2> (cloud_ptr));
geometry_handler_.reset (new pcl::visualization::PointCloudGeometryHandlerXYZ<pcl::PCLPointCloud2> (cloud_ptr));
this->setData (QVariant::fromValue (geometry_handler_), ItemDataRole::GEOMETRY_HANDLER);

properties_->addCategory ("Core Properties");
Expand All @@ -56,7 +56,7 @@ pcl::cloud_composer::CloudItem::CloudItem (QString name,
pcl::cloud_composer::CloudItem*
pcl::cloud_composer::CloudItem::clone () const
{
sensor_msgs::PointCloud2::Ptr cloud_copy (new sensor_msgs::PointCloud2 (*cloud_blob_ptr_));
pcl::PCLPointCloud2::Ptr cloud_copy (new pcl::PCLPointCloud2 (*cloud_blob_ptr_));
//Vector4f and Quaternionf do deep copies using constructor
CloudItem* new_item = new CloudItem (this->text (), cloud_copy, origin_,orientation_);

Expand Down Expand Up @@ -114,8 +114,8 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
if (! template_cloud_set_ )
{
int num_fields = cloud_blob_ptr_->fields.size ();
std::vector<sensor_msgs::PointField>::iterator end = cloud_blob_ptr_->fields.end ();
std::vector<sensor_msgs::PointField>::iterator itr = cloud_blob_ptr_->fields.begin ();
std::vector<pcl::PCLPointField>::iterator end = cloud_blob_ptr_->fields.end ();
std::vector<pcl::PCLPointField>::iterator itr = cloud_blob_ptr_->fields.begin ();
QStringList field_names;
for ( itr = cloud_blob_ptr_->fields.begin () ; itr != end; ++itr)
{
Expand Down Expand Up @@ -145,7 +145,7 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
case (PointTypeFlags::XYZ):
{
pcl::PointCloud <PointXYZ>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZ> >();
pcl::fromROSMsg (*cloud_blob_ptr_, *cloud_ptr);
pcl::fromPCLPointCloud2 (*cloud_blob_ptr_, *cloud_ptr);
cloud_pointer_variant = QVariant::fromValue (cloud_ptr);
//Initialize the search kd-tree for this cloud
pcl::search::KdTree<PointXYZ>::Ptr kd_search = boost::make_shared<search::KdTree<PointXYZ> >();
Expand All @@ -156,7 +156,7 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
case (PointTypeFlags::XYZ | PointTypeFlags::RGB):
{
pcl::PointCloud <PointXYZRGB>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZRGB> >();
pcl::fromROSMsg (*cloud_blob_ptr_, *cloud_ptr);
pcl::fromPCLPointCloud2 (*cloud_blob_ptr_, *cloud_ptr);
cloud_pointer_variant = QVariant::fromValue (cloud_ptr);
pcl::search::KdTree<PointXYZRGB>::Ptr kd_search = boost::make_shared<search::KdTree<PointXYZRGB> >();
kd_search->setInputCloud (cloud_ptr);
Expand All @@ -166,7 +166,7 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
case (PointTypeFlags::XYZ | PointTypeFlags::RGBA):
{
pcl::PointCloud <PointXYZRGBA>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZRGBA> >();
pcl::fromROSMsg (*cloud_blob_ptr_, *cloud_ptr);
pcl::fromPCLPointCloud2 (*cloud_blob_ptr_, *cloud_ptr);
cloud_pointer_variant = QVariant::fromValue (cloud_ptr);
pcl::search::KdTree<PointXYZRGBA>::Ptr kd_search = boost::make_shared<search::KdTree<PointXYZRGBA> >();
kd_search->setInputCloud (cloud_ptr);
Expand Down Expand Up @@ -194,8 +194,8 @@ pcl::cloud_composer::CloudItem::checkIfFinite ()
if (! cloud_blob_ptr_)
return false;

sensor_msgs::PointCloud2::Ptr cloud_filtered = boost::make_shared<sensor_msgs::PointCloud2> ();
pcl::PassThrough<sensor_msgs::PointCloud2> pass_filter;
pcl::PCLPointCloud2::Ptr cloud_filtered = boost::make_shared<pcl::PCLPointCloud2> ();
pcl::PassThrough<pcl::PCLPointCloud2> pass_filter;
pass_filter.setInputCloud (cloud_blob_ptr_);
pass_filter.setKeepOrganized (false);
pass_filter.filter (*cloud_filtered);
Expand Down
6 changes: 3 additions & 3 deletions apps/cloud_composer/src/items/normals_item.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,9 @@ pcl::cloud_composer::NormalsItem::paintView (boost::shared_ptr<pcl::visualizatio
if (parent ()->type () == CLOUD_ITEM)
{
QVariant cloud_ptr = parent ()->data (ItemDataRole::CLOUD_BLOB);
sensor_msgs::PointCloud2::ConstPtr cloud_blob = cloud_ptr.value<sensor_msgs::PointCloud2::ConstPtr> ();
pcl::PCLPointCloud2::ConstPtr cloud_blob = cloud_ptr.value<pcl::PCLPointCloud2::ConstPtr> ();
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg (*cloud_blob, *cloud);
pcl::fromPCLPointCloud2 (*cloud_blob, *cloud);
double scale = properties_->getProperty ("Scale").toDouble ();
int level = properties_->getProperty ("Level").toInt ();
qDebug () << "Removing old normals...";
Expand All @@ -64,4 +64,4 @@ pcl::cloud_composer::NormalsItem::removeFromView (boost::shared_ptr<pcl::visuali
{
//qDebug () << "Removing Normals "<<item_id_;
vis->removePointCloud (getId ().toStdString ());
}
}
16 changes: 8 additions & 8 deletions apps/cloud_composer/src/merge_selection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,22 +53,22 @@ pcl::cloud_composer::MergeSelection::performAction (ConstItemList input_data, Po
}
}

pcl::ExtractIndices<sensor_msgs::PointCloud2> filter;
sensor_msgs::PointCloud2::Ptr merged_cloud (new sensor_msgs::PointCloud2);
pcl::ExtractIndices<pcl::PCLPointCloud2> filter;
pcl::PCLPointCloud2::Ptr merged_cloud (new pcl::PCLPointCloud2);
foreach (const CloudItem* input_cloud_item, selected_item_index_map_.keys ())
{
//If this cloud hasn't been completely selected
if (!input_data.contains (input_cloud_item))
{
sensor_msgs::PointCloud2::ConstPtr input_cloud = input_cloud_item->data (ItemDataRole::CLOUD_BLOB).value <sensor_msgs::PointCloud2::ConstPtr> ();
pcl::PCLPointCloud2::ConstPtr input_cloud = input_cloud_item->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();
qDebug () << "Extracting "<<selected_item_index_map_.value(input_cloud_item)->indices.size() << " points out of "<<input_cloud->width;
filter.setInputCloud (input_cloud);
filter.setIndices (selected_item_index_map_.value (input_cloud_item));
sensor_msgs::PointCloud2::Ptr original_minus_indices = boost::make_shared <sensor_msgs::PointCloud2> ();
pcl::PCLPointCloud2::Ptr original_minus_indices = boost::make_shared <pcl::PCLPointCloud2> ();
filter.setNegative (true);
filter.filter (*original_minus_indices);
filter.setNegative (false);
sensor_msgs::PointCloud2::Ptr selected_points (new sensor_msgs::PointCloud2);
pcl::PCLPointCloud2::Ptr selected_points (new pcl::PCLPointCloud2);
filter.filter (*selected_points);

qDebug () << "Original minus indices is "<<original_minus_indices->width;
Expand All @@ -79,7 +79,7 @@ pcl::cloud_composer::MergeSelection::performAction (ConstItemList input_data, Po
, source_origin
, source_orientation);
output.append (new_cloud_item);
sensor_msgs::PointCloud2::Ptr temp_cloud = boost::make_shared <sensor_msgs::PointCloud2> ();
pcl::PCLPointCloud2::Ptr temp_cloud = boost::make_shared <pcl::PCLPointCloud2> ();
concatenatePointCloud (*merged_cloud, *selected_points, *temp_cloud);
merged_cloud = temp_cloud;
}
Expand All @@ -89,9 +89,9 @@ pcl::cloud_composer::MergeSelection::performAction (ConstItemList input_data, Po
//Just concatenate for all fully selected clouds
foreach (const CloudComposerItem* input_item, input_data)
{
sensor_msgs::PointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <sensor_msgs::PointCloud2::ConstPtr> ();
pcl::PCLPointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();

sensor_msgs::PointCloud2::Ptr temp_cloud = boost::make_shared <sensor_msgs::PointCloud2> ();
pcl::PCLPointCloud2::Ptr temp_cloud = boost::make_shared <pcl::PCLPointCloud2> ();
concatenatePointCloud (*merged_cloud, *input_cloud, *temp_cloud);
merged_cloud = temp_cloud;
}
Expand Down
4 changes: 2 additions & 2 deletions apps/cloud_composer/src/project_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ pcl::cloud_composer::ProjectModel::insertNewCloudFromFile ()
last_directory_ = file_info.absoluteDir ();
}

sensor_msgs::PointCloud2::Ptr cloud_blob (new sensor_msgs::PointCloud2);
pcl::PCLPointCloud2::Ptr cloud_blob (new pcl::PCLPointCloud2);
Eigen::Vector4f origin;
Eigen::Quaternionf orientation;
int version;
Expand Down Expand Up @@ -377,7 +377,7 @@ pcl::cloud_composer::ProjectModel::saveSelectedCloudToFile ()
last_directory_ = file_info.absoluteDir ();
}

sensor_msgs::PointCloud2::ConstPtr cloud = cloud_to_save->data (ItemDataRole::CLOUD_BLOB).value <sensor_msgs::PointCloud2::ConstPtr> ();
pcl::PCLPointCloud2::ConstPtr cloud = cloud_to_save->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();
Eigen::Vector4f origin = cloud_to_save->data (ItemDataRole::ORIGIN).value <Eigen::Vector4f> ();
Eigen::Quaternionf orientation = cloud_to_save->data (ItemDataRole::ORIENTATION).value <Eigen::Quaternionf> ();
int result = pcl::io::savePCDFile (filename.toStdString (), *cloud, origin, orientation );
Expand Down
10 changes: 5 additions & 5 deletions apps/cloud_composer/tools/euclidean_clustering.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,10 @@ pcl::cloud_composer::EuclideanClusteringTool::performAction (ConstItemList input
int min_cluster_size = parameter_model_->getProperty ("Min Cluster Size").toInt();
int max_cluster_size = parameter_model_->getProperty ("Max Cluster Size").toInt();

sensor_msgs::PointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <sensor_msgs::PointCloud2::ConstPtr> ();
pcl::PCLPointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();
//Get the cloud in template form
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg (*input_cloud, *cloud);
pcl::fromPCLPointCloud2 (*input_cloud, *cloud);

//////////////// THE WORK - COMPUTING CLUSTERS ///////////////////
// Creating the KdTree object for the search method of the extraction
Expand All @@ -72,7 +72,7 @@ pcl::cloud_composer::EuclideanClusteringTool::performAction (ConstItemList input
//Put found clusters into new cloud_items!
qDebug () << "Found "<<cluster_indices.size ()<<" clusters!";
int cluster_count = 0;
pcl::ExtractIndices<sensor_msgs::PointCloud2> filter;
pcl::ExtractIndices<pcl::PCLPointCloud2> filter;
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
{
filter.setInputCloud (input_cloud);
Expand All @@ -82,7 +82,7 @@ pcl::cloud_composer::EuclideanClusteringTool::performAction (ConstItemList input
extracted_indices->insert (extracted_indices->end (), it->indices.begin (), it->indices.end ());
//This means remove the other points
filter.setKeepOrganized (false);
sensor_msgs::PointCloud2::Ptr cloud_filtered (new sensor_msgs::PointCloud2);
pcl::PCLPointCloud2::Ptr cloud_filtered (new pcl::PCLPointCloud2);
filter.filter (*cloud_filtered);

qDebug() << "Cluster has " << cloud_filtered->width << " data points.";
Expand All @@ -94,7 +94,7 @@ pcl::cloud_composer::EuclideanClusteringTool::performAction (ConstItemList input
++cluster_count;
}
//We copy input cloud over for special case that no clusters found, since ExtractIndices doesn't work for 0 length vectors
sensor_msgs::PointCloud2::Ptr remainder_cloud (new sensor_msgs::PointCloud2(*input_cloud));
pcl::PCLPointCloud2::Ptr remainder_cloud (new pcl::PCLPointCloud2(*input_cloud));
if (cluster_indices.size () > 0)
{
//make a cloud containing all the remaining points
Expand Down
6 changes: 3 additions & 3 deletions apps/cloud_composer/tools/fpfh_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,10 @@ pcl::cloud_composer::FPFHEstimationTool::performAction (ConstItemList input_data

double radius = parameter_model_->getProperty("Radius").toDouble();

sensor_msgs::PointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <sensor_msgs::PointCloud2::ConstPtr> ();
pcl::PCLPointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();
//Get the cloud in template form
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg (*input_cloud, *cloud);
pcl::fromPCLPointCloud2 (*input_cloud, *cloud);

//Get the normals cloud, we just use the first normals that were found if there are more than one
pcl::PointCloud<pcl::Normal>::ConstPtr input_normals = normals_list.value(0)->data(ItemDataRole::CLOUD_TEMPLATED).value <pcl::PointCloud<pcl::Normal>::ConstPtr> ();
Expand Down Expand Up @@ -110,4 +110,4 @@ pcl::cloud_composer::FPFHEstimationToolFactory::createToolParameterModel (QObjec
parameter_model->addProperty ("Radius", 0.03, Qt::ItemIsEditable | Qt::ItemIsEnabled);

return parameter_model;
}
}
8 changes: 4 additions & 4 deletions apps/cloud_composer/tools/normal_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,16 +37,16 @@ pcl::cloud_composer::NormalEstimationTool::performAction (ConstItemList input_da
}
input_item = input_data.value (0);

sensor_msgs::PointCloud2::ConstPtr input_cloud;
pcl::PCLPointCloud2::ConstPtr input_cloud;
if (input_item->type () == CloudComposerItem::CLOUD_ITEM)
{
double radius = parameter_model_->getProperty("Radius").toDouble();
qDebug () << "Received Radius = " <<radius;
sensor_msgs::PointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <sensor_msgs::PointCloud2::ConstPtr> ();
pcl::PCLPointCloud2::ConstPtr input_cloud = input_item->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();
qDebug () << "Got cloud size = "<<input_cloud->width;
//////////////// THE WORK - COMPUTING NORMALS ///////////////////
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg (*input_cloud, *cloud);
pcl::fromPCLPointCloud2 (*input_cloud, *cloud);
// Create the normal estimation class, and pass the input dataset to it
pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
ne.setInputCloud (cloud);
Expand Down Expand Up @@ -87,4 +87,4 @@ pcl::cloud_composer::NormalEstimationToolFactory::createToolParameterModel (QObj
parameter_model->addProperty ("Radius", 0.04, Qt::ItemIsEditable | Qt::ItemIsEnabled);

return parameter_model;
}
}
Loading