Permalink
Browse files

Fix possible alignement issues on 32 bits CPUs

  • Loading branch information...
1 parent 8609873 commit 0675daf4ede6595866e6038379a37c8e7dcc2f9a @VictorLamoine VictorLamoine committed Oct 29, 2015
@@ -67,7 +67,7 @@ pcl::cloud_composer::MergeSelection::performTemplatedAction (QList <const CloudC
}
pcl::ExtractIndices<PointT> filter;
- typename PointCloud<PointT>::Ptr merged_cloud = boost::make_shared<PointCloud<PointT> > ();
+ typename PointCloud<PointT>::Ptr merged_cloud = boost::shared_ptr<PointCloud<PointT> > (new PointCloud<PointT>);
foreach (const CloudItem* input_cloud_item, selected_item_index_map_.keys ())
{
@@ -79,24 +79,15 @@ pcl::cloud_composer::MergeSelection::performTemplatedAction (QList <const CloudC
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));
- typename PointCloud<PointT>::Ptr original_minus_indices = boost::make_shared<PointCloud<PointT> > ();
+ typename PointCloud<PointT>::Ptr original_minus_indices = boost::shared_ptr<PointCloud<PointT> > (new PointCloud<PointT>);
filter.setNegative (true);
filter.filter (*original_minus_indices);
filter.setNegative (false);
- typename PointCloud<PointT>::Ptr selected_points = boost::make_shared<PointCloud<PointT> > ();
+ typename PointCloud<PointT>::Ptr selected_points = boost::shared_ptr<PointCloud<PointT> > (new PointCloud<PointT>);
filter.filter (*selected_points);
qDebug () << "Original minus indices is "<<original_minus_indices->width;
- //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> ();
- //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
- // , source_orientation);
-
CloudItem* new_cloud_item = CloudItem::createCloudItemFromTemplate<PointT>(input_cloud_item->text (),original_minus_indices);
output.append (new_cloud_item);
@@ -124,4 +115,4 @@ pcl::cloud_composer::MergeSelection::performTemplatedAction (QList <const CloudC
-#endif //IMPL_MERGE_SELECTION_H_
+#endif //IMPL_MERGE_SELECTION_H_
@@ -75,7 +75,7 @@ pcl::cloud_composer::TransformClouds::performTemplatedAction (QList <const Cloud
else
pcl::visualization::PCLVisualizer::convertToEigenMatrix (transform_map_.value (input_item->getId ()), transform);
- typename PointCloud<PointT>::Ptr transformed_cloud = boost::make_shared<PointCloud<PointT> > ();
+ typename PointCloud<PointT>::Ptr transformed_cloud = boost::shared_ptr<PointCloud<PointT> > (new PointCloud<PointT>);
transformPointCloud<PointT> (*input_cloud, *transformed_cloud, transform);
CloudItem* new_cloud_item = CloudItem::createCloudItemFromTemplate<PointT>(input_item->text (),transformed_cloud);
@@ -95,4 +95,4 @@ pcl::cloud_composer::TransformClouds::performTemplatedAction (QList <const Cloud
-#endif //IMPL_TRANSFORM_CLOUDS_HPP_
+#endif //IMPL_TRANSFORM_CLOUDS_HPP_
@@ -131,7 +131,7 @@
{
if (euclidean_label_indices[i].indices.size () >= min_cluster_size)
{
- typename PointCloud<PointT>::Ptr cluster = boost::make_shared <PointCloud<PointT> >();
+ typename PointCloud<PointT>::Ptr cluster = boost::shared_ptr<PointCloud<PointT> > (new PointCloud<PointT>);
pcl::copyPointCloud (*input_cloud,euclidean_label_indices[i].indices,*cluster);
qDebug () << "Found cluster with size " << cluster->width;
QString name = input_item->text () + tr ("- Clstr %1").arg (i);
@@ -146,7 +146,7 @@
{
if (label_indices[i].indices.size () >= min_plane_size)
{
- typename PointCloud<PointT>::Ptr plane = boost::make_shared <PointCloud<PointT> >();
+ typename PointCloud<PointT>::Ptr plane = boost::shared_ptr<PointCloud<PointT> > (new PointCloud<PointT>);
pcl::copyPointCloud (*input_cloud,label_indices[i].indices,*plane);
qDebug () << "Found plane with size " << plane->width;
QString name = input_item->text () + tr ("- Plane %1").arg (i);
@@ -156,7 +156,7 @@
}
}
- typename PointCloud<PointT>::Ptr leftovers = boost::make_shared <PointCloud<PointT> >();
+ typename PointCloud<PointT>::Ptr leftovers = boost::shared_ptr<PointCloud<PointT> > (new PointCloud<PointT>);
if (extracted_indices->size () == 0)
pcl::copyPointCloud (*input_cloud,*leftovers);
else
@@ -183,4 +183,4 @@
- #endif //IMPL_TRANSFORM_CLOUDS_HPP_
+ #endif //IMPL_TRANSFORM_CLOUDS_HPP_
@@ -143,7 +143,7 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
{
case (PointTypeFlags::XYZ):
{
- pcl::PointCloud <PointXYZ>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZ> >();
+ pcl::PointCloud <PointXYZ>::Ptr cloud_ptr = boost::shared_ptr<pcl::PointCloud <PointXYZ> > (new pcl::PointCloud <PointXYZ> );
pcl::fromPCLPointCloud2 (*cloud_blob_ptr_, *cloud_ptr);
cloud_pointer_variant = QVariant::fromValue (cloud_ptr);
//Initialize the search kd-tree for this cloud
@@ -154,7 +154,7 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
}
case (PointTypeFlags::XYZ | PointTypeFlags::RGB):
{
- pcl::PointCloud <PointXYZRGB>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZRGB> >();
+ pcl::PointCloud <PointXYZRGB>::Ptr cloud_ptr = boost::shared_ptr<pcl::PointCloud <PointXYZRGB> > (new pcl::PointCloud <PointXYZRGB>);
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> >();
@@ -164,7 +164,7 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
}
case (PointTypeFlags::XYZ | PointTypeFlags::RGBA):
{
- pcl::PointCloud <PointXYZRGBA>::Ptr cloud_ptr = boost::make_shared<pcl::PointCloud <PointXYZRGBA> >();
+ pcl::PointCloud <PointXYZRGBA>::Ptr cloud_ptr = boost::shared_ptr<pcl::PointCloud <PointXYZRGBA> > (new pcl::PointCloud <PointXYZRGBA>);
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> >();
@@ -274,7 +274,7 @@ pcl::cloud_composer::ProjectModel::insertNewCloudFromRGBandDepth ()
return;
}
qDebug () << "Images loaded, making cloud";
- PointCloud<PointXYZRGB>::Ptr cloud = boost::make_shared <PointCloud<PointXYZRGB> >();
+ PointCloud<PointXYZRGB>::Ptr cloud = boost::shared_ptr<PointCloud<PointXYZRGB> > (new PointCloud<PointXYZRGB>);
cloud->points.reserve (depth_dims[0] * depth_dims[1]);
cloud->width = depth_dims[0];
cloud->height = depth_dims[1];
@@ -100,7 +100,7 @@ main (int argc, char ** argv)
if (depth_file_specified)
pcl::console::parse (argc, argv, "-d", depth_path);
- PointCloudT::Ptr cloud = boost::make_shared < PointCloudT >();
+ PointCloudT::Ptr cloud = boost::shared_ptr<PointCloudT> (new PointCloudT);
NormalCloudT::Ptr input_normals = boost::make_shared < NormalCloudT > ();
bool pcd_file_specified = pcl::console::find_switch (argc, argv, "-p");
@@ -88,9 +88,6 @@ pcl::GRSDEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
rsd.setSearchSurface (input_);
rsd.setInputNormals (normals_);
rsd.setRadiusSearch (std::max (search_radius_, std::sqrt (3.0) * width_ / 2));
-// pcl::KdTree<PointInT>::Ptr tree = boost::make_shared<pcl::KdTreeFLANN<PointInT> >();
-// tree->setInputCloud(input_);
-// rsd.setSearchMethod(tree);
rsd.compute (*radii);
// Save the type of each point
@@ -278,7 +278,7 @@ namespace pcl
typename pcl::PointCloud<PointXYZRGBA>::Ptr
getColoredCloud () const
{
- return boost::make_shared<pcl::PointCloud<PointXYZRGBA> > ();
+ return boost::shared_ptr<pcl::PointCloud<PointXYZRGBA> > (new pcl::PointCloud<PointXYZRGBA>);
}
/** \brief Returns a deep copy of the voxel centroid cloud */
@@ -303,7 +303,7 @@ namespace pcl
pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
getColoredVoxelCloud () const
{
- return boost::make_shared<pcl::PointCloud<PointXYZRGBA> > ();
+ return boost::shared_ptr<pcl::PointCloud<PointXYZRGBA> > (new pcl::PointCloud<PointXYZRGBA>);
}
/** \brief Returns labeled voxelized cloud

0 comments on commit 0675daf

Please sign in to comment.