Skip to content

Commit

Permalink
Merge pull request #1366 from rolalaro/fix_pcl_pointxyz
Browse files Browse the repository at this point in the history
[FIX] Fix PCL version incompatibility when using PCL 1.10.0
  • Loading branch information
fspindle authored Apr 12, 2024
2 parents b22a95e + 0f31e98 commit 90e2bfc
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 0 deletions.
5 changes: 5 additions & 0 deletions modules/core/include/visp3/core/vpImageConvert.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,12 @@
#include <visp3/core/vpImageException.h>
#include <visp3/core/vpPixelMeterConversion.h>

#include <pcl/pcl_config.h>
#if PCL_VERSION_COMPARE(>=,1,14,1)
#include <pcl/impl/point_types.hpp>
#else
#include <pcl/point_types.h>
#endif
#include <pcl/point_cloud.h>
#endif

Expand Down
16 changes: 16 additions & 0 deletions modules/core/src/image/vpImageConvert_pcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,8 +216,16 @@ int vpImageConvert::depthToPointCloud(const vpImage<vpRGBa> &color, const vpImag
#if defined(_OPENMP)
std::lock_guard<std::mutex> lock(mutex);
#endif
#if PCL_VERSION_COMPARE(>=,1,14,1)
pointcloud->push_back(pcl::PointXYZRGB(point_3D[0], point_3D[1], point_3D[2],
color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B));
#else
pcl::PointXYZRGB pt(color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B);
pt.x = point_3D[0];
pt.y = point_3D[1];
pt.z = point_3D[2];
pointcloud->push_back(pcl::PointXYZRGB(pt));
#endif
}
}
}
Expand Down Expand Up @@ -251,8 +259,16 @@ int vpImageConvert::depthToPointCloud(const vpImage<vpRGBa> &color, const vpImag
#if defined(_OPENMP)
std::lock_guard<std::mutex> lock(mutex);
#endif
#if PCL_VERSION_COMPARE(>=,1,14,1)
pointcloud->push_back(pcl::PointXYZRGB(point_3D[0], point_3D[1], point_3D[2],
color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B));
#else
pcl::PointXYZRGB pt(color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B);
pt.x = point_3D[0];
pt.y = point_3D[1];
pt.z = point_3D[2];
pointcloud->push_back(pcl::PointXYZRGB(pt));
#endif
}
}
}
Expand Down

0 comments on commit 90e2bfc

Please sign in to comment.