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
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -1299,6 +1299,11 @@ if(USE_OPENCV)
set(VISP_HAVE_OPENCV_VERSION "(${OpenCV_VERSION_MAJOR}<<16 | ${OpenCV_VERSION_MINOR}<<8 | ${OpenCV_VERSION_PATCH})") # for vpConfig.h
endif()

# PCL version
if(USE_PCL)
set(VISP_HAVE_PCL_VERSION "(${PCL_VERSION_MAJOR}<<16 | ${PCL_VERSION_MINOR}<<8 | ${PCL_VERSION_PATCH})") # for vpConfig.h
endif()

# coin and gui
if(USE_SOWIN OR USE_SOXT OR (USE_SOQT AND SoQt_FOUND) OR (USE_SOQT AND USE_QT))
set(VISP_HAVE_COIN3D_AND_GUI TRUE) # for header vpConfig.h
Expand Down
1 change: 1 addition & 0 deletions cmake/templates/VISPConfig.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -248,6 +248,7 @@ set(VISP_HAVE_OPENMP "@VISP_HAVE_OPENMP@")
set(VISP_HAVE_PANDA3D "@VISP_HAVE_PANDA3D@")
set(VISP_HAVE_PARPORT "@VISP_HAVE_PARPORT@")
set(VISP_HAVE_PCL "@VISP_HAVE_PCL@")
set(VISP_HAVE_PCL_VERSION "@VISP_HAVE_PCL_VERSION@")
set(VISP_HAVE_PIONEER "@VISP_HAVE_PIONEER@")
set(VISP_HAVE_PNG "@VISP_HAVE_PNG@")
set(VISP_HAVE_POLOLU "@VISP_HAVE_POLOLU@")
Expand Down
2 changes: 2 additions & 0 deletions cmake/templates/vpConfig.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -502,6 +502,8 @@ namespace vp = VISP_NAMESPACE_NAME;

// Defined if required PCL components are found
#if defined(VISP_HAVE_PCL)
// PCL version in hexadecimal (for example 1.15.1 gives 0x010F01).
#define VISP_HAVE_PCL_VERSION ${VISP_HAVE_PCL_VERSION}
#cmakedefine VISP_HAVE_PCL_COMMON
#cmakedefine VISP_HAVE_PCL_FILTERS
#cmakedefine VISP_HAVE_PCL_IO
Expand Down
1 change: 1 addition & 0 deletions doc/config-doxygen.in
Original file line number Diff line number Diff line change
Expand Up @@ -2520,6 +2520,7 @@ PREDEFINED = @DOXYGEN_SHOULD_SKIP_THIS@ \
VISP_HAVE_PANDA3D \
VISP_HAVE_PARPORT \
VISP_HAVE_PCL \
VISP_HAVE_PCL_VERSION=0x010E00 \
VISP_HAVE_PCL_COMMON \
VISP_HAVE_PCL_FILTERS \
VISP_HAVE_PCL_IO \
Expand Down
4 changes: 2 additions & 2 deletions modules/core/include/visp3/core/vpImageConvert.h
Original file line number Diff line number Diff line change
Expand Up @@ -368,7 +368,7 @@ class VISP_EXPORT vpImageConvert
#if defined(VISP_HAVE_OPENMP)
std::lock_guard<std::mutex> lock(mutex);
#endif
#if PCL_VERSION_COMPARE(>=,1,14,1)
#if (VISP_HAVE_PCL_VERSION >= 0x010E01) // 1.14.1
pointcloud->push_back(pcl::PointXYZRGB(point_3D[index_0], point_3D[index_1], point_3D[index_2],
color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B));
#else
Expand Down Expand Up @@ -411,7 +411,7 @@ class VISP_EXPORT vpImageConvert
#if defined(VISP_HAVE_OPENMP)
std::lock_guard<std::mutex> lock(mutex);
#endif
#if PCL_VERSION_COMPARE(>=,1,14,1)
#if (VISP_HAVE_PCL_VERSION >= 0x010E01) // 1.14.1
pointcloud->push_back(pcl::PointXYZRGB(point_3D[index_0], point_3D[index_1], point_3D[index_2],
color.bitmap[p].R, color.bitmap[p].G, color.bitmap[p].B));
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1084,7 +1084,7 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloud<pcl::PointXYZRGB
pointcloud->points[static_cast<size_t>(depth_pixel_index)].z = m_invalidDepthValue;

// For out of bounds color data, default to black.
#if PCL_VERSION_COMPARE(<, 1, 1, 0)
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
unsigned int r = 0, g = 0, b = 0;
uint32_t rgb = (static_cast<uint32_t>(r) << 16 | static_cast<uint32_t>(g) << 8 | static_cast<uint32_t>(b));

Expand Down Expand Up @@ -1127,9 +1127,8 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloud<pcl::PointXYZRGB
}

if (color_pixel.y < 0 || color_pixel.y >= color_height || color_pixel.x < 0 || color_pixel.x >= color_width) {
// For out of bounds color data, default to a shade of blue in order to
// visually distinguish holes.
#if PCL_VERSION_COMPARE(<, 1, 1, 0)
// For out of bounds color data, default to a shade of blue in order to visually distinguish holes.
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
unsigned int r = 0, g = 0, b = 0;
uint32_t rgb = (static_cast<uint32_t>(r) << 16 | static_cast<uint32_t>(g) << 8 | static_cast<uint32_t>(b));

Expand All @@ -1144,7 +1143,7 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloud<pcl::PointXYZRGB
unsigned int i_ = static_cast<unsigned int>(color_pixel.x);
unsigned int j_ = static_cast<unsigned int>(color_pixel.y);

#if PCL_VERSION_COMPARE(<, 1, 1, 0)
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
uint32_t rgb = 0;
if (swap_rb) {
rgb =
Expand Down Expand Up @@ -1182,7 +1181,7 @@ void vpOccipitalStructure::getColoredPointcloud(pcl::PointCloud<pcl::PointXYZRGB
}
}
else {
#if PCL_VERSION_COMPARE(<, 1, 1, 0)
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
uint32_t rgb = 0;
if (swap_rb) {
rgb = (static_cast<uint32_t>(p_color_frame[(i * static_cast<unsigned int>(color_width) + j) * nb_color_pixel]) |
Expand Down
8 changes: 4 additions & 4 deletions modules/sensor/src/rgb-depth/realsense/vpRealSense2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1009,7 +1009,7 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2:
// For out of bounds color data, default to a shade of blue in order to
// visually distinguish holes. This color value is same as the librealsense
// out of bounds color value.
#if PCL_VERSION_COMPARE(<, 1, 1, 0)
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
unsigned int r = 96, g = 157, b = 198;
uint32_t rgb = (static_cast<uint32_t>(r) << 16 | static_cast<uint32_t>(g) << 8 | static_cast<uint32_t>(b));

Expand Down Expand Up @@ -1048,7 +1048,7 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2:
// For out of bounds color data, default to a shade of blue in order to
// visually distinguish holes. This color value is same as the librealsense
// out of bounds color value.
#if PCL_VERSION_COMPARE(<, 1, 1, 0)
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
unsigned int r = 96, g = 157, b = 198;
uint32_t rgb = (static_cast<uint32_t>(r) << 16 | static_cast<uint32_t>(g) << 8 | static_cast<uint32_t>(b));

Expand All @@ -1063,7 +1063,7 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2:
unsigned int i_ = static_cast<unsigned int>(color_pixel[1]);
unsigned int j_ = static_cast<unsigned int>(color_pixel[0]);

#if PCL_VERSION_COMPARE(<, 1, 1, 0)
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
uint32_t rgb = 0;
if (swap_rb) {
rgb =
Expand Down Expand Up @@ -1101,7 +1101,7 @@ void vpRealSense2::getPointcloud(const rs2::depth_frame &depth_frame, const rs2:
}
}
else {
#if PCL_VERSION_COMPARE(<, 1, 1, 0)
#if (VISP_HAVE_PCL_VERSION < 0x010100) // 1.1.0
uint32_t rgb = 0;
if (swap_rb) {
rgb = (static_cast<uint32_t>(p_color_frame[(i * static_cast<unsigned int>(color_width) + j) * nb_color_pixel]) |
Expand Down
2 changes: 1 addition & 1 deletion modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -709,7 +709,7 @@ bool vpMbtFaceDepthNormal::computeDesiredFeaturesPCL(const pcl::PointCloud<pcl::
extract.setNegative(false);
extract.filter(*point_cloud_face_extracted);

#if PCL_VERSION_COMPARE(>=, 1, 7, 2)
#if (VISP_HAVE_PCL_VERSION < 0x010702) // 1.7.2
pcl::PointXYZ centroid_point_pcl;
if (pcl::computeCentroid(*point_cloud_face_extracted, centroid_point_pcl)) {
pcl::PointXYZ face_normal;
Expand Down
Loading