New upstream version 1.15.0+dfsg
authorJochen Sprickerhof <git@jochen.sprickerhof.de>
Sun, 23 Feb 2025 06:54:49 +0000 (07:54 +0100)
committerJochen Sprickerhof <git@jochen.sprickerhof.de>
Sun, 23 Feb 2025 06:54:49 +0000 (07:54 +0100)
586 files changed:
.ci/azure-pipelines/azure-pipelines.yaml
.ci/azure-pipelines/build/macos.yaml
.ci/azure-pipelines/build/ubuntu.yaml
.ci/azure-pipelines/env.yml
.ci/azure-pipelines/release.yaml
.ci/azure-pipelines/ubuntu-variety.yaml
.clang-tidy
.dev/docker/env/Dockerfile
.dev/docker/perception_pcl_ros/Dockerfile
.dev/docker/perception_pcl_ros/noetic_rosinstall.yaml [new file with mode: 0644]
.dev/docker/windows/Dockerfile
.github/workflows/clang-tidy.yml
2d/CMakeLists.txt
2d/include/pcl/2d/impl/edge.hpp
CHANGES.md
CMakeLists.txt
PCLConfig.cmake.in
README.md
apps/3d_rec_framework/CMakeLists.txt
apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h
apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_classifier.hpp
apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp
apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp
apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp
apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h
apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp
apps/3d_rec_framework/src/tools/local_recognition_mian_dataset.cpp
apps/CMakeLists.txt
apps/cloud_composer/CMakeLists.txt
apps/in_hand_scanner/CMakeLists.txt
apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h [deleted file]
apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h [deleted file]
apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h
apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h
apps/in_hand_scanner/src/offline_integration.cpp
apps/include/pcl/apps/face_detection/face_detection_apps_utils.h
apps/include/pcl/apps/impl/dominant_plane_segmentation.hpp
apps/include/pcl/apps/pcd_video_player.h
apps/modeler/CMakeLists.txt
apps/point_cloud_editor/CMakeLists.txt
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selection.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selectionTransformTool.h
apps/src/face_detection/filesystem_face_detection.cpp
apps/src/face_detection/openni_face_detection.cpp
apps/src/openni_grab_frame.cpp
apps/src/openni_grab_images.cpp
apps/src/openni_mobile_server.cpp
apps/src/openni_octree_compression.cpp
apps/src/openni_organized_compression.cpp
apps/src/organized_segmentation_demo.cpp
apps/src/pcd_video_player/pcd_video_player.cpp
apps/src/render_views_tesselated_sphere.cpp
apps/src/stereo_ground_segmentation.cpp
benchmarks/CMakeLists.txt
benchmarks/filters/radius_outlier_removal.cpp [new file with mode: 0644]
benchmarks/search/radius_search.cpp
cmake/Modules/FindFLANN.cmake
cmake/Modules/FindGLEW.cmake [deleted file]
cmake/Modules/FindGTestSource.cmake
cmake/Modules/FindOpenMP.cmake [deleted file]
cmake/Modules/FindOpenNI.cmake
cmake/Modules/FindQhull.cmake
cmake/Modules/FindSphinx.cmake
cmake/Modules/NSIS.template.in
cmake/pcl_find_boost.cmake
cmake/pcl_find_cuda.cmake
cmake/pcl_options.cmake
cmake/pcl_pclconfig.cmake
cmake/pcl_targets.cmake
common/CMakeLists.txt
common/include/pcl/PCLPointField.h
common/include/pcl/common/boost.h [deleted file]
common/include/pcl/common/colors.h
common/include/pcl/common/common.h
common/include/pcl/common/impl/centroid.hpp
common/include/pcl/common/impl/eigen.hpp
common/include/pcl/common/impl/file_io.hpp
common/include/pcl/common/impl/generate.hpp
common/include/pcl/common/impl/projection_matrix.hpp
common/include/pcl/common/impl/transforms.hpp
common/include/pcl/common/intersections.h
common/include/pcl/common/io.h
common/include/pcl/common/pcl_filesystem.h [new file with mode: 0644]
common/include/pcl/console/print.h
common/include/pcl/conversions.h
common/include/pcl/exceptions.h
common/include/pcl/impl/instantiate.hpp
common/include/pcl/impl/point_types.hpp
common/include/pcl/make_shared.h [deleted file]
common/include/pcl/memory.h
common/include/pcl/pcl_exports.h
common/include/pcl/pcl_macros.h
common/include/pcl/point_cloud.h
common/include/pcl/point_traits.h [deleted file]
common/include/pcl/range_image/impl/range_image.hpp
common/include/pcl/range_image/range_image.h
common/include/pcl/range_image/range_image_planar.h
common/src/PCLPointCloud2.cpp
common/src/gaussian.cpp
common/src/io.cpp
common/src/pcl_base.cpp
common/src/print.cpp
common/src/range_image.cpp
common/src/range_image_planar.cpp
cuda/CMakeLists.txt
cuda/apps/CMakeLists.txt
cuda/apps/src/kinect_planes_cuda.cpp
cuda/common/CMakeLists.txt
cuda/features/CMakeLists.txt
cuda/io/CMakeLists.txt
cuda/sample_consensus/CMakeLists.txt
cuda/segmentation/CMakeLists.txt
doc/advanced/content/index.rst
doc/tutorials/content/compiling_pcl_windows.rst
doc/tutorials/content/iterative_closest_point.rst
doc/tutorials/content/normal_distributions_transform.rst
doc/tutorials/content/pcl_vcpkg_windows.rst
doc/tutorials/content/sources/bspline_fitting/bspline_fitting.cpp
doc/tutorials/content/sources/ensenso_cameras/ensenso_cloud_images_viewer.cpp
doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp
doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp
doc/tutorials/content/sources/iterative_closest_point/iterative_closest_point.cpp
doc/tutorials/content/sources/normal_distributions_transform/normal_distributions_transform.cpp
doc/tutorials/content/sources/vfh_recognition/build_tree.cpp
doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp
doc/tutorials/content/vfh_recognition.rst
doc/tutorials/content/walkthrough.rst
examples/CMakeLists.txt
examples/common/example_organized_point_cloud.cpp
examples/features/example_difference_of_normals.cpp
examples/geometry/CMakeLists.txt
examples/segmentation/example_cpc_segmentation.cpp
examples/segmentation/example_lccp_segmentation.cpp
examples/segmentation/example_supervoxels.cpp
features/CMakeLists.txt
features/include/pcl/features/boost.h [deleted file]
features/include/pcl/features/eigen.h [deleted file]
features/include/pcl/features/esf.h
features/include/pcl/features/impl/brisk_2d.hpp
features/include/pcl/features/impl/cppf.hpp
features/include/pcl/features/impl/cvfh.hpp
features/include/pcl/features/impl/esf.hpp
features/include/pcl/features/impl/flare.hpp
features/include/pcl/features/impl/integral_image2D.hpp
features/include/pcl/features/impl/integral_image_normal.hpp
features/include/pcl/features/impl/intensity_gradient.hpp
features/include/pcl/features/impl/our_cvfh.hpp
features/include/pcl/features/impl/pfh.hpp
features/include/pcl/features/impl/pfhrgb.hpp
features/include/pcl/features/impl/ppf.hpp
features/include/pcl/features/impl/ppfrgb.hpp
features/include/pcl/features/impl/principal_curvatures.hpp
features/include/pcl/features/impl/range_image_border_extractor.hpp
features/include/pcl/features/impl/rops_estimation.hpp
features/include/pcl/features/impl/shot_lrf_omp.hpp
features/include/pcl/features/moment_of_inertia_estimation.h
features/include/pcl/features/principal_curvatures.h
features/include/pcl/features/rops_estimation.h
features/src/narf.cpp
features/src/range_image_border_extractor.cpp
filters/CMakeLists.txt
filters/include/pcl/filters/approximate_voxel_grid.h
filters/include/pcl/filters/boost.h [deleted file]
filters/include/pcl/filters/convolution_3d.h
filters/include/pcl/filters/covariance_sampling.h
filters/include/pcl/filters/crop_hull.h
filters/include/pcl/filters/impl/bilateral.hpp
filters/include/pcl/filters/impl/conditional_removal.hpp
filters/include/pcl/filters/impl/convolution_3d.hpp
filters/include/pcl/filters/impl/covariance_sampling.hpp
filters/include/pcl/filters/impl/filter_indices.hpp
filters/include/pcl/filters/impl/normal_space.hpp
filters/include/pcl/filters/impl/pyramid.hpp
filters/include/pcl/filters/impl/radius_outlier_removal.hpp
filters/include/pcl/filters/impl/random_sample.hpp
filters/include/pcl/filters/impl/sampling_surface_normal.hpp
filters/include/pcl/filters/impl/statistical_outlier_removal.hpp
filters/include/pcl/filters/impl/uniform_sampling.hpp
filters/include/pcl/filters/impl/voxel_grid.hpp
filters/include/pcl/filters/impl/voxel_grid_covariance.hpp
filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp
filters/include/pcl/filters/model_outlier_removal.h
filters/include/pcl/filters/radius_outlier_removal.h
filters/include/pcl/filters/sampling_surface_normal.h
filters/include/pcl/filters/statistical_outlier_removal.h
filters/include/pcl/filters/uniform_sampling.h
filters/include/pcl/filters/voxel_grid.h
filters/include/pcl/filters/voxel_grid_covariance.h
filters/include/pcl/filters/voxel_grid_occlusion_estimation.h
filters/src/convolution.cpp
filters/src/passthrough.cpp
filters/src/random_sample.cpp
filters/src/statistical_outlier_removal.cpp
filters/src/voxel_grid.cpp
filters/src/voxel_grid_label.cpp
geometry/CMakeLists.txt
geometry/include/pcl/geometry/eigen.h [deleted file]
geometry/include/pcl/geometry/mesh_base.h
gpu/CMakeLists.txt
gpu/containers/CMakeLists.txt
gpu/containers/include/pcl/gpu/containers/impl/repacks.hpp [new file with mode: 0644]
gpu/containers/include/pcl/gpu/containers/impl/texture_binder.hpp [new file with mode: 0644]
gpu/containers/src/initialization.cpp
gpu/containers/src/repacks.cu [new file with mode: 0644]
gpu/features/CMakeLists.txt
gpu/features/src/centroid.cu
gpu/features/src/fpfh.cu
gpu/features/src/normal_3d.cu
gpu/features/test/CMakeLists.txt
gpu/kinfu/CMakeLists.txt
gpu/kinfu/tools/CMakeLists.txt
gpu/kinfu/tools/kinfu_app.cpp
gpu/kinfu/tools/kinfu_app_sim.cpp
gpu/kinfu_large_scale/CMakeLists.txt
gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h
gpu/kinfu_large_scale/src/screenshot_manager.cpp
gpu/kinfu_large_scale/tools/CMakeLists.txt
gpu/kinfu_large_scale/tools/kinfuLS_app.cpp
gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp
gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp
gpu/octree/CMakeLists.txt
gpu/octree/include/pcl/gpu/octree/device_format.hpp
gpu/octree/include/pcl/gpu/octree/octree.hpp
gpu/octree/src/cuda/octree_builder.cu
gpu/octree/src/cuda/octree_host.cu
gpu/octree/src/octree.cpp
gpu/octree/src/utils/approx_nearest_utils.hpp
gpu/people/CMakeLists.txt
gpu/people/include/pcl/gpu/people/label_common.h
gpu/people/src/cuda/elec.cu
gpu/people/src/cuda/multi_tree.cu
gpu/people/src/cuda/prob.cu
gpu/people/src/cuda/utils.cu
gpu/people/tools/CMakeLists.txt
gpu/people/tools/people_app.cpp
gpu/segmentation/CMakeLists.txt
gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp
gpu/surface/CMakeLists.txt
gpu/surface/src/cuda/convex_hull.cu
gpu/surface/test/CMakeLists.txt
gpu/tracking/CMakeLists.txt
gpu/utils/CMakeLists.txt
gpu/utils/include/pcl/gpu/utils/device/functional.hpp
gpu/utils/include/pcl/gpu/utils/device/static_check.hpp [deleted file]
gpu/utils/include/pcl/gpu/utils/device/vector_math.hpp
gpu/utils/include/pcl/gpu/utils/repacks.hpp
gpu/utils/include/pcl/gpu/utils/safe_call.hpp
gpu/utils/include/pcl/gpu/utils/texture_binder.hpp
gpu/utils/src/empty.cu [new file with mode: 0644]
gpu/utils/src/internal.hpp
gpu/utils/src/repacks.cpp [deleted file]
gpu/utils/src/repacks.cu [deleted file]
io/CMakeLists.txt
io/include/pcl/compression/octree_pointcloud_compression.h
io/include/pcl/io/boost.h [deleted file]
io/include/pcl/io/eigen.h [deleted file]
io/include/pcl/io/grabber.h
io/include/pcl/io/hdl_grabber.h
io/include/pcl/io/impl/auto_io.hpp
io/include/pcl/io/io.h [deleted file]
io/include/pcl/io/low_level_io.h
io/include/pcl/io/openni_camera/openni_device.h
io/include/pcl/io/ply/ply_parser.h
io/include/pcl/io/ply_io.h
io/include/pcl/io/robot_eye_grabber.h
io/include/pcl/io/tim_grabber.h
io/include/pcl/io/vtk_lib_io.h
io/src/ascii_io.cpp
io/src/auto_io.cpp
io/src/hdl_grabber.cpp
io/src/ifs_io.cpp
io/src/image_grabber.cpp
io/src/lzf.cpp
io/src/lzf_image_io.cpp
io/src/obj_io.cpp
io/src/openni2/openni2_device.cpp
io/src/openni2/openni2_timer_filter.cpp
io/src/openni2_grabber.cpp
io/src/openni_camera/openni_driver.cpp
io/src/openni_grabber.cpp
io/src/pcd_io.cpp
io/src/ply_io.cpp
io/src/real_sense_2_grabber.cpp
io/src/robot_eye_grabber.cpp
io/src/tim_grabber.cpp
io/src/vlp_grabber.cpp
io/src/vtk_lib_io.cpp
kdtree/CMakeLists.txt
kdtree/include/pcl/kdtree/kdtree.h
kdtree/include/pcl/kdtree/kdtree_flann.h
keypoints/CMakeLists.txt
keypoints/include/pcl/keypoints/uniform_sampling.h [deleted file]
keypoints/src/brisk_2d.cpp
keypoints/src/narf_keypoint.cpp
ml/CMakeLists.txt
ml/include/pcl/ml/svm_wrapper.h
ml/src/svm.cpp
octree/CMakeLists.txt
octree/include/pcl/octree/boost.h [deleted file]
octree/include/pcl/octree/impl/octree2buf_base.hpp
octree/include/pcl/octree/impl/octree_base.hpp
octree/include/pcl/octree/impl/octree_pointcloud.hpp
octree/include/pcl/octree/impl/octree_search.hpp
octree/include/pcl/octree/octree_search.h
octree/octree.doxy
outofcore/CMakeLists.txt
outofcore/include/pcl/outofcore/cJSON.h [deleted file]
outofcore/include/pcl/outofcore/impl/octree_base.hpp
outofcore/include/pcl/outofcore/impl/octree_base_node.hpp
outofcore/include/pcl/outofcore/impl/octree_disk_container.hpp
outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp
outofcore/include/pcl/outofcore/octree_base.h
outofcore/include/pcl/outofcore/octree_base_node.h
outofcore/include/pcl/outofcore/octree_disk_container.h
outofcore/include/pcl/outofcore/outofcore_base_data.h
outofcore/include/pcl/outofcore/outofcore_node_data.h
outofcore/src/cJSON.cpp [deleted file]
outofcore/tools/CMakeLists.txt
pcl_config.h.in
people/CMakeLists.txt
people/include/pcl/people/impl/head_based_subcluster.hpp
people/include/pcl/people/impl/height_map_2d.hpp
recognition/CMakeLists.txt
recognition/include/pcl/recognition/auxiliary.h [deleted file]
recognition/include/pcl/recognition/boost.h [deleted file]
recognition/include/pcl/recognition/bvh.h [deleted file]
recognition/include/pcl/recognition/color_gradient_modality.h
recognition/include/pcl/recognition/dotmod.h
recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h
recognition/include/pcl/recognition/hv/greedy_verification.h
recognition/include/pcl/recognition/hypothesis.h [deleted file]
recognition/include/pcl/recognition/impl/hv/hv_go.hpp
recognition/include/pcl/recognition/impl/implicit_shape_model.hpp
recognition/include/pcl/recognition/impl/line_rgbd.hpp [deleted file]
recognition/include/pcl/recognition/impl/simple_octree.hpp [deleted file]
recognition/include/pcl/recognition/impl/voxel_structure.hpp [deleted file]
recognition/include/pcl/recognition/implicit_shape_model.h
recognition/include/pcl/recognition/line_rgbd.h [deleted file]
recognition/include/pcl/recognition/linemod/line_rgbd.h
recognition/include/pcl/recognition/model_library.h [deleted file]
recognition/include/pcl/recognition/obj_rec_ransac.h [deleted file]
recognition/include/pcl/recognition/orr_graph.h [deleted file]
recognition/include/pcl/recognition/orr_octree.h [deleted file]
recognition/include/pcl/recognition/orr_octree_zprojection.h [deleted file]
recognition/include/pcl/recognition/ransac_based/bvh.h
recognition/include/pcl/recognition/rigid_transform_space.h [deleted file]
recognition/include/pcl/recognition/simple_octree.h [deleted file]
recognition/include/pcl/recognition/trimmed_icp.h [deleted file]
recognition/include/pcl/recognition/voxel_structure.h [deleted file]
recognition/src/face_detection/face_detector_data_provider.cpp
recognition/src/face_detection/rf_face_detector_trainer.cpp
recognition/src/implicit_shape_model.cpp
recognition/src/ransac_based/model_library.cpp
recognition/src/ransac_based/obj_rec_ransac.cpp
registration/CMakeLists.txt
registration/include/pcl/registration/boost.h [deleted file]
registration/include/pcl/registration/correspondence_estimation.h
registration/include/pcl/registration/correspondence_rejection_features.h
registration/include/pcl/registration/eigen.h [deleted file]
registration/include/pcl/registration/gicp.h
registration/include/pcl/registration/ia_fpcs.h
registration/include/pcl/registration/ia_kfpcs.h
registration/include/pcl/registration/icp.h
registration/include/pcl/registration/impl/correspondence_estimation.hpp
registration/include/pcl/registration/impl/correspondence_rejection_distance.hpp [deleted file]
registration/include/pcl/registration/impl/correspondence_rejection_median_distance.hpp [deleted file]
registration/include/pcl/registration/impl/correspondence_rejection_one_to_one.hpp [deleted file]
registration/include/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp [deleted file]
registration/include/pcl/registration/impl/correspondence_rejection_surface_normal.hpp [deleted file]
registration/include/pcl/registration/impl/correspondence_rejection_trimmed.hpp [deleted file]
registration/include/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp [deleted file]
registration/include/pcl/registration/impl/default_convergence_criteria.hpp
registration/include/pcl/registration/impl/elch.hpp
registration/include/pcl/registration/impl/gicp.hpp
registration/include/pcl/registration/impl/ia_fpcs.hpp
registration/include/pcl/registration/impl/ia_kfpcs.hpp
registration/include/pcl/registration/impl/icp_nl.hpp
registration/include/pcl/registration/impl/lum.hpp
registration/include/pcl/registration/impl/ndt.hpp
registration/include/pcl/registration/impl/pyramid_feature_matching.hpp
registration/include/pcl/registration/impl/registration.hpp
registration/include/pcl/registration/impl/sample_consensus_prerejective.hpp
registration/include/pcl/registration/impl/transformation_estimation_2D.hpp
registration/include/pcl/registration/impl/transformation_estimation_3point.hpp
registration/include/pcl/registration/impl/transformation_estimation_dq.hpp [deleted file]
registration/include/pcl/registration/impl/transformation_estimation_svd.hpp
registration/include/pcl/registration/impl/transformation_estimation_svd_scale.hpp
registration/include/pcl/registration/ndt.h
registration/include/pcl/registration/ppf_registration.h
registration/include/pcl/registration/transformation_estimation_dq.h [deleted file]
registration/include/pcl/registration/transforms.h [deleted file]
registration/include/pcl/registration/warp_point_rigid.h
registration/include/pcl/registration/warp_point_rigid_3d.h
registration/include/pcl/registration/warp_point_rigid_6d.h
registration/registration.doxy
registration/src/gicp6d.cpp
registration/src/transformation_estimation_dq.cpp [deleted file]
sample_consensus/CMakeLists.txt
sample_consensus/include/pcl/sample_consensus/boost.h [deleted file]
sample_consensus/include/pcl/sample_consensus/eigen.h [deleted file]
sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp
sample_consensus/include/pcl/sample_consensus/impl/rransac.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_plane.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_torus.hpp [new file with mode: 0644]
sample_consensus/include/pcl/sample_consensus/rmsac.h
sample_consensus/include/pcl/sample_consensus/rransac.h
sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h
sample_consensus/include/pcl/sample_consensus/sac_model_cone.h
sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h
sample_consensus/include/pcl/sample_consensus/sac_model_ellipse3d.h
sample_consensus/include/pcl/sample_consensus/sac_model_plane.h
sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h
sample_consensus/include/pcl/sample_consensus/sac_model_torus.h [new file with mode: 0644]
sample_consensus/sample_consensus.doxy
sample_consensus/src/sac_model_torus.cpp [new file with mode: 0644]
search/CMakeLists.txt
search/include/pcl/search/impl/organized.hpp
search/include/pcl/search/organized.h
segmentation/CMakeLists.txt
segmentation/include/pcl/segmentation/boost.h [deleted file]
segmentation/include/pcl/segmentation/extract_clusters.h
segmentation/include/pcl/segmentation/extract_labeled_clusters.h
segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h
segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp
segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp
segmentation/include/pcl/segmentation/impl/crf_normal_segmentation.hpp
segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp
segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp
segmentation/include/pcl/segmentation/impl/extract_polygonal_prism_data.hpp
segmentation/include/pcl/segmentation/impl/grabcut_segmentation.hpp
segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp
segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp
segmentation/include/pcl/segmentation/impl/region_growing.hpp
segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp
segmentation/include/pcl/segmentation/impl/seeded_hue_segmentation.hpp
segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp
segmentation/include/pcl/segmentation/impl/unary_classifier.hpp
segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h
segmentation/include/pcl/segmentation/plane_refinement_comparator.h
segmentation/include/pcl/segmentation/supervoxel_clustering.h
segmentation/src/crf_segmentation.cpp
segmentation/src/grabcut_segmentation.cpp
segmentation/src/region_growing_rgb.cpp
segmentation/src/supervoxel_clustering.cpp
simulation/CMakeLists.txt
simulation/src/model.cpp
simulation/tools/CMakeLists.txt
simulation/tools/sim_viewer.cpp
stereo/CMakeLists.txt
surface/CMakeLists.txt
surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_polyedgecurve.h
surface/include/pcl/surface/3rdparty/poisson4/octree_poisson.hpp
surface/include/pcl/surface/3rdparty/poisson4/poisson_exceptions.h
surface/include/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp
surface/include/pcl/surface/bilateral_upsampling.h
surface/include/pcl/surface/boost.h [deleted file]
surface/include/pcl/surface/eigen.h [deleted file]
surface/include/pcl/surface/grid_projection.h
surface/include/pcl/surface/impl/convex_hull.hpp
surface/include/pcl/surface/impl/gp3.hpp
surface/include/pcl/surface/impl/grid_projection.hpp
surface/include/pcl/surface/impl/marching_cubes.hpp
surface/include/pcl/surface/impl/marching_cubes_rbf.hpp
surface/include/pcl/surface/mls.h
surface/include/pcl/surface/on_nurbs/fitting_curve_2d_asdm.h
surface/include/pcl/surface/on_nurbs/fitting_curve_2d_atdm.h
surface/include/pcl/surface/on_nurbs/fitting_curve_2d_sdm.h
surface/include/pcl/surface/on_nurbs/fitting_curve_2d_tdm.h
surface/include/pcl/surface/on_nurbs/fitting_surface_tdm.h
surface/src/3rdparty/opennurbs/opennurbs_3dm_settings.cpp
surface/src/3rdparty/opennurbs/opennurbs_archive.cpp
surface/src/3rdparty/opennurbs/opennurbs_lookup.cpp
surface/src/3rdparty/opennurbs/opennurbs_material.cpp
surface/src/3rdparty/opennurbs/opennurbs_math.cpp
surface/src/3rdparty/opennurbs/opennurbs_mesh.cpp
surface/src/3rdparty/opennurbs/opennurbs_nurbssurface.cpp
surface/src/3rdparty/opennurbs/opennurbs_nurbsvolume.cpp
surface/src/3rdparty/opennurbs/opennurbs_object.cpp
surface/src/3rdparty/opennurbs/opennurbs_point.cpp
surface/src/3rdparty/opennurbs/opennurbs_rtree.cpp
surface/src/gp3.cpp
surface/src/on_nurbs/on_nurbs.cmake
test/2d/CMakeLists.txt
test/CMakeLists.txt
test/common/CMakeLists.txt
test/common/test_io.cpp
test/common/test_wrappers.cpp
test/features/CMakeLists.txt
test/features/test_curvatures_estimation.cpp
test/filters/CMakeLists.txt
test/filters/test_filters.cpp
test/filters/test_uniform_sampling.cpp
test/fuzz/build.sh
test/geometry/CMakeLists.txt
test/geometry/test_mesh.cpp
test/geometry/test_mesh_circulators.cpp
test/geometry/test_mesh_common_functions.h
test/geometry/test_mesh_data.cpp
test/geometry/test_polygon_mesh.cpp
test/geometry/test_quad_mesh.cpp
test/geometry/test_triangle_mesh.cpp
test/gpu/octree/CMakeLists.txt
test/io/CMakeLists.txt
test/io/test_grabbers.cpp
test/io/test_io.cpp
test/io/test_timestamp.cpp
test/kdtree/CMakeLists.txt
test/keypoints/CMakeLists.txt
test/ml/CMakeLists.txt
test/octree/CMakeLists.txt
test/octree/test_octree.cpp
test/outofcore/CMakeLists.txt
test/outofcore/test_outofcore.cpp
test/people/CMakeLists.txt
test/recognition/CMakeLists.txt
test/registration/CMakeLists.txt
test/registration/test_correspondence_estimation.cpp
test/registration/test_fpcs_ia.cpp
test/registration/test_fpcs_ia_data.h
test/registration/test_kfpcs_ia.cpp
test/registration/test_kfpcs_ia_data.h
test/registration/test_registration.cpp
test/registration/test_registration_api.cpp
test/sample_consensus/CMakeLists.txt
test/sample_consensus/test_sample_consensus_quadric_models.cpp
test/search/CMakeLists.txt
test/segmentation/CMakeLists.txt
test/segmentation/test_concave_prism.cpp [new file with mode: 0644]
test/segmentation/test_segmentation.cpp
test/surface/CMakeLists.txt
test/visualization/CMakeLists.txt
tools/CMakeLists.txt
tools/cluster_extraction.cpp
tools/converter.cpp
tools/elch.cpp
tools/fast_bilateral_filter.cpp
tools/grid_min.cpp
tools/image_grabber_saver.cpp
tools/image_grabber_viewer.cpp
tools/image_viewer.cpp
tools/local_max.cpp
tools/lum.cpp
tools/morph.cpp
tools/normal_estimation.cpp
tools/oni_viewer_simple.cpp
tools/openni2_viewer.cpp
tools/openni_image.cpp
tools/openni_pcd_recorder.cpp
tools/openni_save_image.cpp
tools/openni_viewer.cpp
tools/openni_viewer_simple.cpp
tools/passthrough_filter.cpp
tools/pcd_grabber_viewer.cpp
tools/pcd_viewer.cpp
tools/progressive_morphological_filter.cpp
tools/radius_filter.cpp
tools/sac_segmentation_plane.cpp
tools/tiff2pcd.cpp
tools/transform_point_cloud.cpp
tools/unary_classifier_segment.cpp
tools/uniform_sampling.cpp
tools/virtual_scanner.cpp
tracking/CMakeLists.txt
tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h
tracking/include/pcl/tracking/particle_filter.h
tracking/include/pcl/tracking/pyramidal_klt.h
tracking/src/coherence.cpp
visualization/CMakeLists.txt
visualization/include/pcl/visualization/area_picking_event.h
visualization/include/pcl/visualization/common/ren_win_interact_map.h
visualization/include/pcl/visualization/eigen.h [deleted file]
visualization/include/pcl/visualization/impl/pcl_visualizer.hpp
visualization/include/pcl/visualization/impl/point_cloud_color_handlers.hpp
visualization/include/pcl/visualization/interactor_style.h
visualization/include/pcl/visualization/pcl_visualizer.h
visualization/include/pcl/visualization/qvtk_compatibility.h
visualization/include/pcl/visualization/vtk.h [deleted file]
visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h
visualization/src/interactor_style.cpp
visualization/src/pcl_visualizer.cpp
visualization/src/point_cloud_handlers.cpp

index bc6d750182067d022839fa3da0283c3f3bfe6bb8..c69343d53b3b03879aac59bd0ad9c7b6a1f61b56 100644 (file)
@@ -24,8 +24,8 @@ resources:
       image: pointcloudlibrary/env:20.04
     - container: env2204
       image: pointcloudlibrary/env:22.04
-    - container: env2304
-      image: pointcloudlibrary/env:23.04
+    - container: env2404
+      image: pointcloudlibrary/env:24.04
 
 stages:
   - stage: formatting
@@ -48,12 +48,13 @@ stages:
               CC: gcc
               CXX: g++
               BUILD_GPU: ON
-              CMAKE_ARGS: '-DPCL_WARNINGS_ARE_ERRORS=ON'
-            23.04 GCC:  # latest Ubuntu
-              CONTAINER: env2304
+              CMAKE_ARGS: '-DPCL_WARNINGS_ARE_ERRORS=ON -DCMAKE_CXX_STANDARD=14 -DCMAKE_CUDA_STANDARD=14'
+            24.04 GCC:  # latest Ubuntu
+              CONTAINER: env2404
               CC: gcc
               CXX: g++
               BUILD_GPU: ON
+              CMAKE_ARGS: '-DCMAKE_CXX_STANDARD=17 -DCMAKE_CUDA_STANDARD=17'
         container: $[ variables['CONTAINER'] ]
         timeoutInMinutes: 0
         variables:
@@ -73,12 +74,12 @@ stages:
           vmImage: '$(VMIMAGE)'
         strategy:
           matrix:
-            Monterey 12:
-              VMIMAGE: 'macOS-12'
-              OSX_VERSION: '12'
             Ventura 13:
               VMIMAGE: 'macOS-13'
               OSX_VERSION: '13'
+            Sonoma 14:
+              VMIMAGE: 'macOS-14'
+              OSX_VERSION: '14'
         timeoutInMinutes: 0
         variables:
           BUILD_DIR: '$(Agent.WorkFolder)/build'
index b085dba0552171fe1e8efb59f519954e36f37220..32a7825bcdfbaa593c19bd38bbc91018a9e1a16a 100644 (file)
@@ -3,7 +3,7 @@ steps:
     # find the commit hash on a quick non-forced update too
     fetchDepth: 10
   - script: |
-      brew install cmake pkg-config boost eigen flann glew libusb qhull vtk glew qt5 libpcap libomp google-benchmark
+      brew install cmake pkg-config boost eigen flann glew libusb qhull vtk glew freeglut qt5 libpcap libomp suite-sparse zlib google-benchmark cjson
       brew install brewsci/science/openni
       git clone https://github.com/abseil/googletest.git $GOOGLE_TEST_DIR # the official endpoint changed to abseil/googletest
       cd $GOOGLE_TEST_DIR && git checkout release-1.8.1
@@ -18,6 +18,7 @@ steps:
         -DGTEST_INCLUDE_DIR="$GOOGLE_TEST_DIR/googletest/include" \
         -DQt5_DIR=/usr/local/opt/qt5/lib/cmake/Qt5 \
         -DPCL_ONLY_CORE_POINT_TYPES=ON \
+        -DBUILD_surface_on_nurbs=ON -DUSE_UMFPACK=ON \
         -DBUILD_simulation=ON \
         -DBUILD_global_tests=ON \
         -DBUILD_benchmarks=ON \
index 961e34ea1288f4ebdd1acb8e9e369586459f82da..ea9897fd376cf70a22b5da8666fcfd4a8e08d9d9 100644 (file)
@@ -27,8 +27,7 @@ steps:
       -DBUILD_GPU=$BUILD_GPU \
       -DBUILD_cuda_io=$BUILD_GPU \
       -DBUILD_gpu_tracking=$BUILD_GPU \
-      -DBUILD_gpu_surface=$BUILD_GPU \
-      -DBUILD_gpu_people=$BUILD_GPU
+      -DBUILD_gpu_surface=$BUILD_GPU
       # Temporary fix to ensure no tests are skipped
       cmake $(Build.SourcesDirectory)
     displayName: 'CMake Configuration'
index a6559a223016493ef3b4b8511bb0e141dbd49fa4..905f59fd795726385cd7e95dec9f63371e7c9d75 100644 (file)
@@ -46,16 +46,21 @@ jobs:
         UBUNTU_VERSION: 20.04
         VTK_VERSION: 7
         TAG: 20.04
-      # Test the latest LTS version of Ubuntu
       Ubuntu 22.04:
         UBUNTU_VERSION: 22.04
         VTK_VERSION: 9
         TAG: 22.04
-      Ubuntu 23.04:
-        UBUNTU_VERSION: 23.04
+      # Test the latest LTS version of Ubuntu
+      Ubuntu 24.04:
+        UBUNTU_VERSION: 24.04
+        VTK_VERSION: 9
+        TAG: 24.04
+      # Test the latest version of Ubuntu (non LTS)
+      Ubuntu 24.10:
+        UBUNTU_VERSION: 24.10
         USE_LATEST_CMAKE: true
         VTK_VERSION: 9
-        TAG: 23.04
+        TAG: 24.10
   steps:
   - script: |
       dockerBuildArgs="" ; \
@@ -114,7 +119,7 @@ jobs:
         PLATFORM: x86
         TAG: windows2022-x86
         GENERATOR: "'Visual Studio 16 2019' -A Win32"
-        VCPKGCOMMIT: 8eb57355a4ffb410a2e94c07b4dca2dffbee8e50
+        VCPKGCOMMIT: f7423ee180c4b7f40d43402c2feb3859161ef625
       Winx64:
         PLATFORM: x64
         TAG: windows2022-x64
index 81ba26c663e23ae66f1c4b15982c8921cf87c279..3a02ab0f3ce576891f61efb15ecc367df801380a 100644 (file)
@@ -89,10 +89,8 @@ stages:
       vmImage: 'ubuntu-latest'
     strategy:
       matrix:
-        # Only ROS Melodic works with current releases of PCL
-        # Kinetic has stopped supporting any version later than PCL 1.7.2
-        ROS Melodic:
-          flavor: "melodic"
+        ROS Noetic:
+          flavor: "noetic"
     variables:
       tag: "ros"
     steps:
index 24f34dbe349fff299f7c3a840ab2d32bfd1f7e5f..997e62726fcb49ba6a8f7af67417273db85ad539 100644 (file)
@@ -30,13 +30,13 @@ jobs:
   steps:
   - script: |
       POSSIBLE_VTK_VERSION=("9") \
-      POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \
+      POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20" "23") \
       POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \
-      POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang libomp-dev" "clang-13 libomp-13-dev" "clang-14 libomp-14-dev" "clang-15 libomp-15-dev" "clang-16 libomp-16-dev" "clang-17 libomp-17-dev") \
-      POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \
-      POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16" "clang++-17") \
+      POSSIBLE_COMPILER_PACKAGE=("g++" "g++-11" "g++-12" "g++-13" "g++-14" "clang libomp-dev" "clang-14 libomp-14-dev" "clang-15 libomp-15-dev" "clang-16 libomp-16-dev" "clang-17 libomp-17-dev" "clang-18 libomp-18-dev" "clang-19 libomp-19-dev") \
+      POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-11" "gcc-12" "gcc-13" "gcc-14" "clang" "clang-14" "clang-15" "clang-16" "clang-17" "clang-18" "clang-19") \
+      POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-11" "g++-12" "g++-13" "g++-14" "clang++" "clang++-14" "clang++-15" "clang++-16" "clang++-17" "clang++-18" "clang++-19") \
       CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \
-      dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]} --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \
+      dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=\"${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]}\" --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \
       echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs"
     displayName: "Prepare docker build arguments"
   - task: Docker@2
index b4a145f835380afe809fb2232a5f6260ca1d4ece..ba61a35b95837aaf6788f3bda87ba08036af216b 100644 (file)
@@ -1,6 +1,8 @@
 ---
 Checks: >
     -*,
+    bugprone-copy-constructor-init,
+    bugprone-macro-parentheses,
     cppcoreguidelines-pro-type-cstyle-cast,
     cppcoreguidelines-pro-type-static-cast-downcast,
     google-readability-casting,
index 27579269a1f554fceaa302298815beb57fccda7e..a8122a96cfb81c242345c5a363bccf71b4b3333e 100644 (file)
@@ -34,8 +34,10 @@ RUN apt-get update \
       libboost-filesystem-dev \
       libboost-iostreams-dev \
       libboost-system-dev \
+      libcjson-dev \
       libflann-dev \
       libglew-dev \
+      freeglut3-dev \
       libgtest-dev \
       libomp-dev \
       libopenni-dev \
index 2541cc6837b198c9bd9fedbc30f551a41f83d46f..3d0cf1413080e37c6bde11bcbaac9a4b32af2f93 100644 (file)
@@ -1,9 +1,9 @@
 # flavor appears twice, once for the FOR, once for the contents since
 # Dockerfile seems to reset arguments after a FOR appears
-ARG flavor="melodic"
+ARG flavor="noetic"
 FROM ros:${flavor}-robot
 
-ARG flavor="melodic"
+ARG flavor="noetic"
 ARG workspace="/root/catkin_ws"
 
 COPY ${flavor}_rosinstall.yaml ${workspace}/src/.rosinstall
@@ -17,10 +17,12 @@ COPY ${flavor}_rosinstall.yaml ${workspace}/src/.rosinstall
 RUN sed -i "s/^# deb-src/deb-src/" /etc/apt/sources.list \
  && apt update \
  && apt install -y \
+    git \
+    libboost-iostreams-dev \
     libeigen3-dev \
     libflann-dev \
     libqhull-dev \
-    python-pip \
+    python3-pip \
     ros-${flavor}-tf2-eigen \
  && pip install -U pip \
  && pip install catkin_tools \
diff --git a/.dev/docker/perception_pcl_ros/noetic_rosinstall.yaml b/.dev/docker/perception_pcl_ros/noetic_rosinstall.yaml
new file mode 100644 (file)
index 0000000..e8f0805
--- /dev/null
@@ -0,0 +1,12 @@
+- git:
+    local-name: 'noetic/perception_pcl'
+    uri: 'https://github.com/ros-perception/perception_pcl'
+    version: 'melodic-devel'
+- git:
+    local-name: 'noetic/pcl_msgs'
+    uri: 'https://github.com/ros-perception/pcl_msgs'
+    version: 'noetic-devel'
+- git:
+    local-name: 'pcl'
+    uri: 'https://github.com/PointCloudLibrary/pcl'
+    version: 'master'
index ae6fc94be867343cdf04fe6a9cb8b59f9ced3173..902cc9a8c1a5cb647a0e5c7e36fe58ccc5f0ab5b 100644 (file)
@@ -30,15 +30,14 @@ RUN wget $Env:CHANNEL_BASE_URL/vs_buildtools.exe -OutFile 'C:\TEMP\vs_buildtools
     "C:\TEMP\VisualStudio.chman",                                   `
     "--add",                                                        `
     "Microsoft.VisualStudio.Workload.VCTools",                      `
-    "Microsoft.Net.Component.4.8.SDK",                            `
+    "Microsoft.Net.Component.4.8.SDK",                              `
     "Microsoft.VisualStudio.Component.VC.ATLMFC",                   `
     "--includeRecommended"                                          `
     -Wait -PassThru;                                                `
     del c:\temp\vs_buildtools.exe;                                  
 
-# VCPKG requires update if Cmake version is > 3.20.5 see: https://github.com/microsoft/vcpkg-tool/pull/107
 RUN iex ((New-Object System.Net.WebClient).DownloadString('https://chocolatey.org/install.ps1'));   `
-    choco install cmake --version=3.20.5 --installargs 'ADD_CMAKE_TO_PATH=System' -y --no-progress; `
+    choco install cmake --installargs 'ADD_CMAKE_TO_PATH=System' -y --no-progress; `
     choco install git -y --no-progress
 
 RUN git clone https://github.com/microsoft/vcpkg.git; cd vcpkg; git checkout $Env:VCPKGCOMMIT;
@@ -46,7 +45,32 @@ RUN git clone https://github.com/microsoft/vcpkg.git; cd vcpkg; git checkout $En
 # To explicit set VCPKG to only build Release version of the libraries.
 COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cmake'
 
-RUN cd .\vcpkg;                                                `
-    .\bootstrap-vcpkg.bat;                                            `
-    .\vcpkg install boost flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b; `
+RUN cd .\vcpkg;                                                     `
+    .\bootstrap-vcpkg.bat;                                          `
+    .\vcpkg install `
+    boost-accumulators `
+    boost-asio `
+    boost-algorithm `
+    boost-filesystem `
+    boost-format `
+    boost-graph `
+    boost-interprocess `
+    boost-iostreams `
+    boost-math `
+    boost-ptr-container `
+    boost-signals2 `
+    boost-sort `
+    boost-uuid `
+    boost-cmake `
+    flann `
+    eigen3 `
+    qhull `
+    glew `
+    freeglut `
+    vtk[qt,opengl] `
+    gtest `
+    benchmark `
+    openni2 `
+    cjson `
+    --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b;
 
index a78a188185a875b464889d72a274c792fc997ff5..59fc4071c269fd72168e1727196944b26adacc1e 100755 (executable)
@@ -6,15 +6,15 @@ jobs:
   tidy:
     runs-on: ubuntu-latest
     container:
-      image: pointcloudlibrary/env:22.04
+      image: pointcloudlibrary/env:24.04
     
     steps:
-    - uses: actions/checkout@v3
+    - uses: actions/checkout@v4
 
     - name: Run clang-tidy
       run: |
           bash -c "$(wget -O - https://apt.llvm.org/llvm.sh)"
-          cmake -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -DCMAKE_CXX_COMPILER=/usr/bin/clang-14 -DCMAKE_C_COMPILER=/usr/bin/clang-14 . \
+          cmake -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -DCMAKE_CXX_COMPILER=/usr/bin/clang-18 -DCMAKE_C_COMPILER=/usr/bin/clang-18 . \
             -DBUILD_benchmarks=ON \
             -DBUILD_examples=ON \
             -DBUILD_simulation=ON \
index e97d4adbb7ae5f64b79e51123c8be6e2ca20d31e..45f9f9e58ec88657303734c09868371950e7819f 100644 (file)
@@ -2,9 +2,8 @@ set(SUBSYS_NAME 2d)
 set(SUBSYS_DESC "Point cloud 2d")
 set(SUBSYS_DEPS common filters)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
-PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS vtk)
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
@@ -30,13 +29,10 @@ set(impl_incs
   "include/pcl/${SUBSYS_NAME}/impl/morphology.hpp"
 )
 
-if(${VTK_FOUND})
-  set(VTK_IO_TARGET_LINK_LIBRARIES vtkCommon vtkWidgets vtkIO vtkImaging)
-endif()
-
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
+PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} INCLUDES ${incs} ${impl_incs})
+target_link_libraries(${LIB_NAME} INTERFACE pcl_filters)
+
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} HEADER_ONLY)
 
 #Install include files
index 75e35f94641dae112e9eb3e1403ac0451530c3f1..a79eb7f93889fa27c6e7242f1d61515b4a89f5c3 100644 (file)
@@ -259,9 +259,7 @@ Edge<PointInT, PointOutT>::suppressNonMaxima(
   const int height = edges.height;
   const int width = edges.width;
 
-  maxima.height = height;
-  maxima.width = width;
-  maxima.resize(height * width);
+  maxima.resize(edges.width, edges.height);
 
   for (auto& point : maxima)
     point.intensity = 0.0f;
index 1faa1b86236f4bdfe702cbf9e0ca70f4cb4dc4d2..76b21eb3f70c918ea08e61d2b6a7d6632dd06269 100644 (file)
@@ -1,5 +1,238 @@
 # ChangeList
 
+## = 1.15.0 (22 February 2025) =
+
+### Notable changes
+
+**New features** *added to PCL*
+
+* **[filters]** UniformSampling Filter: add option for a minimum number of points required per voxel [[#5968](https://github.com/PointCloudLibrary/pcl/pull/5968)]
+* **[sample_consensus]** Torus ransac model [[#5816](https://github.com/PointCloudLibrary/pcl/pull/5816)]
+* **[common]** Allow type conversion in fromPCLPointCloud2 [[#6059](https://github.com/PointCloudLibrary/pcl/pull/6059)]
+* **[segmentation]** ExtractPolygonalPrismData and ConcaveHull bugfix [[#5168](https://github.com/PointCloudLibrary/pcl/pull/5168)]
+* Allow hidden visibility default on gcc/clang [[#5779](https://github.com/PointCloudLibrary/pcl/pull/5779)]
+
+**Deprecation** *of public APIs, scheduled to be removed after two minor releases*
+
+* **[registration]** Fix spelling error in pcl::NormalDistributionsTransform getOulierRatio/setOulierRatio [[#6140](https://github.com/PointCloudLibrary/pcl/pull/6140)]
+
+**Removal** *of the public APIs deprecated in previous releases*
+
+* Remove Deprecated Code for 1.15.0 release [[#6040](https://github.com/PointCloudLibrary/pcl/pull/6040)]
+
+**Behavior changes** *in classes, apps, or tools*
+
+* **[cmake]** Compile PCL as C++17 by default, switching back to C++14 currently still possible [[#6201](https://github.com/PointCloudLibrary/pcl/pull/6201)]
+
+**ABI changes** *that are still API compatible*
+
+* **[recognition]** C++17 filesystem for recognition module [[#5935](https://github.com/PointCloudLibrary/pcl/pull/5935)]
+* **[registration]** Add OMP based Multi-threading to IterativeClosestPoint [[#4520](https://github.com/PointCloudLibrary/pcl/pull/4520)]
+* **[segmentation]** ExtractPolygonalPrismData and ConcaveHull bugfix [[#5168](https://github.com/PointCloudLibrary/pcl/pull/5168)]
+
+### Changes grouped by module
+
+#### CMake:
+
+* Remove global includes and use target include for Apps [[#6009](https://github.com/PointCloudLibrary/pcl/pull/6009)]
+* Give users more control regarding with which point types classes are … [[#6062](https://github.com/PointCloudLibrary/pcl/pull/6062)]
+* Fix finding lib when install with relwithdebinfo or minsizerel [[#6089](https://github.com/PointCloudLibrary/pcl/pull/6089)]
+* Use system-installed cJSON, if available [[#6084](https://github.com/PointCloudLibrary/pcl/pull/6084)]
+* Remove broken support for external metslib. [[#5959](https://github.com/PointCloudLibrary/pcl/pull/5959)]
+* Require at least Boost 1.71, support Boost 1.86, switch to BoostConfig.cmake [[#6105](https://github.com/PointCloudLibrary/pcl/pull/6105)]
+* Remove global includes and use target include for GPU/CUDA [[#6010](https://github.com/PointCloudLibrary/pcl/pull/6010)]
+* Remove findGLEW and FindOpenMP as they are already present in CMake. Update minimum required cmake to 3.16.3 [[#6100](https://github.com/PointCloudLibrary/pcl/pull/6100)]
+* PCLConfig.cmake.in: Handle potentially empty ${LIB} variable [[#6134](https://github.com/PointCloudLibrary/pcl/pull/6134)]
+* Replace make_directory (deprecated since CMake version 3.0) [[#6150](https://github.com/PointCloudLibrary/pcl/pull/6150)]
+* Updates to CXX flags and removal of cmake checks less than 3.16. [[#6144](https://github.com/PointCloudLibrary/pcl/pull/6144)]
+* Fix OpenMP on macOS/homebrew [[#6114](https://github.com/PointCloudLibrary/pcl/pull/6114)]
+* Preparation for Boost 1.87, flag change for GCC 14 [[#6166](https://github.com/PointCloudLibrary/pcl/pull/6166)]
+* Print warning if incompatible alignment option chosen [[#6184](https://github.com/PointCloudLibrary/pcl/pull/6184)]
+* **[behavior change]** Compile PCL as C++17 by default, switching back to C++14 currently still possible [[#6201](https://github.com/PointCloudLibrary/pcl/pull/6201)]
+* Fix linking with pcl_io_ply [[#6205](https://github.com/PointCloudLibrary/pcl/pull/6205)]
+* Remove global includes from PCL_SUBSYS_DEPEND in PCL_TARGETS and adjust accordingly [[#6013](https://github.com/PointCloudLibrary/pcl/pull/6013)]
+
+#### libpcl_common:
+
+* **[new feature]** Allow type conversion in fromPCLPointCloud2 [[#6059](https://github.com/PointCloudLibrary/pcl/pull/6059)]
+* change `sprintf` to `snprintf` to suppress deprecated warning on macOS [[#6102](https://github.com/PointCloudLibrary/pcl/pull/6102)]
+* Remove "No data to copy" warning in conversions.h [[#6108](https://github.com/PointCloudLibrary/pcl/pull/6108)]
+* add PCL_HIGH convenience macro [[#6136](https://github.com/PointCloudLibrary/pcl/pull/6136)]
+* Remove unnecessary PCL_EXPORTS in common [[#6141](https://github.com/PointCloudLibrary/pcl/pull/6141)]
+* Print warning if incompatible alignment option chosen [[#6184](https://github.com/PointCloudLibrary/pcl/pull/6184)]
+* Update `__func__` and `__PRETTY_FUNCTION__` defines for MSVC [[#6222](https://github.com/PointCloudLibrary/pcl/pull/6222)]
+
+#### libpcl_features:
+
+* Added parallel implementation of PrincipalCurvaturesEstimation [[#6048](https://github.com/PointCloudLibrary/pcl/pull/6048)]
+* :bug: Fix RoPS total area [[#6187](https://github.com/PointCloudLibrary/pcl/pull/6187)]
+
+#### libpcl_filters:
+
+* **[new feature]** UniformSampling Filter: add option for a minimum number of points required per voxel [[#5968](https://github.com/PointCloudLibrary/pcl/pull/5968)]
+* Fix issues related to nan/invalid points [[#6036](https://github.com/PointCloudLibrary/pcl/pull/6036)]
+* Make UniformSampling inherit from FilterIndices instead of Filter [[#6064](https://github.com/PointCloudLibrary/pcl/pull/6064)]
+* Fix an integer overflow issue in the PassThrough filter. [[#6097](https://github.com/PointCloudLibrary/pcl/pull/6097)]
+* Convolution3D: use dynamic schedule for OpenMP [[#6155](https://github.com/PointCloudLibrary/pcl/pull/6155)]
+* Add OpenMP to radius outlier removal [[#6182](https://github.com/PointCloudLibrary/pcl/pull/6182)]
+
+#### libpcl_gpu:
+
+* fix int type overflow by casting int to size_t [[#6058](https://github.com/PointCloudLibrary/pcl/pull/6058)]
+
+#### libpcl_io:
+
+* Fix problem with normals in obj loader [[#6047](https://github.com/PointCloudLibrary/pcl/pull/6047)]
+* fix saveRangeImagePlanarFilePNG [[#6095](https://github.com/PointCloudLibrary/pcl/pull/6095)]
+* fix pcd io small probability bug [[#6122](https://github.com/PointCloudLibrary/pcl/pull/6122)]
+* Preparation for Boost 1.87, flag change for GCC 14 [[#6166](https://github.com/PointCloudLibrary/pcl/pull/6166)]
+* Fix linking with pcl_io_ply [[#6205](https://github.com/PointCloudLibrary/pcl/pull/6205)]
+* Fix regression in OBJ loader [[#6228](https://github.com/PointCloudLibrary/pcl/pull/6228)]
+
+#### libpcl_octree:
+
+* Faster octree nearestKSearch [[#6037](https://github.com/PointCloudLibrary/pcl/pull/6037)]
+* Faster octree radiusSearch [[#6045](https://github.com/PointCloudLibrary/pcl/pull/6045)]
+
+#### libpcl_outofcore:
+
+* Use system-installed cJSON, if available [[#6084](https://github.com/PointCloudLibrary/pcl/pull/6084)]
+
+#### libpcl_recognition:
+
+* **[ABI break]** C++17 filesystem for recognition module [[#5935](https://github.com/PointCloudLibrary/pcl/pull/5935)]
+* add border type setting in linemod gauss step [[#6103](https://github.com/PointCloudLibrary/pcl/pull/6103)]
+
+#### libpcl_registration:
+
+* **[ABI break]** Add OMP based Multi-threading to IterativeClosestPoint [[#4520](https://github.com/PointCloudLibrary/pcl/pull/4520)]
+* GICP: parallel covariance computation [[#6046](https://github.com/PointCloudLibrary/pcl/pull/6046)]
+* Fixes and improvements for FPCS and KFPCS [[#6073](https://github.com/PointCloudLibrary/pcl/pull/6073)]
+* **[deprecation]** Fix spelling error in pcl::NormalDistributionsTransform getOulierRatio/setOulierRatio [[#6140](https://github.com/PointCloudLibrary/pcl/pull/6140)]
+* fix registration iteration 1 mse print [[#6198](https://github.com/PointCloudLibrary/pcl/pull/6198)]
+* Speed up PPFRegistration by using a hash function with fewer collisions [[#6223](https://github.com/PointCloudLibrary/pcl/pull/6223)]
+
+#### libpcl_sample_consensus:
+
+* **[new feature]** Torus ransac model [[#5816](https://github.com/PointCloudLibrary/pcl/pull/5816)]
+* Circle3D: fix optimizeModelCoefficients use an uninitialized var [[#6088](https://github.com/PointCloudLibrary/pcl/pull/6088)]
+* Set better default for RRANSAC and RMSAC [[#6158](https://github.com/PointCloudLibrary/pcl/pull/6158)]
+* Circle3D: Changed segmentation collinear check precision from float to double. [[#6175](https://github.com/PointCloudLibrary/pcl/pull/6175)]
+
+#### libpcl_search:
+
+* Faster organized radius search [[#6160](https://github.com/PointCloudLibrary/pcl/pull/6160)]
+
+#### libpcl_segmentation:
+
+* fix pcl::squaredEuclideanDistance already defined in grabcut_2d.cpp.obj [[#5985](https://github.com/PointCloudLibrary/pcl/pull/5985)]
+* **[new feature][ABI break]** ExtractPolygonalPrismData and ConcaveHull bugfix [[#5168](https://github.com/PointCloudLibrary/pcl/pull/5168)]
+* fix: Initialization with correct signedness [[#6111](https://github.com/PointCloudLibrary/pcl/pull/6111)]
+
+#### libpcl_surface:
+
+* Remove deprecated readdir_r [[#6035](https://github.com/PointCloudLibrary/pcl/pull/6035)]
+* Update opennurbs VS issue (opennurbs_lookup.cpp) [[#6143](https://github.com/PointCloudLibrary/pcl/pull/6143)]
+* Add missing include for implementation header in bilateral_upsampling.h [[#6203](https://github.com/PointCloudLibrary/pcl/pull/6203)]
+
+#### libpcl_visualization:
+
+* Fix issues related to nan/invalid points [[#6036](https://github.com/PointCloudLibrary/pcl/pull/6036)]
+* Fix boost hash data type [[#6053](https://github.com/PointCloudLibrary/pcl/pull/6053)]
+
+#### PCL Apps:
+
+* Preparation for Boost 1.87, flag change for GCC 14 [[#6166](https://github.com/PointCloudLibrary/pcl/pull/6166)]
+
+#### PCL Tools:
+
+* compile missing tools/bilateral_upsampling [[#6112](https://github.com/PointCloudLibrary/pcl/pull/6112)]
+
+#### CI:
+
+* Update windows docker boost and cmake [[#6033](https://github.com/PointCloudLibrary/pcl/pull/6033)]
+* CI: Install cjson [[#6082](https://github.com/PointCloudLibrary/pcl/pull/6082)]
+* Update Windows x86 docker, install boost-cmake [[#6109](https://github.com/PointCloudLibrary/pcl/pull/6109)]
+* Update clang-tidy github action [[#6116](https://github.com/PointCloudLibrary/pcl/pull/6116)]
+* Update macOS on CI (macOS 12 is now unmaintained) [[#6147](https://github.com/PointCloudLibrary/pcl/pull/6147)]
+* CI updates [[#6153](https://github.com/PointCloudLibrary/pcl/pull/6153)]
+* Fix OpenMP on macOS/homebrew [[#6114](https://github.com/PointCloudLibrary/pcl/pull/6114)]
+
+## = 1.14.1 (03 May 2024) =
+
+### Notable changes
+
+**New features** *added to PCL*
+
+* **[cmake]** Make Boost filesystem optional for C++17 [[#5937](https://github.com/PointCloudLibrary/pcl/pull/5937)]
+* **[common]** Enhance toPCLPointCloud2 to remove padding on request [[#5913](https://github.com/PointCloudLibrary/pcl/pull/5913)]
+* **[io]** Enable writing data in binary PLY format to std::ostream [[#5975](https://github.com/PointCloudLibrary/pcl/pull/5975)]
+
+### Changes grouped by module
+
+#### CMake:
+
+* Switch latest Ubuntu CI to C++17 [[#5931](https://github.com/PointCloudLibrary/pcl/pull/5931)]
+* **[new feature]** Make Boost filesystem optional for C++17 [[#5937](https://github.com/PointCloudLibrary/pcl/pull/5937)]
+* Add OpenGL_GLU as external dependency. [[#5963](https://github.com/PointCloudLibrary/pcl/pull/5963)]
+* Preparation for default hidden visibility on gcc [[#5970](https://github.com/PointCloudLibrary/pcl/pull/5970)]
+* Cmake cuda find_package cuda is deprecated. [[#5953](https://github.com/PointCloudLibrary/pcl/pull/5953)]
+* fix build with CUDA [[#5976](https://github.com/PointCloudLibrary/pcl/pull/5976)]
+* Enable compatibility with Boost 1.85.0 [[#6014](https://github.com/PointCloudLibrary/pcl/pull/6014)]
+
+#### libpcl_common:
+
+* Rename variables with reserved names (PointXYZLAB) [[#5951](https://github.com/PointCloudLibrary/pcl/pull/5951)]
+* **[new feature]** Enhance toPCLPointCloud2 to remove padding on request [[#5913](https://github.com/PointCloudLibrary/pcl/pull/5913)]
+* Fix behaviour of eigen33 function if smallest eigenvalue is not unique [[#5956](https://github.com/PointCloudLibrary/pcl/pull/5956)]
+* Add option to choose boost filesystem over std filesystem [[#6005](https://github.com/PointCloudLibrary/pcl/pull/6005)]
+
+#### libpcl_filters:
+
+* Fix Bug in NormalSpaceSampling::findBin() [[#5936](https://github.com/PointCloudLibrary/pcl/pull/5936)]
+* VoxelGridOcclusionEstimation should always round down to go from coordinates to voxel indices. [[#5942](https://github.com/PointCloudLibrary/pcl/pull/5942)]
+* StatisticalOutlierRemoval: fix potential container overflow read [[#5980](https://github.com/PointCloudLibrary/pcl/pull/5980)]
+* fixing ignored `pcl::Indices` in `VoxelGrid` of `PCLPointCloud2` [[#5979](https://github.com/PointCloudLibrary/pcl/pull/5979)]
+
+#### libpcl_gpu:
+
+* Add missing PCL_EXPORTS (economical_download, optimizeModelCoefficients, vtkRenderWindowInteractorFixNew) [[#5926](https://github.com/PointCloudLibrary/pcl/pull/5926)]
+
+#### libpcl_io:
+
+* Real Sense 2 grabber stream fix [[#5912](https://github.com/PointCloudLibrary/pcl/pull/5912)]
+* Improve documentation in vtk_lib_io [[#5955](https://github.com/PointCloudLibrary/pcl/pull/5955)]
+* Add special implementation for raw_fallocate for OpenBSD [[#5957](https://github.com/PointCloudLibrary/pcl/pull/5957)]
+* Fix missing include in ply_parser.h (#5962) [[#5964](https://github.com/PointCloudLibrary/pcl/pull/5964)]
+* **[new feature]** Enable writing data in binary PLY format to std::ostream [[#5975](https://github.com/PointCloudLibrary/pcl/pull/5975)]
+* OBJReader: fix possible out-of-bounds access [[#5988](https://github.com/PointCloudLibrary/pcl/pull/5988)]
+* ImageGrabber: Fix potential index out of bounds [[#6016](https://github.com/PointCloudLibrary/pcl/pull/6016)]
+
+#### libpcl_registration:
+
+* NDT: allow access to target cloud distribution [[#5969](https://github.com/PointCloudLibrary/pcl/pull/5969)]
+* Optimize Eigen block operations [[#5974](https://github.com/PointCloudLibrary/pcl/pull/5974)]
+
+#### libpcl_sample_consensus:
+
+* Add missing PCL_EXPORTS (economical_download, optimizeModelCoefficients, vtkRenderWindowInteractorFixNew) [[#5926](https://github.com/PointCloudLibrary/pcl/pull/5926)]
+
+#### libpcl_surface:
+
+* Add `pcl::PointXYZLNormal` to GP3 PCL_INSTANTIATE (#5981) [[#5983](https://github.com/PointCloudLibrary/pcl/pull/5983)]
+
+#### libpcl_visualization:
+
+* Add missing PCL_EXPORTS (economical_download, optimizeModelCoefficients, vtkRenderWindowInteractorFixNew) [[#5926](https://github.com/PointCloudLibrary/pcl/pull/5926)]
+* Add missing pragma once in qvtk_compatibility.h [[#5943](https://github.com/PointCloudLibrary/pcl/pull/5943)]
+* fixed setShapeRenderingProperties(PCL_VISUALIZER_FONT_SIZE) [[#5993](https://github.com/PointCloudLibrary/pcl/pull/5993)]
+* fix addPolygon and addLine return value error [[#5996](https://github.com/PointCloudLibrary/pcl/pull/5996)]
+
+#### CI:
+
+* Switch latest Ubuntu CI to C++17 [[#5931](https://github.com/PointCloudLibrary/pcl/pull/5931)]
+* Fix ubuntu-variety CI and update compilers [[#5990](https://github.com/PointCloudLibrary/pcl/pull/5990)]
+
 ## = 1.14.0 (03 January 2024) =
 
 ### Notable changes
index 1709af51df3b6b6f5159585f5c99c5e792cff82a..617498c7e36ce62f4e7265350dbbc1e25d780b5c 100644 (file)
@@ -1,19 +1,23 @@
 ### ---[ PCL global CMake
-cmake_minimum_required(VERSION 3.10 FATAL_ERROR)
-
-if(POLICY CMP0074)
-  # 1. Remove with 3.12.4.
-  # 2. Remove search paths with *_ROOT since they will be automatically checked
-  cmake_policy(SET CMP0074 NEW)
-endif()
+cmake_minimum_required(VERSION 3.16.3 FATAL_ERROR)
 
 # Set target C++ standard and required compiler features
-set(CMAKE_CXX_STANDARD 14 CACHE STRING "The target C++ standard. PCL requires C++14 or higher.")
+set(CMAKE_CXX_STANDARD 17 CACHE STRING "The target C++ standard. PCL requires C++14 or higher.")
 set(CMAKE_CXX_STANDARD_REQUIRED ON)
 set(CMAKE_CXX_EXTENSIONS OFF)
-set(PCL_CXX_COMPILE_FEATURES cxx_std_14)
+if("${CMAKE_CXX_STANDARD}" GREATER_EQUAL 17)
+  set(PCL_CXX_COMPILE_FEATURES cxx_std_17)
+  set(PCL__cplusplus 201703L)
+  set(PCL_REQUIRES_MSC_VER 1912)
+elseif("${CMAKE_CXX_STANDARD}" EQUAL 14)
+  set(PCL_CXX_COMPILE_FEATURES cxx_std_14)
+  set(PCL__cplusplus 201402L)
+  set(PCL_REQUIRES_MSC_VER 1900)
+else()
+  message(FATAL_ERROR "Unknown or unsupported C++ standard specified")
+endif()
 
-set(CMAKE_CUDA_STANDARD 14 CACHE STRING "The target CUDA/C++ standard. PCL requires CUDA/C++ 14 or higher.")
+set(CMAKE_CUDA_STANDARD 17 CACHE STRING "The target CUDA/C++ standard. PCL requires CUDA/C++ 14 or higher.")
 set(CMAKE_CUDA_STANDARD_REQUIRED ON)
 
 set(CMAKE_CONFIGURATION_TYPES "Debug;Release" CACHE STRING "possible configurations" FORCE)
@@ -23,7 +27,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "")
   set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE)
 endif()
 
-project(PCL VERSION 1.14.0)
+project(PCL VERSION 1.15.0)
 string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
 
 if(MSVC AND ("${MSVC_VERSION}" LESS 1910))
@@ -78,7 +82,8 @@ ENDIF()
 # Create a variable with expected default CXX flags
 # This will be used further down the road to check if the user explicitly provided CXX flags
 if(CMAKE_COMPILER_IS_MSVC)
-  set(CMAKE_CXX_FLAGS_DEFAULT "/DWIN32 /D_WINDOWS /W3 /GR /EHsc")
+  set(CMAKE_CXX_FLAGS_DEFAULT ${CMAKE_CXX_FLAGS_INIT})
+  string(STRIP ${CMAKE_CXX_FLAGS_DEFAULT} CMAKE_CXX_FLAGS_DEFAULT)
 else()
   set(CMAKE_CXX_FLAGS_DEFAULT "")
 endif()
@@ -111,11 +116,18 @@ if(PCL_ENABLE_AVX AND "${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}"
   PCL_CHECK_FOR_AVX()
 endif()
 
+# Cuda
+option(WITH_CUDA "Build NVIDIA-CUDA support" TRUE)
+if(WITH_CUDA)
+  include("${PCL_SOURCE_DIR}/cmake/pcl_find_cuda.cmake")
+endif()
+
+
 # ---[ Unix/Darwin/Windows specific flags
 if(CMAKE_COMPILER_IS_GNUCXX)
   if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
     if (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 7)
-      string(APPEND CMAKE_CXX_FLAGS " -Wabi=11")
+      string(APPEND CMAKE_CXX_FLAGS " -Wabi=18")
     else()
       string(APPEND CMAKE_CXX_FLAGS " -Wabi")
     endif()
@@ -144,20 +156,26 @@ if(CMAKE_COMPILER_IS_GNUCXX)
 endif()
 
 if(CMAKE_COMPILER_IS_MSVC)
-  add_definitions("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX -DPCL_ONLY_CORE_POINT_TYPES ${SSE_DEFINITIONS}")
-  
+  add_definitions("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX ${SSE_DEFINITIONS}")
+
   if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
+    
     string(APPEND CMAKE_CXX_FLAGS " /fp:precise ${SSE_FLAGS} ${AVX_FLAGS}")
+    set(CMAKE_CUDA_FLAGS "${CMAKE_CUDA_FLAGS} -Xcompiler=/bigobj")
+
+    set(PCL_USE_GLOBAL_OPTIMIZATION TRUE)
+    if(CUDA_FOUND)
+      if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "10.0" AND ${CUDA_VERSION_STRING} VERSION_LESS "12.0")
+        set(PCL_USE_GLOBAL_OPTIMIZATION FALSE)
+        message("Global optimizations /GL has been turned off, as it doesn't work with nvcc/thrust in CUDA 10 and 11.")
+      endif()
+    endif()
 
     # Add extra code generation/link optimizations
-    if(CMAKE_MSVC_CODE_LINK_OPTIMIZATION AND (NOT BUILD_CUDA) AND (NOT BUILD_GPU))
+    if(CMAKE_MSVC_CODE_LINK_OPTIMIZATION AND PCL_USE_GLOBAL_OPTIMIZATION)
       string(APPEND CMAKE_CXX_FLAGS_RELEASE " /GL")
       string(APPEND CMAKE_SHARED_LINKER_FLAGS_RELEASE " /LTCG /OPT:REF")
       string(APPEND CMAKE_EXE_LINKER_FLAGS_RELEASE " /LTCG")
-    else()
-      set(CMAKE_CUDA_FLAGS "${CMAKE_CUDA_FLAGS} -Xcompiler=/bigobj")
-      
-      message("Global optimizations /GL has been turned off, as it doesn't work with nvcc/thrust")
     endif()
     # /MANIFEST:NO") # please, don't disable manifest generation, otherwise crash at start for vs2008
 
@@ -182,24 +200,13 @@ if(CMAKE_COMPILER_IS_MSVC)
     include(ProcessorCount)
     ProcessorCount(CPUCores)
     set(MSVC_MP ${CPUCores} CACHE STRING "Number of simultaneously running compilers (0 = automatic detection by MSVC). See documentation of /MP flag.")
-    if (CMAKE_VERSION VERSION_LESS 3.11.0)
-      # Usage of COMPILE_LANGUAGE generator expression for MSVC in add_compile_options requires at least CMake 3.11, see https://gitlab.kitware.com/cmake/cmake/issues/17435
-      if(MSVC_MP EQUAL 0)
-        # MSVC_MP is 0 in case the information cannot be determined by ProcessorCount => fallback
-        string(APPEND CMAKE_C_FLAGS " /MP")
-        string(APPEND CMAKE_CXX_FLAGS " /MP")
-      elseif(MSVC_MP GREATER 1)
-        string(APPEND CMAKE_C_FLAGS " /MP${MSVC_MP}")
-        string(APPEND CMAKE_CXX_FLAGS " /MP${MSVC_MP}")
-      endif()      
-    else()      
-      if(MSVC_MP EQUAL 0)
-        # MSVC_MP is 0 in case the information cannot be determined by ProcessorCount => fallback
-        # Generator expression is necessary to limit /MP flag to C/CXX, so flag will be not set to e.g. CUDA (see https://gitlab.kitware.com/cmake/cmake/issues/17535)
-        add_compile_options($<$<OR:$<COMPILE_LANGUAGE:C>,$<COMPILE_LANGUAGE:CXX>>:/MP>)
-      elseif(MSVC_MP GREATER 1)
-        add_compile_options($<$<OR:$<COMPILE_LANGUAGE:C>,$<COMPILE_LANGUAGE:CXX>>:/MP${MSVC_MP}>)
-      endif()
+    
+    if(MSVC_MP EQUAL 0)
+      # MSVC_MP is 0 in case the information cannot be determined by ProcessorCount => fallback
+      # Generator expression is necessary to limit /MP flag to C/CXX, so flag will be not set to e.g. CUDA (see https://gitlab.kitware.com/cmake/cmake/issues/17535)
+      add_compile_options($<$<OR:$<COMPILE_LANGUAGE:C>,$<COMPILE_LANGUAGE:CXX>>:/MP>)
+    elseif(MSVC_MP GREATER 1)
+      add_compile_options($<$<OR:$<COMPILE_LANGUAGE:C>,$<COMPILE_LANGUAGE:CXX>>:/MP${MSVC_MP}>)
     endif()
   endif()
   string(APPEND CMAKE_CXX_FLAGS " /bigobj")
@@ -232,10 +239,6 @@ if(CMAKE_COMPILER_IS_CLANG)
   set(CLANG_LIBRARIES "stdc++")
 endif()
 
-if(CMAKE_COMPILER_IS_MINGW)
-  add_definitions(-DPCL_ONLY_CORE_POINT_TYPES)
-endif()
-
 include("${PCL_SOURCE_DIR}/cmake/pcl_utils.cmake")
 DISSECT_VERSION()
 GET_OS_INFO()
@@ -248,8 +251,8 @@ endif()
 
 set(PCL_OUTPUT_LIB_DIR "${PCL_BINARY_DIR}/${LIB_INSTALL_DIR}")
 set(PCL_OUTPUT_BIN_DIR "${PCL_BINARY_DIR}/${BIN_INSTALL_DIR}")
-make_directory("${PCL_OUTPUT_LIB_DIR}")
-make_directory("${PCL_OUTPUT_BIN_DIR}")
+file(MAKE_DIRECTORY "${PCL_OUTPUT_LIB_DIR}")
+file(MAKE_DIRECTORY "${PCL_OUTPUT_BIN_DIR}")
 set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${PCL_OUTPUT_LIB_DIR}")
 set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${PCL_OUTPUT_BIN_DIR}")
 if(WIN32)
@@ -296,8 +299,24 @@ endif()
 
 # OpenMP (optional)
 option(WITH_OPENMP "Build with parallelization using OpenMP" TRUE)
+option(USE_HOMEBREW_FALLBACK "(macOS-only) also look in 'brew --prefix' for libraries (e.g. OpenMP)" TRUE)
 if(WITH_OPENMP)
   find_package(OpenMP COMPONENTS C CXX)
+  if(APPLE AND NOT OpenMP_FOUND)
+    if(USE_HOMEBREW_FALLBACK)
+      # libomp 15.0+ from brew is keg-only, so have to search in other locations.
+      # See https://github.com/Homebrew/homebrew-core/issues/112107#issuecomment-1278042927.
+      execute_process(COMMAND brew --prefix libomp
+                      OUTPUT_VARIABLE HOMEBREW_LIBOMP_PREFIX
+                      OUTPUT_STRIP_TRAILING_WHITESPACE)
+      set(OpenMP_C_FLAGS "-Xpreprocessor -fopenmp -I${HOMEBREW_LIBOMP_PREFIX}/include")
+      set(OpenMP_CXX_FLAGS "-Xpreprocessor -fopenmp -I${HOMEBREW_LIBOMP_PREFIX}/include")
+      set(OpenMP_C_LIB_NAMES omp)
+      set(OpenMP_CXX_LIB_NAMES omp)
+      set(OpenMP_omp_LIBRARY ${HOMEBREW_LIBOMP_PREFIX}/lib/libomp.dylib)
+      find_package(OpenMP COMPONENTS C CXX)
+    endif()
+  endif()
 endif()
 if(OpenMP_FOUND)
   string(APPEND CMAKE_C_FLAGS " ${OpenMP_C_FLAGS}")
@@ -349,26 +368,12 @@ PCL_ADD_GRABBER_DEPENDENCY("DSSDK" "DepthSense SDK support")
 PCL_ADD_GRABBER_DEPENDENCY("RSSDK" "RealSense SDK support")
 PCL_ADD_GRABBER_DEPENDENCY("RSSDK2" "RealSense SDK 2.0 (librealsense) support")
 
-# metslib
-if(PKG_CONFIG_FOUND)
-  pkg_check_modules(METSLIB metslib)
-  if(METSLIB_FOUND)
-    set(HAVE_METSLIB ON)
-    include_directories(SYSTEM ${METSLIB_INCLUDE_DIRS})
-  else()
-    include_directories(SYSTEM "${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/")
-  endif()
-else()
-    include_directories(SYSTEM ${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/)
-endif()
-
 # LibPNG
 option(WITH_PNG "PNG file support" TRUE)
 if(WITH_PNG)
   find_package(PNG)
   if(PNG_FOUND)
     set(HAVE_PNG ON)
-    include_directories(SYSTEM "${PNG_INCLUDE_DIR}")
   endif()
 endif()
 
@@ -381,10 +386,10 @@ if(WITH_QHULL)
   endif()
 endif()
 
-# Cuda
-option(WITH_CUDA "Build NVIDIA-CUDA support" TRUE)
-if(WITH_CUDA)
-  include("${PCL_SOURCE_DIR}/cmake/pcl_find_cuda.cmake")
+# find GLEW before VTK as it uses custom findGLEW that doesn't work with cmakes findGLEW.
+option(WITH_GLEW "Support for GLEW" TRUE)
+if(WITH_GLEW)
+  find_package(GLEW QUIET)
 endif()
 
 
@@ -431,6 +436,31 @@ if(WITH_SYSTEM_ZLIB)
   endif()
 endif()
 
+option(WITH_SYSTEM_CJSON "Use system cJSON" TRUE)
+if(WITH_SYSTEM_CJSON)
+  find_package(cJSON)
+  if(cJSON_FOUND)
+    set(HAVE_CJSON ON)
+  else()
+    message(WARNING "It is recommended to install an up-to-date version of cJSON on your system. CMake did not find one, and will instead use a cJSON version bundled with the PCL source code. However, that is an older version which may pose a risk and may be removed in a future PCL release.")
+  endif()
+endif()
+
+set(CMAKE_REQUIRED_LIBRARIES Eigen3::Eigen) # so that Eigen/Core is found below
+CHECK_CXX_SOURCE_COMPILES("
+#include <Eigen/Core>
+#if (EIGEN_DEFAULT_ALIGN_BYTES==0) || EIGEN_MALLOC_ALREADY_ALIGNED
+#error Eigen will not use handmade_aligned_malloc (which is fine, we just throw an error here to make this compilation fail)
+#endif
+int main() { return 0; }"
+PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC)
+if (PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC) # CHECK_CXX_SOURCE_COMPILES does not necessarily set this to 0 or 1
+  set(PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC 1)
+else()
+  set(PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC 0)
+endif()
+unset(CMAKE_REQUIRED_LIBRARIES)
+
 ### ---[ Create the config.h file
 set(pcl_config_h_in "${CMAKE_CURRENT_SOURCE_DIR}/pcl_config.h.in")
 set(pcl_config_h "${CMAKE_CURRENT_BINARY_DIR}/include/pcl/pcl_config.h")
index cf21c443742d448be0f32d8a46164bf43912de16..6e1af47c6746746b9e2d408fffbc368c0c3e2f23 100644 (file)
 #------------------------------------------------------------------------------------
 
 # Set default policy behavior similar to minimum requirement version
-cmake_policy(VERSION 3.10)
-
-# explicitly set policies we already support in newer cmake versions
-if(POLICY CMP0074)
-  # TODO: update *_ROOT variables to be PCL_*_ROOT or equivalent.
-  # CMP0074 directly affects how Find* modules work and *_ROOT variables.  Since
-  # this is a config file that will be consumed by parent projects with (likely)
-  # NEW behavior, we need to push a policy stack.
-  cmake_policy(SET CMP0074 NEW)
-endif()
+cmake_policy(VERSION 3.16.3)
 
 list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/Modules")
 
@@ -93,15 +84,8 @@ macro(find_boost)
   elseif(NOT BOOST_INCLUDEDIR)
     set(BOOST_INCLUDEDIR "@Boost_INCLUDE_DIR@")
   endif()
-  
-  set(Boost_ADDITIONAL_VERSIONS
-    "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@"
-    "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80"
-    "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" 
-    "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70"
-    "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65")
-  
-  find_package(Boost 1.65.0 ${QUIET_} COMPONENTS @PCLCONFIG_AVAILABLE_BOOST_MODULES@)
+
+  find_package(Boost 1.71.0 ${QUIET_} COMPONENTS @PCLCONFIG_AVAILABLE_BOOST_MODULES@ CONFIG)
 
   set(BOOST_FOUND ${Boost_FOUND})
   set(BOOST_INCLUDE_DIRS "${Boost_INCLUDE_DIR}")
@@ -318,17 +302,17 @@ function(find_external_library _component _lib _is_optional)
 
   string(TOUPPER "${_component}" COMPONENT)
   string(TOUPPER "${_lib}" LIB)
-  string(REGEX REPLACE "[.-]" "_" LIB ${LIB})
+  string(REGEX REPLACE "[.-]" "_" LIB "${LIB}")
   if(${LIB}_FOUND)
     list(APPEND PCL_${COMPONENT}_INCLUDE_DIRS ${${LIB}_INCLUDE_DIRS})
     set(PCL_${COMPONENT}_INCLUDE_DIRS ${PCL_${COMPONENT}_INCLUDE_DIRS} PARENT_SCOPE)
-    
+
     if(${LIB} MATCHES "VTK")
       if(${${LIB}_VERSION_MAJOR} GREATER_EQUAL 9)
         set(ISVTK9ORGREATER TRUE)
       endif()
     endif()
-    
+
     if(${LIB}_USE_FILE AND NOT ISVTK9ORGREATER )
       include(${${LIB}_USE_FILE})
     else()
@@ -439,6 +423,8 @@ set(PCL_INCLUDE_DIRS "${PCL_CONF_INCLUDE_DIR}")
 #set a suffix for debug libraries
 set(PCL_DEBUG_SUFFIX "@CMAKE_DEBUG_POSTFIX@")
 set(PCL_RELEASE_SUFFIX "@CMAKE_RELEASE_POSTFIX@")
+set(PCL_RELWITHDEBINFO_SUFFIX "@CMAKE_RELWITHDEBINFO_POSTFIX@")
+set(PCL_MINSIZEREL_SUFFIX "@CMAKE_MINSIZEREL_POSTFIX@")
 
 set(PCL_SHARED_LIBS "@PCL_SHARED_LIBS@")
 
@@ -450,6 +436,10 @@ list(APPEND PCL_COMPILE_OPTIONS @PCLCONFIG_SSE_COMPILE_OPTIONS@)
 list(APPEND PCL_COMPILE_OPTIONS @PCLCONFIG_AVX_COMPILE_OPTIONS@)
 
 set(pcl_all_components @PCLCONFIG_AVAILABLE_COMPONENTS@)
+# insert "io_ply" before "io"
+list(FIND pcl_all_components "io" pcl_pos_io)
+list(INSERT pcl_all_components ${pcl_pos_io} "io_ply")
+unset(pcl_pos_io)
 list(LENGTH pcl_all_components PCL_NB_COMPONENTS)
 
 #list each component dependencies IN PCL
@@ -460,6 +450,11 @@ list(LENGTH pcl_all_components PCL_NB_COMPONENTS)
 
 @PCLCONFIG_OPTIONAL_DEPENDENCIES@
 
+# io_ply subcomponent
+list(APPEND pcl_io_int_dep io_ply)
+set(pcl_io_ply_int_dep common)
+set(pcl_io_ply_ext_dep boost)
+
 # VTK components required by PCL
 set(PCL_VTK_COMPONENTS "@PCL_VTK_COMPONENTS@")
 
@@ -517,18 +512,21 @@ foreach(component ${PCL_TO_FIND_COMPONENTS})
 
   string(REGEX REPLACE "^cuda_(.*)$" "\\1" cuda_component "${component}")
   string(REGEX REPLACE "^gpu_(.*)$" "\\1" gpu_component "${component}")
+  string(REGEX REPLACE "^io_(.*)$" "\\1" io_component "${component}")
 
   find_path(PCL_${COMPONENT}_INCLUDE_DIR
     NAMES pcl/${component}
           pcl/apps/${component}
           pcl/cuda/${cuda_component} pcl/cuda/${component}
           pcl/gpu/${gpu_component} pcl/gpu/${component}
+          pcl/io/${io_component}
     HINTS ${PCL_INCLUDE_DIRS}
     PATH_SUFFIXES
           ${component}/include
           apps/${component}/include
           cuda/${cuda_component}/include
           gpu/${gpu_component}/include
+          io/${io_component}/include
     DOC "path to ${component} headers"
     NO_DEFAULT_PATH)
   mark_as_advanced(PCL_${COMPONENT}_INCLUDE_DIR)
@@ -543,7 +541,8 @@ foreach(component ${PCL_TO_FIND_COMPONENTS})
   # Skip find_library for header only modules
   list(FIND pcl_header_only_components ${component} _is_header_only)
   if(_is_header_only EQUAL -1)
-    find_library(PCL_${COMPONENT}_LIBRARY ${pcl_component}${PCL_RELEASE_SUFFIX}
+    find_library(PCL_${COMPONENT}_LIBRARY
+      NAMES ${pcl_component}${PCL_RELEASE_SUFFIX} ${pcl_component}${PCL_RELWITHDEBINFO_SUFFIX} ${pcl_component}${PCL_MINSIZEREL_SUFFIX}
       HINTS ${PCL_LIBRARY_DIRS}
       DOC "path to ${pcl_component} library"
       NO_DEFAULT_PATH)
index 08318ebf317a23929fd512a1589e97091e32a692..87a931f256d97b0a33e89cf05db60a2206e98c8d 100644 (file)
--- a/README.md
+++ b/README.md
@@ -5,7 +5,7 @@
 [![Release][release-image]][releases]
 [![License][license-image]][license]
 
-[release-image]: https://img.shields.io/badge/release-1.14.0-green.svg?style=flat
+[release-image]: https://img.shields.io/badge/release-1.15.0-green.svg?style=flat
 [releases]: https://github.com/PointCloudLibrary/pcl/releases
 
 [license-image]: https://img.shields.io/badge/license-BSD-green.svg?style=flat
@@ -23,19 +23,19 @@ Continuous integration
 [ci-latest-build]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=9&branchName=master
 [ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2020.04%20GCC&label=Ubuntu%2020.04%20GCC
 [ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2022.04%20Clang&label=Ubuntu%2022.04%20Clang
-[ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2023.04%20GCC&label=Ubuntu%2023.04%20GCC
+[ci-ubuntu-24.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2024.04%20GCC&label=Ubuntu%2024.04%20GCC
 [ci-windows-x86]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x86&label=Windows%20VS2019%20x86
 [ci-windows-x64]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x64&label=Windows%20VS2019%20x64
-[ci-macos-12]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Monterey%2012&label=macOS%20Monterey%2012
 [ci-macos-13]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Ventura%2013&label=macOS%20Ventura%2013
+[ci-macos-14]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Sonoma%2014&label=macOS%20Sonoma%2014
 [ci-docs]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/Documentation?branchName=master
 [ci-latest-docs]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=14&branchName=master
 
 Build Platform           | Status
 ------------------------ | ------------------------------------------------------------------------------------------------- |
-Ubuntu                   | [![Status][ci-ubuntu-20.04]][ci-latest-build] <br> [![Status][ci-ubuntu-22.04]][ci-latest-build] <br> [![Status][ci-ubuntu-23.04]][ci-latest-build] |
+Ubuntu                   | [![Status][ci-ubuntu-20.04]][ci-latest-build] <br> [![Status][ci-ubuntu-22.04]][ci-latest-build] <br> [![Status][ci-ubuntu-24.04]][ci-latest-build] |
 Windows                  | [![Status][ci-windows-x86]][ci-latest-build]  <br> [![Status][ci-windows-x64]][ci-latest-build]   |
-macOS                    | [![Status][ci-macos-12]][ci-latest-build]  <br> [![Status][ci-macos-13]][ci-latest-build]   |
+macOS                    | [![Status][ci-macos-13]][ci-latest-build]  <br> [![Status][ci-macos-14]][ci-latest-build]   |
 Documentation            | [![Status][ci-docs]][ci-latest-docs] |
 Read the Docs            | [![Documentation Status](https://readthedocs.org/projects/pcl-tutorials/badge/?version=master)](https://pcl.readthedocs.io/projects/tutorials/en/master/?badge=master) |
 
index 3e8b8e997d7a2e27c8fdf31bd37b3eac7df273c6..a75d17047a163fb189a1a9506199e02ef339238f 100644 (file)
@@ -2,10 +2,11 @@ set(SUBSUBSYS_NAME 3d_rec_framework)
 set(SUBSUBSYS_DESC "3D recognition framework")
 set(SUBSUBSYS_DEPS common geometry io filters sample_consensus segmentation visualization kdtree features surface octree registration keypoints tracking search recognition ml)
 set(SUBSUBSYS_EXT_DEPS vtk openni)
+set(REASON "")
+set(DEFAULT OFF)
 
-# Default to not building for now
-if(${DEFAULT} STREQUAL "TRUE")
-  set(DEFAULT FALSE)
+if(NOT TARGET Boost::filesystem)
+  set(REASON "Boost filesystem is not available.")
 endif()
 
 PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}")
@@ -15,8 +16,6 @@ if(NOT build)
   return()
 endif()
 
-include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 set(incs_fw
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/feature_wrapper/normal_estimator.h"
 )
@@ -90,7 +89,7 @@ PCL_ADD_INCLUDES("${SUBSUBSYS_NAME}" "${SUBSYS_NAME}/${SUBSUBSYS_NAME}/pipeline/
 
 set(LIB_NAME "pcl_${SUBSUBSYS_NAME}")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSUBSYS_NAME} SOURCES ${srcs} ${impl_incs_pipeline} ${incs_utils} ${incs_fw} ${incs_fw_global} ${incs_fw_local} ${incc_tools_framework} ${incs_pipelines} ${incs_pc_source})
-target_link_libraries("${LIB_NAME}" pcl_apps pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search pcl_registration)
+target_link_libraries("${LIB_NAME}" pcl_apps pcl_common pcl_io pcl_filters pcl_keypoints pcl_recognition pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search pcl_registration)
 
 if(WITH_OPENNI)
   target_link_libraries("${LIB_NAME}" ${OPENNI_LIBRARIES})
index 6e1713618e242e898ed7b7fb16cf92d5f75b721d..4b39619f465526abcfa8f225ca0e5cf2fb6e93c8 100644 (file)
@@ -81,7 +81,7 @@ public:
   loadOrGenerate(std::string& dir, std::string& model_path, ModelT& model)
   {
     const std::string pathmodel = dir + '/' + model.class_ + '/' + model.id_;
-    bf::path trained_dir = pathmodel;
+    pcl_fs::path trained_dir = pathmodel;
 
     model.views_.reset(new std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>);
     model.poses_.reset(
@@ -90,12 +90,12 @@ public:
     model.assembled_.reset(new pcl::PointCloud<pcl::PointXYZ>);
     uniform_sampling(model_path, 100000, *model.assembled_, model_scale_);
 
-    if (bf::exists(trained_dir)) {
+    if (pcl_fs::exists(trained_dir)) {
       // load views, poses and self-occlusions
       std::vector<std::string> view_filenames;
-      for (const auto& dir_entry : bf::directory_iterator(trained_dir)) {
+      for (const auto& dir_entry : pcl_fs::directory_iterator(trained_dir)) {
         // check if its a directory, then get models in it
-        if (!(bf::is_directory(dir_entry))) {
+        if (!(pcl_fs::is_directory(dir_entry))) {
           // check that it is a ply file and then add, otherwise ignore..
           std::vector<std::string> strs;
           std::vector<std::string> strs_;
index 0592be86b937e6595453ec2744d0a9d306dbd67f..79929997ab2bc2ac6e1b9a44ad2b7ba968988d28 100644 (file)
@@ -17,7 +17,7 @@ pcl::rec_3d_framework::GlobalNNPipeline<Distance, PointInT, FeatureT>::
     std::string path =
         source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-    for (const auto& dir_entry : bf::directory_iterator(path)) {
+    for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
       std::string file_name = (dir_entry.path().filename()).string();
 
       std::vector<std::string> strs;
@@ -177,9 +177,9 @@ pcl::rec_3d_framework::GlobalNNPipeline<Distance, PointInT, FeatureT>::initializ
         std::string path =
             source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-        bf::path desc_dir = path;
-        if (!bf::exists(desc_dir))
-          bf::create_directory(desc_dir);
+        pcl_fs::path desc_dir = path;
+        if (!pcl_fs::exists(desc_dir))
+          pcl_fs::create_directory(desc_dir);
 
         const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd";
         pcl::io::savePCDFileBinary(path_view, *processed);
index bf6607eeae7da6d659dfd3458cc6b855c0a8dafd..af7ab87d642b053e75dac0f46f0a71b46851bf8f 100644 (file)
@@ -91,7 +91,7 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer<Distance, PointInT, FeatureT>::
     std::string path =
         source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-    for (const auto& dir_entry : bf::directory_iterator(path)) {
+    for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
       std::string file_name = (dir_entry.path().filename()).string();
 
       std::vector<std::string> strs;
@@ -412,9 +412,9 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer<Distance, PointInT, FeatureT>::init
         std::string path =
             source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-        bf::path desc_dir = path;
-        if (!bf::exists(desc_dir))
-          bf::create_directory(desc_dir);
+        pcl_fs::path desc_dir = path;
+        if (!pcl_fs::exists(desc_dir))
+          pcl_fs::create_directory(desc_dir);
 
         const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd";
         pcl::io::savePCDFileBinary(path_view, *processed);
index fdd83be86d7be779776ea101e8fb847f822e9e19..6a583006cd763608020e27c0ed3cd559dd9c9284 100644 (file)
@@ -51,8 +51,8 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::
   const std::string dir = path + "/roll_trans_" + std::to_string(view_id) + '_' +
                           std::to_string(d_id) + ".txt";
 
-  const bf::path file_path = dir;
-  if (bf::exists(file_path)) {
+  const pcl_fs::path file_path = dir;
+  if (pcl_fs::exists(file_path)) {
     PersistenceUtils::readMatrixFromFile(dir, pose_matrix);
     return true;
   }
@@ -108,7 +108,7 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::
     std::string path =
         source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-    for (const auto& dir_entry : bf::directory_iterator(path)) {
+    for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
       std::string file_name = (dir_entry.path().filename()).string();
 
       std::vector<std::string> strs;
@@ -608,9 +608,9 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::ini
         std::string path =
             source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-        bf::path desc_dir = path;
-        if (!bf::exists(desc_dir))
-          bf::create_directory(desc_dir);
+        pcl_fs::path desc_dir = path;
+        if (!pcl_fs::exists(desc_dir))
+          pcl_fs::create_directory(desc_dir);
 
         const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd";
         pcl::io::savePCDFileBinary(path_view, *processed);
index 3561c3036cdde0a182dad87d0404a377476e6d08..1bf8388f7feea0d1b6b78686428a5ced8ad8a459 100644 (file)
@@ -20,7 +20,7 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
     std::string path =
         source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-    for (const auto& dir_entry : bf::directory_iterator(path)) {
+    for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
       std::string file_name = (dir_entry.path().filename()).string();
 
       std::vector<std::string> strs;
@@ -150,9 +150,9 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
           std::string path =
               source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);
 
-          bf::path desc_dir = path;
-          if (!bf::exists(desc_dir))
-            bf::create_directory(desc_dir);
+          pcl_fs::path desc_dir = path;
+          if (!pcl_fs::exists(desc_dir))
+            pcl_fs::create_directory(desc_dir);
 
           const std::string path_view = path = "/view_" + std::to_string(v) + ".pcd";
           pcl::io::savePCDFileBinary(path_view, *processed);
index a3c5812487ee011788b5c2b404a089483de80673..528a7daf4a8a6a977be054120bee4e6ea4968a16 100644 (file)
@@ -1,7 +1,7 @@
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/io/pcd_io.h>
 
 #include <boost/algorithm/string.hpp>
-#include <boost/filesystem.hpp>
 
 #include <fstream>
 
index 6a88b8f46ea19d8ad41980982621c94de7ed9854..edeff123b8dd499538e9f2b4fa91df30b3f765cd 100644 (file)
@@ -9,13 +9,16 @@
 #include <pcl/apps/3d_rec_framework/utils/metrics.h>
 
 // Instantiation
-template class pcl::rec_3d_framework::
+// GlobalClassifier is the parent class of GlobalNNPipeline. They must be instantiated
+// in this order, otherwise visibility attributes of the former are not applied
+// correctly.
+template class PCL_EXPORTS pcl::rec_3d_framework::GlobalClassifier<pcl::PointXYZ>;
+
+template class PCL_EXPORTS pcl::rec_3d_framework::
     GlobalNNPipeline<flann::L1, pcl::PointXYZ, pcl::VFHSignature308>;
-template class pcl::rec_3d_framework::GlobalNNPipeline<
-    Metrics::HistIntersectionUnionDistance,
-    pcl::PointXYZ,
-    pcl::VFHSignature308>;
-template class pcl::rec_3d_framework::
+template class PCL_EXPORTS
+    pcl::rec_3d_framework::GlobalNNPipeline<Metrics::HistIntersectionUnionDistance,
+                                            pcl::PointXYZ,
+                                            pcl::VFHSignature308>;
+template class PCL_EXPORTS pcl::rec_3d_framework::
     GlobalNNPipeline<flann::L1, pcl::PointXYZ, pcl::ESFSignature640>;
-
-template class pcl::rec_3d_framework::GlobalClassifier<pcl::PointXYZ>;
index 53891821d115d8ed041fb5d6d768105034dabc12..220952347f4931b282970eb5724e129f60d2de5e 100644 (file)
 #include <flann/algorithms/dist.h>
 
 void
-getScenesInDirectory(bf::path& dir,
+getScenesInDirectory(pcl_fs::path& dir,
                      std::string& rel_path_so_far,
                      std::vector<std::string>& relative_paths)
 {
   // list models in MODEL_FILES_DIR_ and return list
-  for (const auto& dir_entry : bf::directory_iterator(dir)) {
+  for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) {
     // check if its a directory, then get models in it
-    if (bf::is_directory(dir_entry)) {
+    if (pcl_fs::is_directory(dir_entry)) {
       std::string so_far =
           rel_path_so_far + (dir_entry.path().filename()).string() + "/";
-      bf::path curr_path = dir_entry.path();
+      pcl_fs::path curr_path = dir_entry.path();
       getScenesInDirectory(curr_path, so_far, relative_paths);
     }
     else {
@@ -86,7 +86,7 @@ recognizeAndVisualize(
 {
 
   // read mians scenes
-  bf::path ply_files_dir = scenes_dir;
+  pcl_fs::path ply_files_dir = scenes_dir;
   std::vector<std::string> files;
   std::string start;
   getScenesInDirectory(ply_files_dir, start, files);
@@ -223,18 +223,18 @@ recognizeAndVisualize(
 }
 
 void
-getModelsInDirectory(bf::path& dir,
+getModelsInDirectory(pcl_fs::path& dir,
                      std::string& rel_path_so_far,
                      std::vector<std::string>& relative_paths,
                      std::string& ext)
 {
-  for (const auto& dir_entry : bf::directory_iterator(dir)) {
+  for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) {
     // check if its a directory, then get models in it
-    if (bf::is_directory(dir_entry)) {
+    if (pcl_fs::is_directory(dir_entry)) {
       std::string so_far =
           rel_path_so_far + (dir_entry.path().filename()).string() + "/";
 
-      bf::path curr_path = dir_entry.path();
+      pcl_fs::path curr_path = dir_entry.path();
       getModelsInDirectory(curr_path, so_far, relative_paths, ext);
     }
     else {
@@ -315,8 +315,8 @@ main(int argc, char** argv)
     return -1;
   }
 
-  bf::path models_dir_path = path;
-  if (!bf::exists(models_dir_path)) {
+  pcl_fs::path models_dir_path = path;
+  if (!pcl_fs::exists(models_dir_path)) {
     PCL_ERROR("Models dir path %s does not exist, use -models_dir [dir] option\n",
               path.c_str());
     return -1;
@@ -324,7 +324,7 @@ main(int argc, char** argv)
   std::vector<std::string> files;
   std::string start;
   std::string ext = std::string("ply");
-  bf::path dir = models_dir_path;
+  pcl_fs::path dir = models_dir_path;
   getModelsInDirectory(dir, start, files, ext);
   assert(files.size() == 4);
 
index 670f2d8fac1abefa689c83e6da8cb87fa1d24fde..ff551b13bb880292eaae53cb88652b1ee8188384 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Application examples/samples that show how PCL works")
 set(SUBSYS_DEPS common geometry io filters sample_consensus segmentation visualization kdtree features surface octree registration keypoints tracking search recognition ml stereo 2d)
 set(SUBSYS_OPT_DEPS openni vtk ${QTX})
 
-set(DEFAULT FALSE)
-set(REASON "Disabled by default")
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${SUBSYS_OPT_DEPS})
 
 if(NOT build)
@@ -17,16 +15,40 @@ set(CMAKE_AUTOMOC ON)
 set(CMAKE_AUTORCC ON)
 set(CMAKE_AUTOUIC ON)
 
+list(APPEND CMAKE_AUTOUIC_SEARCH_PATHS "src")
+
+if(VTK_FOUND)
+  set(incs "include/pcl/${SUBSYS_NAME}/render_views_tesselated_sphere.h")
+  set(srcs "src/render_views_tesselated_sphere.cpp")
+endif()
+
+if(QHULL_FOUND)
+  set(incs
+    "include/pcl/${SUBSYS_NAME}/dominant_plane_segmentation.h"
+    "include/pcl/${SUBSYS_NAME}/timer.h"
+    ${incs}
+  )
+  set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/dominant_plane_segmentation.hpp")
+  set(srcs "src/dominant_plane_segmentation.cpp" ${srcs})
+endif()
+
+set(LIB_NAME "pcl_${SUBSYS_NAME}")
+PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${impl_incs} ${incs})
+target_link_libraries("${LIB_NAME}" pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search)
+PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC})
+# Install include files
+PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs})
+PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs})
+
 # to be filled with all targets the apps subsystem
 set(PCL_APPS_ALL_TARGETS)
 
-include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 PCL_ADD_EXECUTABLE(pcl_test_search_speed COMPONENT ${SUBSYS_NAME} SOURCES src/test_search.cpp)
 target_link_libraries(pcl_test_search_speed pcl_common pcl_io pcl_search pcl_kdtree pcl_visualization)
 
 PCL_ADD_EXECUTABLE(pcl_nn_classification_example COMPONENT ${SUBSYS_NAME} SOURCES src/nn_classification_example.cpp)
 target_link_libraries(pcl_nn_classification_example pcl_common pcl_io pcl_features pcl_kdtree)
+target_include_directories(pcl_nn_classification_example PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
 PCL_ADD_EXECUTABLE(pcl_pyramid_surface_matching COMPONENT ${SUBSYS_NAME} SOURCES src/pyramid_surface_matching.cpp)
 target_link_libraries(pcl_pyramid_surface_matching pcl_common pcl_io pcl_features pcl_registration pcl_filters)
@@ -40,9 +62,6 @@ if(LIBUSB_FOUND)
 endif()
 
 if(VTK_FOUND)
-  set(incs "include/pcl/${SUBSYS_NAME}/render_views_tesselated_sphere.h")
-  set(srcs "src/render_views_tesselated_sphere.cpp")
-
   PCL_ADD_EXECUTABLE(pcl_ppf_object_recognition COMPONENT ${SUBSYS_NAME} SOURCES src/ppf_object_recognition.cpp)
   target_link_libraries(pcl_ppf_object_recognition pcl_common pcl_io pcl_filters pcl_features pcl_registration pcl_visualization pcl_sample_consensus pcl_segmentation)
 
@@ -72,8 +91,9 @@ if(VTK_FOUND)
   PCL_ADD_EXECUTABLE(pcl_face_trainer COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection/face_trainer.cpp)
   target_link_libraries(pcl_face_trainer pcl_features pcl_recognition pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface pcl_keypoints pcl_ml pcl_search pcl_kdtree)
 
-  PCL_ADD_EXECUTABLE(pcl_fs_face_detector COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection//filesystem_face_detection.cpp BUNDLE)
+  PCL_ADD_EXECUTABLE(pcl_fs_face_detector COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection/filesystem_face_detection.cpp BUNDLE)
   target_link_libraries(pcl_fs_face_detector pcl_features pcl_recognition pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface pcl_keypoints pcl_ml pcl_search pcl_kdtree)
+  target_include_directories(pcl_fs_face_detector PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
   PCL_ADD_EXECUTABLE(pcl_stereo_ground_segmentation COMPONENT ${SUBSYS_NAME} SOURCES src/stereo_ground_segmentation.cpp)
   target_link_libraries(pcl_stereo_ground_segmentation pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_features pcl_stereo)
@@ -93,6 +113,7 @@ if(VTK_FOUND)
       BUNDLE)
 
     target_link_libraries(pcl_manual_registration pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface pcl_registration ${QTX}::Widgets)
+    target_include_directories(pcl_manual_registration PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
     PCL_ADD_EXECUTABLE(pcl_pcd_video_player
       COMPONENT
@@ -103,7 +124,8 @@ if(VTK_FOUND)
       src/pcd_video_player/pcd_video_player.ui
       BUNDLE)
 
-    target_link_libraries(pcl_pcd_video_player pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets)
+    target_link_libraries(pcl_pcd_video_player pcl_common pcl_io pcl_registration pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets)
+    target_include_directories(pcl_pcd_video_player PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
   endif()
 
   if(WITH_OPENNI)
@@ -117,8 +139,8 @@ if(VTK_FOUND)
     target_link_libraries(pcl_openni_octree_compression pcl_common pcl_io pcl_filters pcl_visualization pcl_octree)
 
     if(HAVE_PNG)
-    PCL_ADD_EXECUTABLE(pcl_openni_organized_compression COMPONENT ${SUBSYS_NAME} SOURCES src/openni_organized_compression.cpp BUNDLE)
-    target_link_libraries(pcl_openni_organized_compression pcl_common pcl_io pcl_filters pcl_visualization pcl_octree)
+      PCL_ADD_EXECUTABLE(pcl_openni_organized_compression COMPONENT ${SUBSYS_NAME} SOURCES src/openni_organized_compression.cpp BUNDLE)
+      target_link_libraries(pcl_openni_organized_compression pcl_common pcl_io pcl_filters pcl_visualization pcl_octree)
     endif()
 
     PCL_ADD_EXECUTABLE(pcl_openni_shift_to_depth_conversion COMPONENT ${SUBSYS_NAME} SOURCES src/openni_shift_to_depth_conversion.cpp BUNDLE)
@@ -156,6 +178,7 @@ if(VTK_FOUND)
 
     PCL_ADD_EXECUTABLE(pcl_openni_face_detector COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection//openni_face_detection.cpp src/face_detection//openni_frame_source.cpp BUNDLE)
     target_link_libraries(pcl_openni_face_detector pcl_features pcl_recognition pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface pcl_keypoints pcl_ml pcl_search pcl_kdtree)
+    target_include_directories(pcl_openni_face_detector PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
     if(QT_FOUND AND HAVE_QVTK)
       # OpenNI Passthrough application demo
@@ -163,13 +186,13 @@ if(VTK_FOUND)
         COMPONENT
           ${SUBSYS_NAME}
         SOURCES
+          include/pcl/apps/openni_passthrough_qt.h
           include/pcl/apps/openni_passthrough.h
           src/openni_passthrough.cpp
           src/openni_passthrough.ui)
 
       target_link_libraries(pcl_openni_passthrough pcl_common pcl_io pcl_filters pcl_visualization ${QTX}::Widgets)
-
-      list(APPEND CMAKE_AUTOUIC_SEARCH_PATHS "src")
+      target_include_directories(pcl_openni_passthrough PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
       # OpenNI Organized Connected Component application demo
       PCL_ADD_EXECUTABLE(pcl_organized_segmentation_demo
@@ -182,48 +205,51 @@ if(VTK_FOUND)
           src/organized_segmentation_demo.ui
         BUNDLE)
       target_link_libraries(pcl_organized_segmentation_demo pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets)
+      target_include_directories(pcl_organized_segmentation_demo PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
     endif()
 
     if(QHULL_FOUND)
-    PCL_ADD_EXECUTABLE(pcl_openni_3d_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_convex_hull.cpp BUNDLE)
-    target_link_libraries(pcl_openni_3d_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface)
-
-    PCL_ADD_EXECUTABLE(pcl_openni_3d_concave_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_concave_hull.cpp BUNDLE)
-    target_link_libraries(pcl_openni_3d_concave_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface)
-
-    PCL_ADD_EXECUTABLE(pcl_openni_tracking COMPONENT ${SUBSYS_NAME} SOURCES src/openni_tracking.cpp BUNDLE)
-    target_link_libraries(pcl_openni_tracking pcl_common pcl_io pcl_surface pcl_visualization pcl_filters pcl_features pcl_segmentation pcl_tracking pcl_search)
-
-    PCL_ADD_EXECUTABLE(pcl_openni_planar_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_planar_convex_hull.cpp BUNDLE)
-    target_link_libraries(pcl_openni_planar_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface)
-
-    PCL_ADD_EXECUTABLE(pcl_ni_linemod COMPONENT ${SUBSYS_NAME} SOURCES src/ni_linemod.cpp BUNDLE)
-    target_link_libraries(pcl_ni_linemod pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface pcl_search)
+      PCL_ADD_EXECUTABLE(pcl_openni_3d_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_convex_hull.cpp BUNDLE)
+      target_link_libraries(pcl_openni_3d_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface)
+  
+      PCL_ADD_EXECUTABLE(pcl_openni_3d_concave_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_concave_hull.cpp BUNDLE)
+      target_link_libraries(pcl_openni_3d_concave_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface)
+  
+      PCL_ADD_EXECUTABLE(pcl_openni_tracking COMPONENT ${SUBSYS_NAME} SOURCES src/openni_tracking.cpp BUNDLE)
+      target_link_libraries(pcl_openni_tracking pcl_common pcl_io pcl_surface pcl_visualization pcl_filters pcl_features pcl_segmentation pcl_tracking pcl_search)
+  
+      PCL_ADD_EXECUTABLE(pcl_openni_planar_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_planar_convex_hull.cpp BUNDLE)
+      target_link_libraries(pcl_openni_planar_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface)
+  
+      PCL_ADD_EXECUTABLE(pcl_ni_linemod COMPONENT ${SUBSYS_NAME} SOURCES src/ni_linemod.cpp BUNDLE)
+      target_link_libraries(pcl_ni_linemod pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface pcl_search)
+      target_include_directories(pcl_ni_linemod PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
     endif() # QHULL_FOUND
 
     PCL_ADD_EXECUTABLE(pcl_ni_agast COMPONENT ${SUBSYS_NAME} SOURCES src/ni_agast.cpp BUNDLE)
     target_link_libraries(pcl_ni_agast pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_keypoints pcl_surface pcl_search)
+    target_include_directories(pcl_ni_agast PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
     PCL_ADD_EXECUTABLE(pcl_ni_brisk COMPONENT ${SUBSYS_NAME} SOURCES src/ni_brisk.cpp BUNDLE)
     target_link_libraries(pcl_ni_brisk pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_keypoints pcl_surface pcl_search)
+    target_include_directories(pcl_ni_brisk PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
     PCL_ADD_EXECUTABLE(pcl_ni_susan COMPONENT ${SUBSYS_NAME} SOURCES src/ni_susan.cpp BUNDLE)
     target_link_libraries(pcl_ni_susan pcl_common pcl_visualization pcl_features pcl_keypoints pcl_search)
+    target_include_directories(pcl_ni_susan PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
     PCL_ADD_EXECUTABLE(pcl_ni_trajkovic COMPONENT ${SUBSYS_NAME} SOURCES src/ni_trajkovic.cpp BUNDLE)
     target_link_libraries(pcl_ni_trajkovic pcl_common pcl_visualization pcl_features pcl_keypoints pcl_search)
+    target_include_directories(pcl_ni_trajkovic PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
     PCL_ADD_EXECUTABLE(pcl_openni_klt COMPONENT ${SUBSYS_NAME} SOURCES src/openni_klt.cpp BUNDLE)
-    target_link_libraries(pcl_openni_klt pcl_common pcl_io pcl_visualization pcl_tracking)
+    target_link_libraries(pcl_openni_klt pcl_common pcl_io pcl_keypoints pcl_visualization pcl_tracking)
   endif() # WITH_OPENNI
 endif() # VTK_FOUND
 
 # OpenGL and GLUT
 if(OPENGL_FOUND AND GLUT_FOUND)
-  if(NOT WIN32)
-    include_directories(SYSTEM "${OPENGL_INCLUDE_DIR}")
-  endif()
   PCL_ADD_EXECUTABLE(pcl_grabcut_2d COMPONENT ${SUBSYS_NAME} SOURCES src/grabcut_2d.cpp BUNDLE)
   if(APPLE)
     set(_glut_target ${GLUT_glut_LIBRARY})
@@ -238,27 +264,9 @@ set(PCL_APPS_MODULES_NAMES_UNSORTED ${PCL_APPS_MODULES_NAMES})
 topological_sort(PCL_APPS_MODULES_NAMES PCL_APPS_ _DEPENDS)
 sort_relative(PCL_APPS_MODULES_NAMES_UNSORTED PCL_APPS_MODULES_NAMES PCL_APPS_MODULES_DIRS)
 foreach(subdir ${PCL_APPS_MODULES_DIRS})
-add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/${subdir}")
+  add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/${subdir}")
 endforeach()
 
-if(QHULL_FOUND)
-  set(incs
-    "include/pcl/${SUBSYS_NAME}/dominant_plane_segmentation.h"
-    "include/pcl/${SUBSYS_NAME}/timer.h"
-    ${incs}
-  )
-  set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/dominant_plane_segmentation.hpp")
-  set(srcs "src/dominant_plane_segmentation.cpp" ${srcs})
-endif()
-
-set(LIB_NAME "pcl_${SUBSYS_NAME}")
-PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${impl_incs} ${incs})
-target_link_libraries("${LIB_NAME}" pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search)
-PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC})
-# Install include files
-PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs})
-PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs})
-
 if(CMAKE_GENERATOR_IS_IDE)
     set(SUBSYS_TARGET_NAME APPS_BUILD)
 else()
index 24196bcc274ebc4c771ceb6221cea35c098fc744..47668e169a42a2d0a883793feccd5e2712f3a9b8 100644 (file)
@@ -5,21 +5,18 @@
 
 set(SUBSUBSYS_NAME cloud_composer)
 set(SUBSUBSYS_DESC "Cloud Composer - Application for Manipulating Point Clouds")
-set(SUBSUBSYS_DEPS common io visualization filters apps)
+set(SUBSUBSYS_DEPS common io visualization features filters apps)
 set(SUBSUBSYS_EXT_DEPS vtk ${QTX})
+set(REASON "")
+set(DEFAULT OFF)
 
-# QVTK?
-if(NOT HAVE_QVTK)
-  set(DEFAULT AUTO_OFF)
-  set(REASON "Cloud composer requires QVTK")
-elseif(NOT ${DEFAULT} STREQUAL "AUTO_OFF")
-  set(DEFAULT TRUE)
-  set(REASON)
+# Have Qt?
+if("${QTX}" STREQUAL "")
+  set(REASON "Cloud composer requires Qt.")
 endif()
 
-#Default to not building for now
-if("${DEFAULT}" STREQUAL "TRUE")
-  set(DEFAULT FALSE)
+if(NOT HAVE_QVTK)  
+  set(REASON "VTK was not built with Qt support.")
 endif()
 
 PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}")
@@ -31,8 +28,6 @@ if(NOT build)
   return()
 endif()
 
-include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 #Create subdirectory for plugin libs
 set(CLOUD_COMPOSER_PLUGIN_DIR "${CMAKE_LIBRARY_OUTPUT_DIRECTORY}/cloud_composer_plugins")
 make_directory("${CLOUD_COMPOSER_PLUGIN_DIR}")
@@ -76,7 +71,7 @@ set(PCL_LIB_TYPE STATIC)
 PCL_ADD_LIBRARY(pcl_cc_tool_interface COMPONENT ${SUBSUBSYS_NAME} SOURCES ${INTERFACE_HEADERS} ${INTERFACE_SOURCES})
 
 
-target_link_libraries(pcl_cc_tool_interface pcl_common pcl_filters pcl_search pcl_visualization ${QTX}::Widgets)
+target_link_libraries(pcl_cc_tool_interface pcl_common pcl_features pcl_filters pcl_search pcl_visualization ${QTX}::Widgets)
 
 set(PCL_LIB_TYPE ${PCL_LIB_TYPE_ORIGIN})
 
index 5c3350ff43b7973f15a0d635f403c742d00a2582..8a670a5b81a1fde370fab8454cd9ceb7c04c353e 100644 (file)
@@ -1,14 +1,14 @@
 set(SUBSUBSYS_NAME in_hand_scanner)
 set(SUBSUBSYS_DESC "In-hand scanner for small objects")
-set(SUBSUBSYS_DEPS     common     features     io     kdtree apps)
-set(SUBSUBSYS_LIBS pcl_common pcl_features pcl_io pcl_kdtree)
+set(SUBSUBSYS_DEPS     common     geometry     features     io     kdtree)
+set(SUBSUBSYS_LIBS pcl_common pcl_geometry pcl_features pcl_io pcl_kdtree)
 set(SUBSUBSYS_EXT_DEPS ${QTX} OpenGL OpenGL_GLU openni)
+set(REASON "")
+set(DEFAULT OFF)
 
-################################################################################
-
-# Default to not building for now
-if(${DEFAULT} STREQUAL "TRUE")
-  set(DEFAULT FALSE)
+# Have Qt?
+if("${QTX}" STREQUAL "")
+  set(REASON "Cloud composer requires Qt.")
 endif()
 
 pcl_subsubsys_option(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}")
@@ -19,9 +19,7 @@ pcl_add_doc("${SUBSUBSYS_NAME}")
 ################################################################################
 
 set(INCS
-  "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/boost.h"
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/common_types.h"
-  "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/eigen.h"
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/icp.h"
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/input_data_processing.h"
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/integration.h"
@@ -77,8 +75,6 @@ if(NOT build)
   return()
 endif()
 
-include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 set(EXE_NAME "pcl_${SUBSUBSYS_NAME}")
 
 PCL_ADD_EXECUTABLE(
@@ -93,6 +89,7 @@ PCL_ADD_EXECUTABLE(
   BUNDLE)
 
 target_link_libraries("${EXE_NAME}" ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL)
+target_include_directories(${EXE_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 if (${QTX} MATCHES "Qt6")
   target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets)
 endif()
@@ -112,6 +109,7 @@ PCL_ADD_EXECUTABLE(
   BUNDLE)
 
 target_link_libraries(pcl_offline_integration ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL)
+target_include_directories(pcl_offline_integration PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 if (${QTX} MATCHES "Qt6")
   target_link_libraries(pcl_offline_integration ${QTX}::OpenGLWidgets)
 endif()
diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h
deleted file mode 100644 (file)
index f4f5354..0000000
+++ /dev/null
@@ -1,48 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- * Point Cloud Library (PCL) - www.pointclouds.org
- * Copyright (c) 2009-2012, Willow Garage, Inc.
- * Copyright (c) 2012-, Open Perception, Inc.
- *
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of the copyright holder(s) nor the names of its
- *    contributors may be used to endorse or promote products derived
- *    from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-
-#pragma once
-
-#ifdef __GNUC__
-#pragma GCC system_header
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-#include <boost/math/special_functions/fpclassify.hpp>
-#include <boost/signals2/connection.hpp>
diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h
deleted file mode 100644 (file)
index a438031..0000000
+++ /dev/null
@@ -1,49 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- * Point Cloud Library (PCL) - www.pointclouds.org
- * Copyright (c) 2009-2012, Willow Garage, Inc.
- * Copyright (c) 2012-, Open Perception, Inc.
- *
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of the copyright holder(s) nor the names of its
- *    contributors may be used to endorse or promote products derived
- *    from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-
-#pragma once
-
-#ifdef __GNUC__
-#pragma GCC system_header
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-#include <Eigen/Cholesky>
-#include <Eigen/Core>
-#include <Eigen/Geometry>
index 389bc815349cef3526dea123512bceaaa85247e6..b3d2abcf9e382844b24acda976368e9665ed44f0 100644 (file)
@@ -253,7 +253,7 @@ private:
   void
   drawText();
 
-  /** \brief Actual implementeation of startGrabber (needed so it can be run in a
+  /** \brief Actual implementation of startGrabber (needed so it can be run in a
    * different thread and doesn't block the application when starting up). */
   void
   startGrabberImpl();
index c1c86448c06d8058b6c1c67fcfe71cbf187799e3..4ce4e7ca95a6c28934976ff61bd1032a9a395264 100644 (file)
@@ -118,7 +118,7 @@ public:
   /** \brief How to draw the mesh. */
   enum MeshRepresentation {
     MR_POINTS, /**< Draw the points. */
-    MR_EDGES,  /**< Wireframe represen of the mesh. */
+    MR_EDGES,  /**< Wireframe representation of the mesh. */
     MR_FACES   /**< Draw the faces of the mesh without edges. */
   };
 
index 853232dc7f6333b037dd65a395430d35c4fd4f9d..9de7bee7fb6ac18226473d582c20ab8fcb34d0ab 100644 (file)
 
 #include <pcl/apps/in_hand_scanner/integration.h>
 #include <pcl/apps/in_hand_scanner/offline_integration.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/transforms.h>
 #include <pcl/features/integral_image_normal.h>
 #include <pcl/io/pcd_io.h>
 
 #include <boost/algorithm/string/case_conv.hpp>
-#include <boost/filesystem.hpp>
 
 #include <QApplication>
 #include <QFileDialog>
@@ -186,14 +186,14 @@ pcl::ihs::OfflineIntegration::getFilesFromDirectory(
     const std::string& extension,
     std::vector<std::string>& files) const
 {
-  if (path_dir.empty() || !boost::filesystem::exists(path_dir)) {
+  if (path_dir.empty() || !pcl_fs::exists(path_dir)) {
     std::cerr << "ERROR in offline_integration.cpp: Invalid path\n  '" << path_dir
               << "'\n";
     return (false);
   }
 
-  boost::filesystem::directory_iterator it_end;
-  for (boost::filesystem::directory_iterator it(path_dir); it != it_end; ++it) {
+  pcl_fs::directory_iterator it_end;
+  for (pcl_fs::directory_iterator it(path_dir); it != it_end; ++it) {
     if (!is_directory(it->status()) &&
         boost::algorithm::to_upper_copy(it->path().extension().string()) ==
             boost::algorithm::to_upper_copy(extension)) {
index b986ea9a6c1f273fb33bd16b16ae856e12d6b31b..5c3c36fea9da10700bafa4d1c788e428560319d9 100644 (file)
@@ -7,6 +7,8 @@
 
 #pragma once
 
+#include <pcl/common/pcl_filesystem.h>
+
 namespace face_detection_apps_utils {
 
 inline bool
@@ -65,18 +67,18 @@ sortFiles(const std::string& file1, const std::string& file2)
 }
 
 inline void
-getFilesInDirectory(bf::path& dir,
+getFilesInDirectory(pcl_fs::path& dir,
                     std::string& rel_path_so_far,
                     std::vector<std::string>& relative_paths,
                     std::string& ext)
 {
-  for (const auto& dir_entry : bf::directory_iterator(dir)) {
+  for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) {
     // check if its a directory, then get models in it
-    if (bf::is_directory(dir_entry)) {
+    if (pcl_fs::is_directory(dir_entry)) {
       std::string so_far =
           rel_path_so_far + (dir_entry.path().filename()).string() + "/";
 
-      bf::path curr_path = dir_entry.path();
+      pcl_fs::path curr_path = dir_entry.path();
       getFilesInDirectory(curr_path, so_far, relative_paths, ext);
     }
     else {
index 549f893bcff06abc461b3226342fc9aecb626021..119c9f3b9d270979b38c97750975f10989597b83 100644 (file)
@@ -120,7 +120,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_table_plane()
 
   // Compute the plane coefficients
   Eigen::Vector4f model_coefficients;
-  EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
 
   model_coefficients[0] = table_coefficients_->values[0];
   model_coefficients[1] = table_coefficients_->values[1];
@@ -251,7 +250,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_fast(
 
   // Compute the plane coefficients
   Eigen::Vector4f model_coefficients;
-  EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
 
   model_coefficients[0] = table_coefficients_->values[0];
   model_coefficients[1] = table_coefficients_->values[1];
@@ -626,7 +624,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute(
 
   // Compute the plane coefficients
   Eigen::Vector4f model_coefficients;
-  EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
 
   model_coefficients[0] = table_coefficients_->values[0];
   model_coefficients[1] = table_coefficients_->values[1];
@@ -795,7 +792,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_full(
 
   // Compute the plane coefficients
   Eigen::Vector4f model_coefficients;
-  EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
 
   model_coefficients[0] = table_coefficients_->values[0];
   model_coefficients[1] = table_coefficients_->values[1];
index ba177d66f1546a9d1a38197f37e5effdf2af7719..b10c087079a9d6249a849d2a9da8fbf58a813e3b 100644 (file)
@@ -35,6 +35,7 @@
  */
 
 #include <pcl/common/common.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/time.h>
 #include <pcl/registration/transformation_estimation_svd.h>
 #include <pcl/visualization/pcl_visualizer.h>
@@ -42,8 +43,6 @@
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
 
-#include <boost/filesystem.hpp>
-
 #include <QMainWindow>
 #include <QMutex>
 #include <QTimer>
@@ -100,7 +99,7 @@ protected:
   QString dir_;
 
   std::vector<std::string> pcd_files_;
-  std::vector<boost::filesystem::path> pcd_paths_;
+  std::vector<pcl_fs::path> pcd_paths_;
 
   /** \brief The current displayed frame */
   unsigned int current_frame_;
index 7c62124827999d3f1733bdbae794f8f78978bb7e..f7d2bae150d005f88d24c94894e1423118d82a17 100644 (file)
@@ -3,19 +3,15 @@ set(SUBSUBSYS_DESC "PCLModeler: PCL based reconstruction platform")
 set(SUBSUBSYS_DEPS common geometry io filters sample_consensus segmentation visualization kdtree features surface octree registration keypoints tracking search apps)
 set(SUBSUBSYS_EXT_DEPS vtk ${QTX})
 set(REASON "")
+set(DEFAULT OFF)
 
 # QVTK?
 if(NOT HAVE_QVTK)
-  set(DEFAULT AUTO_OFF)
   set(REASON "VTK was not built with Qt support.")
-elseif(NOT ${DEFAULT} STREQUAL "AUTO_OFF")
-  set(DEFAULT TRUE)
-  set(REASON)
 endif()
 
-# Default to not building for now
-if(${DEFAULT} STREQUAL "TRUE")
-  set(DEFAULT FALSE)
+if(NOT HAVE_QVTK)  
+  set(REASON "VTK was not built with Qt support.")
 endif()
 
 PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}")
@@ -27,8 +23,6 @@ if(NOT build)
   return()
 endif()
 
-include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 # Set Qt files and resources here
 set(uis
   main_window.ui
@@ -39,7 +33,7 @@ set(resources
 )
 
 set(incs
-   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/main_window.h"
+  "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/main_window.h"
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/scene_tree.h"
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/parameter_dialog.h"
   "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/thread_controller.h"
@@ -118,7 +112,8 @@ PCL_ADD_EXECUTABLE(
     ${incs}
     ${impl_incs})
 
-target_link_libraries("${EXE_NAME}" pcl_common pcl_io pcl_kdtree pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search ${QTX}::Widgets)
+target_link_libraries("${EXE_NAME}" pcl_common pcl_io pcl_kdtree pcl_filters pcl_registration pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search ${QTX}::Widgets)
+target_include_directories(${EXE_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
 # Install include files
 PCL_ADD_INCLUDES("${SUBSUBSYS_NAME}" "${SUBSUBSYS_NAME}" ${incs})
index 7374b72e0d77628e5eb63721b8dfc98ffc1c0223..6a355b1ece647fc40f4c17bc7080d5a3ea4e17f9 100644 (file)
@@ -1,12 +1,9 @@
 set(SUBSUBSYS_NAME point_cloud_editor)
 set(SUBSUBSYS_DESC "Point Cloud Editor - Simple editor for 3D point clouds")
 set(SUBSUBSYS_DEPS common filters io apps)
-set(SUBSUBSYS_EXT_DEPS vtk ${QTX} OpenGL)
-
-# Default to not building for now
-if(${DEFAULT} STREQUAL "TRUE")
-  set(DEFAULT FALSE)
-endif()
+set(SUBSUBSYS_EXT_DEPS vtk ${QTX} OpenGL OpenGL_GLU)
+set(REASON "")
+set(DEFAULT OFF)
 
 PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSUBSYS_NAME} PARENT_NAME ${SUBSYS_NAME} DEPS ${SUBSUBSYS_DEPS} EXT_DEPS ${SUBSUBSYS_EXT_DEPS})
@@ -71,11 +68,6 @@ set(SRCS
   src/denoiseParameterForm.cpp
 )
 
-include_directories(
-  "${CMAKE_CURRENT_BINARY_DIR}"
-  "${CMAKE_CURRENT_SOURCE_DIR}/include"
-)
-
 set(EXE_NAME "pcl_${SUBSUBSYS_NAME}")
 PCL_ADD_EXECUTABLE(
   ${EXE_NAME}
@@ -87,6 +79,7 @@ PCL_ADD_EXECUTABLE(
     ${INCS})
 
 target_link_libraries("${EXE_NAME}" ${QTX}::Widgets ${QTX}::OpenGL ${OPENGL_LIBRARIES} ${BOOST_LIBRARIES} pcl_common pcl_io pcl_filters)
+target_include_directories(${EXE_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include)
 if (${QTX} MATCHES "Qt6")
   target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets)
 endif()
index 2052f10e8e7e52d94b3d295d6cc018bfb75ebc49..6243fcc65a6d999a458348c0284f0dcdd5798a8a 100644 (file)
@@ -135,7 +135,7 @@ class Select2DTool : public ToolInterface
 
     /// @brief highlight all the points in the rubber band.
     /// @detail draw the cloud using a stencil buffer. During this time, the
-    /// points that are highlighted will not be recorded by the selecion object.
+    /// points that are highlighted will not be recorded by the selection object.
     /// @param viewport the viewport obtained from GL
     void
     highlightPoints (GLint* viewport) const;
index 7855e1711cfdb4bbac86982b37f6e459ab6cdbe4..d0e471517fe163ec2ace0f3600f7236a6af0b897 100644 (file)
@@ -35,7 +35,7 @@
 
 /// @file   selection.h
 /// @details A Selection object maintains the set of indices of points from a
-/// point cloud that have been identifed by the selection tools.
+/// point cloud that have been identified by the selection tools.
 /// @author  Yue Li and Matthew Hielsberg
 
 #pragma once
index d871a44a602cb46a961cdbbdf1402a907d864d7f..d555f007e54deb6ec6c6ed709f4d49809fe51541 100644 (file)
@@ -87,7 +87,7 @@ class SelectionTransformTool : public ToolInterface
     /// mouse screen coordinates. Then depending on the passed modifiers, the
     /// transformation matrix is computed correspondingly. If CONTROL is pressed
     /// the selection will be translated (panned) parallel to the view plane. If
-    /// ALT is pressed the selection witll be translated along the z-axis
+    /// ALT is pressed the selection will be translated along the z-axis
     /// perpendicular to the view plane.  If no key modifiers is pressed the
     /// selection will be rotated.
     /// @param x the x value of the mouse screen coordinates.
index fcb5028b66a33474a8df9f5be2d47a1ace0f7670..a13a49c752fad4f81e95540fcce6a1fc1a50542e 100644 (file)
@@ -5,6 +5,7 @@
  *      Author: Aitor Aldoma
  */
 
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/recognition/face_detection/rf_face_detector_trainer.h>
 #include <pcl/apps/face_detection/face_detection_apps_utils.h>
 // clang-format on
 
-#include <boost/filesystem.hpp>
-
-namespace bf = boost::filesystem;
-
 bool SHOW_GT = false;
 bool VIDEO = false;
 
@@ -101,7 +98,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf,
     bool result = face_detection_apps_utils::readMatrixFromFile(pose_file, pose_mat);
 
     if (result) {
-      Eigen::Vector3f ea = pose_mat.block<3, 3>(0, 0).eulerAngles(0, 1, 2);
+      Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3>().eulerAngles(0, 1, 2);
       Eigen::Vector3f trans_vector =
           Eigen::Vector3f(pose_mat(0, 3), pose_mat(1, 3), pose_mat(2, 3));
       std::cout << ea << std::endl;
@@ -130,7 +127,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf,
                  Eigen::AngleAxisf(ea[1], Eigen::Vector3f::UnitY()) *
                  Eigen::AngleAxisf(ea[2], Eigen::Vector3f::UnitZ());
 
-      // matrixxx = pose_mat.block<3,3>(0,0);
+      // matrixxx = pose_mat.topLeftCorner<3,3>();
       vec = matrixxx * vec;
 
       cylinder_coeff.values[3] = vec[0];
@@ -222,7 +219,7 @@ main(int argc, char** argv)
     // recognize all files in directory...
     std::string start;
     std::string ext = std::string("pcd");
-    bf::path dir = test_directory;
+    pcl_fs::path dir = test_directory;
 
     std::vector<std::string> files;
     face_detection_apps_utils::getFilesInDirectory(dir, start, files, ext);
index 5a12081eb6a716eee6886795c1ab5668fa9c2dc5..6574d1efab83d5b6ce2cd4e503cf15a392e7c0a5 100644 (file)
@@ -19,7 +19,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf, bool heat_map = false, bool show_votes = f
   OpenNIFrameSource::OpenNIFrameSource camera;
   OpenNIFrameSource::PointCloudPtr scene_vis;
 
-  pcl::visualization::PCLVisualizer vis("Face dection");
+  pcl::visualization::PCLVisualizer vis("Face detection");
   vis.addCoordinateSystem(0.1, "global");
 
   // keyboard callback to stop getting frames and finalize application
index fbdc4d42ebf6ea0b3cc7b3208d964931c81d6c80..2f126259619a5507fe99c99d567791bf93bf21cc 100644 (file)
@@ -35,6 +35,7 @@
  *         Christian Potthast (potthast@usc.edu)
  */
 
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/time.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/print.h>
@@ -45,8 +46,6 @@
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
 
-#include <boost/filesystem.hpp>
-
 #include <mutex>
 
 using namespace std::chrono_literals;
@@ -75,7 +74,6 @@ using namespace std::chrono_literals;
 #endif
 
 using namespace pcl::console;
-using namespace boost::filesystem;
 
 template <typename PointType>
 class OpenNIGrabFrame {
@@ -222,7 +220,7 @@ public:
              bool paused,
              bool visualizer)
   {
-    boost::filesystem::path path(filename);
+    pcl_fs::path path(filename);
 
     if (filename.empty()) {
       dir_name_ = ".";
@@ -231,7 +229,7 @@ public:
     else {
       dir_name_ = path.parent_path().string();
 
-      if (!dir_name_.empty() && !boost::filesystem::exists(path.parent_path())) {
+      if (!dir_name_.empty() && !pcl_fs::exists(path.parent_path())) {
         std::cerr << "directory \"" << path.parent_path() << "\" does not exist!\n";
         exit(1);
       }
index 7a8645671296ac5880be6658ab54938e686e87f2..428b083da42c28d69ffc93f818e21c6ac3678db3 100644 (file)
 #include <pcl/visualization/image_viewer.h>
 #include <pcl/point_types.h>
 
-#include <boost/filesystem.hpp>
-
 #include <mutex>
 
 using namespace pcl::console;
-using namespace boost::filesystem;
 
 class OpenNIGrabFrame {
 public:
@@ -254,7 +251,7 @@ public:
             depth_image->getWidth(),
             depth_image->getHeight(),
             std::numeric_limits<unsigned short>::min(),
-            // Scale so that the colors look brigher on screen
+            // Scale so that the colors look brighter on screen
             std::numeric_limits<unsigned short>::max() / 10,
             true);
 
index bf6778d1ff5767efde50e44b16fe2902cc5859ee..aee1892abf651850f41c399adda9aeca290e1ff4 100644 (file)
@@ -157,7 +157,7 @@ public:
 
     viewer_.showCloud(getLatestPointCloud());
 
-    boost::asio::io_service io_service;
+    boost::asio::io_context io_service;
     tcp::endpoint endpoint(tcp::v4(), static_cast<unsigned short>(port_));
     tcp::acceptor acceptor(io_service, endpoint);
     tcp::socket socket(io_service);
index 0a056054f348f7f008e05279bc3e009de53c4dd4..4592cbd3407baf84b031c19945936eab356d7349 100644 (file)
@@ -415,7 +415,7 @@ main(int argc, char** argv)
     if (bEnDecode) {
       // ENCODING
       try {
-        boost::asio::io_service io_service;
+        boost::asio::io_context io_service;
         tcp::endpoint endpoint(tcp::v4(), 6666);
         tcp::acceptor acceptor(io_service, endpoint);
 
@@ -423,7 +423,7 @@ main(int argc, char** argv)
 
         std::cout << "Waiting for connection.." << std::endl;
 
-        acceptor.accept(*socketStream.rdbuf());
+        acceptor.accept(socketStream.rdbuf()->socket());
 
         std::cout << "Connected!" << std::endl;
 
index c0448bde55d36cd0570bde212fdf20334776ccdf..f68314f4bf7e9580c270760d684a561506c7bcb2 100644 (file)
@@ -438,7 +438,7 @@ main(int argc, char** argv)
     if (bEnDecode) {
       // ENCODING
       try {
-        boost::asio::io_service io_service;
+        boost::asio::io_context io_service;
         tcp::endpoint endpoint(tcp::v4(), 6666);
         tcp::acceptor acceptor(io_service, endpoint);
 
@@ -446,7 +446,7 @@ main(int argc, char** argv)
 
         std::cout << "Waiting for connection.." << std::endl;
 
-        acceptor.accept(*socketStream.rdbuf());
+        acceptor.accept(socketStream.rdbuf()->socket());
 
         std::cout << "Connected!" << std::endl;
 
index 480817345a44503c916b0dd2af157ad6f99df006..cbf81a72728e82bacac8d5c5b7b33533a93f74d0 100644 (file)
@@ -15,9 +15,6 @@
 #include <vtkRendererCollection.h>
 #include <vtkRenderWindow.h>
 
-// #include <boost/filesystem.hpp>  // for boost::filesystem::directory_iterator
-#include <boost/signals2/connection.hpp> // for boost::signals2::connection
-
 void
 displayPlanarRegions(
     std::vector<pcl::PlanarRegion<PointT>,
index aa6157e3678400c51317d9010fb7bb53d2ad2849..66c3d4fa104ae4ba8c986772864afbd2ace78c3e 100644 (file)
@@ -167,11 +167,10 @@ PCDVideoPlayer::selectFolderButtonPressed()
                                            QFileDialog::ShowDirsOnly |
                                                QFileDialog::DontResolveSymlinks);
 
-  boost::filesystem::directory_iterator end_itr;
+  pcl_fs::directory_iterator end_itr;
 
-  if (boost::filesystem::is_directory(dir_.toStdString())) {
-    for (boost::filesystem::directory_iterator itr(dir_.toStdString()); itr != end_itr;
-         ++itr) {
+  if (pcl_fs::is_directory(dir_.toStdString())) {
+    for (pcl_fs::directory_iterator itr(dir_.toStdString()); itr != end_itr; ++itr) {
       std::string ext = itr->path().extension().string();
       if (ext == ".pcd") {
         pcd_files_.push_back(itr->path().string());
@@ -211,7 +210,7 @@ void
 PCDVideoPlayer::selectFilesButtonPressed()
 {
   pcd_files_.clear(); // Clear the std::vector
-  pcd_paths_.clear(); // Clear the boost filesystem paths
+  pcd_paths_.clear(); // Clear the filesystem paths
 
   QStringList qt_pcd_files = QFileDialog::getOpenFileNames(
       this, "Select one or more PCD files to open", "/home", "PointClouds (*.pcd)");
index 896b101544ef82269a2e0d5c7234e540f58e515f..9f6ba71ef8c10fe1844c9c757ed48499373df6cf 100644 (file)
@@ -409,7 +409,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews()
         trans_view(x, y) = float(view_transform->GetElement(x, y));
 
     // NOTE: vtk view coordinate system is different than the standard camera
-    // coordinates (z forward, y down, x right) thus, the fliping in y and z
+    // coordinates (z forward, y down, x right) thus, the flipping in y and z
     for (auto& point : cloud->points) {
       point.getVector4fMap() = trans_view * point.getVector4fMap();
       point.y *= -1.0f;
@@ -430,7 +430,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews()
     transOCtoCC->Concatenate(cam_tmp->GetViewTransformMatrix());
 
     // NOTE: vtk view coordinate system is different than the standard camera
-    // coordinates (z forward, y down, x right) thus, the fliping in y and z
+    // coordinates (z forward, y down, x right) thus, the flipping in y and z
     vtkSmartPointer<vtkMatrix4x4> cameraSTD = vtkSmartPointer<vtkMatrix4x4>::New();
     cameraSTD->Identity();
     cameraSTD->SetElement(0, 0, 1);
index 0ef2ed02713fd968e78a35ad2a58da843354f928..576705de5d639e5e5a60785ae668d434e054d3dc 100755 (executable)
@@ -36,6 +36,7 @@
 #include <pcl/common/centroid.h> // for computeMeanAndCovarianceMatrix
 #include <pcl/common/distances.h>
 #include <pcl/common/intersections.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/features/integral_image_normal.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/sample_consensus/sac_model_plane.h>
@@ -50,8 +51,6 @@
 #include <pcl/visualization/pcl_visualizer.h>
 #include <pcl/ModelCoefficients.h>
 
-#include <boost/filesystem.hpp> // for directory_iterator
-
 #include <mutex>
 
 using PointT = pcl::PointXYZRGB;
@@ -541,13 +540,13 @@ main(int argc, char** argv)
 
   // Get list of stereo files
   std::vector<std::string> left_images;
-  boost::filesystem::directory_iterator end_itr;
-  for (boost::filesystem::directory_iterator itr(argv[1]); itr != end_itr; ++itr) {
+  pcl_fs::directory_iterator end_itr;
+  for (pcl_fs::directory_iterator itr(argv[1]); itr != end_itr; ++itr) {
     left_images.push_back(itr->path().string());
   }
   sort(left_images.begin(), left_images.end());
   std::vector<std::string> right_images;
-  for (boost::filesystem::directory_iterator itr(argv[2]); itr != end_itr; ++itr) {
+  for (pcl_fs::directory_iterator itr(argv[2]); itr != end_itr; ++itr) {
     right_images.push_back(itr->path().string());
   }
   sort(right_images.begin(), right_images.end());
index 95f421db5f6d4f1fab966185ad5a41cd07171396..bf353c70f908b451347640a99c5ca666423b0b49 100644 (file)
@@ -1,10 +1,8 @@
 set(SUBSYS_NAME benchmarks)
 set(SUBSYS_DESC "Point cloud library benchmarks")
 set(SUBSYS_DEPS common filters features search kdtree io)
-set(DEFAULT OFF)
-set(build TRUE)
-set(REASON "Disabled by default")
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 if(NOT build)
   return()
@@ -25,6 +23,11 @@ PCL_ADD_BENCHMARK(filters_voxel_grid FILES filters/voxel_grid.cpp
                   ARGUMENTS "${PCL_SOURCE_DIR}/test/table_scene_mug_stereo_textured.pcd"
                             "${PCL_SOURCE_DIR}/test/milk_cartoon_all_small_clorox.pcd")
 
+PCL_ADD_BENCHMARK(filters_radius_outlier_removal FILES filters/radius_outlier_removal.cpp
+                  LINK_WITH pcl_io pcl_filters
+                  ARGUMENTS "${PCL_SOURCE_DIR}/test/table_scene_mug_stereo_textured.pcd"
+                            "${PCL_SOURCE_DIR}/test/milk_cartoon_all_small_clorox.pcd")
+
 PCL_ADD_BENCHMARK(search_radius_search FILES search/radius_search.cpp
                   LINK_WITH pcl_io pcl_search
                   ARGUMENTS "${PCL_SOURCE_DIR}/test/table_scene_mug_stereo_textured.pcd"
diff --git a/benchmarks/filters/radius_outlier_removal.cpp b/benchmarks/filters/radius_outlier_removal.cpp
new file mode 100644 (file)
index 0000000..66aa527
--- /dev/null
@@ -0,0 +1,84 @@
+#include <pcl/filters/radius_outlier_removal.h>
+#include <pcl/io/pcd_io.h> // for PCDReader
+
+#include <benchmark/benchmark.h>
+
+static void
+BM_RadiusOutlierRemoval(benchmark::State& state, const std::string& file)
+{
+  // Perform setup here
+  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
+  pcl::PCDReader reader;
+  reader.read(file, *cloud);
+
+  pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror;
+  ror.setInputCloud(cloud);
+  ror.setRadiusSearch(0.02);
+  ror.setMinNeighborsInRadius(14);
+
+  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_voxelized(
+      new pcl::PointCloud<pcl::PointXYZ>);
+  for (auto _ : state) {
+    // This code gets timed
+    ror.filter(*cloud_voxelized);
+  }
+}
+
+static void
+BM_RadiusOutlierRemovalOpenMP(benchmark::State& state, const std::string& file)
+{
+  // Perform setup here
+  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
+  pcl::PCDReader reader;
+  reader.read(file, *cloud);
+
+  pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror;
+  ror.setInputCloud(cloud);
+  ror.setRadiusSearch(0.02);
+  ror.setMinNeighborsInRadius(14);
+  ror.setNumberOfThreads(0);
+
+  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_voxelized(
+      new pcl::PointCloud<pcl::PointXYZ>);
+  for (auto _ : state) {
+    // This code gets timed
+    ror.filter(*cloud_voxelized);
+  }
+}
+
+int
+main(int argc, char** argv)
+{
+  constexpr int runs = 100;
+
+  if (argc < 3) {
+    std::cerr
+        << "No test files given. Please download `table_scene_mug_stereo_textured.pcd` "
+           "and `milk_cartoon_all_small_clorox.pcd`, and pass their paths to the test."
+        << std::endl;
+    return (-1);
+  }
+
+  benchmark::RegisterBenchmark(
+      "BM_RadiusOutlierRemoval_milk", &BM_RadiusOutlierRemoval, argv[2])
+      ->Unit(benchmark::kMillisecond)
+      ->Iterations(runs);
+
+  benchmark::RegisterBenchmark(
+      "BM_RadiusOutlierRemoval_mug", &BM_RadiusOutlierRemoval, argv[1])
+      ->Unit(benchmark::kMillisecond)
+      ->Iterations(runs);
+
+  benchmark::RegisterBenchmark(
+      "BM_RadiusOutlierRemovalOpenMP_milk", &BM_RadiusOutlierRemovalOpenMP, argv[2])
+      ->Unit(benchmark::kMillisecond)
+      ->Iterations(runs);
+
+  benchmark::RegisterBenchmark(
+      "BM_RadiusOutlierRemovalOpenMP_mug", &BM_RadiusOutlierRemovalOpenMP, argv[1])
+      ->Unit(benchmark::kMillisecond)
+      ->Iterations(runs);
+
+  benchmark::Initialize(&argc, argv);
+  benchmark::RunSpecifiedBenchmarks();
+}
index 9641375bed329fded8499d03d689b412ea2635ca..12336a8f95f3472ecbcbd0d8f4bbc9cc3b888dd7 100644 (file)
@@ -26,7 +26,7 @@ BM_OrganizedNeighborSearch(benchmark::State& state, const std::string& file)
     int searchIdx = indices[radiusSearchIdx++ % indices.size()];
     double searchRadius = 0.1; // or any fixed radius like 0.05
 
-    std::vector<int> k_indices;
+    pcl::Indices k_indices;
     std::vector<float> k_sqr_distances;
 
     auto start_time = std::chrono::high_resolution_clock::now();
index f42bca3f76ef0d2d4fc75b72c4c461b06df22859..8633ac81acabbafe4305932fa0a9cd71b10765b5 100644 (file)
@@ -104,8 +104,6 @@ find_path(FLANN_INCLUDE_DIR
     flann/flann.hpp
   HINTS
     ${PC_FLANN_INCLUDE_DIRS}
-    ${FLANN_ROOT}
-    $ENV{FLANN_ROOT}
   PATHS
     $ENV{PROGRAMFILES}/Flann
     $ENV{PROGRAMW6432}/Flann
@@ -118,8 +116,6 @@ find_library(FLANN_LIBRARY_SHARED
     flann_cpp
   HINTS
     ${PC_FLANN_LIBRARY_DIRS}
-    ${FLANN_ROOT}
-    $ENV{FLANN_ROOT}
   PATHS
     $ENV{PROGRAMFILES}/Flann
     $ENV{PROGRAMW6432}/Flann
@@ -132,8 +128,6 @@ find_library(FLANN_LIBRARY_DEBUG_SHARED
     flann_cpp-gd flann_cppd
   HINTS
     ${PC_FLANN_LIBRARY_DIRS}
-    ${FLANN_ROOT}
-    $ENV{FLANN_ROOT}
   PATHS
     $ENV{PROGRAMFILES}/Flann
     $ENV{PROGRAMW6432}/Flann
@@ -146,8 +140,6 @@ find_library(FLANN_LIBRARY_STATIC
     flann_cpp_s
   HINTS
     ${PC_FLANN_LIBRARY_DIRS}
-    ${FLANN_ROOT}
-    $ENV{FLANN_ROOT}
   PATHS
     $ENV{PROGRAMFILES}/Flann
     $ENV{PROGRAMW6432}/Flann
@@ -160,8 +152,6 @@ find_library(FLANN_LIBRARY_DEBUG_STATIC
     flann_cpp_s-gd flann_cpp_sd
   HINTS
     ${PC_FLANN_LIBRARY_DIRS}
-    ${FLANN_ROOT}
-    $ENV{FLANN_ROOT}
   PATHS
     $ENV{PROGRAMFILES}/Flann
     $ENV{PROGRAMW6432}/Flann
diff --git a/cmake/Modules/FindGLEW.cmake b/cmake/Modules/FindGLEW.cmake
deleted file mode 100644 (file)
index b0e1def..0000000
+++ /dev/null
@@ -1,69 +0,0 @@
-# Distributed under the OSI-approved BSD 3-Clause License.  See accompanying
-# file Copyright.txt or https://cmake.org/licensing for details.
-
-#.rst:
-# FindGLEW
-# --------
-#
-# Find the OpenGL Extension Wrangler Library (GLEW)
-#
-# IMPORTED Targets
-# ^^^^^^^^^^^^^^^^
-#
-# This module defines the :prop_tgt:`IMPORTED` target ``GLEW::GLEW``,
-# if GLEW has been found.
-#
-# Result Variables
-# ^^^^^^^^^^^^^^^^
-#
-# This module defines the following variables:
-#
-# ::
-#
-#   GLEW_INCLUDE_DIRS - include directories for GLEW
-#   GLEW_LIBRARIES - libraries to link against GLEW
-#   GLEW_FOUND - true if GLEW has been found and can be used
-
-find_path(GLEW_INCLUDE_DIR GL/glew.h)
-
-if(NOT GLEW_LIBRARY)
-  find_library(GLEW_LIBRARY_RELEASE NAMES GLEW glew32 glew glew32s PATH_SUFFIXES lib64 libx32)
-  find_library(GLEW_LIBRARY_DEBUG NAMES GLEWd glew32d glewd PATH_SUFFIXES lib64)
-
-  include(SelectLibraryConfigurations)
-  select_library_configurations(GLEW)
-endif ()
-
-include(FindPackageHandleStandardArgs)
-find_package_handle_standard_args(GLEW
-                                  REQUIRED_VARS GLEW_INCLUDE_DIR GLEW_LIBRARY)
-
-if(GLEW_FOUND)
-  set(GLEW_INCLUDE_DIRS ${GLEW_INCLUDE_DIR})
-
-  if(NOT GLEW_LIBRARIES)
-    set(GLEW_LIBRARIES ${GLEW_LIBRARY})
-  endif()
-
-  if (NOT TARGET GLEW::GLEW)
-    add_library(GLEW::GLEW UNKNOWN IMPORTED)
-    set_target_properties(GLEW::GLEW PROPERTIES
-      INTERFACE_INCLUDE_DIRECTORIES "${GLEW_INCLUDE_DIRS}")
-
-    if(GLEW_LIBRARY_RELEASE)
-      set_property(TARGET GLEW::GLEW APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE)
-      set_target_properties(GLEW::GLEW PROPERTIES IMPORTED_LOCATION_RELEASE "${GLEW_LIBRARY_RELEASE}")
-    endif()
-
-    if(GLEW_LIBRARY_DEBUG)
-      set_property(TARGET GLEW::GLEW APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG)
-      set_target_properties(GLEW::GLEW PROPERTIES IMPORTED_LOCATION_DEBUG "${GLEW_LIBRARY_DEBUG}")
-    endif()
-
-    if(NOT GLEW_LIBRARY_RELEASE AND NOT GLEW_LIBRARY_DEBUG)
-      set_property(TARGET GLEW::GLEW APPEND PROPERTY IMPORTED_LOCATION "${GLEW_LIBRARY}")
-    endif()
-  endif()
-endif()
-
-mark_as_advanced(GLEW_INCLUDE_DIR)
\ No newline at end of file
index be2bfd1f2e90272d982010a2e6a3aafeb6ed365b..d5e14b3580c3a7a9f3d497818dc872c313743635 100644 (file)
@@ -15,15 +15,14 @@ if(APPLE)
 endif()
 
 find_path(GTEST_INCLUDE_DIR gtest/gtest.h
-    HINTS "${GTEST_ROOT}" "$ENV{GTEST_ROOT}"
     PATHS "$ENV{PROGRAMFILES}/gtest" "$ENV{PROGRAMW6432}/gtest"
     PATHS "$ENV{PROGRAMFILES}/gtest-1.7.0" "$ENV{PROGRAMW6432}/gtest-1.7.0"
     PATH_SUFFIXES gtest include/gtest include)
 
 find_path(GTEST_SRC_DIR src/gtest-all.cc
-    HINTS "${GTEST_ROOT}" "$ENV{GTEST_ROOT}"
     PATHS "$ENV{PROGRAMFILES}/gtest" "$ENV{PROGRAMW6432}/gtest"
     PATHS "$ENV{PROGRAMFILES}/gtest-1.7.0" "$ENV{PROGRAMW6432}/gtest-1.7.0"
+    PATH /usr/src/googletest
     PATH /usr/src/googletest/googletest
     PATH /usr/src/gtest
     PATH_SUFFIXES gtest src/gtest googletest/googletest)
diff --git a/cmake/Modules/FindOpenMP.cmake b/cmake/Modules/FindOpenMP.cmake
deleted file mode 100644 (file)
index b4f6a6a..0000000
+++ /dev/null
@@ -1,617 +0,0 @@
-# Distributed under the OSI-approved BSD 3-Clause License.  See accompanying
-# file Copyright.txt or https://cmake.org/licensing for details.
-
-#[=======================================================================[.rst:
-
-FindOpenMP is added to PCL local Cmake modules due to bug in earlier version.
-TODO: Can be removed when Cmake 3.11 is required.
-See https://gitlab.kitware.com/cmake/cmake/-/issues/20364
-
-FindOpenMP
-----------
-
-Finds Open Multi-Processing (OpenMP) support.
-
-This module can be used to detect OpenMP support in a compiler.  If
-the compiler supports OpenMP, the flags required to compile with
-OpenMP support are returned in variables for the different languages.
-The variables may be empty if the compiler does not need a special
-flag to support OpenMP.
-
-Variables
-^^^^^^^^^
-
-The module exposes the components ``C``, ``CXX``, and ``Fortran``.
-Each of these controls the various languages to search OpenMP support for.
-
-Depending on the enabled components the following variables will be set:
-
-``OpenMP_FOUND``
-  Variable indicating that OpenMP flags for all requested languages have been found.
-  If no components are specified, this is true if OpenMP settings for all enabled languages
-  were detected.
-``OpenMP_VERSION``
-  Minimal version of the OpenMP standard detected among the requested languages,
-  or all enabled languages if no components were specified.
-
-This module will set the following variables per language in your
-project, where ``<lang>`` is one of C, CXX, or Fortran:
-
-``OpenMP_<lang>_FOUND``
-  Variable indicating if OpenMP support for ``<lang>`` was detected.
-``OpenMP_<lang>_FLAGS``
-  OpenMP compiler flags for ``<lang>``, separated by spaces.
-``OpenMP_<lang>_INCLUDE_DIRS``
-  Directories that must be added to the header search path for ``<lang>``
-  when using OpenMP.
-
-For linking with OpenMP code written in ``<lang>``, the following
-variables are provided:
-
-``OpenMP_<lang>_LIB_NAMES``
-  :ref:`;-list <CMake Language Lists>` of libraries for OpenMP programs for ``<lang>``.
-``OpenMP_<libname>_LIBRARY``
-  Location of the individual libraries needed for OpenMP support in ``<lang>``.
-``OpenMP_<lang>_LIBRARIES``
-  A list of libraries needed to link with OpenMP code written in ``<lang>``.
-
-Additionally, the module provides :prop_tgt:`IMPORTED` targets:
-
-``OpenMP::OpenMP_<lang>``
-  Target for using OpenMP from ``<lang>``.
-
-Specifically for Fortran, the module sets the following variables:
-
-``OpenMP_Fortran_HAVE_OMPLIB_HEADER``
-  Boolean indicating if OpenMP is accessible through ``omp_lib.h``.
-``OpenMP_Fortran_HAVE_OMPLIB_MODULE``
-  Boolean indicating if OpenMP is accessible through the ``omp_lib`` Fortran module.
-
-The module will also try to provide the OpenMP version variables:
-
-``OpenMP_<lang>_SPEC_DATE``
-  Date of the OpenMP specification implemented by the ``<lang>`` compiler.
-``OpenMP_<lang>_VERSION_MAJOR``
-  Major version of OpenMP implemented by the ``<lang>`` compiler.
-``OpenMP_<lang>_VERSION_MINOR``
-  Minor version of OpenMP implemented by the ``<lang>`` compiler.
-``OpenMP_<lang>_VERSION``
-  OpenMP version implemented by the ``<lang>`` compiler.
-
-The specification date is formatted as given in the OpenMP standard:
-``yyyymm`` where ``yyyy`` and ``mm`` represents the year and month of
-the OpenMP specification implemented by the ``<lang>`` compiler.
-
-For some compilers, it may be necessary to add a header search path to find
-the relevant OpenMP headers.  This location may be language-specific.  Where
-this is needed, the module may attempt to find the location, but it can be
-provided directly by setting the ``OpenMP_<lang>_INCLUDE_DIR`` cache variable.
-Note that this variable is an _input_ control to the module.  Project code
-should use the ``OpenMP_<lang>_INCLUDE_DIRS`` _output_ variable if it needs
-to know what include directories are needed.
-#]=======================================================================]
-
-cmake_policy(PUSH)
-cmake_policy(SET CMP0012 NEW) # if() recognizes numbers and booleans
-cmake_policy(SET CMP0054 NEW) # if() quoted variables not dereferenced
-cmake_policy(SET CMP0057 NEW) # if IN_LIST
-
-function(_OPENMP_FLAG_CANDIDATES LANG)
-  if(NOT OpenMP_${LANG}_FLAG)
-    unset(OpenMP_FLAG_CANDIDATES)
-
-    set(OMP_FLAG_GNU "-fopenmp")
-    set(OMP_FLAG_Clang "-fopenmp=libomp" "-fopenmp=libiomp5" "-fopenmp" "-Xclang -fopenmp")
-    set(OMP_FLAG_AppleClang "-Xclang -fopenmp")
-    set(OMP_FLAG_HP "+Oopenmp")
-    if(WIN32)
-      set(OMP_FLAG_Intel "-Qopenmp")
-    elseif(CMAKE_${LANG}_COMPILER_ID STREQUAL "Intel" AND
-           "${CMAKE_${LANG}_COMPILER_VERSION}" VERSION_LESS "15.0.0.20140528")
-      set(OMP_FLAG_Intel "-openmp")
-    else()
-      set(OMP_FLAG_Intel "-qopenmp")
-    endif()
-    set(OMP_FLAG_MSVC "-openmp")
-    set(OMP_FLAG_PathScale "-openmp")
-    set(OMP_FLAG_NAG "-openmp")
-    set(OMP_FLAG_Absoft "-openmp")
-    set(OMP_FLAG_PGI "-mp")
-    set(OMP_FLAG_Flang "-fopenmp")
-    set(OMP_FLAG_SunPro "-xopenmp")
-    set(OMP_FLAG_XL "-qsmp=omp")
-    # Cray compiler activate OpenMP with -h omp, which is enabled by default.
-    set(OMP_FLAG_Cray " " "-h omp")
-
-    # If we know the correct flags, use those
-    if(DEFINED OMP_FLAG_${CMAKE_${LANG}_COMPILER_ID})
-      set(OpenMP_FLAG_CANDIDATES "${OMP_FLAG_${CMAKE_${LANG}_COMPILER_ID}}")
-    # Fall back to reasonable default tries otherwise
-    else()
-      set(OpenMP_FLAG_CANDIDATES "-openmp" "-fopenmp" "-mp" " ")
-    endif()
-    set(OpenMP_${LANG}_FLAG_CANDIDATES "${OpenMP_FLAG_CANDIDATES}" PARENT_SCOPE)
-  else()
-    set(OpenMP_${LANG}_FLAG_CANDIDATES "${OpenMP_${LANG}_FLAG}" PARENT_SCOPE)
-  endif()
-endfunction()
-
-# sample openmp source code to test
-set(OpenMP_C_CXX_TEST_SOURCE
-"
-#include <omp.h>
-int main(void) {
-#ifdef _OPENMP
-  omp_get_max_threads();
-  return 0;
-#elif defined(__HIP_DEVICE_COMPILE__)
-  return 0;
-#else
-  breaks_on_purpose
-#endif
-}
-")
-
-# in Fortran, an implementation may provide an omp_lib.h header
-# or omp_lib module, or both (OpenMP standard, section 3.1)
-# Furthermore !$ is the Fortran equivalent of #ifdef _OPENMP (OpenMP standard, 2.2.2)
-# Without the conditional compilation, some compilers (e.g. PGI) might compile OpenMP code
-# while not actually enabling OpenMP, building code sequentially
-set(OpenMP_Fortran_TEST_SOURCE
-  "
-      program test
-      @OpenMP_Fortran_INCLUDE_LINE@
-  !$  integer :: n
-      n = omp_get_num_threads()
-      end program test
-  "
-)
-
-function(_OPENMP_WRITE_SOURCE_FILE LANG SRC_FILE_CONTENT_VAR SRC_FILE_NAME SRC_FILE_FULLPATH)
-  set(WORK_DIR ${CMAKE_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/FindOpenMP)
-  if("${LANG}" STREQUAL "C")
-    set(SRC_FILE "${WORK_DIR}/${SRC_FILE_NAME}.c")
-    file(WRITE "${SRC_FILE}" "${OpenMP_C_CXX_${SRC_FILE_CONTENT_VAR}}")
-  elseif("${LANG}" STREQUAL "CXX")
-    set(SRC_FILE "${WORK_DIR}/${SRC_FILE_NAME}.cpp")
-    file(WRITE "${SRC_FILE}" "${OpenMP_C_CXX_${SRC_FILE_CONTENT_VAR}}")
-  elseif("${LANG}" STREQUAL "Fortran")
-    set(SRC_FILE "${WORK_DIR}/${SRC_FILE_NAME}.f90")
-    file(WRITE "${SRC_FILE}_in" "${OpenMP_Fortran_${SRC_FILE_CONTENT_VAR}}")
-    configure_file("${SRC_FILE}_in" "${SRC_FILE}" @ONLY)
-  endif()
-  set(${SRC_FILE_FULLPATH} "${SRC_FILE}" PARENT_SCOPE)
-endfunction()
-
-include(CMakeParseImplicitLinkInfo)
-
-function(_OPENMP_GET_FLAGS LANG FLAG_MODE OPENMP_FLAG_VAR OPENMP_LIB_NAMES_VAR)
-  _OPENMP_FLAG_CANDIDATES("${LANG}")
-  _OPENMP_WRITE_SOURCE_FILE("${LANG}" "TEST_SOURCE" OpenMPTryFlag _OPENMP_TEST_SRC)
-
-  unset(OpenMP_VERBOSE_COMPILE_OPTIONS)
-  separate_arguments(OpenMP_VERBOSE_OPTIONS NATIVE_COMMAND "${CMAKE_${LANG}_VERBOSE_FLAG}")
-  foreach(_VERBOSE_OPTION IN LISTS OpenMP_VERBOSE_OPTIONS)
-    if(NOT _VERBOSE_OPTION MATCHES "^-Wl,")
-      list(APPEND OpenMP_VERBOSE_COMPILE_OPTIONS ${_VERBOSE_OPTION})
-    endif()
-  endforeach()
-
-  foreach(OPENMP_FLAG IN LISTS OpenMP_${LANG}_FLAG_CANDIDATES)
-    set(OPENMP_FLAGS_TEST "${OPENMP_FLAG}")
-    if(OpenMP_VERBOSE_COMPILE_OPTIONS)
-      string(APPEND OPENMP_FLAGS_TEST " ${OpenMP_VERBOSE_COMPILE_OPTIONS}")
-    endif()
-    string(REGEX REPLACE "[-/=+]" "" OPENMP_PLAIN_FLAG "${OPENMP_FLAG}")
-    try_compile( OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG} ${CMAKE_BINARY_DIR} ${_OPENMP_TEST_SRC}
-      CMAKE_FLAGS "-DCOMPILE_DEFINITIONS:STRING=${OPENMP_FLAGS_TEST}"
-      LINK_LIBRARIES ${CMAKE_${LANG}_VERBOSE_FLAG}
-      OUTPUT_VARIABLE OpenMP_TRY_COMPILE_OUTPUT
-    )
-
-    if(OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG})
-      set("${OPENMP_FLAG_VAR}" "${OPENMP_FLAG}" PARENT_SCOPE)
-
-      if(CMAKE_${LANG}_VERBOSE_FLAG)
-        unset(OpenMP_${LANG}_IMPLICIT_LIBRARIES)
-        unset(OpenMP_${LANG}_IMPLICIT_LINK_DIRS)
-        unset(OpenMP_${LANG}_IMPLICIT_FWK_DIRS)
-        unset(OpenMP_${LANG}_LOG_VAR)
-
-        file(APPEND ${CMAKE_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/CMakeOutput.log
-        "Detecting ${LANG} OpenMP compiler ABI info compiled with the following output:\n${OpenMP_TRY_COMPILE_OUTPUT}\n\n")
-
-        cmake_parse_implicit_link_info("${OpenMP_TRY_COMPILE_OUTPUT}"
-          OpenMP_${LANG}_IMPLICIT_LIBRARIES
-          OpenMP_${LANG}_IMPLICIT_LINK_DIRS
-          OpenMP_${LANG}_IMPLICIT_FWK_DIRS
-          OpenMP_${LANG}_LOG_VAR
-          "${CMAKE_${LANG}_IMPLICIT_OBJECT_REGEX}"
-        )
-
-        file(APPEND ${CMAKE_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/CMakeOutput.log
-        "Parsed ${LANG} OpenMP implicit link information from above output:\n${OpenMP_${LANG}_LOG_VAR}\n\n")
-
-        unset(_OPENMP_LIB_NAMES)
-        foreach(_OPENMP_IMPLICIT_LIB IN LISTS OpenMP_${LANG}_IMPLICIT_LIBRARIES)
-          get_filename_component(_OPENMP_IMPLICIT_LIB_DIR "${_OPENMP_IMPLICIT_LIB}" DIRECTORY)
-          get_filename_component(_OPENMP_IMPLICIT_LIB_NAME "${_OPENMP_IMPLICIT_LIB}" NAME)
-          get_filename_component(_OPENMP_IMPLICIT_LIB_PLAIN "${_OPENMP_IMPLICIT_LIB}" NAME_WE)
-          string(REGEX REPLACE "([][+.*?()^$])" "\\\\\\1" _OPENMP_IMPLICIT_LIB_PLAIN_ESC "${_OPENMP_IMPLICIT_LIB_PLAIN}")
-          string(REGEX REPLACE "([][+.*?()^$])" "\\\\\\1" _OPENMP_IMPLICIT_LIB_PATH_ESC "${_OPENMP_IMPLICIT_LIB}")
-          if(NOT ( "${_OPENMP_IMPLICIT_LIB}" IN_LIST CMAKE_${LANG}_IMPLICIT_LINK_LIBRARIES
-            OR "${CMAKE_${LANG}_STANDARD_LIBRARIES}" MATCHES "(^| )(-Wl,)?(-l)?(${_OPENMP_IMPLICIT_LIB_PLAIN_ESC}|${_OPENMP_IMPLICIT_LIB_PATH_ESC})( |$)"
-            OR "${CMAKE_${LANG}_LINK_EXECUTABLE}" MATCHES "(^| )(-Wl,)?(-l)?(${_OPENMP_IMPLICIT_LIB_PLAIN_ESC}|${_OPENMP_IMPLICIT_LIB_PATH_ESC})( |$)" ) )
-            if(_OPENMP_IMPLICIT_LIB_DIR)
-              set(OpenMP_${_OPENMP_IMPLICIT_LIB_PLAIN}_LIBRARY "${_OPENMP_IMPLICIT_LIB}" CACHE FILEPATH
-                "Path to the ${_OPENMP_IMPLICIT_LIB_PLAIN} library for OpenMP")
-            else()
-              find_library(OpenMP_${_OPENMP_IMPLICIT_LIB_PLAIN}_LIBRARY
-                NAMES "${_OPENMP_IMPLICIT_LIB_NAME}"
-                DOC "Path to the ${_OPENMP_IMPLICIT_LIB_PLAIN} library for OpenMP"
-                HINTS ${OpenMP_${LANG}_IMPLICIT_LINK_DIRS}
-                CMAKE_FIND_ROOT_PATH_BOTH
-                NO_DEFAULT_PATH
-              )
-            endif()
-            mark_as_advanced(OpenMP_${_OPENMP_IMPLICIT_LIB_PLAIN}_LIBRARY)
-            list(APPEND _OPENMP_LIB_NAMES ${_OPENMP_IMPLICIT_LIB_PLAIN})
-          endif()
-        endforeach()
-        set("${OPENMP_LIB_NAMES_VAR}" "${_OPENMP_LIB_NAMES}" PARENT_SCOPE)
-      else()
-        # We do not know how to extract implicit OpenMP libraries for this compiler.
-        # Assume that it handles them automatically, e.g. the Intel Compiler on
-        # Windows should put the dependency in its object files.
-        set("${OPENMP_LIB_NAMES_VAR}" "" PARENT_SCOPE)
-      endif()
-      break()
-    elseif(CMAKE_${LANG}_COMPILER_ID STREQUAL "AppleClang"
-      AND CMAKE_${LANG}_COMPILER_VERSION VERSION_GREATER_EQUAL "7.0")
-
-      # Check for separate OpenMP library on AppleClang 7+
-      find_library(OpenMP_libomp_LIBRARY
-        NAMES omp gomp iomp5
-        HINTS ${CMAKE_${LANG}_IMPLICIT_LINK_DIRECTORIES}
-      )
-      mark_as_advanced(OpenMP_libomp_LIBRARY)
-
-      if(OpenMP_libomp_LIBRARY)
-        # Try without specifying include directory first. We only want to
-        # explicitly add a search path if the header can't be found on the
-        # default header search path already.
-        try_compile( OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG} ${CMAKE_BINARY_DIR} ${_OPENMP_TEST_SRC}
-          CMAKE_FLAGS "-DCOMPILE_DEFINITIONS:STRING=${OPENMP_FLAGS_TEST}"
-          LINK_LIBRARIES ${CMAKE_${LANG}_VERBOSE_FLAG} ${OpenMP_libomp_LIBRARY}
-          OUTPUT_VARIABLE OpenMP_TRY_COMPILE_OUTPUT
-        )
-        if(NOT OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG})
-          find_path(OpenMP_${LANG}_INCLUDE_DIR omp.h)
-          mark_as_advanced(OpenMP_${LANG}_INCLUDE_DIR)
-          set(OpenMP_${LANG}_INCLUDE_DIR "${OpenMP_${LANG}_INCLUDE_DIR}" PARENT_SCOPE)
-          if(OpenMP_${LANG}_INCLUDE_DIR)
-            try_compile( OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG} ${CMAKE_BINARY_DIR} ${_OPENMP_TEST_SRC}
-              CMAKE_FLAGS "-DCOMPILE_DEFINITIONS:STRING=${OPENMP_FLAGS_TEST}"
-                          "-DINCLUDE_DIRECTORIES:STRING=${OpenMP_${LANG}_INCLUDE_DIR}"
-              LINK_LIBRARIES ${CMAKE_${LANG}_VERBOSE_FLAG} ${OpenMP_libomp_LIBRARY}
-              OUTPUT_VARIABLE OpenMP_TRY_COMPILE_OUTPUT
-            )
-          endif()
-        endif()
-        if(OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG})
-          set("${OPENMP_FLAG_VAR}" "${OPENMP_FLAG}" PARENT_SCOPE)
-          set("${OPENMP_LIB_NAMES_VAR}" "libomp" PARENT_SCOPE)
-          break()
-        endif()
-      endif()
-    elseif(CMAKE_${LANG}_COMPILER_ID STREQUAL "Clang" AND WIN32)
-      # Check for separate OpenMP library for Clang on Windows
-      find_library(OpenMP_libomp_LIBRARY
-        NAMES libomp libgomp libiomp5
-        HINTS ${CMAKE_${LANG}_IMPLICIT_LINK_DIRECTORIES}
-      )
-      mark_as_advanced(OpenMP_libomp_LIBRARY)
-      if(OpenMP_libomp_LIBRARY)
-        try_compile( OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG} ${CMAKE_BINARY_DIR} ${_OPENMP_TEST_SRC}
-          CMAKE_FLAGS "-DCOMPILE_DEFINITIONS:STRING=${OPENMP_FLAGS_TEST}"
-          LINK_LIBRARIES ${CMAKE_${LANG}_VERBOSE_FLAG} ${OpenMP_libomp_LIBRARY}
-          OUTPUT_VARIABLE OpenMP_TRY_COMPILE_OUTPUT
-        )
-        if(OpenMP_COMPILE_RESULT_${FLAG_MODE}_${OPENMP_PLAIN_FLAG})
-          set("${OPENMP_FLAG_VAR}" "${OPENMP_FLAG}" PARENT_SCOPE)
-          set("${OPENMP_LIB_NAMES_VAR}" "libomp" PARENT_SCOPE)
-          break()
-        endif()
-      endif()
-    else()
-      file(APPEND ${CMAKE_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/CMakeError.log
-        "Detecting ${LANG} OpenMP failed with the following output:\n${OpenMP_TRY_COMPILE_OUTPUT}\n\n")
-    endif()
-    set("${OPENMP_LIB_NAMES_VAR}" "NOTFOUND" PARENT_SCOPE)
-    set("${OPENMP_FLAG_VAR}" "NOTFOUND" PARENT_SCOPE)
-  endforeach()
-
-  unset(OpenMP_VERBOSE_COMPILE_OPTIONS)
-endfunction()
-
-set(OpenMP_C_CXX_CHECK_VERSION_SOURCE
-"
-#include <stdio.h>
-#include <omp.h>
-const char ompver_str[] = { 'I', 'N', 'F', 'O', ':', 'O', 'p', 'e', 'n', 'M',
-                            'P', '-', 'd', 'a', 't', 'e', '[',
-                            ('0' + ((_OPENMP/100000)%10)),
-                            ('0' + ((_OPENMP/10000)%10)),
-                            ('0' + ((_OPENMP/1000)%10)),
-                            ('0' + ((_OPENMP/100)%10)),
-                            ('0' + ((_OPENMP/10)%10)),
-                            ('0' + ((_OPENMP/1)%10)),
-                            ']', '\\0' };
-int main(void)
-{
-  puts(ompver_str);
-  return 0;
-}
-")
-
-set(OpenMP_Fortran_CHECK_VERSION_SOURCE
-"
-      program omp_ver
-      @OpenMP_Fortran_INCLUDE_LINE@
-      integer, parameter :: zero = ichar('0')
-      integer, parameter :: ompv = openmp_version
-      character, dimension(24), parameter :: ompver_str =&
-      (/ 'I', 'N', 'F', 'O', ':', 'O', 'p', 'e', 'n', 'M', 'P', '-',&
-         'd', 'a', 't', 'e', '[',&
-         char(zero + mod(ompv/100000, 10)),&
-         char(zero + mod(ompv/10000, 10)),&
-         char(zero + mod(ompv/1000, 10)),&
-         char(zero + mod(ompv/100, 10)),&
-         char(zero + mod(ompv/10, 10)),&
-         char(zero + mod(ompv/1, 10)), ']' /)
-      print *, ompver_str
-      end program omp_ver
-")
-
-function(_OPENMP_GET_SPEC_DATE LANG SPEC_DATE)
-  _OPENMP_WRITE_SOURCE_FILE("${LANG}" "CHECK_VERSION_SOURCE" OpenMPCheckVersion _OPENMP_TEST_SRC)
-
-  unset(_includeDirFlags)
-  if(OpenMP_${LANG}_INCLUDE_DIR)
-    set(_includeDirFlags "-DINCLUDE_DIRECTORIES:STRING=${OpenMP_${LANG}_INCLUDE_DIR}")
-  endif()
-
-  set(BIN_FILE "${CMAKE_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/FindOpenMP/ompver_${LANG}.bin")
-  string(REGEX REPLACE "[-/=+]" "" OPENMP_PLAIN_FLAG "${OPENMP_FLAG}")
-  try_compile(OpenMP_SPECTEST_${LANG}_${OPENMP_PLAIN_FLAG} "${CMAKE_BINARY_DIR}" "${_OPENMP_TEST_SRC}"
-              CMAKE_FLAGS "-DCOMPILE_DEFINITIONS:STRING=${OpenMP_${LANG}_FLAGS}" ${_includeDirFlags}
-              COPY_FILE ${BIN_FILE}
-              OUTPUT_VARIABLE OpenMP_TRY_COMPILE_OUTPUT)
-
-  if(${OpenMP_SPECTEST_${LANG}_${OPENMP_PLAIN_FLAG}})
-    file(STRINGS ${BIN_FILE} specstr LIMIT_COUNT 1 REGEX "INFO:OpenMP-date")
-    set(regex_spec_date ".*INFO:OpenMP-date\\[0*([^]]*)\\].*")
-    if("${specstr}" MATCHES "${regex_spec_date}")
-      set(${SPEC_DATE} "${CMAKE_MATCH_1}" PARENT_SCOPE)
-    endif()
-  else()
-    file(APPEND ${CMAKE_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/CMakeError.log
-        "Detecting ${LANG} OpenMP version failed with the following output:\n${OpenMP_TRY_COMPILE_OUTPUT}\n\n")
-  endif()
-endfunction()
-
-macro(_OPENMP_SET_VERSION_BY_SPEC_DATE LANG)
-  set(OpenMP_SPEC_DATE_MAP
-    # Preview versions
-    "201611=5.0" # OpenMP 5.0 preview 1
-    # Combined versions, 2.5 onwards
-    "201811=5.0"
-    "201511=4.5"
-    "201307=4.0"
-    "201107=3.1"
-    "200805=3.0"
-    "200505=2.5"
-    # C/C++ version 2.0
-    "200203=2.0"
-    # Fortran version 2.0
-    "200011=2.0"
-    # Fortran version 1.1
-    "199911=1.1"
-    # C/C++ version 1.0 (there's no 1.1 for C/C++)
-    "199810=1.0"
-    # Fortran version 1.0
-    "199710=1.0"
-  )
-  if(MSVC)
-    list(APPEND OpenMP_SPEC_DATE_MAP "2019=2.0")
-  endif()
-
-  if(OpenMP_${LANG}_SPEC_DATE)
-    string(REGEX MATCHALL "${OpenMP_${LANG}_SPEC_DATE}=([0-9]+)\\.([0-9]+)" _version_match "${OpenMP_SPEC_DATE_MAP}")
-  else()
-    set(_version_match "")
-  endif()
-  if(NOT _version_match STREQUAL "")
-    set(OpenMP_${LANG}_VERSION_MAJOR ${CMAKE_MATCH_1})
-    set(OpenMP_${LANG}_VERSION_MINOR ${CMAKE_MATCH_2})
-    set(OpenMP_${LANG}_VERSION "${OpenMP_${LANG}_VERSION_MAJOR}.${OpenMP_${LANG}_VERSION_MINOR}")
-  else()
-    unset(OpenMP_${LANG}_VERSION_MAJOR)
-    unset(OpenMP_${LANG}_VERSION_MINOR)
-    unset(OpenMP_${LANG}_VERSION)
-  endif()
-  unset(_version_match)
-  unset(OpenMP_SPEC_DATE_MAP)
-endmacro()
-
-foreach(LANG IN ITEMS C CXX)
-  if(CMAKE_${LANG}_COMPILER_LOADED)
-    if(NOT DEFINED OpenMP_${LANG}_FLAGS OR "${OpenMP_${LANG}_FLAGS}" STREQUAL "NOTFOUND"
-      OR NOT DEFINED OpenMP_${LANG}_LIB_NAMES OR "${OpenMP_${LANG}_LIB_NAMES}" STREQUAL "NOTFOUND")
-      _OPENMP_GET_FLAGS("${LANG}" "${LANG}" OpenMP_${LANG}_FLAGS_WORK OpenMP_${LANG}_LIB_NAMES_WORK)
-      set(OpenMP_${LANG}_FLAGS "${OpenMP_${LANG}_FLAGS_WORK}"
-        CACHE STRING "${LANG} compiler flags for OpenMP parallelization" FORCE)
-      set(OpenMP_${LANG}_LIB_NAMES "${OpenMP_${LANG}_LIB_NAMES_WORK}"
-        CACHE STRING "${LANG} compiler libraries for OpenMP parallelization" FORCE)
-      mark_as_advanced(OpenMP_${LANG}_FLAGS OpenMP_${LANG}_LIB_NAMES)
-    endif()
-  endif()
-endforeach()
-
-if(CMAKE_Fortran_COMPILER_LOADED)
-  if(NOT DEFINED OpenMP_Fortran_FLAGS OR "${OpenMP_Fortran_FLAGS}" STREQUAL "NOTFOUND"
-    OR NOT DEFINED OpenMP_Fortran_LIB_NAMES OR "${OpenMP_Fortran_LIB_NAMES}" STREQUAL "NOTFOUND"
-    OR NOT DEFINED OpenMP_Fortran_HAVE_OMPLIB_MODULE)
-    set(OpenMP_Fortran_INCLUDE_LINE "use omp_lib\n      implicit none")
-    _OPENMP_GET_FLAGS("Fortran" "FortranHeader" OpenMP_Fortran_FLAGS_WORK OpenMP_Fortran_LIB_NAMES_WORK)
-    if(OpenMP_Fortran_FLAGS_WORK)
-      set(OpenMP_Fortran_HAVE_OMPLIB_MODULE TRUE CACHE BOOL INTERNAL "")
-    endif()
-
-    set(OpenMP_Fortran_FLAGS "${OpenMP_Fortran_FLAGS_WORK}"
-      CACHE STRING "Fortran compiler flags for OpenMP parallelization")
-    set(OpenMP_Fortran_LIB_NAMES "${OpenMP_Fortran_LIB_NAMES_WORK}"
-      CACHE STRING "Fortran compiler libraries for OpenMP parallelization")
-    mark_as_advanced(OpenMP_Fortran_FLAGS OpenMP_Fortran_LIB_NAMES)
-  endif()
-
-  if(NOT DEFINED OpenMP_Fortran_FLAGS OR "${OpenMP_Fortran_FLAGS}" STREQUAL "NOTFOUND"
-    OR NOT DEFINED OpenMP_Fortran_LIB_NAMES OR "${OpenMP_Fortran_LIB_NAMES}" STREQUAL "NOTFOUND"
-    OR NOT DEFINED OpenMP_Fortran_HAVE_OMPLIB_HEADER)
-    set(OpenMP_Fortran_INCLUDE_LINE "implicit none\n      include 'omp_lib.h'")
-    _OPENMP_GET_FLAGS("Fortran" "FortranModule" OpenMP_Fortran_FLAGS_WORK OpenMP_Fortran_LIB_NAMES_WORK)
-    if(OpenMP_Fortran_FLAGS_WORK)
-      set(OpenMP_Fortran_HAVE_OMPLIB_HEADER TRUE CACHE BOOL INTERNAL "")
-    endif()
-
-    set(OpenMP_Fortran_FLAGS "${OpenMP_Fortran_FLAGS_WORK}"
-      CACHE STRING "Fortran compiler flags for OpenMP parallelization")
-
-    set(OpenMP_Fortran_LIB_NAMES "${OpenMP_Fortran_LIB_NAMES}"
-      CACHE STRING "Fortran compiler libraries for OpenMP parallelization")
-  endif()
-
-  if(OpenMP_Fortran_HAVE_OMPLIB_MODULE)
-    set(OpenMP_Fortran_INCLUDE_LINE "use omp_lib\n      implicit none")
-  else()
-    set(OpenMP_Fortran_INCLUDE_LINE "implicit none\n      include 'omp_lib.h'")
-  endif()
-endif()
-
-if(NOT OpenMP_FIND_COMPONENTS)
-  set(OpenMP_FINDLIST C CXX Fortran)
-else()
-  set(OpenMP_FINDLIST ${OpenMP_FIND_COMPONENTS})
-endif()
-
-unset(_OpenMP_MIN_VERSION)
-
-include(FindPackageHandleStandardArgs)
-
-foreach(LANG IN LISTS OpenMP_FINDLIST)
-  if(CMAKE_${LANG}_COMPILER_LOADED)
-    if (NOT OpenMP_${LANG}_SPEC_DATE AND OpenMP_${LANG}_FLAGS)
-      _OPENMP_GET_SPEC_DATE("${LANG}" OpenMP_${LANG}_SPEC_DATE_INTERNAL)
-      set(OpenMP_${LANG}_SPEC_DATE "${OpenMP_${LANG}_SPEC_DATE_INTERNAL}" CACHE
-        INTERNAL "${LANG} compiler's OpenMP specification date")
-    endif()
-    _OPENMP_SET_VERSION_BY_SPEC_DATE("${LANG}")
-
-    set(OpenMP_${LANG}_FIND_QUIETLY ${OpenMP_FIND_QUIETLY})
-    set(OpenMP_${LANG}_FIND_REQUIRED ${OpenMP_FIND_REQUIRED})
-    set(OpenMP_${LANG}_FIND_VERSION ${OpenMP_FIND_VERSION})
-    set(OpenMP_${LANG}_FIND_VERSION_EXACT ${OpenMP_FIND_VERSION_EXACT})
-
-    set(_OPENMP_${LANG}_REQUIRED_VARS OpenMP_${LANG}_FLAGS)
-    if("${OpenMP_${LANG}_LIB_NAMES}" STREQUAL "NOTFOUND")
-      set(_OPENMP_${LANG}_REQUIRED_LIB_VARS OpenMP_${LANG}_LIB_NAMES)
-    else()
-      foreach(_OPENMP_IMPLICIT_LIB IN LISTS OpenMP_${LANG}_LIB_NAMES)
-        list(APPEND _OPENMP_${LANG}_REQUIRED_LIB_VARS OpenMP_${_OPENMP_IMPLICIT_LIB}_LIBRARY)
-      endforeach()
-    endif()
-
-    if (CMAKE_VERSION VERSION_GREATER_EQUAL "3.17")
-      find_package_handle_standard_args(OpenMP_${LANG}
-        NAME_MISMATCHED
-        REQUIRED_VARS OpenMP_${LANG}_FLAGS ${_OPENMP_${LANG}_REQUIRED_LIB_VARS}
-        VERSION_VAR OpenMP_${LANG}_VERSION
-      )
-    else()
-      find_package_handle_standard_args(OpenMP_${LANG}
-        REQUIRED_VARS OpenMP_${LANG}_FLAGS ${_OPENMP_${LANG}_REQUIRED_LIB_VARS}
-        VERSION_VAR OpenMP_${LANG}_VERSION
-      )
-    endif()
-
-    if(OpenMP_${LANG}_FOUND)
-      if(DEFINED OpenMP_${LANG}_VERSION)
-        if(NOT _OpenMP_MIN_VERSION OR _OpenMP_MIN_VERSION VERSION_GREATER OpenMP_${LANG}_VERSION)
-          set(_OpenMP_MIN_VERSION OpenMP_${LANG}_VERSION)
-        endif()
-      endif()
-      set(OpenMP_${LANG}_LIBRARIES "")
-      foreach(_OPENMP_IMPLICIT_LIB IN LISTS OpenMP_${LANG}_LIB_NAMES)
-        list(APPEND OpenMP_${LANG}_LIBRARIES "${OpenMP_${_OPENMP_IMPLICIT_LIB}_LIBRARY}")
-      endforeach()
-      if(OpenMP_${LANG}_INCLUDE_DIR)
-        set(OpenMP_${LANG}_INCLUDE_DIRS ${OpenMP_${LANG}_INCLUDE_DIR})
-      else()
-        set(OpenMP_${LANG}_INCLUDE_DIRS "")
-      endif()
-
-      if(NOT TARGET OpenMP::OpenMP_${LANG})
-        add_library(OpenMP::OpenMP_${LANG} INTERFACE IMPORTED)
-      endif()
-      if(OpenMP_${LANG}_FLAGS)
-        separate_arguments(_OpenMP_${LANG}_OPTIONS NATIVE_COMMAND "${OpenMP_${LANG}_FLAGS}")
-        set_property(TARGET OpenMP::OpenMP_${LANG} PROPERTY
-          INTERFACE_COMPILE_OPTIONS "$<$<COMPILE_LANGUAGE:${LANG}>:${_OpenMP_${LANG}_OPTIONS}>")
-        unset(_OpenMP_${LANG}_OPTIONS)
-      endif()
-      if(OpenMP_${LANG}_INCLUDE_DIRS)
-        set_property(TARGET OpenMP::OpenMP_${LANG} PROPERTY
-          INTERFACE_INCLUDE_DIRECTORIES "$<BUILD_INTERFACE:${OpenMP_${LANG}_INCLUDE_DIRS}>")
-      endif()
-      if(OpenMP_${LANG}_LIBRARIES)
-        set_property(TARGET OpenMP::OpenMP_${LANG} PROPERTY
-          INTERFACE_LINK_LIBRARIES "${OpenMP_${LANG}_LIBRARIES}")
-      endif()
-    endif()
-  endif()
-endforeach()
-
-unset(_OpenMP_REQ_VARS)
-foreach(LANG IN ITEMS C CXX Fortran)
-  if((NOT OpenMP_FIND_COMPONENTS AND CMAKE_${LANG}_COMPILER_LOADED) OR LANG IN_LIST OpenMP_FIND_COMPONENTS)
-    list(APPEND _OpenMP_REQ_VARS "OpenMP_${LANG}_FOUND")
-  endif()
-endforeach()
-
-find_package_handle_standard_args(OpenMP
-    REQUIRED_VARS ${_OpenMP_REQ_VARS}
-    VERSION_VAR ${_OpenMP_MIN_VERSION}
-    HANDLE_COMPONENTS)
-
-set(OPENMP_FOUND ${OpenMP_FOUND})
-
-if(CMAKE_Fortran_COMPILER_LOADED AND OpenMP_Fortran_FOUND)
-  if(NOT DEFINED OpenMP_Fortran_HAVE_OMPLIB_MODULE)
-    set(OpenMP_Fortran_HAVE_OMPLIB_MODULE FALSE CACHE BOOL INTERNAL "")
-  endif()
-  if(NOT DEFINED OpenMP_Fortran_HAVE_OMPLIB_HEADER)
-    set(OpenMP_Fortran_HAVE_OMPLIB_HEADER FALSE CACHE BOOL INTERNAL "")
-  endif()
-endif()
-
-if(NOT ( CMAKE_C_COMPILER_LOADED OR CMAKE_CXX_COMPILER_LOADED OR CMAKE_Fortran_COMPILER_LOADED ))
-  message(SEND_ERROR "FindOpenMP requires the C, CXX or Fortran languages to be enabled")
-endif()
-
-unset(OpenMP_C_CXX_TEST_SOURCE)
-unset(OpenMP_Fortran_TEST_SOURCE)
-unset(OpenMP_C_CXX_CHECK_VERSION_SOURCE)
-unset(OpenMP_Fortran_CHECK_VERSION_SOURCE)
-unset(OpenMP_Fortran_INCLUDE_LINE)
-
-cmake_policy(POP)
index e86ab40b2ab5d0f6f43cd9729cd66f12c185bc7c..5f5ab9535442c18cf68d2fcae544a300945a5149 100644 (file)
@@ -27,8 +27,6 @@ find_path(OPENNI_INCLUDE_DIR XnStatus.h
                 /usr/include/openni
                 /usr/include/ni
                 /opt/local/include/ni
-                "${OPENNI_ROOT}"
-                "$ENV{OPENNI_ROOT}"
           PATHS "$ENV{OPEN_NI_INSTALL_PATH${OPENNI_SUFFIX}}/Include"
           PATH_SUFFIXES openni include Include)
 
@@ -38,8 +36,6 @@ find_library(OPENNI_LIBRARY
              HINTS ${PC_OPENNI_LIBDIR}
                    ${PC_OPENNI_LIBRARY_DIRS}
                    /usr/lib
-                   "${OPENNI_ROOT}"
-                   "$ENV{OPENNI_ROOT}"
              PATHS "$ENV{OPEN_NI_LIB${OPENNI_SUFFIX}}"
              PATH_SUFFIXES lib Lib Lib64)
 
index 5368c1dcbf7ac46fafd5f7ea3b08ef7c37689c3d..bd68796c98e2487a5b84ae890bf425f452901c36 100755 (executable)
@@ -83,7 +83,7 @@ endif()
 
 find_file(QHULL_HEADER
           NAMES libqhull_r.h
-          HINTS "${QHULL_ROOT}" "$ENV{QHULL_ROOT}" "${QHULL_INCLUDE_DIR}"
+          HINTS "${QHULL_INCLUDE_DIR}"
           PATHS "$ENV{PROGRAMFILES}/QHull" "$ENV{PROGRAMW6432}/QHull"
           PATH_SUFFIXES qhull_r src/libqhull_r libqhull_r include)
 
@@ -103,25 +103,21 @@ endif()
 
 find_library(QHULL_LIBRARY_SHARED
              NAMES qhull_r qhull
-             HINTS "${QHULL_ROOT}" "$ENV{QHULL_ROOT}"
              PATHS "$ENV{PROGRAMFILES}/QHull" "$ENV{PROGRAMW6432}/QHull"
              PATH_SUFFIXES project build bin lib)
 
 find_library(QHULL_LIBRARY_DEBUG
              NAMES qhull_rd qhull_d
-             HINTS "${QHULL_ROOT}" "$ENV{QHULL_ROOT}"
              PATHS "$ENV{PROGRAMFILES}/QHull" "$ENV{PROGRAMW6432}/QHull"
              PATH_SUFFIXES project build bin lib debug/lib)
 
 find_library(QHULL_LIBRARY_STATIC
              NAMES qhullstatic_r
-             HINTS "${QHULL_ROOT}" "$ENV{QHULL_ROOT}"
              PATHS "$ENV{PROGRAMFILES}/QHull" "$ENV{PROGRAMW6432}/QHull"
              PATH_SUFFIXES project build bin lib)
 
 find_library(QHULL_LIBRARY_DEBUG_STATIC
              NAMES qhullstatic_rd
-             HINTS "${QHULL_ROOT}" "$ENV{QHULL_ROOT}"
              PATHS "$ENV{PROGRAMFILES}/QHull" "$ENV{PROGRAMW6432}/QHull"
              PATH_SUFFIXES project build bin lib debug/lib)
 
index 61f5521c832fef20aabe473c4f2f4dc224ffae45..6c5571aad523e1bcf7d79c1d91a8c88e4c076496 100644 (file)
@@ -8,10 +8,9 @@
 find_package(PkgConfig QUIET)
 pkg_check_modules(PC_SPHINX sphinx-build)
 
-find_package(PythonInterp)
-
-if(PYTHONINTERP_FOUND)
-  get_filename_component(PYTHON_DIR "${PYTHON_EXECUTABLE}" PATH)
+find_package(Python)
+if(Python_Interpreter_FOUND)
+  get_filename_component(PYTHON_DIR "${Python_EXECUTABLE}" PATH)
 endif()
 
 find_program(SPHINX_EXECUTABLE NAMES sphinx-build
index e344c8d84de253e2eefa9d80c51456dd50fae40b..a1a1034ecae56978b6517788799f456da9f58f54 100644 (file)
@@ -386,7 +386,7 @@ Function un.RemoveFromPath
 FunctionEnd
 
 ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
-; Uninstall sutff
+; Uninstall stuff
 ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
 
 ###########################################
index 770607f82dcf0d5c8088a6fc233e0325c67ef452..5d5c7859e0a761aa99b93f1b5cc27d18c37f587b 100644 (file)
@@ -13,21 +13,20 @@ else()
   endif()
 endif()
 
-set(Boost_ADDITIONAL_VERSIONS
-  "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80"
-  "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" 
-  "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70"
-  "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65")
-
-# Optional boost modules
-find_package(Boost 1.65.0 QUIET COMPONENTS serialization mpi)
-if(Boost_SERIALIZATION_FOUND)
-  set(BOOST_SERIALIZATION_FOUND TRUE)
+if(CMAKE_CXX_STANDARD MATCHES "14")
+  # Optional boost modules
+  set(BOOST_OPTIONAL_MODULES serialization mpi)
+  # Required boost modules
+  set(BOOST_REQUIRED_MODULES filesystem iostreams system)
+else()
+  # Optional boost modules
+  set(BOOST_OPTIONAL_MODULES filesystem serialization mpi)
+  # Required boost modules
+  set(BOOST_REQUIRED_MODULES iostreams system)
 endif()
 
-# Required boost modules
-set(BOOST_REQUIRED_MODULES filesystem iostreams system)
-find_package(Boost 1.65.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES})
+find_package(Boost 1.71.0 QUIET COMPONENTS ${BOOST_OPTIONAL_MODULES} CONFIG)
+find_package(Boost 1.71.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES} CONFIG)
 
 if(Boost_FOUND)
   set(BOOST_FOUND TRUE)
index 21aeac2e1dc0cf03d593c8437221b475b90c0647..03d0a40fc135f7e8342d6a8e992e7a329add64e0 100644 (file)
@@ -4,13 +4,28 @@ if(MSVC)
   set(CUDA_ATTACH_VS_BUILD_RULE_TO_CUDA_FILE OFF CACHE BOOL "CUDA_ATTACH_VS_BUILD_RULE_TO_CUDA_FILE")
 endif()
 
-set(CUDA_FIND_QUIETLY TRUE)
-find_package(CUDA 9.0)
+include(CheckLanguage)
+check_language(CUDA)
+if(CMAKE_CUDA_COMPILER)
+  enable_language(CUDA)
+
+  if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.17)
+    find_package(CUDAToolkit QUIET)
+    set(CUDA_TOOLKIT_INCLUDE ${CUDAToolkit_INCLUDE_DIRS})
+  else()
+    set(CUDA_FIND_QUIETLY TRUE)
+    find_package(CUDA 9.0)
+  endif()
+
+  set(CUDA_FOUND TRUE)
+  set(CUDA_VERSION_STRING ${CMAKE_CUDA_COMPILER_VERSION})
+else()
+  message(STATUS "No CUDA compiler found")
+endif()
 
 if(CUDA_FOUND)
   message(STATUS "Found CUDA Toolkit v${CUDA_VERSION_STRING}")
   
-  enable_language(CUDA)
   set(HAVE_CUDA TRUE)
 
   if (CMAKE_CUDA_COMPILER_ID STREQUAL "NVIDIA")
@@ -45,19 +60,14 @@ if(CUDA_FOUND)
     cmake_policy(SET CMP0104 NEW)
     set(CMAKE_CUDA_ARCHITECTURES ${CUDA_ARCH_BIN})
     message(STATUS "CMAKE_CUDA_ARCHITECTURES: ${CMAKE_CUDA_ARCHITECTURES}")
-    
-    #Add empty project as its not required with newer CMake
-    add_library(pcl_cuda INTERFACE)
   else()
     # Generate SASS
     set(CMAKE_CUDA_ARCHITECTURES ${CUDA_ARCH_BIN})
     # Generate PTX for last architecture
     list(GET CUDA_ARCH_BIN -1 ver)
     set(CMAKE_CUDA_FLAGS "${CMAKE_CUDA_FLAGS} -gencode arch=compute_${ver},code=compute_${ver}")
-    message(STATUS "CMAKE_CUDA_FLAGS: ${CMAKE_CUDA_FLAGS}")
-    
-    add_library(pcl_cuda INTERFACE)
-    target_include_directories(pcl_cuda INTERFACE ${CUDA_TOOLKIT_INCLUDE})
-    
+    message(STATUS "CMAKE_CUDA_FLAGS: ${CMAKE_CUDA_FLAGS}")   
   endif ()
+else()
+  message(STATUS "CUDA was not found.")
 endif()
index e4ca977857ac4d5b001b9b56c4e083fe98ae6dfc..1c9781e00b847e9d7f0f31af046e082dab84f3a8 100644 (file)
@@ -45,8 +45,21 @@ set(PCL_QHULL_REQUIRED_TYPE "DONTCARE" CACHE STRING "Select build type to use ST
 set_property(CACHE PCL_QHULL_REQUIRED_TYPE PROPERTY STRINGS DONTCARE SHARED STATIC)
 mark_as_advanced(PCL_QHULL_REQUIRED_TYPE)
 
+option(PCL_PREFER_BOOST_FILESYSTEM "Prefer boost::filesystem over std::filesystem (if compiled as C++17 or higher, std::filesystem is chosen by default)" OFF)
+mark_as_advanced(PCL_PREFER_BOOST_FILESYSTEM)
+
+set(PCL_XYZ_POINT_TYPES "(pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZL)(pcl::PointXYZRGBA)(pcl::PointXYZRGB)(pcl::PointXYZRGBL)(pcl::PointXYZLAB)(pcl::PointXYZHSV)(pcl::InterestPoint)(pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal)(pcl::PointXYZLNormal)(pcl::PointWithRange)(pcl::PointWithViewpoint)(pcl::PointWithScale)(pcl::PointSurfel)(pcl::PointDEM)" CACHE STRING "Point types with xyz information for which PCL classes will be instantiated. Alternative to PCL_ONLY_CORE_POINT_TYPES. You can remove unneeded types to reduce compile time and library size.")
+mark_as_advanced(PCL_XYZ_POINT_TYPES)
+
+set(PCL_NORMAL_POINT_TYPES "(pcl::Normal)(pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal)(pcl::PointXYZLNormal)(pcl::PointSurfel)" CACHE STRING "Point types with normal information for which PCL classes will be instantiated. Alternative to PCL_ONLY_CORE_POINT_TYPES. You can remove unneeded types to reduce compile time and library size.")
+mark_as_advanced(PCL_NORMAL_POINT_TYPES)
+
 # Precompile for a minimal set of point types instead of all.
+if(CMAKE_COMPILER_IS_MSVC OR CMAKE_COMPILER_IS_MINGW)
+option(PCL_ONLY_CORE_POINT_TYPES "Compile explicitly only for a small subset of point types (e.g., pcl::PointXYZ instead of PCL_XYZ_POINT_TYPES)." ON)
+else()
 option(PCL_ONLY_CORE_POINT_TYPES "Compile explicitly only for a small subset of point types (e.g., pcl::PointXYZ instead of PCL_XYZ_POINT_TYPES)." OFF)
+endif()
 mark_as_advanced(PCL_ONLY_CORE_POINT_TYPES)
 
 # Precompile for a minimal set of point types instead of all.
@@ -88,8 +101,6 @@ mark_as_advanced(CMAKE_MSVC_CODE_LINK_OPTIMIZATION)
 # Project folders
 set_property(GLOBAL PROPERTY USE_FOLDERS ON)
 
-option(BUILD_tools "Useful PCL-based command line tools" ON)
-
 option(WITH_DOCS "Build doxygen documentation" OFF)
 
 # set index size
@@ -111,3 +122,11 @@ option(PCL_DISABLE_GPU_TESTS "Disable running GPU tests. If disabled, tests will
 # Set whether visualizations tests should be run
 # (Used to prevent visualizations tests from executing in CI where visualization is unavailable)
 option(PCL_DISABLE_VISUALIZATION_TESTS "Disable running visualizations tests. If disabled, tests will still be built." OFF)
+
+# This leads to smaller libraries, possibly faster code, and fixes some bugs. See https://gcc.gnu.org/wiki/Visibility
+option(PCL_SYMBOL_VISIBILITY_HIDDEN "Hide all binary symbols by default, export only those explicitly marked (gcc and clang only). Experimental!" OFF)
+mark_as_advanced(PCL_SYMBOL_VISIBILITY_HIDDEN)
+if(PCL_SYMBOL_VISIBILITY_HIDDEN)
+  set(CMAKE_CXX_VISIBILITY_PRESET hidden)
+  set(CMAKE_VISIBILITY_INLINES_HIDDEN ON)
+endif()
index f0656e6ec3bf3c2443951fd4f7f3e7316059d55c..f9941b143559e1a33444a5a54402decc4f963053 100644 (file)
@@ -85,13 +85,13 @@ foreach(_ss ${PCL_SUBSYSTEMS_MODULES})
 endforeach()
 
 #Boost modules
-set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system filesystem iostreams")
+set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system iostreams")
+if(Boost_FILESYSTEM_FOUND)
+  string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " filesystem")
+endif()
 if(Boost_SERIALIZATION_FOUND)
   string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " serialization")
 endif()
-if(Boost_CHRONO_FOUND)
-  string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " chrono")
-endif()
 
 configure_file("${PCL_SOURCE_DIR}/PCLConfig.cmake.in"
                "${PCL_BINARY_DIR}/PCLConfig.cmake" @ONLY)
@@ -101,4 +101,4 @@ install(FILES
         "${PCL_BINARY_DIR}/PCLConfig.cmake"
         "${PCL_BINARY_DIR}/PCLConfigVersion.cmake"
         COMPONENT pclconfig
-        DESTINATION ${PCLCONFIG_INSTALL_DIR})
\ No newline at end of file
+        DESTINATION ${PCLCONFIG_INSTALL_DIR})
index 2da076c23c5c40d2a46e4b2615d655e50a07a2cd..be9da33cbc250eb3a3948c7a2d9cd4cda0db5b94 100644 (file)
@@ -118,9 +118,6 @@ macro(PCL_SUBSYS_DEPEND _var)
         if(NOT _status)
           set(${_var} FALSE)
           PCL_SET_SUBSYS_STATUS(${_name} FALSE "Requires ${_dep}.")
-        else()
-          PCL_GET_SUBSYS_INCLUDE_DIR(_include_dir ${_dep})
-          include_directories(${PROJECT_SOURCE_DIR}/${_include_dir}/include)
         endif()
       endforeach()
     endif()
@@ -134,12 +131,6 @@ macro(PCL_SUBSYS_DEPEND _var)
         endif()
       endforeach()
     endif()
-    if(ARGS_OPT_DEPS)
-      foreach(_dep ${ARGS_OPT_DEPS})
-        PCL_GET_SUBSYS_INCLUDE_DIR(_include_dir ${_dep})
-        include_directories(${PROJECT_SOURCE_DIR}/${_include_dir}/include)
-      endforeach()
-    endif()
   endif()
 endmacro()
 
@@ -181,7 +172,7 @@ endmacro()
 function(PCL_ADD_LIBRARY _name)
   set(options)
   set(oneValueArgs COMPONENT)
-  set(multiValueArgs SOURCES)
+  set(multiValueArgs SOURCES INCLUDES)
   cmake_parse_arguments(ARGS "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN})
 
   if(ARGS_UNPARSED_ARGUMENTS)
@@ -192,32 +183,53 @@ function(PCL_ADD_LIBRARY _name)
     message(FATAL_ERROR "PCL_ADD_LIBRARY requires parameter COMPONENT.")
   endif()
 
-  add_library(${_name} ${PCL_LIB_TYPE} ${ARGS_SOURCES})
-  PCL_ADD_VERSION_INFO(${_name})
-  target_compile_features(${_name} PUBLIC ${PCL_CXX_COMPILE_FEATURES})
+  if(NOT ARGS_SOURCES)
+    if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.19)
+      add_library(${_name} INTERFACE ${ARGS_INCLUDES})
 
-  target_link_libraries(${_name} Threads::Threads)
-  if(TARGET OpenMP::OpenMP_CXX)
-    target_link_libraries(${_name} OpenMP::OpenMP_CXX)
-  endif()
+      set_target_properties(${_name} PROPERTIES FOLDER "Libraries")
+    else()
+      add_library(${_name} INTERFACE)
+    endif()
+    
+    target_include_directories(${_name} INTERFACE
+      $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
+      $<INSTALL_INTERFACE:${INCLUDE_INSTALL_ROOT}> 
+    )
+  else()
+    add_library(${_name} ${PCL_LIB_TYPE} ${ARGS_SOURCES})
+    PCL_ADD_VERSION_INFO(${_name})
+    target_compile_features(${_name} PUBLIC ${PCL_CXX_COMPILE_FEATURES})
+
+    target_include_directories(${_name} PUBLIC
+      $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
+      $<INSTALL_INTERFACE:${INCLUDE_INSTALL_ROOT}> 
+    )
+
+    target_link_libraries(${_name} Threads::Threads)
+    if(TARGET OpenMP::OpenMP_CXX)
+      target_link_libraries(${_name} OpenMP::OpenMP_CXX)
+    endif()
 
-  if((UNIX AND NOT ANDROID) OR MINGW)
-    target_link_libraries(${_name} m ${ATOMIC_LIBRARY})
-  endif()
+    if((UNIX AND NOT ANDROID) OR MINGW)
+      target_link_libraries(${_name} m ${ATOMIC_LIBRARY})
+    endif()
 
-  if(MINGW)
-    target_link_libraries(${_name} gomp)
-  endif()
+    if(MINGW)
+      target_link_libraries(${_name} gomp)
+    endif()
 
-  if(MSVC)
-    target_link_libraries(${_name} delayimp.lib)  # because delay load is enabled for openmp.dll
-  endif()
+    if(MSVC)
+      target_link_libraries(${_name} delayimp.lib)  # because delay load is enabled for openmp.dll
+    endif()
+    
+    set_target_properties(${_name} PROPERTIES
+      VERSION ${PCL_VERSION}
+      SOVERSION ${PCL_VERSION_MAJOR}.${PCL_VERSION_MINOR}
+      DEFINE_SYMBOL "PCLAPI_EXPORTS")
 
-  set_target_properties(${_name} PROPERTIES
-    VERSION ${PCL_VERSION}
-    SOVERSION ${PCL_VERSION_MAJOR}.${PCL_VERSION_MINOR}
-    DEFINE_SYMBOL "PCLAPI_EXPORTS")
-  set_target_properties(${_name} PROPERTIES FOLDER "Libraries")
+      set_target_properties(${_name} PROPERTIES FOLDER "Libraries")
+  endif()
 
   install(TARGETS ${_name}
           RUNTIME DESTINATION ${BIN_INSTALL_DIR} COMPONENT pcl_${ARGS_COMPONENT}
@@ -250,25 +262,39 @@ function(PCL_CUDA_ADD_LIBRARY _name)
   endif()
 
   REMOVE_VTK_DEFINITIONS()
+  if(NOT ARGS_SOURCES)
+    add_library(${_name} INTERFACE)
+    
+    target_include_directories(${_name} INTERFACE
+        $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
+        $<INSTALL_INTERFACE:${INCLUDE_INSTALL_ROOT}> 
+    )
 
-  add_library(${_name} ${PCL_LIB_TYPE} ${ARGS_SOURCES})
-
-  PCL_ADD_VERSION_INFO(${_name})
-
-  target_compile_options(${_name} PRIVATE $<$<COMPILE_LANGUAGE:CUDA>: ${GEN_CODE} --expt-relaxed-constexpr>)
-
-  target_include_directories(${_name} PRIVATE ${CUDA_TOOLKIT_INCLUDE})
-
-  if(MSVC)
-    target_link_libraries(${_name} delayimp.lib)  # because delay load is enabled for openmp.dll
+  else()
+    add_library(${_name} ${PCL_LIB_TYPE} ${ARGS_SOURCES})
+  
+    PCL_ADD_VERSION_INFO(${_name})
+  
+    target_compile_options(${_name} PRIVATE $<$<COMPILE_LANGUAGE:CUDA>: ${GEN_CODE} --expt-relaxed-constexpr>)
+  
+    target_include_directories(${_name} PUBLIC
+      $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
+      $<INSTALL_INTERFACE:${INCLUDE_INSTALL_ROOT}> 
+    )
+  
+    target_include_directories(${_name} PRIVATE ${CUDA_TOOLKIT_INCLUDE})
+  
+    if(MSVC)
+      target_link_libraries(${_name} delayimp.lib)  # because delay load is enabled for openmp.dll
+    endif()
+  
+    set_target_properties(${_name} PROPERTIES
+      VERSION ${PCL_VERSION}
+      SOVERSION ${PCL_VERSION_MAJOR}.${PCL_VERSION_MINOR}
+      DEFINE_SYMBOL "PCLAPI_EXPORTS")
+    set_target_properties(${_name} PROPERTIES FOLDER "Libraries")
   endif()
 
-  set_target_properties(${_name} PROPERTIES
-    VERSION ${PCL_VERSION}
-    SOVERSION ${PCL_VERSION_MAJOR}.${PCL_VERSION_MINOR}
-    DEFINE_SYMBOL "PCLAPI_EXPORTS")
-  set_target_properties(${_name} PROPERTIES FOLDER "Libraries")
-
   install(TARGETS ${_name}
           RUNTIME DESTINATION ${BIN_INSTALL_DIR} COMPONENT pcl_${ARGS_COMPONENT}
           LIBRARY DESTINATION ${LIB_INSTALL_DIR} COMPONENT pcl_${ARGS_COMPONENT}
@@ -400,16 +426,10 @@ macro(PCL_ADD_TEST _name _exename)
 
   #Only applies to MSVC
   if(MSVC)
-    #Requires CMAKE version 3.13.0
-    if(CMAKE_VERSION VERSION_LESS "3.13.0" AND (NOT ArgumentWarningShown))
-      message(WARNING "Arguments for unit test projects are not added - this requires at least CMake 3.13. Can be added manually in \"Project settings -> Debugging -> Command arguments\"")
-      SET (ArgumentWarningShown TRUE PARENT_SCOPE)
-    else()
-      #Only add if there are arguments to test
-      if(ARGS_ARGUMENTS)
-        string (REPLACE ";" " " ARGS_ARGUMENTS_STR "${ARGS_ARGUMENTS}")
-        set_target_properties(${_exename} PROPERTIES VS_DEBUGGER_COMMAND_ARGUMENTS ${ARGS_ARGUMENTS_STR})
-      endif()
+    #Only add if there are arguments to test
+    if(ARGS_ARGUMENTS)
+      string (REPLACE ";" " " ARGS_ARGUMENTS_STR "${ARGS_ARGUMENTS}")
+      set_target_properties(${_exename} PROPERTIES VS_DEBUGGER_COMMAND_ARGUMENTS ${ARGS_ARGUMENTS_STR})
     endif()
   endif()
 
@@ -450,15 +470,10 @@ function(PCL_ADD_BENCHMARK _name)
   if(MSVC)
     #Requires CMAKE version 3.13.0
     get_target_property(BenchmarkArgumentWarningShown run_benchmarks PCL_BENCHMARK_ARGUMENTS_WARNING_SHOWN)
-    if(CMAKE_VERSION VERSION_LESS "3.13.0" AND (NOT BenchmarkArgumentWarningShown))
-      message(WARNING "Arguments for benchmark projects are not added - this requires at least CMake 3.13. Can be added manually in \"Project settings -> Debugging -> Command arguments\"")
-      set_target_properties(run_benchmarks PROPERTIES PCL_BENCHMARK_ARGUMENTS_WARNING_SHOWN TRUE)
-    else()
-      #Only add if there are arguments to test
-      if(ARGS_ARGUMENTS)
-        string (REPLACE ";" " " ARGS_ARGUMENTS_STR "${ARGS_ARGUMENTS}")
-        set_target_properties(benchmark_${_name} PROPERTIES VS_DEBUGGER_COMMAND_ARGUMENTS ${ARGS_ARGUMENTS_STR})
-      endif()
+    #Only add if there are arguments to test
+    if(ARGS_ARGUMENTS)
+      string (REPLACE ";" " " ARGS_ARGUMENTS_STR "${ARGS_ARGUMENTS}")
+      set_target_properties(benchmark_${_name} PROPERTIES VS_DEBUGGER_COMMAND_ARGUMENTS ${ARGS_ARGUMENTS_STR})
     endif()
   endif()
 
index fe0ad8fa3eac71d457381a9bacbeb5883325b2dd..0a27abc2956232fd8896ddd7c5b83d2d9f81ee30 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME common)
 set(SUBSYS_DESC "Point cloud common library")
 set(SUBSYS_DEPS)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS eigen3 boost)
 
@@ -60,7 +59,6 @@ set(incs
   include/pcl/types.h
   include/pcl/point_cloud.h
   include/pcl/point_struct_traits.h
-  include/pcl/point_traits.h
   include/pcl/type_traits.h
   include/pcl/point_types_conversion.h
   include/pcl/point_representation.h
@@ -80,11 +78,9 @@ set(incs
   include/pcl/PointIndices.h
   include/pcl/register_point_struct.h
   include/pcl/conversions.h
-  include/pcl/make_shared.h
 )
 
 set(common_incs
-  include/pcl/common/boost.h
   include/pcl/common/angles.h
   include/pcl/common/bivariate_polynomial.h
   include/pcl/common/centroid.h
@@ -98,6 +94,7 @@ set(common_incs
   include/pcl/common/file_io.h
   include/pcl/common/intersections.h
   include/pcl/common/norms.h
+  include/pcl/common/pcl_filesystem.h
   include/pcl/common/piecewise_linear_function.h
   include/pcl/common/polynomial_calculations.h
   include/pcl/common/poses_from_matches.h
@@ -174,11 +171,6 @@ set(kissfft_srcs
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${kissfft_srcs} ${incs} ${common_incs} ${impl_incs} ${tools_incs} ${kissfft_incs} ${common_incs_impl} ${range_image_incs} ${range_image_incs_impl})
 
-target_include_directories(${LIB_NAME} PUBLIC
-  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
-  $<INSTALL_INTERFACE:include> 
-)
-
 target_link_libraries(${LIB_NAME} Boost::boost Eigen3::Eigen)
 
 if(MSVC AND NOT (MSVC_VERSION LESS 1915))
index 67acf07bd08b5442899df689fcfb8849543f6b44..f4f12e3e697f6472e150c1936c98c2a3d6291fa8 100644 (file)
@@ -45,12 +45,15 @@ namespace pcl
     s << "  " << v.offset << std::endl;
     s << "datatype: ";
     switch(v.datatype) {
+      case ::pcl::PCLPointField::PointFieldTypes::BOOL: s << "  BOOL" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::INT8: s << "  INT8" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::UINT8: s << "  UINT8" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::INT16: s << "  INT16" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::UINT16: s << "  UINT16" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::INT32: s << "  INT32" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::UINT32: s << "  UINT32" << std::endl; break;
+      case ::pcl::PCLPointField::PointFieldTypes::INT64: s << "  INT64" << std::endl; break;
+      case ::pcl::PCLPointField::PointFieldTypes::UINT64: s << "  UINT64" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::FLOAT32: s << "  FLOAT32" << std::endl; break;
       case ::pcl::PCLPointField::PointFieldTypes::FLOAT64: s << "  FLOAT64" << std::endl; break;
       default: s << "  " << static_cast<int>(v.datatype) << std::endl;
diff --git a/common/include/pcl/common/boost.h b/common/include/pcl/common/boost.h
deleted file mode 100644 (file)
index 068e489..0000000
+++ /dev/null
@@ -1,53 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- */
-
-#pragma once
-
-#ifdef __GNUC__
-#pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-
-#ifndef Q_MOC_RUN
-// Marking all Boost headers as system headers to remove warnings
-#include <boost/fusion/sequence/intrinsic/at_key.hpp>
-#include <boost/mpl/size.hpp>
-#include <boost/signals2.hpp>
-#include <boost/signals2/slot.hpp>
-#include <boost/algorithm/string.hpp>
-#endif
index 7c1fc883c664b97897fc65dc485ececcc729a25f..136fe77781a89e324be7f49b181299b7e499a7c6 100644 (file)
@@ -98,7 +98,7 @@ namespace pcl
    * www.srgb.com, www.color.org/srgb.html
    */
   template <typename T, std::uint8_t bits = 8>
-  PCL_EXPORTS inline std::array<T, 1 << bits>
+  inline std::array<T, 1 << bits>
   RGB2sRGB_LUT() noexcept
   {
     static_assert(std::is_floating_point<T>::value, "LUT value must be a floating point");
@@ -144,7 +144,7 @@ namespace pcl
    * Reference: Billmeyer and Saltzman’s Principles of Color Technology
    */
   template <typename T, std::size_t discretizations = 4000>
-  PCL_EXPORTS inline const std::array<T, discretizations>&
+  inline const std::array<T, discretizations>&
   XYZ2LAB_LUT() noexcept
   {
     static_assert(std::is_floating_point<T>::value, "LUT value must be a floating point");
index af32634ca6535ed8694506deaf7fa2fefab27104..857cca893ac92890c140fce694ba390fe39a6eec 100644 (file)
@@ -180,7 +180,7 @@ namespace pcl
   getMaxDistance (const pcl::PointCloud<PointT> &cloud, const Indices &indices,
                   const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt);
 
-  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
+  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
     * \param[in] cloud the point cloud data message
     * \param[out] min_pt the resultant minimum bounds
     * \param[out] max_pt the resultant maximum bounds
@@ -189,7 +189,7 @@ namespace pcl
   template <typename PointT> inline void 
   getMinMax3D (const pcl::PointCloud<PointT> &cloud, PointT &min_pt, PointT &max_pt);
   
-  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
+  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
     * \param[in] cloud the point cloud data message
     * \param[out] min_pt the resultant minimum bounds
     * \param[out] max_pt the resultant maximum bounds
@@ -199,7 +199,7 @@ namespace pcl
   getMinMax3D (const pcl::PointCloud<PointT> &cloud, 
                Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
 
-  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
+  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
     * \param[in] cloud the point cloud data message
     * \param[in] indices the vector of point indices to use from \a cloud
     * \param[out] min_pt the resultant minimum bounds
@@ -210,7 +210,7 @@ namespace pcl
   getMinMax3D (const pcl::PointCloud<PointT> &cloud, const Indices &indices,
                Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
 
-  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
+  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
     * \param[in] cloud the point cloud data message
     * \param[in] indices the vector of point indices to use from \a cloud
     * \param[out] min_pt the resultant minimum bounds
index 36d4317a14e4f479e2986f3d555ac0022d5f6758..bc0885be58fbe31eadfc9a8e4b185f294fa55eb5 100644 (file)
@@ -690,13 +690,13 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
   //obb_rotational_matrix.col(1)==middle_axis
   //obb_rotational_matrix.col(2)==minor_axis
 
-  //Trasforming the point cloud in the (Centroid, ma-mi-mi_axis) reference
+  //Transforming the point cloud in the (Centroid, ma-mi-mi_axis) reference
   //with homogeneous matrix
   //[R^t  , -R^t*Centroid ]
   //[0    , 1             ]
   Eigen::Matrix<Scalar, 4, 4> transform = Eigen::Matrix<Scalar, 4, 4>::Identity();
-  transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose();
-  transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid;
+  transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose();
+  transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid;
 
   //when Scalar==double on a Windows 10 machine and MSVS:
   //if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse
@@ -824,13 +824,13 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
   //obb_rotational_matrix.col(1)==middle_axis
   //obb_rotational_matrix.col(2)==minor_axis
 
-  //Trasforming the point cloud in the (Centroid, ma-mi-mi_axis) reference
+  //Transforming the point cloud in the (Centroid, ma-mi-mi_axis) reference
   //with homogeneous matrix
   //[R^t  , -R^t*Centroid ]
   //[0    , 1             ]
   Eigen::Matrix<Scalar, 4, 4> transform = Eigen::Matrix<Scalar, 4, 4>::Identity();
-  transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose();
-  transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid;
+  transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose();
+  transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid;
 
   //when Scalar==double on a Windows 10 machine and MSVS:
   //if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse
index 031a8ee0b7cb4f1ad3c55bd9685503d94e31a031..8f628f1d4ea24b8f54a894cf735c70cd0812e5e6 100644 (file)
@@ -308,10 +308,21 @@ eigen33 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& eigenve
   computeRoots (scaledMat, eigenvalues);
 
   eigenvalue = eigenvalues (0) * scale;
-
-  scaledMat.diagonal ().array () -= eigenvalues (0);
-
-  eigenvector = detail::getLargest3x3Eigenvector<Vector> (scaledMat).vector;
+  if ( (eigenvalues (1) - eigenvalues (0)) > Eigen::NumTraits < Scalar > ::epsilon ()) {
+    // usual case: first and second are not equal (so first and third are also not equal).
+    // second and third could be equal, but that does not matter here
+    scaledMat.diagonal ().array () -= eigenvalues (0);
+    eigenvector = detail::getLargest3x3Eigenvector<Vector> (scaledMat).vector;
+  }
+  else if ( (eigenvalues (2) - eigenvalues (0)) > Eigen::NumTraits < Scalar > ::epsilon ()) {
+    // first and second equal: choose any unit vector that is orthogonal to third eigenvector
+    scaledMat.diagonal ().array () -= eigenvalues (2);
+    eigenvector = detail::getLargest3x3Eigenvector<Vector> (scaledMat).vector.unitOrthogonal ();
+  }
+  else {
+    // all three equal: just use an arbitrary unit vector
+    eigenvector << Scalar (1.0), Scalar (0.0), Scalar (0.0);
+  }
 }
 
 
index 1c1fe9ec876777c0fd6243ca84c8b587a98d5da7..1719e80dbd94e2b2362e4242657cd559c73d3767 100644 (file)
@@ -39,7 +39,8 @@
 #ifndef PCL_COMMON_FILE_IO_IMPL_HPP_
 #define PCL_COMMON_FILE_IO_IMPL_HPP_
 
-#include <boost/filesystem.hpp>
+#include <pcl/common/pcl_filesystem.h>
+
 #include <boost/range/iterator_range.hpp>
 
 #include <algorithm>
@@ -53,12 +54,12 @@ namespace pcl
 
 void getAllPcdFilesInDirectory(const std::string& directory, std::vector<std::string>& file_names)
 {
-  boost::filesystem::path p(directory);
-  if(boost::filesystem::is_directory(p))
+  pcl_fs::path p(directory);
+  if(pcl_fs::is_directory(p))
   {
-    for(const auto& entry : boost::make_iterator_range(boost::filesystem::directory_iterator(p), {}))
+    for(const auto& entry : boost::make_iterator_range(pcl_fs::directory_iterator(p), {}))
     {
-      if (boost::filesystem::is_regular_file(entry))
+      if (pcl_fs::is_regular_file(entry))
       {
         if (entry.path().extension() == ".pcd")
           file_names.emplace_back(entry.path().filename().string());
index ea137ae316d391152fe19a4f502908100eada248..17b5eafea89ebae05e66e39aa3e6fead48cb909d 100644 (file)
@@ -276,9 +276,7 @@ CloudGenerator<pcl::PointXY, GeneratorT>::fill (int width, int height, pcl::Poin
   if (!cloud.empty ())
     PCL_WARN ("[pcl::common::CloudGenerator] Cloud data will be erased with new data\n!");
 
-  cloud.width = width;
-  cloud.height = height;
-  cloud.resize (cloud.width * cloud.height);
+  cloud.resize (width, height);
   cloud.is_dense = true;
 
   for (auto &point : cloud)
index b5e2deb9a816d8a7ce30140c3a397d53b6d99422..3bbd6e5695c43a3f84535db81764f75671534f2e 100644 (file)
@@ -103,18 +103,18 @@ estimateProjectionMatrix (
 
   while (pointIt)
   {
-    unsigned yIdx = pointIt.getCurrentPointIndex () / cloud->width;
-    unsigned xIdx = pointIt.getCurrentPointIndex () % cloud->width;
+    Scalar yIdx = pointIt.getCurrentPointIndex () / cloud->width;
+    Scalar xIdx = pointIt.getCurrentPointIndex () % cloud->width;
 
     const PointT& point = *pointIt;
     if (std::isfinite (point.x))
     {
-      Scalar xx = point.x * point.x;
-      Scalar xy = point.x * point.y;
-      Scalar xz = point.x * point.z;
-      Scalar yy = point.y * point.y;
-      Scalar yz = point.y * point.z;
-      Scalar zz = point.z * point.z;
+      Scalar xx = static_cast<Scalar>(point.x) * static_cast<Scalar>(point.x);
+      Scalar xy = static_cast<Scalar>(point.x) * static_cast<Scalar>(point.y);
+      Scalar xz = static_cast<Scalar>(point.x) * static_cast<Scalar>(point.z);
+      Scalar yy = static_cast<Scalar>(point.y) * static_cast<Scalar>(point.y);
+      Scalar yz = static_cast<Scalar>(point.y) * static_cast<Scalar>(point.z);
+      Scalar zz = static_cast<Scalar>(point.z) * static_cast<Scalar>(point.z);
       Scalar xx_yy = xIdx * xIdx + yIdx * yIdx;
 
       A.coeffRef (0) += xx;
index 6c884d16c08e2e863de104abe8f52c39a784dafd..c255161b51e684b37c5abd0ac437bb622d346e69 100644 (file)
@@ -507,7 +507,7 @@ getPrincipalTransformation (const pcl::PointCloud<PointT> &cloud,
   double rel1 = eigen_vals.coeff (0) / eigen_vals.coeff (1);
   double rel2 = eigen_vals.coeff (1) / eigen_vals.coeff (2);
 
-  transform.translation () = centroid.head (3);
+  transform.translation () = centroid.template head<3> ();
   transform.linear () = eigen_vects;
 
   return (std::min (rel1, rel2));
index 28a3f80e828cbd3dea431464e57fd9226e6a5f1b..687a69d0a120859d909d49759848755ee88ec86a 100644 (file)
@@ -81,18 +81,18 @@ namespace pcl
     * \note Described in: "Intersection of Two Planes, John Krumm, Microsoft Research, Redmond, WA, USA"
     * \param[in] plane_a coefficients of plane A and plane B in the form ax + by + cz + d = 0
     * \param[in] plane_b coefficients of line where line.tail<3>() = direction vector and
-    * line.head<3>() the point on the line clossest to (0, 0, 0)
+    * line.head<3>() the point on the line closest to (0, 0, 0)
     * \param[out] line the intersected line to be filled
     * \param[in] angular_tolerance tolerance in radians
     * \return true if succeeded/planes aren't parallel
     */
-  PCL_EXPORTS template <typename Scalar> bool
+  template <typename Scalar> bool
   planeWithPlaneIntersection (const Eigen::Matrix<Scalar, 4, 1> &plane_a,
                               const Eigen::Matrix<Scalar, 4, 1> &plane_b,
                               Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &line,
                               double angular_tolerance = 0.1);
 
-  PCL_EXPORTS inline bool
+  inline bool
   planeWithPlaneIntersection (const Eigen::Vector4f &plane_a,
                               const Eigen::Vector4f &plane_b,
                               Eigen::VectorXf &line,
@@ -101,7 +101,7 @@ namespace pcl
     return (planeWithPlaneIntersection<float> (plane_a, plane_b, line, angular_tolerance));
   }
 
-  PCL_EXPORTS inline bool
+  inline bool
   planeWithPlaneIntersection (const Eigen::Vector4d &plane_a,
                               const Eigen::Vector4d &plane_b,
                               Eigen::VectorXd &line,
@@ -121,7 +121,7 @@ namespace pcl
     * \param[out] intersection_point the three coordinates x, y, z of the intersection point
     * \return true if succeeded/planes aren't parallel
     */
-  PCL_EXPORTS template <typename Scalar> bool
+  template <typename Scalar> bool
   threePlanesIntersection (const Eigen::Matrix<Scalar, 4, 1> &plane_a,
                            const Eigen::Matrix<Scalar, 4, 1> &plane_b,
                            const Eigen::Matrix<Scalar, 4, 1> &plane_c,
@@ -129,7 +129,7 @@ namespace pcl
                            double determinant_tolerance = 1e-6);
 
 
-  PCL_EXPORTS inline bool
+  inline bool
   threePlanesIntersection (const Eigen::Vector4f &plane_a,
                            const Eigen::Vector4f &plane_b,
                            const Eigen::Vector4f &plane_c,
@@ -140,7 +140,7 @@ namespace pcl
                                             intersection_point, determinant_tolerance));
   }
 
-  PCL_EXPORTS inline bool
+  inline bool
   threePlanesIntersection (const Eigen::Vector4d &plane_a,
                            const Eigen::Vector4d &plane_b,
                            const Eigen::Vector4d &plane_c,
index 984b73065538b36815d575d40709b96c50151e76..8cbb94e20ea0efa1d1184062acab97b1e6cfd02a 100644 (file)
@@ -277,7 +277,7 @@ namespace pcl
     * \ingroup common
     */
   template <typename PointT>
-  PCL_EXPORTS bool
+  bool
   concatenate (const pcl::PointCloud<PointT> &cloud1,
                const pcl::PointCloud<PointT> &cloud2,
                pcl::PointCloud<PointT> &cloud_out)
@@ -295,7 +295,7 @@ namespace pcl
     * \return true if successful, false otherwise
     * \ingroup common
     */
-  PCL_EXPORTS inline bool
+  inline bool
   concatenate (const pcl::PCLPointCloud2 &cloud1,
                const pcl::PCLPointCloud2 &cloud2,
                pcl::PCLPointCloud2 &cloud_out)
@@ -310,7 +310,7 @@ namespace pcl
     * \return true if successful, false otherwise
     * \ingroup common
     */
-  PCL_EXPORTS inline bool
+  inline bool
   concatenate (const pcl::PolygonMesh &mesh1,
                const pcl::PolygonMesh &mesh2,
                pcl::PolygonMesh &mesh_out)
diff --git a/common/include/pcl/common/pcl_filesystem.h b/common/include/pcl/common/pcl_filesystem.h
new file mode 100644 (file)
index 0000000..eb6c414
--- /dev/null
@@ -0,0 +1,51 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (C) 2024 Kino <cybao292261@163.com>
+ *
+ *  All rights reserved.
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * Redistributions in binary form must reproduce the above
+ *     copyright notice, this list of conditions and the following
+ *     disclaimer in the documentation and/or other materials provided
+ *     with the distribution.
+ *   * Neither the name of the copyright holder(s) nor the names of its
+ *     contributors may be used to endorse or promote products derived
+ *     from this software without specific prior written permission.
+ *
+ *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ *  POSSIBILITY OF SUCH DAMAGE.
+ *
+ * $Id$
+ */
+
+#pragma once
+
+#include <pcl/pcl_config.h> // for PCL_PREFER_BOOST_FILESYSTEM
+
+#if (__cplusplus >= 201703L) && !defined(PCL_PREFER_BOOST_FILESYSTEM)
+#define PCL_USING_STD_FILESYSTEM
+#include <filesystem>
+namespace pcl_fs = std::filesystem;
+#else
+#define PCL_USING_BOOST_FILESYSTEM
+#include <boost/filesystem.hpp>
+namespace pcl_fs = boost::filesystem;
+#endif
index 0e84427b1c9a76822c07a358c7d1c723a5e0a5de..ccf218efa63d8d02d9e333d7de55be939fdd7878 100644 (file)
@@ -45,7 +45,9 @@
 // Use e.g. like this:
 // PCL_INFO_STREAM("Info: this is a point: " << pcl::PointXYZ(1.0, 2.0, 3.0) << std::endl);
 // PCL_ERROR_STREAM("Error: an Eigen vector: " << std::endl << Eigen::Vector3f(1.0, 2.0, 3.0) << std::endl);
+// NOLINTBEGIN(bugprone-macro-parentheses)
 #define PCL_LOG_STREAM(LEVEL, STREAM, CSTR, ATTR, FG, ARGS) if(pcl::console::isVerbosityLevelEnabled(pcl::console::LEVEL)) { fflush(stdout); pcl::console::change_text_color(CSTR, pcl::console::ATTR, pcl::console::FG); STREAM << ARGS; pcl::console::reset_text_color(CSTR); }
+// NOLINTEND(bugprone-macro-parentheses)
 #define PCL_ALWAYS_STREAM(ARGS)  PCL_LOG_STREAM(L_ALWAYS,  std::cout, stdout, TT_RESET,  TT_WHITE,  ARGS)
 #define PCL_ERROR_STREAM(ARGS)   PCL_LOG_STREAM(L_ERROR,   std::cerr, stderr, TT_BRIGHT, TT_RED,    ARGS)
 #define PCL_WARN_STREAM(ARGS)    PCL_LOG_STREAM(L_WARN,    std::cerr, stderr, TT_BRIGHT, TT_YELLOW, ARGS)
@@ -60,6 +62,7 @@
 #define PCL_INFO(...)    pcl::console::print (pcl::console::L_INFO, __VA_ARGS__)
 #define PCL_DEBUG(...)   pcl::console::print (pcl::console::L_DEBUG, __VA_ARGS__)
 #define PCL_VERBOSE(...) pcl::console::print (pcl::console::L_VERBOSE, __VA_ARGS__)
+#define PCL_HIGH(...)    pcl::console::print_highlight (__VA_ARGS__)
 
 #define PCL_ASSERT_ERROR_PRINT_CHECK(pred, msg) \
     do \
index 631b7443c685bf2cc30a244e5969f0f2b453068c..9e1972d4c59f6f481d52728998a19435f61b58ea 100644 (file)
@@ -53,6 +53,7 @@
 
 #include <algorithm>
 #include <iterator>
+#include <numeric> // for accumulate
 
 namespace pcl
 {
@@ -103,7 +104,7 @@ namespace pcl
           }
         }
         // Disable thrown exception per #595: http://dev.pointclouds.org/issues/595
-        PCL_WARN ("Failed to find match for field '%s'.\n", pcl::traits::name<PointT, Tag>::value);
+        PCL_WARN ("Failed to find exact match for field '%s'.\n", pcl::traits::name<PointT, Tag>::value);
         //throw pcl::InvalidConversionException (ss.str ());
       }
 
@@ -117,6 +118,71 @@ namespace pcl
       return (a.serialized_offset < b.serialized_offset);
     }
 
+    // Helps converting PCLPointCloud2 to templated point cloud. Casts fields if datatype is different.
+    template<typename PointT>
+    struct FieldCaster
+    {
+      FieldCaster (const std::vector<pcl::PCLPointField>& fields, const pcl::PCLPointCloud2& msg, const std::uint8_t* msg_data, std::uint8_t* cloud_data)
+        : fields_ (fields), msg_(msg), msg_data_(msg_data), cloud_data_(cloud_data)
+      {}
+
+      template<typename Tag> void
+      operator () ()
+      {
+        // first check whether any field matches exactly. Then there is nothing to do because the contents are memcpy-ed elsewhere
+        for (const auto& field : fields_) {
+          if (FieldMatches<PointT, Tag>()(field)) {
+            return;
+          }
+        }
+        for (const auto& field : fields_)
+        {
+          // The following check is similar to FieldMatches, but it tests for different datatypes
+          if ((field.name == pcl::traits::name<PointT, Tag>::value) &&
+              (field.datatype != pcl::traits::datatype<PointT, Tag>::value) &&
+              ((field.count == pcl::traits::datatype<PointT, Tag>::size) ||
+               (field.count == 0 && pcl::traits::datatype<PointT, Tag>::size == 1))) {
+#define PCL_CAST_POINT_FIELD(TYPE) case ::pcl::traits::asEnum_v<TYPE>: \
+            PCL_WARN("Will try to cast field '%s' (original type is " #TYPE "). You may loose precision during casting. Make sure that this is acceptable or choose a different point type.\n", pcl::traits::name<PointT, Tag>::value); \
+            for (std::size_t row = 0; row < msg_.height; ++row) { \
+              const std::uint8_t* row_data = msg_data_ + row * msg_.row_step; \
+              for (std::size_t col = 0; col < msg_.width; ++col) { \
+                const std::uint8_t* msg_data = row_data + col * msg_.point_step; \
+                for(std::uint32_t i=0; i<pcl::traits::datatype<PointT, Tag>::size; ++i) { \
+                  *(reinterpret_cast<typename pcl::traits::datatype<PointT, Tag>::decomposed::type*>(cloud_data + pcl::traits::offset<PointT, Tag>::value) + i) = *(reinterpret_cast<const TYPE*>(msg_data + field.offset) + i); \
+                } \
+                cloud_data += sizeof (PointT); \
+              } \
+            } \
+            break;
+            // end of PCL_CAST_POINT_FIELD definition
+
+            std::uint8_t* cloud_data = cloud_data_;
+            switch(field.datatype) {
+              PCL_CAST_POINT_FIELD(bool)
+              PCL_CAST_POINT_FIELD(std::int8_t)
+              PCL_CAST_POINT_FIELD(std::uint8_t)
+              PCL_CAST_POINT_FIELD(std::int16_t)
+              PCL_CAST_POINT_FIELD(std::uint16_t)
+              PCL_CAST_POINT_FIELD(std::int32_t)
+              PCL_CAST_POINT_FIELD(std::uint32_t)
+              PCL_CAST_POINT_FIELD(std::int64_t)
+              PCL_CAST_POINT_FIELD(std::uint64_t)
+              PCL_CAST_POINT_FIELD(float)
+              PCL_CAST_POINT_FIELD(double)
+              default: std::cout << "Unknown datatype: " << field.datatype << std::endl;
+            }
+            return;
+          }
+#undef PCL_CAST_POINT_FIELD
+        }
+      }
+
+      const std::vector<pcl::PCLPointField>& fields_;
+      const pcl::PCLPointCloud2& msg_;
+      const std::uint8_t* msg_data_;
+      std::uint8_t* cloud_data_;
+    };
   } //namespace detail
 
   template<typename PointT> void
@@ -175,7 +241,6 @@ namespace pcl
     // check if there is data to copy
     if (msg.width * msg.height == 0)
     {
-      PCL_WARN("[pcl::fromPCLPointCloud2] No data to copy.\n");
       return;
     }
 
@@ -222,6 +287,9 @@ namespace pcl
         }
       }
     }
+    // if any fields in msg and cloud have different datatypes but the same name, we cast them:
+    detail::FieldCaster<PointT> caster (msg.fields, msg, msg_data, reinterpret_cast<std::uint8_t*>(cloud.data()));
+    for_each_type< typename traits::fieldList<PointT>::type > (caster);
   }
 
   /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
@@ -256,12 +324,52 @@ namespace pcl
     fromPCLPointCloud2 (msg, cloud, field_map);
   }
 
+  namespace detail {
+    /** \brief Used together with `pcl::for_each_type`, copies all point fields from `cloud_data` (respecting each field offset) to `msg_data` (tightly packed).
+      */
+    template<typename PointT>
+    struct FieldCopier {
+      FieldCopier(std::uint8_t*& msg_data, const std::uint8_t*& cloud_data) : msg_data_ (msg_data), cloud_data_ (cloud_data) {};
+
+      template<typename U> void operator() () {
+        memcpy(msg_data_, cloud_data_ + pcl::traits::offset<PointT, U>::value, sizeof(typename pcl::traits::datatype<PointT, U>::type));
+        msg_data_ += sizeof(typename pcl::traits::datatype<PointT, U>::type);
+      }
+
+      std::uint8_t*& msg_data_;
+      const std::uint8_t*& cloud_data_;
+    };
+
+    /** \brief Used together with `pcl::for_each_type`, creates list of all fields, and list of size of each field.
+      */
+    template<typename PointT>
+    struct FieldAdderAdvanced
+    {
+      FieldAdderAdvanced (std::vector<pcl::PCLPointField>& fields, std::vector<std::size_t>& field_sizes) : fields_ (fields), field_sizes_ (field_sizes) {};
+
+      template<typename U> void operator() ()
+      {
+        pcl::PCLPointField f;
+        f.name = pcl::traits::name<PointT, U>::value;
+        f.offset = pcl::traits::offset<PointT, U>::value;
+        f.datatype = pcl::traits::datatype<PointT, U>::value;
+        f.count = pcl::traits::datatype<PointT, U>::size;
+        fields_.push_back (f);
+        field_sizes_.push_back (sizeof(typename pcl::traits::datatype<PointT, U>::type)); // If field is an array, then this is the size of all array elements
+      }
+
+      std::vector<pcl::PCLPointField>& fields_;
+      std::vector<std::size_t>& field_sizes_;
+    };
+  } // namespace detail
+
   /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
     * \param[in] cloud the input pcl::PointCloud<T>
     * \param[out] msg the resultant PCLPointCloud2 binary blob
+    * \param[in] padding Many point types have padding to ensure alignment and SIMD compatibility. Setting this to true will copy the padding to the `PCLPointCloud2` (the default in older PCL versions). Setting this to false will make the data blob in `PCLPointCloud2` smaller, while still keeping all information (useful e.g. when sending msg over network or storing it). The amount of padding depends on the point type, and can in some cases be up to 50 percent.
     */
   template<typename PointT> void
-  toPCLPointCloud2 (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg)
+  toPCLPointCloud2 (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg, bool padding)
   {
     // Ease the user's burden on specifying width/height for unorganized datasets
     if (cloud.width == 0 && cloud.height == 0)
@@ -275,26 +383,55 @@ namespace pcl
       msg.height = cloud.height;
       msg.width  = cloud.width;
     }
-
-    // Fill point cloud binary data (padding and all)
-    std::size_t data_size = sizeof (PointT) * cloud.size ();
-    msg.data.resize (data_size);
-    if (data_size)
-    {
-      memcpy(msg.data.data(), cloud.data(), data_size);
-    }
-
     // Fill fields metadata
     msg.fields.clear ();
-    for_each_type<typename traits::fieldList<PointT>::type> (detail::FieldAdder<PointT>(msg.fields));
+    std::vector<std::size_t> field_sizes;
+    for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdderAdvanced<PointT>(msg.fields, field_sizes));
+    // Check if padding should be kept, or if the point type does not contain padding (then the single memcpy is faster)
+    if (padding || std::accumulate(field_sizes.begin(), field_sizes.end(), static_cast<std::size_t>(0)) == sizeof (PointT)) {
+      // Fill point cloud binary data (padding and all)
+      std::size_t data_size = sizeof (PointT) * cloud.size ();
+      msg.data.resize (data_size);
+      if (data_size)
+      {
+        memcpy(msg.data.data(), cloud.data(), data_size);
+      }
+
+      msg.point_step = sizeof (PointT);
+      msg.row_step   = (sizeof (PointT) * msg.width);
+    } else {
+      std::size_t point_size = 0;
+      for(std::size_t i=0; i<msg.fields.size(); ++i) {
+        msg.fields[i].offset = point_size; // Adjust offset when padding is removed
+        point_size += field_sizes[i];
+      }
+      msg.data.resize (point_size * cloud.size());
+      std::uint8_t* msg_data = &msg.data[0];
+      const std::uint8_t* cloud_data=reinterpret_cast<const std::uint8_t*>(&cloud[0]);
+      const std::uint8_t* end = cloud_data + sizeof (PointT) * cloud.size ();
+      pcl::detail::FieldCopier<PointT> copier(msg_data, cloud_data); // copier takes msg_data and cloud_data as references, so the two are shared
+      for (; cloud_data<end; cloud_data+=sizeof(PointT)) {
+        for_each_type< typename traits::fieldList<PointT>::type > (copier);
+      }
 
+      msg.point_step = point_size;
+      msg.row_step   = point_size * msg.width;
+    }
     msg.header     = cloud.header;
-    msg.point_step = sizeof (PointT);
-    msg.row_step   = (sizeof (PointT) * msg.width);
     msg.is_dense   = cloud.is_dense;
     /// @todo msg.is_bigendian = ?;
   }
 
+  /** \brief Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
+    * \param[in] cloud the input pcl::PointCloud<T>
+    * \param[out] msg the resultant PCLPointCloud2 binary blob
+    */
+  template<typename PointT> void
+  toPCLPointCloud2 (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg)
+  {
+    toPCLPointCloud2 (cloud, msg, true); // true is the default in older PCL version
+  }
+
    /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format
      * \param[in] cloud the point cloud message
      * \param[out] msg the resultant pcl::PCLImage
index 3814839c89cd86102ac51d88efcc23b7e40e136d..5adfccf7585b2a65af577ef25132af58cf2e4ab7 100644 (file)
 #include <stdexcept>
 #include <sstream>
 #include <boost/current_function.hpp>
+#include <pcl/pcl_exports.h> // for PCL_EXPORTS
 
 /** PCL_THROW_EXCEPTION a helper macro to be used for throwing exceptions.
   * This is an example on how to use:
   * PCL_THROW_EXCEPTION(IOException,
   *                     "encountered an error while opening " << filename << " PCD file");
   */
+// NOLINTBEGIN(bugprone-macro-parentheses)
 #define PCL_THROW_EXCEPTION(ExceptionName, message)                         \
 {                                                                           \
   std::ostringstream s;                                                     \
   s << message;                                                             \
   throw ExceptionName(s.str(), __FILE__, BOOST_CURRENT_FUNCTION, __LINE__); \
 }
+// NOLINTEND(bugprone-macro-parentheses)
 
 namespace pcl
 {
@@ -60,7 +63,7 @@ namespace pcl
     * \brief A base class for all pcl exceptions which inherits from std::runtime_error
     * \author Eitan Marder-Eppstein, Suat Gedikli, Nizar Sallem
     */
-  class PCLException : public std::runtime_error
+  class PCL_EXPORTS PCLException : public std::runtime_error
   {
     public:
 
@@ -132,7 +135,7 @@ namespace pcl
   /** \class InvalidConversionException
     * \brief An exception that is thrown when a PCLPointCloud2 message cannot be converted into a PCL type
     */
-  class InvalidConversionException : public PCLException
+  class PCL_EXPORTS InvalidConversionException : public PCLException
   {
     public:
 
@@ -146,7 +149,7 @@ namespace pcl
   /** \class IsNotDenseException
     * \brief An exception that is thrown when a PointCloud is not dense but is attempted to be used as dense
     */
-  class IsNotDenseException : public PCLException
+  class PCL_EXPORTS IsNotDenseException : public PCLException
   {
     public:
 
@@ -161,7 +164,7 @@ namespace pcl
     * \brief An exception that is thrown when a sample consensus model doesn't
     * have the correct number of samples defined in model_types.h
     */
-  class InvalidSACModelTypeException : public PCLException
+  class PCL_EXPORTS InvalidSACModelTypeException : public PCLException
   {
     public:
 
@@ -175,7 +178,7 @@ namespace pcl
   /** \class IOException
     * \brief An exception that is thrown during an IO error (typical read/write errors)
     */
-  class IOException : public PCLException
+  class PCL_EXPORTS IOException : public PCLException
   {
     public:
 
@@ -190,7 +193,7 @@ namespace pcl
     * \brief An exception thrown when init can not be performed should be used in all the
     * PCLBase class inheritants.
     */
-  class InitFailedException : public PCLException
+  class PCL_EXPORTS InitFailedException : public PCLException
   {
     public:
       InitFailedException (const std::string& error_description = "",
@@ -204,7 +207,7 @@ namespace pcl
     * \brief An exception that is thrown when an organized point cloud is needed
     * but not provided.
     */
-  class UnorganizedPointCloudException : public PCLException
+  class PCL_EXPORTS UnorganizedPointCloudException : public PCLException
   {
     public:
     
@@ -218,7 +221,7 @@ namespace pcl
   /** \class KernelWidthTooSmallException
     * \brief An exception that is thrown when the kernel size is too small
     */
-  class KernelWidthTooSmallException : public PCLException
+  class PCL_EXPORTS KernelWidthTooSmallException : public PCLException
   {
     public:
     
@@ -229,7 +232,7 @@ namespace pcl
       : pcl::PCLException (error_description, file_name, function_name, line_number) { }
   } ;
 
-  class UnhandledPointTypeException : public PCLException
+  class PCL_EXPORTS UnhandledPointTypeException : public PCLException
   {
     public:
     UnhandledPointTypeException (const std::string& error_description,
@@ -239,7 +242,7 @@ namespace pcl
       : pcl::PCLException (error_description, file_name, function_name, line_number) { }
   };
 
-  class ComputeFailedException : public PCLException
+  class PCL_EXPORTS ComputeFailedException : public PCLException
   {
     public:
     ComputeFailedException (const std::string& error_description,
@@ -252,7 +255,7 @@ namespace pcl
   /** \class BadArgumentException
     * \brief An exception that is thrown when the arguments number or type is wrong/unhandled.
     */
-  class BadArgumentException : public PCLException
+  class PCL_EXPORTS BadArgumentException : public PCLException
   {
     public:
     BadArgumentException (const std::string& error_description,
index ea73a0c3d687eb7f61d21acc9ddd8c5cb0e9352b..9eca81a0d58bfe43eb86639f5a33800e2725125c 100644 (file)
@@ -95,7 +95,7 @@
 //
 //    ((x)(y)(z))((1)(2)(3))((dracula)(radu))
 //
-#ifdef _MSC_VER
+#if defined(_MSC_VER) && !defined(__clang__)
 #define PCL_INSTANTIATE_PRODUCT_IMPL(r, product) \
   BOOST_PP_CAT(PCL_INSTANTIATE_, BOOST_PP_SEQ_HEAD(product)) \
           BOOST_PP_EXPAND(BOOST_PP_SEQ_TO_TUPLE(BOOST_PP_SEQ_TAIL(product))) 
index cb08b4deb25262a6f415188909d9797991a071ae..88ca63a4d1a432f7cdac307738877e7128c4af5e 100644 (file)
@@ -39,6 +39,7 @@
 #pragma once
 
 #include <pcl/memory.h>                 // for PCL_MAKE_ALIGNED_OPERATOR_NEW
+#include <pcl/pcl_config.h>             // for PCL_XYZ_POINT_TYPES, PCL_NORMAL_POINT_TYPES
 #include <pcl/pcl_macros.h>             // for PCL_EXPORTS
 #include <pcl/PCLPointField.h>          // for PCLPointField
 #include <pcl/point_types.h>            // implementee
   (pcl::PointXYZRGBNormal)      \
   (pcl::PointSurfel)            \
 
-// Define all point types that include XYZ data
-#define PCL_XYZ_POINT_TYPES   \
-  (pcl::PointXYZ)             \
-  (pcl::PointXYZI)            \
-  (pcl::PointXYZL)            \
-  (pcl::PointXYZRGBA)         \
-  (pcl::PointXYZRGB)          \
-  (pcl::PointXYZRGBL)         \
-  (pcl::PointXYZLAB)          \
-  (pcl::PointXYZHSV)          \
-  (pcl::InterestPoint)        \
-  (pcl::PointNormal)          \
-  (pcl::PointXYZRGBNormal)    \
-  (pcl::PointXYZINormal)      \
-  (pcl::PointXYZLNormal)      \
-  (pcl::PointWithRange)       \
-  (pcl::PointWithViewpoint)   \
-  (pcl::PointWithScale)       \
-  (pcl::PointSurfel)          \
-  (pcl::PointDEM)
-
 // Define all point types with XYZ and label
 #define PCL_XYZL_POINT_TYPES  \
   (pcl::PointXYZL)            \
   (pcl::PointXYZRGBL)         \
   (pcl::PointXYZLNormal)
 
-// Define all point types that include normal[3] data
-#define PCL_NORMAL_POINT_TYPES  \
-  (pcl::Normal)                 \
-  (pcl::PointNormal)            \
-  (pcl::PointXYZRGBNormal)      \
-  (pcl::PointXYZINormal)        \
-  (pcl::PointXYZLNormal)        \
-  (pcl::PointSurfel)
-
 // Define all point types that represent features
 #define PCL_FEATURE_POINT_TYPES \
   (pcl::PFHSignature125)        \
@@ -691,8 +662,8 @@ namespace pcl
     inline constexpr PointXYZLAB() : PointXYZLAB{0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f} {}
 
     inline constexpr PointXYZLAB (float _x, float _y, float _z,
-                        float _L, float _a, float _b) :
-      _PointXYZLAB{ {{_x, _y, _z, 1.0f}}, {{_L, _a, _b}} } {}
+                        float _l, float _a, float _b) :
+      _PointXYZLAB{ {{_x, _y, _z, 1.0f}}, {{_l, _a, _b}} } {}
 
     friend std::ostream& operator << (std::ostream& os, const PointXYZLAB& p);
     PCL_MAKE_ALIGNED_OPERATOR_NEW
diff --git a/common/include/pcl/make_shared.h b/common/include/pcl/make_shared.h
deleted file mode 100644 (file)
index 983a63c..0000000
+++ /dev/null
@@ -1,42 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2019-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-#pragma once
-
-PCL_DEPRECATED_HEADER(1, 15, "Use <pcl/memory.h> instead.")
-
-#include <pcl/memory.h>
-
index d42e47aa42e021e8855bc1ca506c96caa4ed57bd..98d1d9b45f27f5639697e3c2ce308c28ec09bdd1 100644 (file)
@@ -44,6 +44,7 @@
  */
 
 #include <pcl/type_traits.h>  // for has_custom_allocator
+#include <pcl/pcl_config.h> // for PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC
 
 #include <Eigen/Core>  // for EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
 #include <type_traits>  // for std::enable_if_t, std::false_type, std::true_type
 #include <utility>  // for std::forward
 
+#if !defined(PCL_SILENCE_MALLOC_WARNING) && !defined(__NVCC__)
+#if PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC
+// EIGEN_DEFAULT_ALIGN_BYTES and EIGEN_MALLOC_ALREADY_ALIGNED will be set after including Eigen/Core
+// this condition is the same as in the function aligned_malloc in Memory.h in the Eigen code
+#if (defined(EIGEN_DEFAULT_ALIGN_BYTES) && EIGEN_DEFAULT_ALIGN_BYTES==0) || (defined(EIGEN_MALLOC_ALREADY_ALIGNED) && EIGEN_MALLOC_ALREADY_ALIGNED)
+#if defined(_MSC_VER)
+#error "Potential runtime error due to aligned malloc mismatch! You likely have to compile your code with AVX enabled or define EIGEN_MAX_ALIGN_BYTES=32 (to silence this message at your own risk, define PCL_SILENCE_MALLOC_WARNING=1)"
+#else // defined(_MSC_VER)
+#warning "Potential runtime error due to aligned malloc mismatch! You likely have to compile your code with AVX enabled or define EIGEN_MAX_ALIGN_BYTES=32 (to silence this message at your own risk, define PCL_SILENCE_MALLOC_WARNING=1)"
+#endif // defined(_MSC_VER)
+#endif
+#else // PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC
+#if (defined(EIGEN_DEFAULT_ALIGN_BYTES) && EIGEN_DEFAULT_ALIGN_BYTES!=0) && (defined(EIGEN_MALLOC_ALREADY_ALIGNED) && !EIGEN_MALLOC_ALREADY_ALIGNED)
+#if defined(_MSC_VER)
+#error "Potential runtime error due to aligned malloc mismatch! PCL was likely compiled without AVX support but you enabled AVX for your code (to silence this message at your own risk, define PCL_SILENCE_MALLOC_WARNING=1)"
+#else // defined(_MSC_VER)
+#warning "Potential runtime error due to aligned malloc mismatch! PCL was likely compiled without AVX support but you enabled AVX for your code (to silence this message at your own risk, define PCL_SILENCE_MALLOC_WARNING=1)"
+#endif // defined(_MSC_VER)
+#endif
+#endif // PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC
+#endif // !defined(PCL_SILENCE_MALLOC_WARNING)
+
 /**
  * \brief Macro to signal a class requires a custom allocator
  *
index ef71bddadd84ab6a963a951577419a4489e5bc00..f386303bc46e7f414b8f8ec6f8eaef63ffe052f9 100644 (file)
@@ -34,6 +34,8 @@
 
 #pragma once
 
+#include <pcl/pcl_config.h> // for PCL_SYMBOL_VISIBILITY_HIDDEN
+
 // This header is created to include to NVCC compiled sources.
 // Header 'pcl_macros' is not suitable since it includes <Eigen/Core>,
 // which can't be eaten by nvcc (it's too weak)
@@ -45,5 +47,9 @@
         #define PCL_EXPORTS
     #endif
 #else
-    #define PCL_EXPORTS
+    #ifdef PCL_SYMBOL_VISIBILITY_HIDDEN
+        #define PCL_EXPORTS __attribute__ ((visibility ("default")))
+    #else
+        #define PCL_EXPORTS
+    #endif
 #endif
index da487b5e1bcff322f11016a837dc05675cbc65b3..d76d5c3c9786ee0a99c9a8342d1af9e0bb1adbf9 100644 (file)
@@ -82,7 +82,7 @@
 // MSVC < 2019 have issues:
 // * can't short-circuiting logic in macros
 // * don't define standard macros
-// => this leads to annyoing C4067 warnings (see https://developercommunity.visualstudio.com/content/problem/327796/-has-cpp-attribute-emits-warning-is-wrong-highligh.html)
+// => this leads to annoying C4067 warnings (see https://developercommunity.visualstudio.com/content/problem/327796/-has-cpp-attribute-emits-warning-is-wrong-highligh.html)
 #if defined(_MSC_VER)
   // nvcc on msvc can't work with [[deprecated]]
   #if !defined(__CUDACC__)
   #define _PCL_DEPRECATED_HEADER_IMPL(Message)
 #endif
 
+// NOLINTBEGIN(bugprone-macro-parentheses)
 /**
  * \brief A handy way to inform the user of the removal deadline
  */
 #define _PCL_PREPARE_REMOVAL_MESSAGE(Major, Minor, Msg)                                 \
   Msg " (It will be removed in PCL " BOOST_PP_STRINGIZE(Major.Minor) ")"
+// NOLINTEND(bugprone-macro-parentheses)
 
 /**
  * \brief Tests for Minor < PCL_MINOR_VERSION
     #define NOMINMAX
   #endif
 
-  #define __PRETTY_FUNCTION__ __FUNCTION__
-  #define __func__ __FUNCTION__
+  #define __PRETTY_FUNCTION__ __FUNCSIG__
 #endif
 #endif // defined _WIN32
 
@@ -294,18 +295,18 @@ pcl_round (float number)
 #endif
 
 #define FIXED(s) \
-  std::fixed << s << std::resetiosflags(std::ios_base::fixed)
+  std::fixed << (s) << std::resetiosflags(std::ios_base::fixed)
 
 #ifndef ERASE_STRUCT
-#define ERASE_STRUCT(var) memset(&var, 0, sizeof(var))
+#define ERASE_STRUCT(var) memset(&(var), 0, sizeof(var))
 #endif
 
 #ifndef ERASE_ARRAY
-#define ERASE_ARRAY(var, size) memset(var, 0, size*sizeof(*var))
+#define ERASE_ARRAY(var, size) memset(var, 0, (size)*sizeof(*(var)))
 #endif
 
 #ifndef SET_ARRAY
-#define SET_ARRAY(var, value, size) { for (decltype(size) i = 0; i < size; ++i) var[i]=value; }
+#define SET_ARRAY(var, value, size) { for (decltype(size) i = 0; i < (size); ++i) (var)[i]=value; }
 #endif
 
 #ifndef PCL_EXTERN_C
@@ -323,7 +324,11 @@ pcl_round (float number)
         #define PCL_EXPORTS
     #endif
 #else
-    #define PCL_EXPORTS
+    #ifdef PCL_SYMBOL_VISIBILITY_HIDDEN
+        #define PCL_EXPORTS __attribute__ ((visibility ("default")))
+    #else
+        #define PCL_EXPORTS
+    #endif
 #endif
 
 #if defined WIN32 || defined _WIN32
index a5607bffced1a05b805abbe117491a71bd5a370f..f7b63ba7b1e9dbc47416d492f7d610961cbfbe29 100644 (file)
@@ -169,7 +169,7 @@ namespace pcl
     * \author Patrick Mihelich, Radu B. Rusu
     */
   template <typename PointT>
-  class PCL_EXPORTS PointCloud
+  class PointCloud
   {
     public:
       /** \brief Default constructor. Sets \ref is_dense to true, \ref width
@@ -921,5 +921,3 @@ namespace pcl
     return (s);
   }
 }
-
-#define PCL_INSTANTIATE_PointCloud(T) template class PCL_EXPORTS pcl::PointCloud<T>;
diff --git a/common/include/pcl/point_traits.h b/common/include/pcl/point_traits.h
deleted file mode 100644 (file)
index 4136fa9..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2012, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- */
-
-#pragma once
-
-PCL_DEPRECATED_HEADER(1, 15, "Use <pcl/type_traits.h> instead.")
-
-#include <pcl/type_traits.h>
index 01e396e290e34d0be3799abc811956e3b75f53e7..7a985b56ef16b7390ce695d352fcbb991f1e2def 100644 (file)
@@ -194,7 +194,7 @@ RangeImage::createFromPointCloudWithKnownSize (const PointCloudType& point_cloud
   image_offset_y_ = (std::max) (0, center_pixel_y-pixel_radius_y);
 
   points.clear ();
-  points.resize (width*height, unobserved_point);
+  points.resize (static_cast<std::size_t>(width)*static_cast<std::size_t>(height), unobserved_point);
   
   int top=height, right=-1, bottom=-1, left=width;
   doZBuffer (point_cloud, noise_level, min_range, top, right, bottom, left);
@@ -470,7 +470,7 @@ RangeImage::isValid (int index) const
 bool 
 RangeImage::isObserved (int x, int y) const
 {
-  return !(!isInImage (x,y) || (std::isinf (getPoint (x,y).range) && getPoint (x,y).range < 0.0f));
+  return (isInImage (x,y) && (!std::isinf (getPoint (x,y).range) || getPoint (x,y).range >= 0.0f));
 }
 
 /////////////////////////////////////////////////////////////////////////
index 051979fe91feea5913b4de4d1fbb05f220c25b99..6392b723a142f4e4881b90e155494a0b4c29829a 100644 (file)
@@ -71,7 +71,7 @@ namespace pcl
       /** Constructor */
       PCL_EXPORTS RangeImage ();
       /** Destructor */
-      PCL_EXPORTS virtual ~RangeImage () = default;
+      PCL_EXPORTS virtual ~RangeImage ();
 
       // =====STATIC VARIABLES=====
       /** The maximum number of openmp threads that can be used in this class */
@@ -782,10 +782,10 @@ namespace pcl
 
 
       // =====STATIC PROTECTED=====
-      static const int lookup_table_size;
-      static std::vector<float> asin_lookup_table;
-      static std::vector<float> atan_lookup_table;
-      static std::vector<float> cos_lookup_table;
+      PCL_EXPORTS static const int lookup_table_size;
+      PCL_EXPORTS static std::vector<float> asin_lookup_table;
+      PCL_EXPORTS static std::vector<float> atan_lookup_table;
+      PCL_EXPORTS static std::vector<float> cos_lookup_table;
       /** Create lookup tables for trigonometric functions */
       static void
       createLookupTables ();
index 85afe3889b37c8b3be558ed8e5d75a8d22302e22..4abdf7412855a7c3aa108ceb156be9608d47af2c 100644 (file)
@@ -133,7 +133,7 @@ namespace pcl
         * \param sensor_pose the pose of the virtual depth camera
         * \param coordinate_frame the used coordinate frame of the point cloud
         * \param noise_level what is the typical noise of the sensor - is used for averaging in the z-buffer
-        * \param min_range minimum range to consifder points
+        * \param min_range minimum range to consider points
         */
       template <typename PointCloudType> void
       createFromPointCloudWithFixedSize (const PointCloudType& point_cloud,
index f5a47a2acfafc2404ef45822bc2c86e2fd4d3525..067276041072c21d6cf74b501ded23ef8eb8a43e 100644 (file)
@@ -137,6 +137,7 @@ pcl::PCLPointCloud2::concatenate (pcl::PCLPointCloud2 &cloud1, const pcl::PCLPoi
   cloud1.is_dense = cloud1.is_dense && cloud2.is_dense;
   cloud1.height = 1;
   cloud1.width = size1 + size2;
+  cloud1.row_step = cloud1.width * cloud1.point_step; // changed width
 
   if (simple_layout)
   {
@@ -145,13 +146,13 @@ pcl::PCLPointCloud2::concatenate (pcl::PCLPointCloud2 &cloud1, const pcl::PCLPoi
   }
   const auto data1_size = cloud1.data.size ();
   cloud1.data.resize(data1_size + cloud2.data.size ());
-  for (uindex_t cp = 0; cp < size2; ++cp)
+  for (std::size_t cp = 0; cp < size2; ++cp)
   {
     for (const auto& field_data: valid_fields)
     {
       const auto& i = field_data.idx1;
       const auto& j = field_data.idx2;
-      const auto& size = field_data.size;
+      const std::size_t size = field_data.size;
       // Leave the data for the skip fields untouched in cloud1
       // Copy only the required data from cloud2 to the correct location for cloud1
       memcpy (reinterpret_cast<char*> (&cloud1.data[data1_size + cp * cloud1.point_step + cloud1.fields[i].offset]),
index 2b6a667164f2d1bc5a2eed26c87f77a7ee0ceb3c..7702de38453dca9ee572543b368c00d0499c4d90 100644 (file)
@@ -145,9 +145,7 @@ pcl::GaussianKernel::convolveRows (const pcl::PointCloud<float>& input,
   {
     if (output.height < input.height || output.width < input.width)
     {
-      output.width = input.width;
-      output.height = input.height;
-      output.resize (input.height * input.width);
+      output.resize (static_cast<uindex_t>(input.width), static_cast<uindex_t>(input.height)); // Casting is necessary to resolve ambiguous call to resize
     }
     unaliased_input = &input;
   }
@@ -189,9 +187,7 @@ pcl::GaussianKernel::convolveCols (const pcl::PointCloud<float>& input,
   {
     if (output.height < input.height || output.width < input.width)
     {
-      output.width = input.width;
-      output.height = input.height;
-      output.resize (input.height * input.width);
+      output.resize (static_cast<uindex_t>(input.width), static_cast<uindex_t>(input.height)); // Casting is necessary to resolve ambiguous call to resize
     }
     unaliased_input = &input;
   }
index 85d6f27dc3ae10ca4ce444869e757bc854003c2e..0be99ddb4a0531f8ced618ed286b121262e1385e 100644 (file)
@@ -102,6 +102,8 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
   //by offset so that we can compute sizes correctly. There is no
   //guarantee that the fields are in the correct order when they come in
   std::vector<const pcl::PCLPointField*> cloud1_fields_sorted;
+  cloud1_fields_sorted.reserve(cloud1.fields.size());
+  
   for (const auto &field : cloud1.fields)
     cloud1_fields_sorted.push_back (&field);
 
@@ -149,7 +151,7 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
 
   //the total size of extra data should be the size of data per point
   //multiplied by the total number of points in the cloud
-  std::uint32_t cloud1_unique_data_size = cloud1_unique_point_step * cloud1.width * cloud1.height; 
+  const std::size_t cloud1_unique_data_size = static_cast<std::size_t>(cloud1_unique_point_step) * cloud1.width * cloud1.height;
 
   // Point step must increase with the length of each matching field
   cloud_out.point_step = cloud2.point_step + cloud1_unique_point_step;
@@ -175,8 +177,9 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
   }
  
   // Iterate over each point and perform the appropriate memcpys
-  int point_offset = 0;
-  for (uindex_t cp = 0; cp < cloud_out.width * cloud_out.height; ++cp)
+  std::size_t point_offset = 0;
+  const std::size_t npts = static_cast<std::size_t>(cloud_out.width) * static_cast<std::size_t>(cloud_out.height);
+  for (std::size_t cp = 0; cp < npts; ++cp)
   {
     memcpy (&cloud_out.data[point_offset], &cloud2.data[cp * cloud2.point_step], cloud2.point_step);
     int field_offset = cloud2.point_step;
@@ -229,7 +232,7 @@ pcl::getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out)
     return (false);
   }
 
-  std::size_t npts = in.width * in.height;
+  std::size_t npts = static_cast<std::size_t>(in.width) * static_cast<std::size_t>(in.height);
   out = Eigen::MatrixXf::Ones (4, npts);
 
   Eigen::Array4i xyz_offset (in.fields[x_idx].offset, in.fields[y_idx].offset, in.fields[z_idx].offset, 0);
@@ -311,11 +314,11 @@ pcl::copyPointCloud (
   cloud_out.row_step     = cloud_in.point_step * static_cast<std::uint32_t> (indices.size ());
   cloud_out.is_dense     = cloud_in.is_dense;
 
-  cloud_out.data.resize (cloud_out.width * cloud_out.height * cloud_out.point_step);
+  cloud_out.data.resize (static_cast<std::size_t>(cloud_out.width) * static_cast<std::size_t>(cloud_out.height) * static_cast<std::size_t>(cloud_out.point_step));
 
   // Iterate over each point
   for (std::size_t i = 0; i < indices.size (); ++i)
-    memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[indices[i] * cloud_in.point_step], cloud_in.point_step);
+    memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[static_cast<std::size_t>(indices[i]) * cloud_in.point_step], cloud_in.point_step);
 }
 
 //////////////////////////////////////////////////////////////////////////
@@ -334,11 +337,11 @@ pcl::copyPointCloud (
   cloud_out.row_step     = cloud_in.point_step * static_cast<std::uint32_t> (indices.size ());
   cloud_out.is_dense     = cloud_in.is_dense;
 
-  cloud_out.data.resize (cloud_out.width * cloud_out.height * cloud_out.point_step);
+  cloud_out.data.resize (static_cast<std::size_t>(cloud_out.width) * cloud_out.height * cloud_out.point_step);
 
   // Iterate over each point
   for (std::size_t i = 0; i < indices.size (); ++i)
-    memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[indices[i] * cloud_in.point_step], cloud_in.point_step);
+    memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[static_cast<std::size_t>(indices[i]) * cloud_in.point_step], cloud_in.point_step);
 }
 
 ////////////////////////////////////////////////////////////////////////////////
index b53d0a87ead8bec749810293d30d8f25b791ec5d..5a482c2dc90575e587c25c63c796fc6f4d36d2a0 100644 (file)
@@ -114,12 +114,12 @@ pcl::PCLBase<pcl::PCLPointCloud2>::initCompute ()
   }
 
   // If we have a set of fake indices, but they do not match the number of points in the cloud, update them
-  if (fake_indices_ && indices_->size () != (input_->width * input_->height))
+  if (fake_indices_ && indices_->size () != (static_cast<std::size_t>(input_->width) * static_cast<std::size_t>(input_->height)))
   {
     const auto indices_size = indices_->size ();
     try
     {
-      indices_->resize (input_->width * input_->height);
+      indices_->resize (static_cast<std::size_t>(input_->width) * static_cast<std::size_t>(input_->height));
     }
     catch (const std::bad_alloc&)
     {
index 5e99d8fbefdc5a12b256aae30a8dc938f275db08..0441649ccfd7a48bd89baf4839777dd24cceee54 100644 (file)
@@ -52,7 +52,7 @@
 # define COMMON_LVB_REVERSE_VIDEO 0
 #endif
 
-WORD 
+WORD
 convertAttributesColor (int attribute, int fg, int bg=0)
 {
   static WORD wAttributes[7]  = { 0,                        // TT_RESET
@@ -129,7 +129,7 @@ pcl::console::change_text_color (FILE *stream, int attribute, int fg, int bg)
 #else
   char command[40];
   // Command is the control command to the terminal
-  sprintf (command, "%c[%d;%d;%dm", 0x1B, attribute, fg + 30, bg + 40);
+  snprintf (command, sizeof(command), "%c[%d;%d;%dm", 0x1B, attribute, fg + 30, bg + 40);
   fprintf (stream, "%s", command);
 #endif
 }
@@ -146,7 +146,7 @@ pcl::console::change_text_color (FILE *stream, int attribute, int fg)
 #else
   char command[17];
   // Command is the control command to the terminal
-  sprintf (command, "%c[%d;%dm", 0x1B, attribute, fg + 30);
+  snprintf (command, sizeof(command), "%c[%d;%dm", 0x1B, attribute, fg + 30);
   fprintf (stream, "%s", command);
 #endif
 }
@@ -163,7 +163,7 @@ pcl::console::reset_text_color (FILE *stream)
 #else
   char command[13];
   // Command is the control command to the terminal
-  sprintf (command, "%c[0;m", 0x1B);
+  snprintf (command, sizeof(command), "%c[0;m", 0x1B);
   fprintf (stream, "%s", command);
 #endif
 }
@@ -178,7 +178,7 @@ pcl::console::print_color (FILE *stream, int attr, int fg, const char *format, .
   va_start (ap, format);
   vfprintf (stream, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stream);
 }
 
@@ -186,7 +186,7 @@ pcl::console::print_color (FILE *stream, int attr, int fg, const char *format, .
 void
 pcl::console::print_info (const char *format, ...)
 {
-  if (!isVerbosityLevelEnabled (L_INFO)) return; 
+  if (!isVerbosityLevelEnabled (L_INFO)) return;
 
   reset_text_color (stdout);
 
@@ -258,7 +258,7 @@ pcl::console::print_error (const char *format, ...)
   va_start (ap, format);
   vfprintf (stderr, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stderr);
 }
 
@@ -274,7 +274,7 @@ pcl::console::print_error (FILE *stream, const char *format, ...)
   va_start (ap, format);
   vfprintf (stream, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stream);
 }
 
@@ -290,7 +290,7 @@ pcl::console::print_warn (const char *format, ...)
   va_start (ap, format);
   vfprintf (stderr, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stderr);
 }
 
@@ -306,7 +306,7 @@ pcl::console::print_warn (FILE *stream, const char *format, ...)
   va_start (ap, format);
   vfprintf (stream, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stream);
 }
 
@@ -322,7 +322,7 @@ pcl::console::print_value (const char *format, ...)
   va_start (ap, format);
   vfprintf (stdout, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stdout);
 }
 
@@ -338,7 +338,7 @@ pcl::console::print_value (FILE *stream, const char *format, ...)
   va_start (ap, format);
   vfprintf (stream, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stream);
 }
 
@@ -354,7 +354,7 @@ pcl::console::print_debug (const char *format, ...)
   va_start (ap, format);
   vfprintf (stdout, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stdout);
 }
 
@@ -370,7 +370,7 @@ pcl::console::print_debug (FILE *stream, const char *format, ...)
   va_start (ap, format);
   vfprintf (stream, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stream);
 }
 
@@ -381,7 +381,7 @@ namespace pcl
   {
     static bool s_NeedVerbosityInit = true;
 #ifdef VERBOSITY_LEVEL_ALWAYS
-  static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_ALWAYS; 
+  static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_ALWAYS;
 #elif defined VERBOSITY_LEVEL_ERROR
   static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_ERROR;
 #elif defined VERBOSITY_LEVEL_WARN
@@ -389,9 +389,9 @@ namespace pcl
 #elif defined VERBOSITY_LEVEL_DEBUG
   static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_DEBUG;
 #elif defined VERBOSITY_LEVEL_VERBOSE
-  static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_VERBOSE; 
-#else 
-  static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_INFO; 
+  static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_VERBOSE;
+#else
+  static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_INFO;
 #endif
   }
 }
@@ -416,15 +416,15 @@ bool
 pcl::console::isVerbosityLevelEnabled (pcl::console::VERBOSITY_LEVEL level)
 {
   if (s_NeedVerbosityInit) pcl::console::initVerbosityLevel ();
-  return level <= s_VerbosityLevel;  
+  return level <= s_VerbosityLevel;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
-bool 
+bool
 pcl::console::initVerbosityLevel ()
 {
 #ifdef VERBOSITY_LEVEL_ALWAYS
-  s_VerbosityLevel = pcl::console::L_ALWAYS; 
+  s_VerbosityLevel = pcl::console::L_ALWAYS;
 #elif defined VERBOSITY_LEVEL_ERROR
   s_VerbosityLevel = pcl::console::L_ERROR;
 #elif defined VERBOSITY_LEVEL_WARN
@@ -432,8 +432,8 @@ pcl::console::initVerbosityLevel ()
 #elif defined VERBOSITY_LEVEL_DEBUG
   s_VerbosityLevel = pcl::console::L_DEBUG;
 #elif defined VERBOSITY_LEVEL_VERBOSE
-  s_VerbosityLevel = pcl::console::L_VERBOSE; 
-#else 
+  s_VerbosityLevel = pcl::console::L_VERBOSE;
+#else
   s_VerbosityLevel = pcl::console::L_INFO; // Default value
 #endif
 
@@ -457,7 +457,7 @@ pcl::console::initVerbosityLevel ()
 }
 
 ////////////////////////////////////////////////////////////////////////////////
-void 
+void
 pcl::console::print (pcl::console::VERBOSITY_LEVEL level, FILE *stream, const char *format, ...)
 {
   if (!isVerbosityLevelEnabled (level)) return;
@@ -484,12 +484,12 @@ pcl::console::print (pcl::console::VERBOSITY_LEVEL level, FILE *stream, const ch
   va_start (ap, format);
   vfprintf (stream, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stream);
 }
 
 ////////////////////////////////////////////////////////////////////////////////
-void 
+void
 pcl::console::print (pcl::console::VERBOSITY_LEVEL level, const char *format, ...)
 {
   if (!isVerbosityLevelEnabled (level)) return;
@@ -511,13 +511,13 @@ pcl::console::print (pcl::console::VERBOSITY_LEVEL level, const char *format, ..
     default:
       break;
   }
-  
+
   va_list ap;
 
   va_start (ap, format);
   vfprintf (stream, format, ap);
   va_end (ap);
-  
+
   reset_text_color (stream);
 
 }
index 91ba59bf5fcf89fffb758e2dacfea874540651a5..2ae3c432a4b17604092131dec3ff5214c8703329 100644 (file)
@@ -113,6 +113,8 @@ RangeImage::RangeImage () :
   unobserved_point.range = -std::numeric_limits<float>::infinity ();
 }
 
+RangeImage::~RangeImage () = default;
+
 /////////////////////////////////////////////////////////////////////////
 void
 RangeImage::reset ()
@@ -238,7 +240,7 @@ RangeImage::cropImage (int borderSize, int top, int right, int bottom, int left)
   width = right-left+1; height = bottom-top+1;
   image_offset_x_ = left+oldRangeImage.image_offset_x_;
   image_offset_y_ = top+oldRangeImage.image_offset_y_;
-  points.resize (width*height);
+  points.resize (static_cast<std::size_t>(width)*static_cast<std::size_t>(height));
   
   //std::cout << oldRangeImage.width<<"x"<<oldRangeImage.height<<" -> "<<width<<"x"<<height<<"\n";
   
@@ -289,9 +291,9 @@ RangeImage::getRangesArray () const
 void 
 RangeImage::getIntegralImage (float*& integral_image, int*& valid_points_num_image) const
 {
-  integral_image = new float[width*height];
+  integral_image = new float[static_cast<std::size_t>(width)*static_cast<std::size_t>(height)];
   float* integral_image_ptr = integral_image;
-  valid_points_num_image = new int[width*height];
+  valid_points_num_image = new int[static_cast<std::size_t>(width)*static_cast<std::size_t>(height)];
   int* valid_points_num_image_ptr = valid_points_num_image;
   for (int y = 0; y < static_cast<int> (height); ++y)
   {
@@ -350,7 +352,7 @@ RangeImage::getHalfImage (RangeImage& half_image) const
   half_image.height = height/2;
   half_image.is_dense = is_dense;
   half_image.clear ();
-  half_image.resize (half_image.width*half_image.height);
+  half_image.resize (half_image.widthhalf_image.height);
   
   int src_start_x = 2*half_image.image_offset_x_ - image_offset_x_,
       src_start_y = 2*half_image.image_offset_y_ - image_offset_y_;
@@ -394,7 +396,7 @@ RangeImage::getSubImage (int sub_image_image_offset_x, int sub_image_image_offse
   sub_image.height = sub_image_height;
   sub_image.is_dense = is_dense;
   sub_image.clear ();
-  sub_image.resize (sub_image.width*sub_image.height);
+  sub_image.resize (sub_image.widthsub_image.height);
   
   int src_start_x = combine_pixels*sub_image.image_offset_x_ - image_offset_x_,
       src_start_y = combine_pixels*sub_image.image_offset_y_ - image_offset_y_;
index 206288016eae85329629927be400e27219a05f8e..0d513d4bba069dc0869782a637a7e2cdb3aa76a9 100644 (file)
@@ -69,7 +69,7 @@ namespace pcl
     focal_length_x_reciprocal_ = focal_length_y_reciprocal_ = 1.0f / focal_length_x_;
     center_x_ = static_cast<float> (di_width)  / static_cast<float> (2 * skip);
     center_y_ = static_cast<float> (di_height) / static_cast<float> (2 * skip);
-    points.resize (width*height);
+    points.resize (static_cast<std::size_t>(width)*static_cast<std::size_t>(height));
     
     //std::cout << PVARN (*this);
     
@@ -130,7 +130,7 @@ namespace pcl
     focal_length_y_reciprocal_ = 1.0f / focal_length_y_;
     center_x_ = static_cast<float> (di_center_x) / static_cast<float> (skip);
     center_y_ = static_cast<float> (di_center_y) / static_cast<float> (skip);
-    points.resize (width * height);
+    points.resize (static_cast<std::size_t>(width) * static_cast<std::size_t>(height));
     
     for (int y=0; y < static_cast<int> (height); ++y)
     {
@@ -176,7 +176,7 @@ namespace pcl
     focal_length_y_reciprocal_ = 1.0f / focal_length_y_;
     center_x_ = static_cast<float> (di_center_x) / static_cast<float> (skip);
     center_y_ = static_cast<float> (di_center_y) / static_cast<float> (skip);
-    points.resize (width * height);
+    points.resize (static_cast<std::size_t>(width) * static_cast<std::size_t>(height));
 
     for (int y = 0; y < static_cast<int> (height); ++y)
     {
index c327f95e5dce054539630d78a4852b767f379fbe..ed1c888f8064d2ae3740347b51a69ea2d5ee9c6b 100644 (file)
@@ -2,7 +2,7 @@ set(SUBSYS_NAME cuda)
 set(SUBSYS_DESC "Point cloud CUDA libraries")
 set(SUBSYS_DEPS)
 
-option(BUILD_CUDA "Build the CUDA-related subsystems" ${DEFAULT})
+option(BUILD_CUDA "Build the CUDA-related subsystems" OFF)
 
 if(NOT (BUILD_CUDA AND CUDA_FOUND))
   return()
index a8190839eb65c277e1dbc5b1af62b218d703ca72..f15ad2765729e1bbb2cd135e6987026b6a9acfdc 100644 (file)
@@ -10,7 +10,6 @@ if(NOT VTK_FOUND)
 else()
   set(DEFAULT TRUE)
   set(REASON)
-  include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 endif()
 
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
index c61c03364f2435d64e3f532ae11ded0af329458f..33157b5305e8cb650843cac82dfb6d99283e1ef1 100644 (file)
@@ -49,6 +49,7 @@
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
 #include <pcl/pcl_macros.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/io/openni_grabber.h>
 #include <pcl/io/pcd_grabber.h>
 #include <pcl/visualization/cloud_viewer.h>
@@ -61,8 +62,6 @@
 #include <Eigen/Core>
 #include <Eigen/Geometry>
 
-#include <boost/filesystem.hpp>
-
 #include <functional>
 #include <iostream>
 #include <mutex>
@@ -273,7 +272,7 @@ class MultiRansac
       //bool repeat = false;
 
       //std::string path = "./pcl_logo.pcd";
-      //if (path.empty() || !boost::filesystem::exists (path))
+      //if (path.empty() || !pcl_fs::exists (path))
       //{
       //  std::cerr << "did not find file" << std::endl;
       //}
index 2c4c119afa0af15520a42d0da7e8baf0938d5e7b..2524242b5daca0fad90a4f9c8f2154883699d71d 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_PATH cuda/common)
 set(SUBSYS_DESC "Point cloud CUDA common library")
 set(SUBSYS_DEPS)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ON)
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
@@ -28,8 +27,8 @@ set(common_incs
     include/pcl/cuda/common/point_type_rgb.h
     )
 
-include_directories(./include)
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
+PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME})
 set(EXT_DEPS CUDA)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC "${SUBSYS_DESC}"
     PCL_DEPS "${SUBSYS_DEPS}" EXT_DEPS "" HEADER_ONLY)
index 7d2710297086f1ec1ad8665ecca1caeab96c3906..cc1bdfe283bc35d0a0fe01591c48c59e454a98d4 100644 (file)
@@ -5,7 +5,6 @@ set(SUBSYS_DEPS cuda_common io common)
 
 # ---[ Point Cloud Library - pcl/cuda/io
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
@@ -24,9 +23,8 @@ set(incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
-target_link_libraries(${LIB_NAME} pcl_common)
+target_link_libraries(${LIB_NAME} pcl_common pcl_io pcl_cuda_common)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
index fcf78689437d40a763e21da2131efe48a91d8667..da89395110544addfa7d2271f2037094260c6f58 100644 (file)
@@ -6,7 +6,6 @@ set(SUBSYS_EXT_DEPS openni)
 
 # ---[ Point Cloud Library - pcl/cuda/io
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF)
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS ${SUBSYS_EXT_DEPS})
@@ -35,9 +34,8 @@ set(incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
-target_link_libraries(${LIB_NAME} pcl_common)
+target_link_libraries(${LIB_NAME} pcl_common pcl_io pcl_cuda_common)
 
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${SUBSYS_EXT_DEPS})
 
index 42cdc30c875b0c355c37e7587d20d52e3643a3a4..59455e4228f9b69bd54700cdd1ce05c8892c7e32 100644 (file)
@@ -5,7 +5,6 @@ set(SUBSYS_DEPS cuda_common io common)
 
 # ---[ Point Cloud Library - pcl/cuda/io
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
@@ -33,7 +32,6 @@ set(incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
 target_link_libraries("${LIB_NAME}" pcl_cuda_features)
 
index 38a17aa490f16b3a4bc54026c6e349c578393059..d32560f84443622bd7611bb1fe49e2aa05212839 100644 (file)
@@ -5,7 +5,6 @@ set(SUBSYS_DEPS cuda_common io common)
 
 # ---[ Point Cloud Library - pcl/cuda/io
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
@@ -25,9 +24,8 @@ set(srcs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
-target_link_libraries(${LIB_NAME} pcl_common)
+target_link_libraries(${LIB_NAME} pcl_common pcl_io pcl_cuda_common)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
index 93d4a1a1f18e03c5405b45134a784b895f504188..d89455457c815358baa344258653e5138161d508 100644 (file)
@@ -98,7 +98,7 @@ development that everyone should follow:
 
 Committing changes to the git master
 ------------------------------------
-In order to oversee the commit messages more easier and that the changelist looks homogenous please keep the following format:
+In order to oversee the commit messages more easier and that the changelist looks homogeneous please keep the following format:
 
 "* <fixed|bugfix|changed|new> X in @<classname>@ (#<bug number>)" 
 
index 7a7624b23fb96c1da6982fe77582e2c3095ea8f8..e93ef5bf56309083ced13c9e0fc86cde5c00ac2d 100644 (file)
@@ -132,7 +132,7 @@ CMake window. Let's check also the `Advanced` checkbox to show some advanced CMa
 variable value, we can either browse the CMake variables to look for it, or we can use the `Search:` field to type the variable name.
 
 .. image:: images/windows/cmake_grouped_advanced.png
-    :alt: CMake groupped and advanced variables
+    :alt: CMake grouped and advanced variables
     :align: center
        
 Let's check whether CMake did actually find the needed third party dependencies or not :
@@ -332,3 +332,6 @@ Using PCL
 We finally managed to compile the Point Cloud Library (PCL) as binaries for
 Windows. You can start using them in your project by following the
 :ref:`using_pcl_pcl_config` tutorial. 
+
+.. note::
+       You may get errors when your program is linked if you use specific point types that are not used so often (so for example `pcl::PointXYZ` and `pcl::PointXYZI` are usually not affected). Of course, the first thing you should check is whether you correctly link to all PCL libraries (`target_link_libraries(<my_executable> ${PCL_LIBRARIES})` in CMake). The next thing you can try is adding `#define PCL_NO_PRECOMPILE` before including any PCL headers. The background is that on Windows, PCL is always compiled with `PCL_ONLY_CORE_POINT_TYPES` enabled, otherwise some PCL modules (e.g. pcl_features) would fail to build due to limitations of the Windows linker. The effect is that the templated classes are only instantiated for some commonly used point types, not for all. For further explanations, see the :ref:`adding_custom_ptype` tutorial.
index 80782c9bbf928ac0705c400567f153c3069ec1f3..024b685dec59edb1ade2acb16840477002afa9a7 100644 (file)
@@ -107,7 +107,7 @@ You will see something similar to::
   1 [20.000000%].
   [pcl::IterativeClosestPoint::computeTransformation] Convergence reached.
   Number of iterations: 1 out of 0. Transformation difference: 0.700001
-  has converged:1 score: 1.95122e-14
+  ICP has converged, score: 1.95122e-14
             1  4.47035e-08 -3.25963e-09          0.7
   2.98023e-08            1 -1.08499e-07 -2.98023e-08
   1.30385e-08 -1.67638e-08            1  1.86265e-08
index cf85d9ec5d64dfb240ca738c487304f29c354c5f..5363612ba7202f29d005e7450fc0dd53491524f7 100644 (file)
@@ -110,4 +110,4 @@ You should see results similar those below as well as a visualization of the ali
   Loaded 112586 data points from room_scan1.pcd
   Loaded 112624 data points from room_scan2.pcd
   Filtered cloud contains 12433 data points from room_scan2.pcd
-  Normal Distributions Transform has converged:1 score: 0.638694
+  Normal Distributions Transform has converged, score: 0.638694
index f97ebd747c84063132b6bba8deeab11e1e99920d..33d40cbe70236bada4f4bb74951fad4f6440564d 100644 (file)
@@ -88,7 +88,7 @@ will install PCL with default options as well as default triplet type (ie. x86).
 .. note::
 
   If there are new features or bugfixes that are not yet part of a release,
-  you can try to use --head, which downloads the master of PCL.
+  you can try to use `--head`, which downloads the master of PCL.
   
 You can see the available PCL version and options in VCPKG `here <https://github.com/microsoft/vcpkg/blob/master/ports/pcl/vcpkg.json>`_.
 
@@ -100,6 +100,9 @@ And all features:
 
   ./vcpkg install pcl[*]
 
+.. note::
+  If you want to use anything from the PCL visualization module (like the `PCLVisualizer`  for example), you need to explicitly request this from vcpkg by `./vcpkg install pcl[visualization]` or `./vcpkg install pcl[*]` (it is disabled by default).
+
 If you want to install with a different triplet type, the easiest way is:
 
   ./vcpkg install pcl --triplet triplet_type
@@ -136,6 +139,9 @@ Find PCL using CMake
 
 To use PCL in CMake project, take a look at Kunal Tyagi's minimal example `in this repository <https://github.com/kunaltyagi/pcl-cmake-minimum>`_
 
+.. note::
+       You may get errors when your program is linked if you use specific point types that are not used so often (so for example `pcl::PointXYZ` and `pcl::PointXYZI` are usually not affected). Of course, the first thing you should check is whether you correctly link to all PCL libraries (`target_link_libraries(<my_executable> ${PCL_LIBRARIES})` in CMake). The next thing you can try is adding `#define PCL_NO_PRECOMPILE` before including any PCL headers. The background is that on Windows, PCL is always compiled with `PCL_ONLY_CORE_POINT_TYPES` enabled, otherwise some PCL modules (e.g. pcl_features) would fail to build due to limitations of the Windows linker. The effect is that the templated classes are only instantiated for some commonly used point types, not for all. For further explanations, see the :ref:`adding_custom_ptype` tutorial.
+
 
 Install PCL dependencies for contributions
 ==========================================
index 2bcb0a174b697ef787f628363ed8d7f374d4a70f..4119d93b84ede34285601743f62995f988b821c1 100644 (file)
@@ -25,7 +25,7 @@ main (int argc, char *argv[])
   if (argc < 3)
   {
     printf ("\nUsage: pcl_example_nurbs_fitting_surface pcd<PointXYZ>-in-file 3dm-out-file\n\n");
-    exit (0);
+    exit (EXIT_FAILURE);
   }
   pcd_file = argv[1];
   file_3dm = argv[2];
index 6d4d10a698493a0ad6a04a609cba1910f3d8b14a..1904f620226d3fe97c2e096f78381a2d12f7274b 100644 (file)
@@ -27,7 +27,7 @@ typedef pcl::PointXYZ PointT;
 /** @brief Convenience typedef */
 typedef pcl::PointCloud<PointT> PointCloudT;
 
-/** @brief Convenience typdef for the Ensenso grabber callback */
+/** @brief Convenience typedef for the Ensenso grabber callback */
 typedef std::pair<pcl::PCLImage, pcl::PCLImage> PairOfImages;
 typedef pcl::shared_ptr<PairOfImages> PairOfImagesPtr;
 
index b9f2b423846d7218a415d6008845abb90a251432..562e2edbc272255ae40327475dcd1a647b6a2884 100644 (file)
@@ -3,23 +3,23 @@
 #include <string>
 #include <sstream>
 #include <iostream>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/visualization/pcl_visualizer.h>
-#include <boost/filesystem.hpp>
+
 #include <boost/algorithm/string.hpp> // for split, is_any_of
-namespace bf = boost::filesystem;
 
 inline void
-getModelsInDirectory (bf::path & dir, std::string & rel_path_so_far, std::vector<std::string> & relative_paths)
+getModelsInDirectory (pcl_fs::path & dir, std::string & rel_path_so_far, std::vector<std::string> & relative_paths)
 {
-  for (const auto& dir_entry : bf::directory_iterator(dir))
+  for (const auto& dir_entry : pcl_fs::directory_iterator(dir))
   {
     //check if its a directory, then get models in it
-    if (bf::is_directory (dir_entry))
+    if (pcl_fs::is_directory (dir_entry))
     {
       std::string so_far = rel_path_so_far + dir_entry.path ().filename ().string () + "/";
-      bf::path curr_path = dir_entry.path ();
+      pcl_fs::path curr_path = dir_entry.path ();
       getModelsInDirectory (curr_path, so_far, relative_paths);
     }
     else
@@ -189,7 +189,7 @@ main (int argc, char ** argv)
 
   std::string directory (argv[1]);
   //Find all raw* files in input_directory
-  bf::path dir_path = directory;
+  pcl_fs::path dir_path = directory;
   std::vector < std::string > files;
   std::string start = "";
   getModelsInDirectory (dir_path, start, files);
index b9f2b423846d7218a415d6008845abb90a251432..562e2edbc272255ae40327475dcd1a647b6a2884 100644 (file)
@@ -3,23 +3,23 @@
 #include <string>
 #include <sstream>
 #include <iostream>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/visualization/pcl_visualizer.h>
-#include <boost/filesystem.hpp>
+
 #include <boost/algorithm/string.hpp> // for split, is_any_of
-namespace bf = boost::filesystem;
 
 inline void
-getModelsInDirectory (bf::path & dir, std::string & rel_path_so_far, std::vector<std::string> & relative_paths)
+getModelsInDirectory (pcl_fs::path & dir, std::string & rel_path_so_far, std::vector<std::string> & relative_paths)
 {
-  for (const auto& dir_entry : bf::directory_iterator(dir))
+  for (const auto& dir_entry : pcl_fs::directory_iterator(dir))
   {
     //check if its a directory, then get models in it
-    if (bf::is_directory (dir_entry))
+    if (pcl_fs::is_directory (dir_entry))
     {
       std::string so_far = rel_path_so_far + dir_entry.path ().filename ().string () + "/";
-      bf::path curr_path = dir_entry.path ();
+      pcl_fs::path curr_path = dir_entry.path ();
       getModelsInDirectory (curr_path, so_far, relative_paths);
     }
     else
@@ -189,7 +189,7 @@ main (int argc, char ** argv)
 
   std::string directory (argv[1]);
   //Find all raw* files in input_directory
-  bf::path dir_path = directory;
+  pcl_fs::path dir_path = directory;
   std::vector < std::string > files;
   std::string start = "";
   getModelsInDirectory (dir_path, start, files);
index d45ab78c837b38387ef9ec2d4785ddb5a516db68..202b353826ea442b3d5e2eaa3e8a9d3d07ee3291 100644 (file)
@@ -40,7 +40,7 @@ int
   pcl::PointCloud<pcl::PointXYZ> Final;
   icp.align(Final);
 
-  std::cout << "has converged:" << icp.hasConverged() << " score: " <<
+  std::cout << "ICP has " << (icp.hasConverged()?"converged":"not converged") << ", score: " <<
   icp.getFitnessScore() << std::endl;
   std::cout << icp.getFinalTransformation() << std::endl;
 
index b5a525d25da9d433e845afb93bb9e4912c43f52b..732eb408fabc6337a6da9d4ec904f6a49798a799 100644 (file)
@@ -69,8 +69,8 @@ main ()
   pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud (new pcl::PointCloud<pcl::PointXYZ>);
   ndt.align (*output_cloud, init_guess);
 
-  std::cout << "Normal Distributions Transform has converged:" << ndt.hasConverged ()
-            << " score: " << ndt.getFitnessScore () << std::endl;
+  std::cout << "Normal Distributions Transform has " << (ndt.hasConverged ()?"converged":"not converged")
+            << ", score: " << ndt.getFitnessScore () << std::endl;
 
   // Transforming unfiltered, input cloud using found transform.
   pcl::transformPointCloud (*input_cloud, *output_cloud, ndt.getFinalTransformation ());
index 5ecb2325af5f34f036967364776f611e2d1e6bec..01babb17b4bce1d13eefc754e1781384b262daa8 100644 (file)
@@ -1,8 +1,9 @@
 #include <pcl/point_types.h>
 #include <pcl/point_cloud.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/io/pcd_io.h>
-#include <boost/filesystem.hpp>
+
 #include <flann/flann.h>
 #include <flann/io/hdf5.h>
 #include <fstream>
@@ -15,7 +16,7 @@ typedef std::pair<std::string, std::vector<float> > vfh_model;
   * \param vfh the resultant VFH model
   */
 bool
-loadHist (const boost::filesystem::path &path, vfh_model &vfh)
+loadHist (const pcl_fs::path &path, vfh_model &vfh)
 {
   int vfh_idx;
   // Load the file as a PCD
@@ -63,22 +64,22 @@ loadHist (const boost::filesystem::path &path, vfh_model &vfh)
   * \param models the resultant vector of histogram models
   */
 void
-loadFeatureModels (const boost::filesystem::path &base_dir, const std::string &extension, 
+loadFeatureModels (const pcl_fs::path &base_dir, const std::string &extension, 
                    std::vector<vfh_model> &models)
 {
-  if (!boost::filesystem::exists (base_dir) && !boost::filesystem::is_directory (base_dir))
+  if (!pcl_fs::exists (base_dir) && !pcl_fs::is_directory (base_dir))
     return;
 
-  for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it)
+  for (pcl_fs::directory_iterator it (base_dir); it != pcl_fs::directory_iterator (); ++it)
   {
-    if (boost::filesystem::is_directory (it->status ()))
+    if (pcl_fs::is_directory (it->status ()))
     {
       std::stringstream ss;
       ss << it->path ();
       pcl::console::print_highlight ("Loading %s (%lu models loaded so far).\n", ss.str ().c_str (), (unsigned long)models.size ());
       loadFeatureModels (it->path (), extension, models);
     }
-    if (boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension)
+    if (pcl_fs::is_regular_file (it->status ()) && it->path ().extension ().string () == extension)
     {
       vfh_model m;
       if (loadHist (base_dir / it->path ().filename (), m))
index e377394bcd62f1fad09f784120bdbe45ae260479..b168d4f43e6ea9cd8e6dd29d70c66214bbf078d5 100644 (file)
@@ -3,6 +3,7 @@
 #include <pcl/common/common.h>
 #include <pcl/common/centroid.h> // for compute3DCentroid
 #include <pcl/visualization/pcl_visualizer.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/print.h>
 #include <pcl/io/pcd_io.h>
@@ -10,7 +11,7 @@
 #include <limits>
 #include <flann/flann.h>
 #include <flann/io/hdf5.h>
-#include <boost/filesystem.hpp>
+
 #include <boost/algorithm/string/replace.hpp> // for replace_last
 typedef std::pair<std::string, std::vector<float> > vfh_model;
 
@@ -19,7 +20,7 @@ typedef std::pair<std::string, std::vector<float> > vfh_model;
   * \param vfh the resultant VFH model
   */
 bool
-loadHist (const boost::filesystem::path &path, vfh_model &vfh)
+loadHist (const pcl_fs::path &path, vfh_model &vfh)
 {
   int vfh_idx;
   // Load the file as a PCD
@@ -152,7 +153,7 @@ main (int argc, char** argv)
   flann::Matrix<float> k_distances;
   flann::Matrix<float> data;
   // Check if the data has already been saved to disk
-  if (!boost::filesystem::exists ("training_data.h5") || !boost::filesystem::exists ("training_data.list"))
+  if (!pcl_fs::exists ("training_data.h5") || !pcl_fs::exists ("training_data.list"))
   {
     pcl::console::print_error ("Could not find training data models files %s and %s!\n", 
         training_data_h5_file_name.c_str (), training_data_list_file_name.c_str ());
@@ -167,7 +168,7 @@ main (int argc, char** argv)
   }
 
   // Check if the tree index has already been saved to disk
-  if (!boost::filesystem::exists (kdtree_idx_file_name))
+  if (!pcl_fs::exists (kdtree_idx_file_name))
   {
     pcl::console::print_error ("Could not find kd-tree index in file %s!", kdtree_idx_file_name.c_str ());
     return (-1);
index 41b9b626c0950395bd73aa9d9de237ca2411272b..095fe6ec69f66bf5692c0829b3b468169b22a4b6 100644 (file)
@@ -110,21 +110,21 @@ Once all VFH features have been loaded, we convert them to FLANN format, using:
 
 .. literalinclude:: sources/vfh_recognition/build_tree.cpp
    :language: cpp
-   :lines: 113-118
+   :lines: 114-119
 
 
 Since we're lazy, and we want to use this data (and not reload it again by crawling the directory structure in the testing phase), we dump the data to disk:
 
 .. literalinclude:: sources/vfh_recognition/build_tree.cpp
    :language: cpp
-   :lines: 120-126
+   :lines: 121-127
 
 
 Finally, we create the KdTree, and save its structure to disk:
 
 .. literalinclude:: sources/vfh_recognition/build_tree.cpp
    :language: cpp
-   :lines: 129-133
+   :lines: 130-134
 
 
 Here we will use a ``LinearIndex``, which does a brute-force search using a
@@ -164,7 +164,7 @@ In lines:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 132-143
+   :lines: 134-145
 
 
 we load the first given user histogram (and ignore the rest). Then we proceed
@@ -177,7 +177,7 @@ In lines:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 162-163
+   :lines: 164-165
 
    
 we load the training data from disk, together with the list of file names that
@@ -185,7 +185,7 @@ we previously stored in ``build_tree.cpp``. Then, we read the kd-tree and rebuil
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 176-177
+   :lines: 178-179
 
    
 Here we need to make sure that we use the **exact** distance metric
@@ -194,53 +194,53 @@ the tree. The most important part of the code comes here:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 178
+   :lines: 180
 
 Inside ``nearestKSearch``, we first convert the query point to FLANN format:
 
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 75-76
+   :lines: 77-78
 
 Followed by obtaining the resultant nearest neighbor indices and distances for the query in:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 77-80
+   :lines: 79-82
 
 
 Lines:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 177-191
+   :lines: 179-193
 
 create a ``PCLVisualizer`` object, and sets up a set of different viewports (e.g., splits the screen into different chunks), which will be enabled in:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 211
+   :lines: 213
 
 Using the file names representing the models that we previously obtained in
 ``loadFileList``, we proceed at loading the model file names using:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 219-226
+   :lines: 221-228
 
 For visualization purposes, we demean the point cloud by computing its centroid and then subtracting it:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 238-243
+   :lines: 240-245
 
    
 Finally we check if the distance obtained by ``nearestKSearch`` is larger than the user given threshold, and if it is, we display a red line over the cloud that is being rendered in the viewport:
 
 .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp
    :language: cpp
-   :lines: 252-258
+   :lines: 254-260
 
 
 Compiling and running the code
index 971d9a8f78ebdfb7fd7cd5d614c39cb716b83987..706be8f79700b40391d18143bea5b1756d500e3f 100644 (file)
@@ -249,7 +249,7 @@ Kd-tree
 
        A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/kdtree_search.html>`_.
 
-       The *kdtree* library provides the kd-tree data-structure, using `FLANN <http://www.cs.ubc.ca/~mariusm/index.php/FLANN/FLANN>`_, that allows for fast `nearest neighbor searches <https://en.wikipedia.org/wiki/Nearest_neighbor_search>`_.
+       The *kdtree* library provides the kd-tree data-structure, using `FLANN <http://www.cs.ubc.ca/research/flann/>`_, that allows for fast `nearest neighbor searches <https://en.wikipedia.org/wiki/Nearest_neighbor_search>`_.
 
        A `Kd-tree <https://en.wikipedia.org/wiki/Kd-tree>`_ (k-dimensional tree) is a space-partitioning data structure that stores a set of k-dimensional points in a tree structure that enables efficient range searches and nearest neighbor searches. Nearest neighbor searches are a core operation when working with point cloud data and can be used to find correspondences between groups of points or feature descriptors or to define the local neighborhood around a point or points.
 
@@ -261,7 +261,7 @@ Kd-tree
 
 **Documentation:** https://pointclouds.org/documentation/group__kdtree.html
 
-**Tutorials:** http://pointclouds.org/documentation/tutorials/#kdtree-tutorial
+**Tutorials:** https://pcl.readthedocs.io/projects/tutorials/en/master/kdtree_search.html
 
 **Interacts with:** Common_
 
@@ -291,7 +291,7 @@ Octree
 
        The *octree* library provides efficient methods for creating a hierarchical tree data structure from point cloud data. This enables spatial partitioning, downsampling and search operations on the point data set. Each octree node has either eight children or no children. The root node describes a cubic bounding box which encapsulates all points. At every tree level, this space becomes subdivided by a factor of 2 which results in an increased voxel resolution.
 
-       The *octree* implementation provides efficient nearest neighbor search routines, such as "Neighbors within Voxel Search”, “K Nearest Neighbor Search” and “Neighbors within Radius Search”. It automatically adjusts its dimension to the point data set. A set of leaf node classes provide additional functionality, such as spacial "occupancy" and "point density per voxel" checks. Functions for serialization and deserialization enable to efficiently encode the octree structure into a binary format. Furthermore, a memory pool implementation reduces expensive memory allocation and deallocation operations in scenarios where octrees needs to be created at high rate.
+       The *octree* implementation provides efficient nearest neighbor search routines, such as "Neighbors within Voxel Search”, “K Nearest Neighbor Search” and “Neighbors within Radius Search”. It automatically adjusts its dimension to the point data set. A set of leaf node classes provide additional functionality, such as spatial "occupancy" and "point density per voxel" checks. Functions for serialization and deserialization enable to efficiently encode the octree structure into a binary format. Furthermore, a memory pool implementation reduces expensive memory allocation and deallocation operations in scenarios where octrees needs to be created at high rate.
 
        The following figure illustrates the voxel bounding boxes of an octree nodes at lowest tree level. The octree voxels are surrounding every 3D point from the Stanford bunny's surface. The red dots represent the point data. This image is created with the `octree_viewer`_.
 
index d89aa99bc1154fbf7428edd4d434e73ce7aa65ad..54f7c1f8d8af72503aaa251ef8c4b23a9c5d8f47 100644 (file)
@@ -2,9 +2,7 @@ set(SUBSYS_NAME examples)
 set(SUBSYS_DESC "PCL examples")
 set(SUBSYS_DEPS common io features search kdtree octree filters keypoints segmentation sample_consensus outofcore stereo geometry surface)
 
-set(DEFAULT FALSE)
-set(REASON "Code examples are disabled by default.")
-PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ${DEFAULT} ${REASON})
+PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} OFF)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
 if(NOT build)
@@ -14,7 +12,6 @@ endif()
 # this variable will filled with all targets added with pcl_add_example
 set(PCL_EXAMPLES_ALL_TARGETS)
 
-include_directories(${PCL_INCLUDE_DIRS})
 # This looks for all examples/XXX/CMakeLists.txt
 file (GLOB examples_sbudirs */CMakeLists.txt)
 # Extract only relevant XXX and append it to PCL_EXAMPLES_SUBDIRS
@@ -41,4 +38,3 @@ else()
 endif()
 add_custom_target(${SUBSYS_TARGET_NAME} DEPENDS ${PCL_EXAMPLES_ALL_TARGETS})
 set_target_properties(${SUBSYS_TARGET_NAME} PROPERTIES FOLDER "Examples")
-
index 5f17d1562f76dbf9589aaa962af64923061d08a0..fa37267a9f60448c61f0519ba9225109f2e5c25b 100644 (file)
@@ -53,10 +53,8 @@ main ()
   CloudType::Ptr cloud (new CloudType);
   
   // Make the cloud a 10x10 grid
-  cloud->height = 10;
-  cloud->width = 10;
   cloud->is_dense = true;
-  cloud->resize(cloud->height * cloud->width);
+  cloud->resize(10, 10);
 
   // Output the (0,0) point
   std::cout << (*cloud)(0,0) << std::endl;
index d98d68cf5eb82a8ab549efc573cb19ff3dbcce7a..90e830c10f8790362649b372328149cb8302a83d 100644 (file)
@@ -46,8 +46,9 @@ int main (int argc, char *argv[])
   bool approx = false;
   constexpr double decimation = 100;
 
-  if(argc < 2){
+  if(argc < 3){
     std::cerr << "Expected 2 arguments: inputfile outputfile" << std::endl;
+    return 0;
   }
 
   ///The file to read from.
index 271296c6819c3bcfccab481e44f0c353e757237e..4f3696605a81c5249d1d9d78d75179db43de94be 100644 (file)
@@ -3,4 +3,4 @@ if(NOT BUILD_geometry)
 endif()
 
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS geometry)
-PCL_ADD_EXAMPLE(pcl_example_half_edge_mesh FILES example_half_edge_mesh.cpp LINK_WITH pcl_common)
+PCL_ADD_EXAMPLE(pcl_example_half_edge_mesh FILES example_half_edge_mesh.cpp LINK_WITH pcl_common pcl_geometry)
index bbb357f673a5ba37b7a7e4fcf74547995b730be2..c65e2c3a9c5ed8ece6c26680e9b2d5d0313106e5 100644 (file)
@@ -369,7 +369,7 @@ CPCSegmentation Parameters: \n\
   std::multimap<std::uint32_t, std::uint32_t>supervoxel_adjacency;
   super.getSupervoxelAdjacency (supervoxel_adjacency);
 
-  /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visulization)
+  /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visualization)
   pcl::PointCloud<pcl::PointNormal>::Ptr sv_centroid_normal_cloud = pcl::SupervoxelClustering<PointT>::makeSupervoxelNormalCloud (supervoxel_clusters);
 
   /// Set parameters for LCCP preprocessing and CPC (CPC inherits from LCCP, thus it includes LCCP's functionality)
index 09a811e567e5b94ed583ff417ad7d0141a5f5fb2..e7e7df3569527581c87e150c46f9f5e95da466c7 100644 (file)
@@ -296,7 +296,7 @@ LCCPSegmentation Parameters: \n\
   std::multimap<std::uint32_t, std::uint32_t> supervoxel_adjacency;
   super.getSupervoxelAdjacency (supervoxel_adjacency);
 
-  /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visulization)
+  /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visualization)
   pcl::PointCloud<pcl::PointNormal>::Ptr sv_centroid_normal_cloud = pcl::SupervoxelClustering<PointT>::makeSupervoxelNormalCloud (supervoxel_clusters);
 
   /// The Main Step: Perform LCCPSegmentation
index 11d8ec1420a606a979710ab59da591a0be30dd59..536c8d0867216f44879322284ae3fb552e437305 100644 (file)
@@ -194,7 +194,7 @@ main (int argc, char ** argv)
       return (1);
     }
  
-    cloud->points.reserve (depth_dims[0] * depth_dims[1]);
+    cloud->reserve (static_cast<std::size_t>(depth_dims[0]) * static_cast<std::size_t>(depth_dims[1]));
     cloud->width = depth_dims[0];
     cloud->height = depth_dims[1];
     cloud->is_dense = false;
index b5f902aece8b96d0c2bcc9a951d3c0d06db74018..f0a565ebccf60e39000a2d8362846032baee3c42 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME features)
 set(SUBSYS_DESC "Point cloud features library")
 set(SUBSYS_DEPS common search kdtree octree filters 2d)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
@@ -12,11 +11,7 @@ if(NOT build)
   return()
 endif()
 
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
-  "include/pcl/${SUBSYS_NAME}/eigen.h"
   "include/pcl/${SUBSYS_NAME}/board.h"
   "include/pcl/${SUBSYS_NAME}/flare.h"
   "include/pcl/${SUBSYS_NAME}/brisk_2d.h"
@@ -171,7 +166,7 @@ endif()
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
-target_link_libraries("${LIB_NAME}" pcl_common pcl_search pcl_kdtree pcl_octree pcl_filters)
+target_link_libraries("${LIB_NAME}" pcl_common pcl_2d pcl_search pcl_kdtree pcl_octree pcl_filters)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
 # Install headers
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs})
diff --git a/features/include/pcl/features/boost.h b/features/include/pcl/features/boost.h
deleted file mode 100644 (file)
index 4f49824..0000000
+++ /dev/null
@@ -1,46 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-#include <boost/property_map/property_map.hpp>
diff --git a/features/include/pcl/features/eigen.h b/features/include/pcl/features/eigen.h
deleted file mode 100644 (file)
index 5638748..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-#include <Eigen/StdVector>
-#include <Eigen/Geometry>
index 503d110c4a00b610e3cff1eddcd092df33150746..221a9444400d5c350f5f1e54692c38f33eed7294 100644 (file)
@@ -42,7 +42,7 @@
 
 #include <pcl/features/feature.h>
 #define GRIDSIZE 64
-#define GRIDSIZE_H GRIDSIZE/2
+#define GRIDSIZE_H (GRIDSIZE/2)
 #include <vector>
 
 namespace pcl
index 8d22f39bd8718246fd0e79c8f4e0632e0c7a2147..cb06ac9f18e100396347a25b87d8b4b13931b684 100644 (file)
@@ -107,7 +107,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
     points_ += number;
 
   // set up the patterns
-  pattern_points_ = new BriskPatternPoint[points_*scales_*n_rot_];
+  pattern_points_ = new BriskPatternPoint[static_cast<std::size_t>(points_)*static_cast<std::size_t>(scales_)*static_cast<std::size_t>(n_rot_)];
   BriskPatternPoint* pattern_iterator = pattern_points_;
 
   // define the scale discretization:
@@ -223,7 +223,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
   const float yf = brisk_point.y + key_y;
   const int x = static_cast<int>(xf);
   const int y = static_cast<int>(yf);
-  const int& imagecols = image_width;
+  const std::ptrdiff_t imagecols = image_width;
 
   // get the sigma:
   const float sigma_half = brisk_point.sigma;
@@ -271,7 +271,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
   const int scaling2 = static_cast<int> (static_cast<float>(scaling) * area / 1024.0f);
 
   // the integral image is larger:
-  const int integralcols = imagecols + 1;
+  const std::ptrdiff_t integralcols = image_width + 1;
 
   // calculate borders
   const float x_1 = xf - sigma_half;
@@ -450,7 +450,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
   const auto height = static_cast<index_t>(input_cloud_->height);
 
   // destination for intensity data; will be forwarded to BRISK
-  std::vector<unsigned char> image_data (width*height);
+  std::vector<unsigned char> image_data (static_cast<std::size_t>(width)*static_cast<std::size_t>(height));
 
   for (std::size_t i = 0; i < image_data.size (); ++i)
     image_data[i] = static_cast<unsigned char> (intensity_ ((*input_cloud_)[i]));
@@ -512,7 +512,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
 
   // first, calculate the integral image over the whole image:
   // current integral image
-  std::vector<int> integral ((width+1)*(height+1), 0);    // the integral image
+  std::vector<int> integral (static_cast<std::size_t>(width+1)*static_cast<std::size_t>(height+1), 0);    // the integral image
 
   for (index_t row_index = 1; row_index < height; ++row_index)
   {
index 975bb98cc81e0aeb7e9b63cfaaf2b2ee5fae293e..94f9c3a61f3833042a3d6c0786e97b2994417e0c 100755 (executable)
@@ -42,6 +42,7 @@
 #define PCL_FEATURES_IMPL_CPPF_H_
 
 #include <pcl/features/cppf.h>
+#include <pcl/search/kdtree.h> // for KdTree
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointInT, typename PointNT, typename PointOutT>
index d5df1e6551bf8219c72118222033a1b4e4644aa8..5517330545636aa3005abe390681f82449a17b67 100644 (file)
@@ -44,6 +44,7 @@
 #include <pcl/features/cvfh.h>
 #include <pcl/features/normal_3d.h>
 #include <pcl/common/centroid.h>
+#include <pcl/search/kdtree.h> // for KdTree
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template<typename PointInT, typename PointNT, typename PointOutT> void
@@ -96,6 +97,8 @@ pcl::CVFHEstimation<PointInT, PointNT, PointOutT>::extractEuclideanClustersSmoot
               static_cast<std::size_t>(normals.size()));
     return;
   }
+  // If tree gives sorted results, we can skip the first one because it is the query point itself
+  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
 
   // Create a bool vector of processed point indices, and initialize it to false
   std::vector<bool> processed (cloud.size (), false);
@@ -124,8 +127,7 @@ pcl::CVFHEstimation<PointInT, PointNT, PointOutT>::extractEuclideanClustersSmoot
         continue;
       }
 
-      // skip index 0, since nn_indices[0] == idx, worth it?
-      for (std::size_t j = 1; j < nn_indices.size (); ++j)
+      for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
       {
         if (processed[nn_indices[j]]) // Has this point been processed before ?
           continue;
index f36826f5d193940fea739f080b6ca39ab33f9f3c..d8695be362dc1fc800d5869b78568e222ba637e3 100644 (file)
@@ -53,7 +53,7 @@ pcl::ESFEstimation<PointInT, PointOutT>::computeESF (
     PointCloudIn &pc, std::vector<float> &hist)
 {
   const int binsize = 64;
-  unsigned int sample_size = 20000;
+  const std::size_t sample_size = 20000;
   // @TODO: Replace with c++ stdlib uniform_random_generator
   srand (static_cast<unsigned int> (time (nullptr)));
   const auto maxindex = pc.size ();
@@ -269,7 +269,7 @@ pcl::ESFEstimation<PointInT, PointOutT>::computeESF (
   //float weights[10] = {1,  1,  1,  1,  1,  1,  1,  1 , 1 ,  1};
   float weights[10] = {0.5f, 0.5f, 0.5f, 0.5f, 0.5f, 1.0f,  1.0f, 2.0f, 2.0f, 2.0f};
 
-  hist.reserve (binsize * 10);
+  hist.reserve (static_cast<std::size_t>(binsize) * 10);
   for (const float &i : h_a3_in)
     hist.push_back (i * weights[0]);
   for (const float &i : h_a3_out)
index 2f8d3c9577d5490255d7e9952d7d49b4a14bd8ab..e00f242f422cab7e2cf3c295e97d6c6afd096a3b 100644 (file)
@@ -41,6 +41,8 @@
 
 #include <pcl/features/flare.h>
 #include <pcl/common/geometry.h>
+#include <pcl/search/kdtree.h> // for KdTree
+#include <pcl/search/organized.h> // for OrganizedNeighbor
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template<typename PointInT, typename PointNT, typename PointOutT, typename SignedDistanceT> bool
index 88902cf6ddcbcc984ba85460bba8e88109995c81..a8ffd0e504536977778fea2a8892db86715f9923 100644 (file)
@@ -59,10 +59,11 @@ IntegralImage2D<DataType, Dimension>::setInput (const DataType * data, unsigned
   {
     width_  = width;
     height_ = height;
-    first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
-    finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
+    const std::size_t ii_size = static_cast<std::size_t>(width_ + 1) * static_cast<std::size_t>(height_ + 1);
+    first_order_integral_image_.resize (ii_size);
+    finite_values_integral_image_.resize (ii_size);
     if (compute_second_order_integral_images_)
-      second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
+      second_order_integral_image_.resize (ii_size);
   }
   computeIntegralImages (data, row_stride, element_stride);
 }
@@ -230,10 +231,11 @@ IntegralImage2D<DataType, 1>::setInput (const DataType * data, unsigned width,un
   {
     width_  = width;
     height_ = height;
-    first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
-    finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
+    const std::size_t ii_size = static_cast<std::size_t>(width_ + 1) * static_cast<std::size_t>(height_ + 1);
+    first_order_integral_image_.resize (ii_size);
+    finite_values_integral_image_.resize (ii_size);
     if (compute_second_order_integral_images_)
-      second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
+      second_order_integral_image_.resize (ii_size);
   }
   computeIntegralImages (data, row_stride, element_stride);
 }
index f76765a1bcc69e739f904f67c526687787431684..612a6df80a16c0c11f836065cee4730d93231e06 100644 (file)
@@ -36,6 +36,7 @@
  *
  */
 #pragma once
+#include <pcl/common/eigen.h> // for eigen33
 #include <pcl/features/integral_image_normal.h>
 
 #include <algorithm>
@@ -491,7 +492,6 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computePointNormalMirro
     Eigen::Vector3f center;
     typename IntegralImage2D<float, 3>::SecondOrderType so_elements;
     typename IntegralImage2D<float, 3>::ElementType tmp_center;
-    typename IntegralImage2D<float, 3>::SecondOrderType tmp_so_elements;
 
     center[0] = 0;
     center[1] = 0;
index a16b671942173936aef74b31e27db425b49fe755..fcb8c85f4f24b54e2fba6ba9eaff6ffb8d071045 100644 (file)
@@ -43,6 +43,7 @@
 #include <pcl/features/intensity_gradient.h>
 
 #include <pcl/common/point_tests.h> // for pcl::isFinite
+#include <pcl/common/eigen.h> // for eigen33
 
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -148,6 +149,13 @@ pcl::IntensityGradientEstimation<PointInT, PointNT, PointOutT, IntensitySelector
   std::vector<float> nn_dists (k_);
   output.is_dense = true;
 
+#ifdef _OPENMP
+  if (threads_ == 0) {
+    threads_ = omp_get_num_procs();
+    PCL_DEBUG ("[pcl::IntensityGradientEstimation::computeFeature] Setting number of threads to %u.\n", threads_);
+  }
+#endif // _OPENMP
+
   // If the data is dense, we don't need to check for NaN
   if (surface_->is_dense)
   {
index 34caf74c6155d576c7444ef2f59b9f450ae7fbf5..15fab1548056a45f182af2e4307ee29cb135186c 100644 (file)
@@ -47,6 +47,7 @@
 #include <pcl/common/io.h> // for copyPointCloud
 #include <pcl/common/common.h> // for getMaxDistance
 #include <pcl/common/transforms.h>
+#include <pcl/search/kdtree.h> // for KdTree
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template<typename PointInT, typename PointNT, typename PointOutT> void
@@ -97,6 +98,8 @@ pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::extractEuclideanClustersSm
               static_cast<std::size_t>(normals.size()));
     return;
   }
+  // If tree gives sorted results, we can skip the first one because it is the query point itself
+  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
 
   // Create a bool vector of processed point indices, and initialize it to false
   std::vector<bool> processed (cloud.size (), false);
@@ -124,7 +127,7 @@ pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::extractEuclideanClustersSm
         continue;
       }
 
-      for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx
+      for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
       {
         if (processed[nn_indices[j]]) // Has this point been processed before ?
           continue;
@@ -621,7 +624,6 @@ pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloud
     {
 
       pcl::PointIndices pi;
-      pcl::PointIndices pi_cvfh;
       pcl::PointIndices pi_filtered;
 
       clusters_.push_back (pi);
index f1828ddeb049bf7815eab8976e7d7de5a0f2d28d..280078349196d30911fd7ea482161929f1b24445 100644 (file)
@@ -171,7 +171,7 @@ pcl::PFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
   std::queue<std::pair<int, int> > empty;
   std::swap (key_list_, empty);
 
-  pfh_histogram_.setZero (nr_subdiv_ * nr_subdiv_ * nr_subdiv_);
+  pfh_histogram_.setZero (static_cast<Eigen::Index>(nr_subdiv_) * nr_subdiv_ * nr_subdiv_);
 
   // Allocate enough space to hold the results
   // \note This resize is irrelevant for a radiusSearch ().
index 18bb5baf6d87ce31ffb15038c57f3e8b958ff1f5..e14787e92bd40785df4691340cc43174e20b8b13 100644 (file)
@@ -135,7 +135,7 @@ template <typename PointInT, typename PointNT, typename PointOutT> void
 pcl::PFHRGBEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
 {
   /// nr_subdiv^3 for RGB and nr_subdiv^3 for the angular features
-  pfhrgb_histogram_.setZero (2 * nr_subdiv_ * nr_subdiv_ * nr_subdiv_);
+  pfhrgb_histogram_.setZero (static_cast<Eigen::Index>(2) * nr_subdiv_ * nr_subdiv_ * nr_subdiv_);
   pfhrgb_tuple_.setZero (7);
 
   // Allocate enough space to hold the results
index 8cdb914a9757a839906e346dd7b1cebdaea2f455..7fb8818a6452b839c8b615773b08c0ee7ead56dd 100644 (file)
@@ -43,6 +43,7 @@
 #include <pcl/features/ppf.h>
 #include <pcl/features/pfh.h>
 #include <pcl/features/pfh_tools.h> // for computePairFeatures
+#include <pcl/search/kdtree.h> // for KdTree
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointInT, typename PointNT, typename PointOutT>
index 87f74548a628239a84cd69d0af11d7e50c2eceaa..193d54d6f5644fdfcba82ba5dc5c8c9d2b24c1a1 100644 (file)
@@ -40,6 +40,7 @@
 
 #include <pcl/features/ppfrgb.h>
 #include <pcl/features/pfhrgb.h>
+#include <pcl/search/kdtree.h> // for KdTree
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointInT, typename PointNT, typename PointOutT>
index ba32ee2a18a4473c17d721b6eca6cb4370ca68d5..8c0561c41d5d6d15f3769246fc930f5c8686e351 100644 (file)
 #include <pcl/features/principal_curvatures.h>
 
 #include <pcl/common/point_tests.h> // for pcl::isFinite
+#include <pcl/common/eigen.h> // for eigen33
 
+///////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointInT, typename PointNT, typename PointOutT> void
+pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
+{
+#ifdef _OPENMP
+  if (nr_threads == 0)
+    threads_ = omp_get_num_procs();
+  else
+    threads_ = nr_threads;
+  PCL_DEBUG ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Setting number of threads to %u.\n", threads_);
+#else
+  threads_ = 1;
+  if (nr_threads != 1)
+    PCL_WARN ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n");
+#endif // _OPENMP
+}
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointInT, typename PointNT, typename PointOutT> void
@@ -51,62 +68,60 @@ pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computePointPr
       const pcl::PointCloud<PointNT> &normals, int p_idx, const pcl::Indices &indices,
       float &pcx, float &pcy, float &pcz, float &pc1, float &pc2)
 {
-  EIGEN_ALIGN16 Eigen::Matrix3f I = Eigen::Matrix3f::Identity ();
-  Eigen::Vector3f n_idx (normals[p_idx].normal[0], normals[p_idx].normal[1], normals[p_idx].normal[2]);
-  EIGEN_ALIGN16 Eigen::Matrix3f M = I - n_idx * n_idx.transpose ();    // projection matrix (into tangent plane)
+  const auto n_idx = normals[p_idx].getNormalVector3fMap();
+  EIGEN_ALIGN16 const Eigen::Matrix3f I = Eigen::Matrix3f::Identity ();
+  EIGEN_ALIGN16 const Eigen::Matrix3f M = I - n_idx * n_idx.transpose ();    // projection matrix (into tangent plane)
 
   // Project normals into the tangent plane
-  Eigen::Vector3f normal;
-  projected_normals_.resize (indices.size ());
-  xyz_centroid_.setZero ();
+  std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > projected_normals (indices.size());
+  Eigen::Vector3f xyz_centroid = Eigen::Vector3f::Zero();
   for (std::size_t idx = 0; idx < indices.size(); ++idx)
   {
-    normal[0] = normals[indices[idx]].normal[0];
-    normal[1] = normals[indices[idx]].normal[1];
-    normal[2] = normals[indices[idx]].normal[2];
-
-    projected_normals_[idx] = M * normal;
-    xyz_centroid_ += projected_normals_[idx];
+    const auto normal = normals[indices[idx]].getNormalVector3fMap();
+    projected_normals[idx] = M * normal;
+    xyz_centroid += projected_normals[idx];
   }
 
   // Estimate the XYZ centroid
-  xyz_centroid_ /= static_cast<float> (indices.size ());
+  xyz_centroid /= static_cast<float> (indices.size ());
 
   // Initialize to 0
-  covariance_matrix_.setZero ();
+  EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix = Eigen::Matrix3f::Zero();
 
   // For each point in the cloud
   for (std::size_t idx = 0; idx < indices.size (); ++idx)
   {
-    demean_ = projected_normals_[idx] - xyz_centroid_;
+    const Eigen::Vector3f demean = projected_normals[idx] - xyz_centroid;
 
-    double demean_xy = demean_[0] * demean_[1];
-    double demean_xz = demean_[0] * demean_[2];
-    double demean_yz = demean_[1] * demean_[2];
+    const double demean_xy = demean[0] * demean[1];
+    const double demean_xz = demean[0] * demean[2];
+    const double demean_yz = demean[1] * demean[2];
 
-    covariance_matrix_(0, 0) += demean_[0] * demean_[0];
-    covariance_matrix_(0, 1) += static_cast<float> (demean_xy);
-    covariance_matrix_(0, 2) += static_cast<float> (demean_xz);
+    covariance_matrix(0, 0) += demean[0] * demean[0];
+    covariance_matrix(0, 1) += static_cast<float> (demean_xy);
+    covariance_matrix(0, 2) += static_cast<float> (demean_xz);
 
-    covariance_matrix_(1, 0) += static_cast<float> (demean_xy);
-    covariance_matrix_(1, 1) += demean_[1] * demean_[1];
-    covariance_matrix_(1, 2) += static_cast<float> (demean_yz);
+    covariance_matrix(1, 0) += static_cast<float> (demean_xy);
+    covariance_matrix(1, 1) += demean[1] * demean[1];
+    covariance_matrix(1, 2) += static_cast<float> (demean_yz);
 
-    covariance_matrix_(2, 0) += static_cast<float> (demean_xz);
-    covariance_matrix_(2, 1) += static_cast<float> (demean_yz);
-    covariance_matrix_(2, 2) += demean_[2] * demean_[2];
+    covariance_matrix(2, 0) += static_cast<float> (demean_xz);
+    covariance_matrix(2, 1) += static_cast<float> (demean_yz);
+    covariance_matrix(2, 2) += demean[2] * demean[2];
   }
 
   // Extract the eigenvalues and eigenvectors
-  pcl::eigen33 (covariance_matrix_, eigenvalues_);
-  pcl::computeCorrespondingEigenVector (covariance_matrix_, eigenvalues_ [2], eigenvector_);
-
-  pcx = eigenvector_ [0];
-  pcy = eigenvector_ [1];
-  pcz = eigenvector_ [2];
-  float indices_size = 1.0f / static_cast<float> (indices.size ());
-  pc1 = eigenvalues_ [2] * indices_size;
-  pc2 = eigenvalues_ [1] * indices_size;
+  Eigen::Vector3f eigenvalues;
+  Eigen::Vector3f eigenvector;
+  pcl::eigen33 (covariance_matrix, eigenvalues);
+  pcl::computeCorrespondingEigenVector (covariance_matrix, eigenvalues [2], eigenvector);
+
+  pcx = eigenvector [0];
+  pcy = eigenvector [1];
+  pcz = eigenvector [2];
+  const float indices_size = 1.0f / static_cast<float> (indices.size ());
+  pc1 = eigenvalues [2] * indices_size;
+  pc2 = eigenvalues [1] * indices_size;
 }
 
 
@@ -123,8 +138,14 @@ pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computeFeature
   // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense
   if (input_->is_dense)
   {
+#pragma omp parallel for \
+  default(none) \
+  shared(output) \
+  firstprivate(nn_indices, nn_dists) \
+  num_threads(threads_) \
+  schedule(dynamic, chunk_size_)
     // Iterating over the entire index vector
-    for (std::size_t idx = 0; idx < indices_->size (); ++idx)
+    for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
     {
       if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
       {
@@ -142,8 +163,14 @@ pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computeFeature
   }
   else
   {
+#pragma omp parallel for \
+  default(none) \
+  shared(output) \
+  firstprivate(nn_indices, nn_dists) \
+  num_threads(threads_) \
+  schedule(dynamic, chunk_size_)
     // Iterating over the entire index vector
-    for (std::size_t idx = 0; idx < indices_->size (); ++idx)
+    for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
     {
       if (!isFinite ((*input_)[(*indices_)[idx]]) ||
           this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
index 092dbd3c09c87ff3cd4887bb0f623376c7ec8601..6ca506ecab49f8e1a9aa9070f4d11ca17d3b52f3 100644 (file)
@@ -334,7 +334,7 @@ bool RangeImageBorderExtractor::calculateMainPrincipalCurvature(int x, int y, in
         bool& beam_valid = beams_valid[beam_idx++];
         if (step==1)
         {
-          beam_valid = !(x2==x && y2==y);
+          beam_valid = (x2!=x || y2!=y);
         }
         else
           if (!beam_valid)
index 510153637dfb4b26f8275d241131486059d0f599..f454f75ca9a2ca2eefbec6c7b042fbe38f40db62 100644 (file)
@@ -283,9 +283,9 @@ pcl::ROPSEstimation <PointInT, PointOutT>::computeLRF (const PointInT& point, co
   }
 
   if (std::abs (total_area) < std::numeric_limits <float>::epsilon ())
-    total_area = 1.0f / total_area;
-  else
     total_area = 1.0f;
+  else
+    total_area = 1.0f / total_area;
 
   Eigen::Matrix3f overall_scatter_matrix;
   overall_scatter_matrix.setZero ();
index a28123b3e03c9a0da2274117e41ff4735243cc15..cde3a58d1ee0545c8bad04f7dec6454dd57e38da 100644 (file)
@@ -84,9 +84,6 @@ pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::computeFeature (
     //output_rf.confidence = getLocalRF ((*indices_)[i], rf);
     //if (output_rf.confidence == std::numeric_limits<float>::max ())
 
-    pcl::Indices n_indices;
-    std::vector<float> n_sqr_distances;
-    this->searchForNeighbors ((*indices_)[i], search_parameter_, n_indices, n_sqr_distances);
     if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits<float>::max ())
     {
       output.is_dense = false;
index 9d96d4071575a07e22500394b0bfccb129195451..9fa7669d6db83715cc1d044ae0aa2f0ea458c13a 100644 (file)
@@ -352,7 +352,7 @@ namespace pcl
   };
 }
 
-#define PCL_INSTANTIATE_MomentOfInertiaEstimation(T) template class pcl::MomentOfInertiaEstimation<T>;
+#define PCL_INSTANTIATE_MomentOfInertiaEstimation(T) template class PCL_EXPORTS pcl::MomentOfInertiaEstimation<T>;
 
 #ifdef PCL_NO_PRECOMPILE
 #include <pcl/features/impl/moment_of_inertia_estimation.hpp>
index 620259947ddc937c7799556061b7a7c8fd75d5f0..f7285a113cecd7a6b5b543155c7cdd312add2b8f 100644 (file)
 namespace pcl
 {
   /** \brief PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of
-    * principal surface curvatures for a given point cloud dataset containing points and normals.
+    * principal surface curvatures for a given point cloud dataset containing points and normals. The output contains 
+    * the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) and min (pc2) 
+    * eigenvalues. Parallel execution is supported through OpenMP.
     *
     * The recommended PointOutT is pcl::PrincipalCurvatures.
     *
-    * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at
-    * \ref NormalEstimationOMP for an example on how to extend this to parallel implementations.
-    *
-    * \author Radu B. Rusu, Jared Glover
+    * \author Radu B. Rusu, Jared Glover, Alex Navarro
     * \ingroup features
     */
   template <typename PointInT, typename PointNT, typename PointOutT = pcl::PrincipalCurvatures>
@@ -73,15 +72,18 @@ namespace pcl
       using PointCloudOut = typename Feature<PointInT, PointOutT>::PointCloudOut;
       using PointCloudIn = pcl::PointCloud<PointInT>;
 
-      /** \brief Empty constructor. */
-      PrincipalCurvaturesEstimation () : 
-        xyz_centroid_ (Eigen::Vector3f::Zero ()), 
-        demean_ (Eigen::Vector3f::Zero ()),
-        covariance_matrix_ (Eigen::Matrix3f::Zero ()),
-        eigenvector_ (Eigen::Vector3f::Zero ()),
-        eigenvalues_ (Eigen::Vector3f::Zero ())
+      /** \brief Initialize the scheduler and set the number of threads to use.
+        * \param nr_threads the number of hardware threads to use (0 sets the value to automatic)
+        * \param chunk_size PCL will use dynamic scheduling with this chunk size. Setting it too 
+        *                   low will lead to more parallelization overhead. Setting it too high 
+        *                   will lead to a worse balancing between the threads.
+        */
+      PrincipalCurvaturesEstimation (unsigned int nr_threads = 1, int chunk_size = 256) : 
+        chunk_size_(chunk_size) 
       {
         feature_name_ = "PrincipalCurvaturesEstimation";
+
+        setNumberOfThreads(nr_threads);
       };
 
       /** \brief Perform Principal Components Analysis (PCA) on the point normals of a surface patch in the tangent
@@ -101,7 +103,19 @@ namespace pcl
                                        int p_idx, const pcl::Indices &indices,
                                        float &pcx, float &pcy, float &pcz, float &pc1, float &pc2);
 
+      /** \brief Initialize the scheduler and set the number of threads to use. The default behavior is
+       *         single threaded exectution
+       * \param nr_threads the number of hardware threads to use (0 sets the value to automatic)
+       */
+      void
+      setNumberOfThreads (unsigned int nr_threads);
+
     protected:
+      /** \brief The number of threads the scheduler should use. */
+      unsigned int threads_;
+
+      /** \brief Chunk size for (dynamic) scheduling. */
+      int chunk_size_;
 
       /** \brief Estimate the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1)
         * and min (pc2) eigenvalues for all points given in <setInputCloud (), setIndices ()> using the surface in
@@ -110,24 +124,6 @@ namespace pcl
         */
       void
       computeFeature (PointCloudOut &output) override;
-
-    private:
-      /** \brief A pointer to the input dataset that contains the point normals of the XYZ dataset. */
-      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > projected_normals_;
-
-      /** \brief SSE aligned placeholder for the XYZ centroid of a surface patch. */
-      Eigen::Vector3f xyz_centroid_;
-
-      /** \brief Temporary point placeholder. */
-      Eigen::Vector3f demean_;
-
-      /** \brief Placeholder for the 3x3 covariance matrix at each surface patch. */
-      EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_;
-
-      /** \brief SSE aligned eigenvectors placeholder for a covariance matrix. */
-      Eigen::Vector3f eigenvector_;
-      /** \brief eigenvalues placeholder for a covariance matrix. */
-      Eigen::Vector3f eigenvalues_;
   };
 }
 
index a34e09fc9417dfe529bc7370b3610ba0f8b0001b..b46c504c59ea0202f100d6586dc4ab49d9547f20 100644 (file)
@@ -227,7 +227,7 @@ namespace pcl
   };
 }
 
-#define PCL_INSTANTIATE_ROPSEstimation(InT, OutT) template class pcl::ROPSEstimation<InT, OutT>;
+#define PCL_INSTANTIATE_ROPSEstimation(InT, OutT) template class PCL_EXPORTS pcl::ROPSEstimation<InT, OutT>;
 
 #ifdef PCL_NO_PRECOMPILE
 #include <pcl/features/impl/rops_estimation.hpp>
index b391e3fcff5308408b96a16075b7c16a2d33746b..c2532d4bc076be1b3b4f9901fdd99e7e8700955b 100644 (file)
@@ -109,9 +109,9 @@ Narf::deepCopy (const Narf& other)
   {
     surface_patch_pixel_size_ = other.surface_patch_pixel_size_;
     delete[] surface_patch_;
-    surface_patch_ = new float[surface_patch_pixel_size_*surface_patch_pixel_size_];
+    surface_patch_ = new float[static_cast<std::size_t>(surface_patch_pixel_size_)*static_cast<std::size_t>(surface_patch_pixel_size_)];
   }
-  std::copy(other.surface_patch_, other.surface_patch_ + surface_patch_pixel_size_*surface_patch_pixel_size_, surface_patch_);
+  std::copy(other.surface_patch_, other.surface_patch_ + static_cast<ptrdiff_t>(surface_patch_pixel_size_)*static_cast<ptrdiff_t>(surface_patch_pixel_size_), surface_patch_);
   surface_patch_world_size_ = other.surface_patch_world_size_;
   surface_patch_rotation_ = other.surface_patch_rotation_;
   
@@ -521,7 +521,7 @@ Narf::saveBinary (std::ostream& file) const
   pcl::saveBinary(transformation_.matrix(), file);
   file.write(reinterpret_cast<const char*>(&surface_patch_pixel_size_), sizeof(surface_patch_pixel_size_));
   file.write(reinterpret_cast<const char*>(surface_patch_),
-             surface_patch_pixel_size_*surface_patch_pixel_size_*sizeof(*surface_patch_));
+             sizeof(*surface_patch_)*surface_patch_pixel_size_*surface_patch_pixel_size_);
   file.write(reinterpret_cast<const char*>(&surface_patch_world_size_), sizeof(surface_patch_world_size_));
   file.write(reinterpret_cast<const char*>(&surface_patch_rotation_), sizeof(surface_patch_rotation_));
   file.write(reinterpret_cast<const char*>(&descriptor_size_), sizeof(descriptor_size_));
@@ -573,9 +573,9 @@ Narf::loadBinary (std::istream& file)
   pcl::loadBinary(position_.matrix(), file);
   pcl::loadBinary(transformation_.matrix(), file);
   file.read(reinterpret_cast<char*>(&surface_patch_pixel_size_), sizeof(surface_patch_pixel_size_));
-  surface_patch_ = new float[surface_patch_pixel_size_*surface_patch_pixel_size_];
+  surface_patch_ = new float[static_cast<std::size_t>(surface_patch_pixel_size_)*static_cast<std::size_t>(surface_patch_pixel_size_)];
   file.read(reinterpret_cast<char*>(surface_patch_),
-            surface_patch_pixel_size_*surface_patch_pixel_size_*sizeof(*surface_patch_));
+            sizeof(*surface_patch_)*surface_patch_pixel_size_*surface_patch_pixel_size_);
   file.read(reinterpret_cast<char*>(&surface_patch_world_size_), sizeof(surface_patch_world_size_));
   file.read(reinterpret_cast<char*>(&surface_patch_rotation_), sizeof(surface_patch_rotation_));
   file.read(reinterpret_cast<char*>(&descriptor_size_), sizeof(descriptor_size_));
index 6590b57aa459836aac228377e767f6035cc01613..7d331368015314b11d57b1662f8571ff75512e93 100644 (file)
@@ -201,7 +201,7 @@ RangeImageBorderExtractor::extractBorderScoreImages ()
 float*
 RangeImageBorderExtractor::updatedScoresAccordingToNeighborValues (const float* border_scores) const
 {
-  float* new_scores = new float[range_image_->width*range_image_->height];
+  float* new_scores = new float[static_cast<std::size_t>(range_image_->width)*static_cast<std::size_t>(range_image_->height)];
   float* new_scores_ptr = new_scores;
   for (int y=0; y < static_cast<int> (range_image_->height); ++y)
     for (int x=0; x < static_cast<int> (range_image_->width); ++x)
@@ -213,7 +213,7 @@ std::vector<float>
 RangeImageBorderExtractor::updatedScoresAccordingToNeighborValues (const std::vector<float>& border_scores) const
 {
   std::vector<float> new_border_scores;
-  new_border_scores.reserve (range_image_->width*range_image_->height);
+  new_border_scores.reserve (static_cast<std::size_t>(range_image_->width)*static_cast<std::size_t>(range_image_->height));
   for (int y=0; y < static_cast<int> (range_image_->height); ++y)
     for (int x=0; x < static_cast<int> (range_image_->width); ++x)
       new_border_scores.push_back (updatedScoreAccordingToNeighborValues(x, y, border_scores.data ()));
@@ -248,15 +248,14 @@ RangeImageBorderExtractor::findAndEvaluateShadowBorders ()
 
   //MEASURE_FUNCTION_TIME;
 
-  int width  = range_image_->width,
+  std::size_t width  = range_image_->width,
       height = range_image_->height;
   shadow_border_informations_ = new ShadowBorderIndices*[width*height];
   for (int y = 0; y < static_cast<int> (height); ++y)
   {
     for (int x = 0; x < static_cast<int> (width); ++x)
     {
-      int index = y*width+x;
-      ShadowBorderIndices*& shadow_border_indices = shadow_border_informations_[index];
+      ShadowBorderIndices*& shadow_border_indices = shadow_border_informations_[y*width+x];
       shadow_border_indices = nullptr;
       int shadow_border_idx;
 
@@ -611,8 +610,8 @@ RangeImageBorderExtractor::blurSurfaceChanges ()
 
   const RangeImage& range_image = *range_image_;
 
-  auto* blurred_directions = new Eigen::Vector3f[range_image.width*range_image.height];
-  float* blurred_scores = new float[range_image.width*range_image.height];
+  auto* blurred_directions = new Eigen::Vector3f[static_cast<std::size_t>(range_image.width)*static_cast<std::size_t>(range_image.height)];
+  float* blurred_scores = new float[static_cast<std::size_t>(range_image.width)*static_cast<std::size_t>(range_image.height)];
   for (int y=0; y<static_cast<int>(range_image.height); ++y)
   {
     for (int x=0; x<static_cast<int>(range_image.width); ++x)
index f4541889fdf335b1bd5f039099d7c11042667aae..3fc7c64104e0b43e859ee876eaecf2a2c88b8403 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME filters)
 set(SUBSYS_DESC "Point cloud filters library")
 set(SUBSYS_DEPS common sample_consensus search kdtree octree)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
@@ -50,7 +49,6 @@ set(srcs
 )
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
   "include/pcl/${SUBSYS_NAME}/conditional_removal.h"
   "include/pcl/${SUBSYS_NAME}/crop_box.h"
   "include/pcl/${SUBSYS_NAME}/clipper3D.h"
@@ -132,7 +130,6 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_common pcl_sample_consensus pcl_search pcl_kdtree pcl_octree)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
index 95e16a1d868ec5e26aca2b6aeabf6f48da73fd07..07bf3404cb3720768be45c65e8aa1bf293f079a3 100644 (file)
@@ -92,6 +92,7 @@ namespace pcl
   /** \brief ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
     * Thus, this is similar to the \ref VoxelGrid filter.
     * This class works best if points that are stored in memory next to each other (in the input point cloud), are also somewhat close in 3D euclidean space (this is for example usually the case for organized point clouds). If the points have no storage order (e.g. in synthetic, randomly generated point clouds), this class will give very poor results, and \ref VoxelGrid should be used instead.
+    * \sa VoxelGrid
     * \author James Bowman, Radu B. Rusu
     * \ingroup filters
     */
diff --git a/filters/include/pcl/filters/boost.h b/filters/include/pcl/filters/boost.h
deleted file mode 100644 (file)
index 273c1e6..0000000
+++ /dev/null
@@ -1,54 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: io.h 5850 2012-06-06 14:04:59Z stfox88 $
- *
- */
-
-#pragma once
-
-#ifdef __GNUC__
-#pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-
-// Marking all Boost headers as system headers to remove warnings
-#include <boost/random.hpp>
-#include <boost/random/normal_distribution.hpp>
-#include <boost/dynamic_bitset.hpp>
-#include <boost/mpl/size.hpp>
-#include <boost/fusion/sequence/intrinsic/at_key.hpp>
-#include <boost/optional.hpp>
index bb701725713945c7d78a0d0e6ccf89f0ba092ec0..8cb21bdee3ff9876cfe38e4df08916a2e398b5d7 100644 (file)
@@ -40,7 +40,9 @@
 #pragma once
 
 #include <pcl/pcl_base.h>
+#include <pcl/search/search.h> // for pcl::search::Search
 #include <boost/optional.hpp>
+#include <pcl/search/search.h>
 
 namespace pcl
 {
@@ -270,7 +272,7 @@ namespace pcl
         double search_radius_;
 
         /** \brief number of threads */
-        unsigned int threads_;
+        unsigned int threads_{1};
 
         /** \brief convlving kernel */
         KernelT kernel_;
index d44b2e66a094a90d06bfac1e4f5f0a5793af3835..831a623be33020b5e31e33642fe6765b755ea855 100644 (file)
@@ -56,6 +56,7 @@ namespace pcl
     * Based on the following publication:
     *    * "Geometrically Stable Sampling for the ICP Algorithm" - N. Gelfand, L. Ikemoto, S. Rusinkiewicz, M. Levoy
     *
+    * \ingroup filters
     * \author Alexandru E. Ichim, alex.e.ichim@gmail.com
     */
   template <typename PointT, typename PointNT>
index 081c2f5d38e997a09fc006941d530244e1f362d5..9ec44921a304b4205d68d596918468d8a62cff30 100644 (file)
@@ -109,7 +109,7 @@ namespace pcl
         * This should be set to correspond to the dimensionality of the
         * convex/concave hull produced by the pcl::ConvexHull and
         * pcl::ConcaveHull classes.
-        * \param[in] dim Dimensionailty of the hull used to filter points.
+        * \param[in] dim Dimensionality of the hull used to filter points.
         */
       inline void
       setDim (int dim)
index 2c707d38fbb1d03f6dff727ed69a26dd99085d96..3a3a403d4efb01bbc0bea77c61f605a22308411a 100644 (file)
@@ -43,6 +43,7 @@
 #include <pcl/filters/bilateral.h>
 #include <pcl/search/organized.h> // for OrganizedNeighbor
 #include <pcl/search/kdtree.h> // for KdTree
+#include <pcl/common/point_tests.h> // for isXYZFinite
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT> double
@@ -101,11 +102,14 @@ pcl::BilateralFilter<PointT>::applyFilter (PointCloud &output)
   // For all the indices given (equal to the entire cloud if none given)
   for (const auto& idx : (*indices_))
   {
-    // Perform a radius search to find the nearest neighbors
-    tree_->radiusSearch (idx, sigma_s_ * 2, k_indices, k_distances);
+    if (input_->is_dense || pcl::isXYZFinite((*input_)[idx]))
+    {
+      // Perform a radius search to find the nearest neighbors
+      tree_->radiusSearch (idx, sigma_s_ * 2, k_indices, k_distances);
 
-    // Overwrite the intensity value with the computed average
-    output[idx].intensity = static_cast<float> (computePointWeight (idx, k_indices, k_distances));
+      // Overwrite the intensity value with the computed average
+      output[idx].intensity = static_cast<float> (computePointWeight (idx, k_indices, k_distances));
+    }
   }
 }
  
index 99cc9295b58899f5873765d077a733fc4ad49336..57baf8e1951887a2d10d596a26e15c0bf55d78b9 100644 (file)
@@ -529,8 +529,8 @@ pcl::PointDataAtOffset<PointT>::compare (const PointT& p, const double& val)
   case CASE_LABEL: {                                                                   \
     pcl::traits::asType_t<CASE_LABEL> pt_val;                                          \
     memcpy(&pt_val, pt_data + this->offset_, sizeof(pt_val));                          \
-    return (pt_val > static_cast<pcl::traits::asType_t<CASE_LABEL>>(val)) -            \
-           (pt_val < static_cast<pcl::traits::asType_t<CASE_LABEL>>(val));             \
+    return (pt_val > static_cast<pcl::traits::asType_t<(CASE_LABEL)>>(val)) -          \
+           (pt_val < static_cast<pcl::traits::asType_t<(CASE_LABEL)>>(val));           \
   }
 
   switch (datatype_)
index f3901fca5247a4bdc3e6a7763b5c8187fbe9e9fb..1001bce731940a71cb98d05066b7987515fa502f 100644 (file)
 #ifndef PCL_FILTERS_CONVOLUTION_3D_IMPL_HPP
 #define PCL_FILTERS_CONVOLUTION_3D_IMPL_HPP
 
+#include <pcl/common/point_tests.h> // for isFinite
 #include <pcl/search/organized.h>
 #include <pcl/search/kdtree.h>
 #include <pcl/pcl_config.h>
 #include <pcl/point_types.h>
+#include <pcl/common/point_tests.h>
 
 #include <cmath>
 #include <cstdint>
@@ -247,7 +249,8 @@ pcl::filters::Convolution3D<PointInT, PointOutT, KernelT>::convolve (PointCloudO
   default(none) \
   shared(output) \
   firstprivate(nn_indices, nn_distances) \
-  num_threads(threads_)
+  num_threads(threads_) \
+  schedule(dynamic, 64)
   for (std::int64_t point_idx = 0; point_idx < static_cast<std::int64_t> (surface_->size ()); ++point_idx)
   {
     const PointInT& point_in = surface_->points [point_idx];
index 99d8da8f55086889d12cd34b85b850968ef3aaf2..a3885cf6aebbfe8f7b767500d1939fc28d6591fb 100644 (file)
@@ -164,7 +164,7 @@ pcl::CovarianceSampling<PointT, PointNT>::applyFilter (Indices &sampled_indices)
   for (std::size_t i = 0; i < 6; ++i)
   {
     for (std::size_t p_i = 0; p_i < candidate_indices.size (); ++p_i)
-      L[i].push_back (std::make_pair (p_i, std::abs (v[p_i].dot (x.block<6, 1> (0, i)))));
+      L[i].emplace_back(p_i, std::abs (v[p_i].dot (x.block<6, 1> (0, i))));
 
     // Sort in decreasing order
     L[i].sort (sort_dot_list_function);
index d408ee8db12fef68c6e9022ea49062e46d0a14dd..de53d91c7814a18263451b9ff865d7d8a1c6fd8b 100644 (file)
@@ -100,7 +100,6 @@ pcl::FilterIndices<PointT>::applyFilter (PointCloud &output)
   }
   else
   {
-    output.is_dense = true;
     applyFilter (indices);
     pcl::copyPointCloud (*input_, indices, output);
   }
index e0100a2f4b4a9fb7c1d4bf0b67aa4669609aa50b..3bbc610d53282261218564727a64d9d3b36bfb2a 100644 (file)
@@ -80,9 +80,11 @@ pcl::NormalSpaceSampling<PointT, NormalT>::isEntireBinSampled (boost::dynamic_bi
 template<typename PointT, typename NormalT> unsigned int 
 pcl::NormalSpaceSampling<PointT, NormalT>::findBin (const float *normal)
 {
-  const auto ix = static_cast<unsigned> (std::round (0.5f * (binsx_ - 1.f) * (normal[0] + 1.f)));
-  const auto iy = static_cast<unsigned> (std::round (0.5f * (binsy_ - 1.f) * (normal[1] + 1.f)));
-  const auto iz = static_cast<unsigned> (std::round (0.5f * (binsz_ - 1.f) * (normal[2] + 1.f)));
+  // in the case where normal[0] == 1.0f, ix will be binsx_, which is out of range.
+  // thus, use std::min to avoid this situation.
+  const auto ix = std::min (binsx_ - 1, static_cast<unsigned> (std::max (0.0f, std::floor (0.5f * (binsx_) * (normal[0] + 1.f)))));
+  const auto iy = std::min (binsy_ - 1, static_cast<unsigned> (std::max (0.0f, std::floor (0.5f * (binsy_) * (normal[1] + 1.f)))));
+  const auto iz = std::min (binsz_ - 1, static_cast<unsigned> (std::max (0.0f, std::floor (0.5f * (binsz_) * (normal[2] + 1.f)))));
   return ix * (binsy_*binsz_) + iy * binsz_ + iz;
 }
 
index f4fe5a4643836c9073adf97c488fbf60937c74e5..dc47d935320963cf2a69853697920fa9c3ff5e88 100644 (file)
@@ -55,13 +55,13 @@ Pyramid<PointT>::initCompute ()
 {
   if (!input_->isOrganized ())
   {
-    PCL_ERROR ("[pcl::fileters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ());
+    PCL_ERROR ("[pcl::filters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ());
     return (false);
   }
 
   if (levels_ < 2)
   {
-    PCL_ERROR ("[pcl::fileters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ());
+    PCL_ERROR ("[pcl::filters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ());
     return (false);
   }
 
@@ -71,7 +71,7 @@ Pyramid<PointT>::initCompute ()
 
   if (levels_ > 4)
   {
-    PCL_ERROR ("[pcl::fileters::%s::initCompute] Number of levels should not exceed 4!\n", getClassName ().c_str ());
+    PCL_ERROR ("[pcl::filters::%s::initCompute] Number of levels should not exceed 4!\n", getClassName ().c_str ());
     return (false);
   }
 
index 8e13ec06824a9b0e70ad059c5a4f37178699df0b..54cddb5b46951a2cc352ebd83cc6b9705323fb4f 100644 (file)
@@ -72,9 +72,17 @@ pcl::RadiusOutlierRemoval<PointT>::applyFilterIndices (Indices &indices)
     return;
   }
 
+  // Note: k includes the query point, so is always at least 1
+  const int mean_k = min_pts_radius_ + 1;
+  const double nn_dists_max = search_radius_ * search_radius_;
+
   // The arrays to be used
-  Indices nn_indices (indices_->size ());
-  std::vector<float> nn_dists (indices_->size ());
+  Indices nn_indices (mean_k);
+  std::vector<float> nn_dists(mean_k);
+  // Set to keep all points and in the filtering set those we don't want to keep, assuming
+  // we want to keep the majority of the points.
+  // 0 = remove, 1 = keep
+  std::vector<std::uint8_t> to_keep(indices_->size(), 1);
   indices.resize (indices_->size ());
   removed_indices_->resize (indices_->size ());
   int oii = 0, rii = 0;  // oii = output indices iterator, rii = removed indices iterator
@@ -82,77 +90,85 @@ pcl::RadiusOutlierRemoval<PointT>::applyFilterIndices (Indices &indices)
   // If the data is dense => use nearest-k search
   if (input_->is_dense)
   {
-    // Note: k includes the query point, so is always at least 1
-    int mean_k = min_pts_radius_ + 1;
-    double nn_dists_max = search_radius_ * search_radius_;
-
-    for (const auto& index : (*indices_))
+    #pragma omp parallel for \
+    schedule(dynamic,64) \
+    firstprivate(nn_indices, nn_dists)                                                 \
+    shared(to_keep) \
+    num_threads(num_threads_)
+    for (ptrdiff_t i = 0; i < static_cast<ptrdiff_t>(indices_->size()); i++)
     {
+      const auto& index = (*indices_)[i];
       // Perform the nearest-k search
-      int k = searcher_->nearestKSearch (index, mean_k, nn_indices, nn_dists);
+      const int k = searcher_->nearestKSearch (index, mean_k, nn_indices, nn_dists);
 
       // Check the number of neighbors
       // Note: nn_dists is sorted, so check the last item
-      bool chk_neighbors = true;
       if (k == mean_k)
       {
-        if (negative_)
-        {
-          chk_neighbors = false;
-          if (nn_dists_max < nn_dists[k-1])
-          {
-            chk_neighbors = true;
-          }
-        }
-        else
-        {
-          chk_neighbors = true;
-          if (nn_dists_max < nn_dists[k-1])
+          // if negative_ is false and a neighbor is further away than max distance, remove the point
+          // or
+          // if negative is true and a neighbor is closer than max distance, remove the point
+          if ((!negative_ && nn_dists_max < nn_dists[k-1]) || (negative_ && nn_dists_max >= nn_dists[k - 1]))
           {
-            chk_neighbors = false;
+            to_keep[i] = 0;
+            continue;
           }
-        }
       }
       else
       {
-        chk_neighbors = negative_;
-      }
-
-      // Points having too few neighbors are outliers and are passed to removed indices
-      // Unless negative was set, then it's the opposite condition
-      if (!chk_neighbors)
-      {
-        if (extract_removed_indices_)
-          (*removed_indices_)[rii++] = index;
-        continue;
+        if (!negative_)
+        {
+          // if too few neighbors, remove the point
+          to_keep[i] = 0;
+          continue;
+        }
       }
-
-      // Otherwise it was a normal point for output (inlier)
-      indices[oii++] = index;
     }
   }
   // NaN or Inf values could exist => use radius search
   else
   {
-    for (const auto& index : (*indices_))
+    #pragma omp parallel for \
+    schedule(dynamic, 64) \
+    firstprivate(nn_indices, nn_dists) \
+    shared(to_keep) \
+    num_threads(num_threads_)
+    for (ptrdiff_t i = 0; i < static_cast<ptrdiff_t>(indices_->size()); i++)
     {
+      const auto& index = (*indices_)[i];
+      if (!pcl::isXYZFinite((*input_)[index]))
+      {
+        to_keep[i] = 0;
+        continue;
+      }
+        
       // Perform the radius search
       // Note: k includes the query point, so is always at least 1
-      int k = searcher_->radiusSearch (index, search_radius_, nn_indices, nn_dists);
+      // last parameter (max_nn) is the maximum number of neighbors returned. If enough neighbors are found so that point can not be an outlier, we stop searching.
+      const int k = searcher_->radiusSearch (index, search_radius_, nn_indices, nn_dists, min_pts_radius_ + 1);
 
-      // Points having too few neighbors are outliers and are passed to removed indices
-      // Unless negative was set, then it's the opposite condition
+      // Points having too few neighbors are removed
+      // or if negative_ is true, then if it has too many neighbors
       if ((!negative_ && k <= min_pts_radius_) || (negative_ && k > min_pts_radius_))
+      {
+        to_keep[i] = 0;
+        continue;
+      }
+    }
+  }
+
+    for (index_t i=0; i < static_cast<index_t>(to_keep.size()); i++)
+    {
+      if (to_keep[i] == 0)
       {
         if (extract_removed_indices_)
-          (*removed_indices_)[rii++] = index;
+          (*removed_indices_)[rii++] = (*indices_)[i];
         continue;
       }
 
       // Otherwise it was a normal point for output (inlier)
-      indices[oii++] = index;
+      indices[oii++] = (*indices_)[i];
     }
-  }
 
   // Resize the output arrays
   indices.resize (oii);
index 24a0c571a672d7b29e2d0420182a1423bac19763..f4138afcf3c0e93a9e9cd26ba9c2cc2cadac2f7e 100644 (file)
@@ -63,7 +63,11 @@ pcl::RandomSample<PointT>::applyFilter (Indices &indices)
       removed_indices_->resize (N - sample_size);
 
     // Set random seed so derived indices are the same each time the filter runs
+#ifdef __OpenBSD__
+    srand_deterministic (seed_); // OpenBSD only offers repeatable sequences with this function
+#else
     std::srand (seed_);
+#endif // __OpenBSD__
 
     // Algorithm S
     std::size_t i = 0;
index a711bf8cba049a7e902aaecff948a898d4ee8067..3a2959b015cad6a91488e6df1039bf2badbd7b4e 100644 (file)
 template<typename PointT> void
 pcl::SamplingSurfaceNormal<PointT>::applyFilter (PointCloud &output)
 {
+  if (ratio_ <= 0.0f)
+  {
+    PCL_ERROR("[SamplingSurfaceNormal::applyFilter] Parameter 'ratio' must be larger than zero!\n");
+    output.clear();
+    return;
+  }
+  if (sample_ < 5)
+  {
+    PCL_ERROR("[SamplingSurfaceNormal::applyFilter] Parameter 'sample' must be at least 5!\n");
+    output.clear();
+    return;
+  }
   Indices indices;
   std::size_t npts = input_->size ();
   for (std::size_t i = 0; i < npts; i++)
index 0e9359f0bad18ee145ab16ef04b9eec6b9a2e3f7..3b81df8b3fbabd20ead6a0815ef3411cd482786b 100644 (file)
@@ -93,11 +93,11 @@ pcl::StatisticalOutlierRemoval<PointT>::applyFilterIndices (Indices &indices)
       continue;
     }
 
-    // Calculate the mean distance to its neighbors
+    // Calculate the mean distance to its neighbors.
     double dist_sum = 0.0;
-    for (int k = 1; k < searcher_k; ++k)  // k = 0 is the query point
-      dist_sum += sqrt (nn_dists[k]);
-    distances[iii] = static_cast<float> (dist_sum / mean_k_);
+    for (std::size_t k = 1; k < nn_dists.size(); ++k) // k = 0 is the query point
+      dist_sum += sqrt(nn_dists[k]);
+    distances[iii] = static_cast<float>(dist_sum / (nn_dists.size() - 1));
     valid_distances++;
   }
 
index a46902c470430cfa5e2b29f60b8d3f10091251a1..c1c0f251de1d6ee34fa3bb0f8a43d07c4af14dc0 100644 (file)
 
 #include <pcl/common/common.h>
 #include <pcl/filters/uniform_sampling.h>
+#include <pcl/common/point_tests.h>
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT> void
-pcl::UniformSampling<PointT>::applyFilter (PointCloud &output)
+pcl::UniformSampling<PointT>::applyFilter (Indices &indices)
 {
-  // Has the input dataset been set already?
-  if (!input_)
-  {
-    PCL_WARN ("[pcl::%s::detectKeypoints] No input dataset given!\n", getClassName ().c_str ());
-    output.width = output.height = 0;
-    output.clear ();
-    return;
-  }
+  // The arrays to be used
+  indices.resize (indices_->size ());
+  removed_indices_->resize (indices_->size ());
 
-  output.height       = 1;                    // downsampling breaks the organized structure
-  output.is_dense     = true;                 // we filter out invalid points
+  int oii = 0, rii = 0;  // oii = output indices iterator, rii = removed indices iterator
 
   Eigen::Vector4f min_p, max_p;
   // Get the minimum and maximum dimensions
@@ -79,35 +74,36 @@ pcl::UniformSampling<PointT>::applyFilter (PointCloud &output)
   // Set up the division multiplier
   divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
 
-  removed_indices_->clear();
   // First pass: build a set of leaves with the point index closest to the leaf center
-  for (std::size_t cp = 0; cp < indices_->size (); ++cp)
+  for (const auto& cp : *indices_)
   {
     if (!input_->is_dense)
     {
       // Check if the point is invalid
-      if (!std::isfinite ((*input_)[(*indices_)[cp]].x) || 
-          !std::isfinite ((*input_)[(*indices_)[cp]].y) || 
-          !std::isfinite ((*input_)[(*indices_)[cp]].z))
+      if (!pcl::isXYZFinite ((*input_)[cp]))
       {
         if (extract_removed_indices_)
-          removed_indices_->push_back ((*indices_)[cp]);
+          (*removed_indices_)[rii++] = cp;
         continue;
       }
     }
 
     Eigen::Vector4i ijk = Eigen::Vector4i::Zero ();
-    ijk[0] = static_cast<int> (std::floor ((*input_)[(*indices_)[cp]].x * inverse_leaf_size_[0]));
-    ijk[1] = static_cast<int> (std::floor ((*input_)[(*indices_)[cp]].y * inverse_leaf_size_[1]));
-    ijk[2] = static_cast<int> (std::floor ((*input_)[(*indices_)[cp]].z * inverse_leaf_size_[2]));
+    ijk[0] = static_cast<int> (std::floor ((*input_)[cp].x * inverse_leaf_size_[0]));
+    ijk[1] = static_cast<int> (std::floor ((*input_)[cp].y * inverse_leaf_size_[1]));
+    ijk[2] = static_cast<int> (std::floor ((*input_)[cp].z * inverse_leaf_size_[2]));
 
     // Compute the leaf index
     int idx = (ijk - min_b_).dot (divb_mul_);
     Leaf& leaf = leaves_[idx];
+
+    // Increment the count of points in this voxel
+    ++leaf.count;
+
     // First time we initialize the index
     if (leaf.idx == -1)
     {
-      leaf.idx = (*indices_)[cp];
+      leaf.idx = cp;
       continue;
     }
 
@@ -115,30 +111,36 @@ pcl::UniformSampling<PointT>::applyFilter (PointCloud &output)
     Eigen::Vector4f voxel_center = (ijk.cast<float>() + Eigen::Vector4f::Constant(0.5)) * search_radius_;
     voxel_center[3] = 0;
     // Check to see if this point is closer to the leaf center than the previous one we saved
-    float diff_cur   = ((*input_)[(*indices_)[cp]].getVector4fMap () - voxel_center).squaredNorm ();
+    float diff_cur   = ((*input_)[cp].getVector4fMap () - voxel_center).squaredNorm ();
     float diff_prev  = ((*input_)[leaf.idx].getVector4fMap ()        - voxel_center).squaredNorm ();
 
     // If current point is closer, copy its index instead
     if (diff_cur < diff_prev)
     {
       if (extract_removed_indices_)
-        removed_indices_->push_back (leaf.idx);
-      leaf.idx = (*indices_)[cp];
+        (*removed_indices_)[rii++] = leaf.idx;
+      leaf.idx = cp;
     }
     else
     {
       if (extract_removed_indices_)
-        removed_indices_->push_back ((*indices_)[cp]);
+        (*removed_indices_)[rii++] = cp;
     }
   }
+  removed_indices_->resize(rii);
 
   // Second pass: go over all leaves and copy data
-  output.resize (leaves_.size ());
-  int cp = 0;
-
+  indices.resize (leaves_.size ());
   for (const auto& leaf : leaves_)
-    output[cp++] = (*input_)[leaf.second.idx];
-  output.width = output.size ();
+  {
+    if (leaf.second.count >= min_points_per_voxel_)
+      indices[oii++] = leaf.second.idx;
+  }
+  indices.resize (oii);
+  if(negative_){
+     indices.swap(*removed_indices_);
+  }
 }
 
 #define PCL_INSTANTIATE_UniformSampling(T) template class PCL_EXPORTS pcl::UniformSampling<T>;
index 66de0a081006eaf5a9dd2ecba176cce054be3a88..5297a49dc2a2da717902496610f28a3f58807b85 100644 (file)
@@ -211,16 +211,6 @@ pcl::getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
   max_pt = max_p;
 }
 
-struct cloud_point_index_idx 
-{
-  unsigned int idx;
-  unsigned int cloud_point_index;
-
-  cloud_point_index_idx() = default;
-  cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {}
-  bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); }
-};
-
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT> void
 pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
@@ -273,7 +263,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
   divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
 
   // Storage for mapping leaf and pointcloud indexes
-  std::vector<cloud_point_index_idx> index_vector;
+  std::vector<internal::cloud_point_index_idx> index_vector;
   index_vector.reserve (indices_->size ());
 
   // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
@@ -350,7 +340,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
 
   // Second pass: sort the index_vector vector using value representing target cell as index
   // in effect all points belonging to the same output cell will be next to each other
-  auto rightshift_func = [](const cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
+  auto rightshift_func = [](const internal::cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
   boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func);
   
   // Third pass: count output cells
index 0c4c458bac4683a97c6a96fd15bb8a4ae8ae05a9..1c60d354ee6841c8ba4fc2efddaf0ac1799aa317 100644 (file)
@@ -442,11 +442,11 @@ pcl::VoxelGridCovariance<PointT>::getAllNeighborsAtPoint(const PointT& reference
 
 //////////////////////////////////////////////////////////////////////////////////////////
 template<typename PointT> void
-pcl::VoxelGridCovariance<PointT>::getDisplayCloud (pcl::PointCloud<PointXYZ>& cell_cloud)
+pcl::VoxelGridCovariance<PointT>::getDisplayCloud (pcl::PointCloud<PointXYZ>& cell_cloud, int pnt_per_cell) const
 {
   cell_cloud.clear ();
 
-  int pnt_per_cell = 1000;
+  // for now, we use random generator and normal distribution from boost instead of std because switching to std would make this function up to 2.8 times slower
   boost::mt19937 rng;
   boost::normal_distribution<> nd (0.0, 1.0);
   boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor (rng, nd);
@@ -463,7 +463,7 @@ pcl::VoxelGridCovariance<PointT>::getDisplayCloud (pcl::PointCloud<PointXYZ>& ce
   // Generate points for each occupied voxel with sufficient points.
   for (auto it = leaves_.begin (); it != leaves_.end (); ++it)
   {
-    Leaf& leaf = it->second;
+    const Leaf& leaf = it->second;
 
     if (leaf.nr_points >= min_points_per_voxel_)
     {
index 63fac68a2676506c4c94af8102523aa4b0a08ebb..f065e2da49defe8802b3cb6281eeb0f585adb7d4 100644 (file)
@@ -47,7 +47,7 @@ pcl::VoxelGridOcclusionEstimation<PointT>::initializeVoxelGrid ()
 {
   // initialization set to true
   initialized_ = true;
-  
+
   // create the voxel grid and store the output cloud
   this->filter (filtered_cloud_);
 
@@ -162,13 +162,13 @@ pcl::VoxelGridOcclusionEstimation<PointT>::occlusionEstimationAll (std::vector<E
           Eigen::Vector4f p = getCentroidCoordinate (ijk);
           Eigen::Vector4f direction = p - sensor_origin_;
           direction.normalize ();
-          
+
           // estimate entry point into the voxel grid
           float tmin = rayBoxIntersection (sensor_origin_, direction);
 
           // ray traversal
           int state = rayTraversal (ijk, sensor_origin_, direction, tmin);
-          
+
           // if voxel is occluded
           if (state == 1)
             occluded_voxels.push_back (ijk);
@@ -179,7 +179,7 @@ pcl::VoxelGridOcclusionEstimation<PointT>::occlusionEstimationAll (std::vector<E
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT> float
-pcl::VoxelGridOcclusionEstimation<PointT>::rayBoxIntersection (const Eigen::Vector4f& origin, 
+pcl::VoxelGridOcclusionEstimation<PointT>::rayBoxIntersection (const Eigen::Vector4f& origin,
                                                                const Eigen::Vector4f& direction)
 {
   float tmin, tmax, tymin, tymax, tzmin, tzmax;
@@ -198,7 +198,7 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayBoxIntersection (const Eigen::Vect
   if (direction[1] >= 0)
   {
     tymin = (b_min_[1] - origin[1]) / direction[1];
-    tymax = (b_max_[1] - origin[1]) / direction[1]; 
+    tymax = (b_max_[1] - origin[1]) / direction[1];
   }
   else
   {
@@ -233,7 +233,7 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayBoxIntersection (const Eigen::Vect
   {
     PCL_ERROR ("no intersection with the bounding box \n");
     tmin = -1.0f;
-    return tmin;       
+    return tmin;
   }
 
   if (tzmin > tmin)
@@ -246,15 +246,16 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayBoxIntersection (const Eigen::Vect
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT> int
 pcl::VoxelGridOcclusionEstimation<PointT>::rayTraversal (const Eigen::Vector3i& target_voxel,
-                                                         const Eigen::Vector4f& origin, 
+                                                         const Eigen::Vector4f& origin,
                                                          const Eigen::Vector4f& direction,
                                                          const float t_min)
 {
-  // coordinate of the boundary of the voxel grid
-  Eigen::Vector4f start = origin + t_min * direction;
+  // coordinate of the boundary of the voxel grid. To avoid numerical imprecision
+  // causing the start voxel index to be off by one, we add the machine epsilon
+  Eigen::Vector4f start = origin + (t_min > 0.0f ? (t_min + std::numeric_limits<float>::epsilon()) : t_min) * direction;
 
   // i,j,k coordinate of the voxel were the ray enters the voxel grid
-  Eigen::Vector3i ijk = getGridCoordinatesRound (start[0], start[1], start[2]);
+  Eigen::Vector3i ijk = this->getGridCoordinates(start[0], start[1], start[2]);
 
   // steps in which direction we have to travel in the voxel grid
   int step_x, step_y, step_z;
@@ -296,13 +297,13 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayTraversal (const Eigen::Vector3i&
   float t_max_x = t_min + (voxel_max[0] - start[0]) / direction[0];
   float t_max_y = t_min + (voxel_max[1] - start[1]) / direction[1];
   float t_max_z = t_min + (voxel_max[2] - start[2]) / direction[2];
-     
+
   float t_delta_x = leaf_size_[0] / static_cast<float> (std::abs (direction[0]));
   float t_delta_y = leaf_size_[1] / static_cast<float> (std::abs (direction[1]));
   float t_delta_z = leaf_size_[2] / static_cast<float> (std::abs (direction[2]));
 
-  while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) && 
-          (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && 
+  while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) &&
+          (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) &&
           (ijk[2] < max_b_[2]+1) && (ijk[2] >= min_b_[2]) )
   {
     // check if we reached target voxel
@@ -339,7 +340,7 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayTraversal (const Eigen::Vector3i&
 template <typename PointT> int
 pcl::VoxelGridOcclusionEstimation<PointT>::rayTraversal (std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> >& out_ray,
                                                          const Eigen::Vector3i& target_voxel,
-                                                         const Eigen::Vector4f& origin, 
+                                                         const Eigen::Vector4f& origin,
                                                          const Eigen::Vector4f& direction,
                                                          const float t_min)
 {
@@ -347,12 +348,12 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayTraversal (std::vector<Eigen::Vect
   int reserve_size = div_b_.maxCoeff () * div_b_.maxCoeff ();
   out_ray.reserve (reserve_size);
 
-  // coordinate of the boundary of the voxel grid
-  Eigen::Vector4f start = origin + t_min * direction;
+  // coordinate of the boundary of the voxel grid. To avoid numerical imprecision
+  // causing the start voxel index to be off by one, we add the machine epsilon
+  Eigen::Vector4f start = origin + (t_min > 0.0f ? (t_min + std::numeric_limits<float>::epsilon()) : t_min) * direction;
 
   // i,j,k coordinate of the voxel were the ray enters the voxel grid
-  Eigen::Vector3i ijk = getGridCoordinatesRound (start[0], start[1], start[2]);
-  //Eigen::Vector3i ijk = this->getGridCoordinates (start_x, start_y, start_z);
+  Eigen::Vector3i ijk = this->getGridCoordinates (start[0], start[1], start[2]);
 
   // steps in which direction we have to travel in the voxel grid
   int step_x, step_y, step_z;
@@ -394,7 +395,7 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayTraversal (std::vector<Eigen::Vect
   float t_max_x = t_min + (voxel_max[0] - start[0]) / direction[0];
   float t_max_y = t_min + (voxel_max[1] - start[1]) / direction[1];
   float t_max_z = t_min + (voxel_max[2] - start[2]) / direction[2];
-     
+
   float t_delta_x = leaf_size_[0] / static_cast<float> (std::abs (direction[0]));
   float t_delta_y = leaf_size_[1] / static_cast<float> (std::abs (direction[1]));
   float t_delta_z = leaf_size_[2] / static_cast<float> (std::abs (direction[2]));
@@ -402,8 +403,8 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayTraversal (std::vector<Eigen::Vect
   // the index of the cloud (-1 if empty)
   int result = 0;
 
-  while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) && 
-          (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && 
+  while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) &&
+          (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) &&
           (ijk[2] < max_b_[2]+1) && (ijk[2] >= min_b_[2]) )
   {
     // add voxel to ray
index 8fbe3dce188bd3da24690b2760f551405ce1b901..bc8112901914cf7a39f4a011e112842b460d19fe 100644 (file)
@@ -67,6 +67,7 @@ namespace pcl
    * filter.filter (*cloud_out);
 
    * \endcode
+   * \ingroup filters
    */
   template <typename PointT>
   class ModelOutlierRemoval : public FilterIndices<PointT>
index 23f1d48317d96d72e05fca04981cfa39a4eed772..272d091b01581aac8b689fea17ba7a47169e6ece 100644 (file)
@@ -64,6 +64,7 @@ namespace pcl
     * indices_rem = rorfilter.getRemovedIndices ();
     * // The indices_rem array indexes all points of cloud_in that have 5 or more neighbors within the 0.1 search radius
     * \endcode
+    * \sa StatisticalOutlierRemoval
     * \author Radu Bogdan Rusu
     * \ingroup filters
     */
@@ -142,6 +143,24 @@ namespace pcl
         */
       inline void
       setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; }
+
+      /** \brief Set the number of threads to use.
+       * \param nr_threads the number of hardware threads to use (0 sets the value back
+       * to automatic)
+       */
+      void
+      setNumberOfThreads(unsigned int nr_threads = 0)
+      {
+#ifdef _OPENMP
+        num_threads_ = nr_threads != 0 ? nr_threads : omp_get_num_procs();
+#else
+        if (num_threads_ != 1) {
+          PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
+        }
+        num_threads_ = 1;
+#endif
+      }
+
     protected:
       using PCLBase<PointT>::input_;
       using PCLBase<PointT>::indices_;
@@ -177,6 +196,11 @@ namespace pcl
 
       /** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier. */
       int min_pts_radius_{1};
+
+      /**
+       * @brief Number of threads used during filtering
+       */
+      int num_threads_{1};
   };
 
   //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
index 3c2e8397404aa717f523206a956628bdc8924068..25253747a51d5eba0d635b78837674cec26731aa 100644 (file)
@@ -61,7 +61,7 @@ namespace pcl
     using PointCloudPtr = typename PointCloud::Ptr;
     using PointCloudConstPtr = typename PointCloud::ConstPtr;
 
-    using Vector = Eigen::Matrix<float, Eigen::Dynamic, 1>;
+    using Vector = Eigen::Matrix<float, 3, 1>;
 
     public:
 
index 4abfd12316ee0d200b53dc6535ede505a89ce9f4..c752935b906d5321b91bd4f30a93e0e41586af17 100644 (file)
@@ -73,6 +73,7 @@ namespace pcl
     * indices_rem = sorfilter.getRemovedIndices ();
     * // The indices_rem array indexes all points of cloud_in that are outliers
     * \endcode
+    * \sa RadiusOutlierRemoval
     * \author Radu Bogdan Rusu
     * \ingroup filters
     */
index 39d0815d32a77bf3a4e6e99b8c525225eaeeea52..53b6c26dd24158844f7c28be8451fecfddc82b4e 100644 (file)
@@ -39,7 +39,7 @@
 
 #pragma once
 
-#include <pcl/filters/filter.h>
+#include <pcl/filters/filter_indices.h>
 
 #include <unordered_map>
 
@@ -52,13 +52,16 @@ namespace pcl
     * Then, in each *voxel* (i.e., 3D box), all the points present will be
     * approximated (i.e., *downsampled*) with the closest point to the center of the voxel.
     *
+    * \sa VoxelGrid
     * \author Radu Bogdan Rusu
     * \ingroup filters
     */ 
   template <typename PointT>
-  class UniformSampling: public Filter<PointT>
+  class UniformSampling: public FilterIndices<PointT>
   {
-    using PointCloud = typename Filter<PointT>::PointCloud;
+    using PointCloud = typename FilterIndices<PointT>::PointCloud;
+
+    using FilterIndices<PointT>::negative_;
 
     using Filter<PointT>::filter_name_;
     using Filter<PointT>::input_;
@@ -75,7 +78,7 @@ namespace pcl
 
       /** \brief Empty constructor. */
       UniformSampling (bool extract_removed_indices = false) :
-        Filter<PointT>(extract_removed_indices),
+        FilterIndices<PointT>(extract_removed_indices),
         leaves_ (),
         leaf_size_ (Eigen::Vector4f::Zero ()),
         inverse_leaf_size_ (Eigen::Vector4f::Zero ()),
@@ -108,12 +111,25 @@ namespace pcl
         search_radius_ = radius;
       }
 
+      /** \brief Set the minimum number of points required for a voxel to be used.
+        * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used
+        */
+      inline void
+      setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) { min_points_per_voxel_ = min_points_per_voxel; }
+
+      /** \brief Return the minimum number of points required for a voxel to be used.
+        */
+      inline unsigned int
+      getMinimumPointsNumberPerVoxel () const { return min_points_per_voxel_; }
+
+      
     protected:
       /** \brief Simple structure to hold an nD centroid and the number of points in a leaf. */
       struct Leaf
       {
         Leaf () = default;
         int idx{-1};
+        unsigned int count{0};
       };
 
       /** \brief The 3D grid leaves. */
@@ -131,11 +147,14 @@ namespace pcl
       /** \brief The nearest neighbors search radius for each point. */
       double search_radius_{0.0};
 
-      /** \brief Downsample a Point Cloud using a voxelized grid approach
-        * \param[out] output the resultant point cloud message
+      /** \brief Minimum number of points per voxel. */
+      unsigned int min_points_per_voxel_{0};
+
+      /** \brief Filtered results are indexed by an indices array.
+        * \param[out] indices The resultant indices.
         */
       void
-      applyFilter (PointCloud &output) override;
+      applyFilter (Indices &indices) override;
   };
 }
 
index 24615c43e7ffc0b561e26fa1b4223522a938468b..00bdcf50c42444d9d345271004cc215b7f03529c 100644 (file)
 
 namespace pcl
 {
+  /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
+      * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset
+      * \param[in] x_idx the index of the X channel
+      * \param[in] y_idx the index of the Y channel
+      * \param[in] z_idx the index of the Z channel
+      * \param[out] min_pt the minimum data point
+      * \param[out] max_pt the maximum data point
+   */
+  PCL_EXPORTS void
+  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
+              Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
+
   /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
     * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset
+    * \param[in] indices the point cloud indices that need to be considered
     * \param[in] x_idx the index of the X channel
     * \param[in] y_idx the index of the Y channel
     * \param[in] z_idx the index of the Z channel
     * \param[out] min_pt the minimum data point
     * \param[out] max_pt the maximum data point
-    */
+   */
   PCL_EXPORTS void
-  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
-               Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
+  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const Indices &indices, int x_idx, int y_idx, int z_idx,
+              Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
 
   /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
     * \note Performs internal data filtering as well.
@@ -69,9 +82,29 @@ namespace pcl
     * \param[out] max_pt the maximum data point
     * \param[in] limit_negative \b false if data \b inside of the [min_distance; max_distance] interval should be
     * considered, \b true otherwise.
-    */
+   */
   PCL_EXPORTS void
   getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
+              const std::string &distance_field_name, float min_distance, float max_distance,
+              Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
+
+  /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
+    * \note Performs internal data filtering as well.
+    * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset
+    * \param[in] indices the point cloud indices that need to be considered
+    * \param[in] x_idx the index of the X channel
+    * \param[in] y_idx the index of the Y channel
+    * \param[in] z_idx the index of the Z channel
+    * \param[in] distance_field_name the name of the dimension to filter data along to
+    * \param[in] min_distance the minimum acceptable value in \a distance_field_name data
+    * \param[in] max_distance the maximum acceptable value in \a distance_field_name data
+    * \param[out] min_pt the minimum data point
+    * \param[out] max_pt the maximum data point
+    * \param[in] limit_negative \b false if data \b inside of the [min_distance; max_distance] interval should be
+    * considered, \b true otherwise.
+   */
+  PCL_EXPORTS void
+  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const Indices &indices, int x_idx, int y_idx, int z_idx,
                const std::string &distance_field_name, float min_distance, float max_distance,
                Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
 
@@ -515,7 +548,7 @@ namespace pcl
       VoxelGrid () :
         leaf_size_ (Eigen::Vector4f::Zero ()),
         inverse_leaf_size_ (Eigen::Array4f::Zero ()),
-        
+
         min_b_ (Eigen::Vector4i::Zero ()),
         max_b_ (Eigen::Vector4i::Zero ()),
         div_b_ (Eigen::Vector4i::Zero ()),
@@ -833,6 +866,21 @@ namespace pcl
       void
       applyFilter (PCLPointCloud2 &output) override;
   };
+
+  namespace internal
+  {
+    /** \brief Used internally in voxel grid classes.
+      */
+    struct cloud_point_index_idx
+    {
+      unsigned int idx;
+      unsigned int cloud_point_index;
+
+      cloud_point_index_idx() = default;
+      cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {}
+      bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); }
+    };
+  }
 }
 
 #ifdef PCL_NO_PRECOMPILE
index d2f69e788a00ef61e3391579822a0387b1eab6a5..2446a53d62c1b791ea2132b1151127361c13d000 100644 (file)
@@ -434,9 +434,10 @@ namespace pcl
 
       /** \brief Get a cloud to visualize each voxels normal distribution.
        * \param[out] cell_cloud a cloud created by sampling the normal distributions of each voxel
+       * \param[in] pnt_per_cell how many points should be generated for each cell
        */
       void
-      getDisplayCloud (pcl::PointCloud<PointXYZ>& cell_cloud);
+      getDisplayCloud (pcl::PointCloud<PointXYZ>& cell_cloud, int pnt_per_cell = 1000) const;
 
       /** \brief Search for the k-nearest occupied voxels for the given query point.
        * \note Only voxels containing a sufficient number of points are used.
index a55b84b3f30777606f45a46911e9b2cbd629b6da..1518d329809d909878d50330e278eb74782e9d0e 100644 (file)
@@ -216,7 +216,7 @@ namespace pcl
                     const Eigen::Vector4f& direction,
                     const float t_min);
 
-      /** \brief Returns a rounded value. 
+      /** \brief Returns a value rounded to the nearest integer
         * \param[in] d
         * \return rounded value
         */
@@ -226,8 +226,7 @@ namespace pcl
         return static_cast<float> (std::floor (d + 0.5f));
       }
 
-      // We use round here instead of std::floor due to some numerical issues.
-      /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). 
+      /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
         * \param[in] x the X point coordinate to get the (i, j, k) index at
         * \param[in] y the Y point coordinate to get the (i, j, k) index at
         * \param[in] z the Z point coordinate to get the (i, j, k) index at
index 7d35a463a0c41806bcd414fdf3f13a79ac04415b..41ffd02be9c9422575b68c8b87eb291e7beb73bd 100644 (file)
@@ -189,17 +189,5 @@ Convolution<pcl::RGB, pcl::RGB>::convolveOneColDense(int i, int j)
   result.b = static_cast<std::uint8_t>(b);
   return (result);
 }
-
-#ifndef PCL_NO_PRECOMPILE
-#include <pcl/impl/instantiate.hpp>
-#include <pcl/point_types.h>
-
-PCL_INSTANTIATE_PRODUCT(
-    Convolution, ((pcl::RGB))((pcl::RGB)))
-
-PCL_INSTANTIATE_PRODUCT(
-    Convolution, ((pcl::PointXYZRGB))((pcl::PointXYZRGB)))
-#endif // PCL_NO_PRECOMPILE
-
 } // namespace filters
 } // namespace pcl
index c56a285a0f51859582adcd7c2dd4acaeebc39e1d..4614bd186845c559ad9742906da28242bdec58c5 100644 (file)
@@ -61,7 +61,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     return;
   }
 
-  int nr_points = input_->width * input_->height;
+  uindex_t nr_points = input_->width * input_->height;
 
   // Check if we're going to keep the organized structure of the cloud or not
   if (keep_organized_)
@@ -96,10 +96,10 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
 
   removed_indices_->resize (input_->data.size ());
 
-  int nr_p = 0;
-  int nr_removed_p = 0;
+  uindex_t nr_p = 0;
+  uindex_t nr_removed_p = 0;
   // Create the first xyz_offset
-  Eigen::Array4i xyz_offset (input_->fields[x_idx_].offset, input_->fields[y_idx_].offset,
+  Eigen::Array<uindex_t, 4, 1> xyz_offset (input_->fields[x_idx_].offset, input_->fields[y_idx_].offset,
                              input_->fields[z_idx_].offset, 0);
 
   Eigen::Vector4f pt = Eigen::Vector4f::Zero ();
@@ -131,7 +131,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     {
       float distance_value = 0;
       // Go over all points
-      for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
+      for (uindex_t cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
       {
         // Copy all the fields
         memcpy (&output.data[cp * output.point_step], &input_->data[cp * output.point_step], output.point_step);
@@ -175,7 +175,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     {
       // Go over all points
       float distance_value = 0;
-      for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
+      for (uindex_t cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
       {
         // Get the distance value
         memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset],
@@ -242,7 +242,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
   // No distance filtering, process all data. No need to check for is_organized here as we did it above
   else
   {
-    for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
+    for (uindex_t cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
     {
       // Unoptimized memcpys: assume fields x, y, z are in random order
       memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer)
@@ -296,7 +296,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (Indices &indices)
   // The arrays to be used
   indices.resize (indices_->size ());
   removed_indices_->resize (indices_->size ());
-  int oii = 0, rii = 0;  // oii = output indices iterator, rii = removed indices iterator
+  uindex_t oii = 0, rii = 0;  // oii = output indices iterator, rii = removed indices iterator
   const auto x_offset = input_->fields[x_idx_].offset,
              y_offset = input_->fields[y_idx_].offset,
              z_offset = input_->fields[z_idx_].offset;
index f271d8d4da25888a0d66a29396a3320eb3513da4..97a75a6dbf1cab3bd71b35adf57b43d59ce7b164 100644 (file)
@@ -117,7 +117,11 @@ pcl::RandomSample<pcl::PCLPointCloud2>::applyFilter (Indices &indices)
       removed_indices_->resize (N - sample_size);
 
     // Set random seed so derived indices are the same each time the filter runs
+#ifdef __OpenBSD__
+    srand_deterministic (seed_); // OpenBSD only offers repeatable sequences with this function
+#else
     std::srand (seed_);
+#endif // __OpenBSD__
 
     // Algorithm S
     std::size_t i = 0;
index 3690d86c3fa64e19eb16a53491b4920336460bbf..a72ff3fdd6d16ef229d5916c5933d2ef953efde9 100644 (file)
@@ -227,11 +227,11 @@ pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2>::generateStatistics (double&
       continue;
     }
 
-    // Minimum distance (if mean_k_ == 2) or mean distance
-    double dist_sum = 0;
-    for (int j = 1; j < mean_k_; ++j)
-      dist_sum += sqrt (nn_dists[j]);
-    distances[cp] = static_cast<float> (dist_sum / (mean_k_ - 1));
+    // Calculate the mean distance to its neighbors.
+    double dist_sum = 0.0;
+    for (std::size_t k = 1; k < nn_dists.size(); ++k) // k = 0 is the query point
+      dist_sum += sqrt(nn_dists[k]);
+    distances[cp] = static_cast<float>(dist_sum / (nn_dists.size() - 1));
     valid_distances++;
   }
 
index 2a3ab968bfd42e114126aeba6def62887b8b65fa..7c83f27780708bcb75c6040771956e332d0b9582 100644 (file)
@@ -49,7 +49,7 @@ using Array4size_t = Eigen::Array<std::size_t, 4, 1>;
 ///////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
-                  Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
+                 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
 {
   // @todo fix this
   if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 ||
@@ -76,8 +76,8 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx
     memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float));
     memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float));
     // Check if the point is invalid
-    if (!std::isfinite (pt[0]) || 
-        !std::isfinite (pt[1]) || 
+    if (!std::isfinite (pt[0]) ||
+        !std::isfinite (pt[1]) ||
         !std::isfinite (pt[2]))
     {
       xyz_offset += cloud->point_step;
@@ -91,11 +91,66 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx
   max_pt = max_p;
 }
 
+///////////////////////////////////////////////////////////////////////////////////////////
+void
+pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const pcl::Indices &indices, int x_idx, int y_idx, int z_idx,
+            Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
+{
+  if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 ||
+      cloud->fields[y_idx].datatype != pcl::PCLPointField::FLOAT32 ||
+      cloud->fields[z_idx].datatype != pcl::PCLPointField::FLOAT32)
+  {
+    PCL_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!\n");
+    return;
+  }
+
+  Eigen::Array4f min_p, max_p;
+  min_p.setConstant (std::numeric_limits<float>::max());
+  max_p.setConstant (std::numeric_limits<float>::lowest());
+
+  Eigen::Array4f pt = Eigen::Array4f::Zero ();
+  Array4size_t xyz_offset (cloud->fields[x_idx].offset, cloud->fields[y_idx].offset, cloud->fields[z_idx].offset, 0);
+
+  if(cloud->is_dense) // no need to check validity of points
+  {
+    for (const auto& index : indices)
+    {
+      // Unoptimized memcpys: assume fields x, y, z are in random order
+      memcpy(&pt[0],&cloud->data[xyz_offset[0] + cloud->point_step * index],sizeof(float));
+      memcpy(&pt[1],&cloud->data[xyz_offset[1] + cloud->point_step * index],sizeof(float));
+      memcpy(&pt[2],&cloud->data[xyz_offset[2] + cloud->point_step * index],sizeof(float));
+      min_p = (min_p.min)(pt);
+      max_p = (max_p.max)(pt);
+    }
+  }
+  else
+  {
+    for (const auto& index : indices)
+    {
+      // Unoptimized memcpys: assume fields x, y, z are in random order
+      memcpy(&pt[0],&cloud->data[xyz_offset[0] + cloud->point_step * index],sizeof(float));
+      memcpy(&pt[1],&cloud->data[xyz_offset[1] + cloud->point_step * index],sizeof(float));
+      memcpy(&pt[2],&cloud->data[xyz_offset[2] + cloud->point_step * index],sizeof(float));
+      // Check if the point is invalid
+      if (!std::isfinite(pt[0]) ||
+          !std::isfinite(pt[1]) ||
+          !std::isfinite(pt[2]))
+      {
+        continue;
+      }
+      min_p = (min_p.min)(pt);
+      max_p = (max_p.max)(pt);
+    }
+  }
+  min_pt = min_p;
+  max_pt = max_p;
+}
+
 ///////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
-                  const std::string &distance_field_name, float min_distance, float max_distance,
-                  Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
+                 const std::string &distance_field_name, float min_distance, float max_distance,
+                 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
 {
   // @todo fix this
   if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 ||
@@ -124,9 +179,9 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx
 
   Eigen::Array4f pt = Eigen::Array4f::Zero ();
   Array4size_t xyz_offset (cloud->fields[x_idx].offset,
-                           cloud->fields[y_idx].offset,
-                           cloud->fields[z_idx].offset,
-                           0);
+                          cloud->fields[y_idx].offset,
+                          cloud->fields[z_idx].offset,
+                          0);
   float distance_value = 0;
   for (std::size_t cp = 0; cp < nr_points; ++cp)
   {
@@ -159,8 +214,8 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx
     memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float));
     memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float));
     // Check if the point is invalid
-    if (!std::isfinite (pt[0]) || 
-        !std::isfinite (pt[1]) || 
+    if (!std::isfinite (pt[0]) ||
+        !std::isfinite (pt[1]) ||
         !std::isfinite (pt[2]))
     {
       xyz_offset += cloud->point_step;
@@ -174,6 +229,124 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx
   max_pt = max_p;
 }
 
+///////////////////////////////////////////////////////////////////////////////////////////
+void
+pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const pcl::Indices &indices, int x_idx, int y_idx, int z_idx,
+            const std::string &distance_field_name, float min_distance, float max_distance,
+            Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
+{
+  // @todo fix this
+  if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 ||
+      cloud->fields[y_idx].datatype != pcl::PCLPointField::FLOAT32 ||
+      cloud->fields[z_idx].datatype != pcl::PCLPointField::FLOAT32)
+  {
+    PCL_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!\n");
+    return;
+  }
+
+  Eigen::Array4f min_p, max_p;
+  min_p.setConstant (std::numeric_limits<float>::max());
+  max_p.setConstant (std::numeric_limits<float>::lowest());
+
+  // Get the distance field index
+  int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name);
+
+  // @todo fix this
+  if (cloud->fields[distance_idx].datatype != pcl::PCLPointField::FLOAT32)
+  {
+    PCL_ERROR ("[pcl::getMinMax3D] Filtering dimensions is not float type!\n");
+    return;
+  }
+
+  Eigen::Array4f pt = Eigen::Array4f::Zero ();
+  Array4size_t xyz_offset (cloud->fields[x_idx].offset,
+                           cloud->fields[y_idx].offset,
+                           cloud->fields[z_idx].offset,
+                           0);
+  float distance_value = 0;
+  if(cloud->is_dense)
+  {
+    for (const auto& index : indices) {
+      std::size_t point_offset = index * cloud->point_step;
+
+      // Get the distance value
+      memcpy(&distance_value,
+             &cloud->data[point_offset + cloud->fields[distance_idx].offset],
+             sizeof(float));
+
+      if (limit_negative) {
+        // Use a threshold for cutting out points which inside the interval
+        if ((distance_value < max_distance) && (distance_value > min_distance)) {
+          continue;
+        }
+      }
+      else {
+        // Use a threshold for cutting out points which are too close/far away
+        if ((distance_value > max_distance) || (distance_value < min_distance)) {
+          continue;
+        }
+      }
+
+      // Unoptimized memcpys: assume fields x, y, z are in random order
+      memcpy(&pt[0],
+             &cloud->data[xyz_offset[0] + index * cloud->point_step],
+             sizeof(float));
+      memcpy(&pt[1],
+             &cloud->data[xyz_offset[1] + index * cloud->point_step],
+             sizeof(float));
+      memcpy(&pt[2],
+             &cloud->data[xyz_offset[2] + index * cloud->point_step],
+             sizeof(float));
+      min_p = (min_p.min)(pt);
+      max_p = (max_p.max)(pt);
+    }
+  }
+  else
+  {
+    for (const auto& index : indices)
+    {
+      std::size_t point_offset = index * cloud->point_step;
+
+      // Get the distance value
+      memcpy(&distance_value,&cloud->data[point_offset + cloud->fields[distance_idx].offset],sizeof(float));
+
+      if (limit_negative)
+      {
+        // Use a threshold for cutting out points which inside the interval
+        if ((distance_value < max_distance) && (distance_value > min_distance))
+        {
+          continue;
+        }
+      }
+      else
+      {
+        // Use a threshold for cutting out points which are too close/far away
+        if ((distance_value > max_distance) || (distance_value < min_distance))
+        {
+          continue;
+        }
+      }
+
+      // Unoptimized memcpys: assume fields x, y, z are in random order
+      memcpy(&pt[0],&cloud->data[xyz_offset[0] + index * cloud->point_step],sizeof(float));
+      memcpy(&pt[1],&cloud->data[xyz_offset[1] + index * cloud->point_step],sizeof(float));
+      memcpy(&pt[2],&cloud->data[xyz_offset[2] + index * cloud->point_step],sizeof(float));
+      // Check if the point is invalid
+      if (!std::isfinite(pt[0])
+          || !std::isfinite(pt[1])
+          || !std::isfinite(pt[2]))
+      {
+        continue;
+      }
+      min_p = (min_p.min)(pt);
+      max_p = (max_p.max)(pt);
+    }
+  }
+  min_pt = min_p;
+  max_pt = max_p;
+}
+
+
 ///////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
@@ -186,7 +359,6 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     output.data.clear ();
     return;
   }
-  std::size_t nr_points  = input_->width * input_->height;
 
   // Copy the header (and thus the frame_id) + allocate enough space for points
   output.height         = 1;                    // downsampling breaks the organized structure
@@ -217,11 +389,11 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
   Eigen::Vector4f min_p, max_p;
   // Get the minimum and maximum dimensions
   if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud...
-    getMinMax3D (input_, x_idx_, y_idx_, z_idx_, filter_field_name_, 
-                 static_cast<float> (filter_limit_min_), 
+    getMinMax3D (input_, *indices_, x_idx_, y_idx_, z_idx_, filter_field_name_,
+                 static_cast<float> (filter_limit_min_),
                  static_cast<float> (filter_limit_max_), min_p, max_p, filter_limit_negative_);
   else
-    getMinMax3D (input_, x_idx_, y_idx_, z_idx_, min_p, max_p);
+    getMinMax3D (input_, *indices_, x_idx_, y_idx_, z_idx_, min_p, max_p);
 
   // Check that the leaf size is not too small, given the size of the data
   std::int64_t dx = static_cast<std::int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
@@ -248,8 +420,8 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
   div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
   div_b_[3] = 0;
 
-  std::vector<cloud_point_index_idx> index_vector;
-  index_vector.reserve (nr_points);
+  std::vector<internal::cloud_point_index_idx> index_vector;
+  index_vector.reserve (indices_->size());
 
   // Create the first xyz_offset, and set up the division multiplier
   Array4size_t xyz_offset (input_->fields[x_idx_].offset,
@@ -265,8 +437,8 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
   if (downsample_all_data_)
   {
     centroid_size = static_cast<int> (input_->fields.size ());
-    
-    // ---[ RGB special case 
+
+    // ---[ RGB special case
     // if the data contains "rgba" or "rgb", add an extra field for r/g/b in centroid
     for (int d = 0; d < centroid_size; ++d)
     {
@@ -278,7 +450,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
       }
     }
   }
-  
+
   // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
   if (!filter_field_name_.empty ())
   {
@@ -298,9 +470,9 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     // with calculated idx. Points with the same idx value will contribute to the
     // same point of resulting CloudPoint
     float distance_value = 0;
-    for (std::size_t cp = 0; cp < nr_points; ++cp)
+    for (const auto &index : *indices_)
     {
-      std::size_t point_offset = cp * input_->point_step;
+      std::size_t point_offset = index * input_->point_step;
       // Get the distance value
       memcpy (&distance_value, &input_->data[point_offset + input_->fields[distance_idx].offset], sizeof (float));
 
@@ -309,7 +481,6 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
         // Use a threshold for cutting out points which inside the interval
         if (distance_value < filter_limit_max_ && distance_value > filter_limit_min_)
         {
-          xyz_offset += input_->point_step;
           continue;
         }
       }
@@ -318,22 +489,20 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
         // Use a threshold for cutting out points which are too close/far away
         if (distance_value > filter_limit_max_ || distance_value < filter_limit_min_)
         {
-          xyz_offset += input_->point_step;
           continue;
         }
       }
 
       // Unoptimized memcpys: assume fields x, y, z are in random order
-      memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
-      memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
-      memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
+      memcpy (&pt[0], &input_->data[xyz_offset[0] + index * input_->point_step], sizeof (float));
+      memcpy (&pt[1], &input_->data[xyz_offset[1] + index * input_->point_step], sizeof (float));
+      memcpy (&pt[2], &input_->data[xyz_offset[2] + index * input_->point_step], sizeof (float));
 
       // Check if the point is invalid
-      if (!std::isfinite (pt[0]) || 
-          !std::isfinite (pt[1]) || 
+      if (!std::isfinite (pt[0]) ||
+          !std::isfinite (pt[1]) ||
           !std::isfinite (pt[2]))
       {
-        xyz_offset += input_->point_step;
         continue;
       }
 
@@ -342,28 +511,26 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
       int ijk2 = static_cast<int> (std::floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]);
       // Compute the centroid leaf index
       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
-      index_vector.emplace_back(idx, static_cast<unsigned int> (cp));
+      index_vector.emplace_back(idx, static_cast<unsigned int> (index));
 
-      xyz_offset += input_->point_step;
     }
   }
   // No distance filtering, process all data
   else
   {
     // First pass: go over all points and insert them into the right leaf
-    for (std::size_t cp = 0; cp < nr_points; ++cp)
+    for (const auto &index : *indices_)
     {
       // Unoptimized memcpys: assume fields x, y, z are in random order
-      memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
-      memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
-      memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
+      memcpy (&pt[0], &input_->data[xyz_offset[0] + index * input_->point_step], sizeof (float));
+      memcpy (&pt[1], &input_->data[xyz_offset[1] + index * input_->point_step], sizeof (float));
+      memcpy (&pt[2], &input_->data[xyz_offset[2] + index * input_->point_step], sizeof (float));
 
       // Check if the point is invalid
-      if (!std::isfinite (pt[0]) || 
-          !std::isfinite (pt[1]) || 
+      if (!std::isfinite (pt[0]) ||
+          !std::isfinite (pt[1]) ||
           !std::isfinite (pt[2]))
       {
-        xyz_offset += input_->point_step;
         continue;
       }
 
@@ -372,14 +539,13 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
       int ijk2 = static_cast<int> (std::floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]);
       // Compute the centroid leaf index
       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
-      index_vector.emplace_back(idx, static_cast<unsigned int> (cp));
-      xyz_offset += input_->point_step;
+      index_vector.emplace_back(idx, static_cast<unsigned int> (index));
     }
   }
 
   // Second pass: sort the index_vector vector using value representing target cell as index
   // in effect all points belonging to the same output cell will be next to each other
-  auto rightshift_func = [](const cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
+  auto rightshift_func = [](const internal::cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
   boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func);
 
   // Third pass: count output cells
@@ -392,10 +558,10 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
   std::vector<std::pair<index_t, index_t> > first_and_last_indices_vector;
   // Worst case size
   first_and_last_indices_vector.reserve (index_vector.size ());
-  while (index < index_vector.size ()) 
+  while (index < index_vector.size ())
   {
     std::size_t i = index + 1;
-    while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) 
+    while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx)
       ++i;
     if ((i - index) >= min_points_per_voxel_)
     {
@@ -410,7 +576,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
   output.row_step = output.point_step * output.width;
   output.data.resize (output.width * output.point_step);
 
-  if (save_leaf_layout_) 
+  if (save_leaf_layout_)
   {
     try
     {
@@ -421,21 +587,21 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
       for (std::uint32_t i = 0; i < reinit_size; i++)
       {
         leaf_layout_[i] = -1;
-      }        
-      leaf_layout_.resize (new_layout_size, -1);           
+      }
+      leaf_layout_.resize (new_layout_size, -1);
     }
     catch (std::bad_alloc&)
     {
-      throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
-        "voxel_grid.cpp", "applyFilter");      
+      throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout",
+        "voxel_grid.cpp", "applyFilter");
     }
     catch (std::length_error&)
     {
-      throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
-        "voxel_grid.cpp", "applyFilter");      
+      throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout",
+        "voxel_grid.cpp", "applyFilter");
     }
   }
-  
+
   // If we downsample each field, the {x,y,z}_idx_ offsets should correspond in input_ and output
   if (downsample_all_data_)
     xyz_offset = Array4size_t (output.fields[x_idx_].offset,
@@ -506,7 +672,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
         centroid += temporary;
       }
       centroid /= static_cast<float> (last_index - first_index);
-      
+
       std::size_t point_offset = index * output.point_step;
       // Copy all the fields
       for (std::size_t d = 0; d < output.fields.size (); ++d)
@@ -514,14 +680,14 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
 
       // ---[ RGB special case
       // full extra r/g/b centroid field
-      if (rgba_index >= 0) 
+      if (rgba_index >= 0)
       {
         float r = centroid[centroid_size-4], g = centroid[centroid_size-3], b = centroid[centroid_size-2], a = centroid[centroid_size-1];
         int rgb = (static_cast<int> (a) << 24) | (static_cast<int> (r) << 16) | (static_cast<int> (g) << 8) | static_cast<int> (b);
         memcpy (&output.data[point_offset + output.fields[rgba_index].offset], &rgb, sizeof (float));
       }
     }
-     
+
     ++index;
   }
 }
index 13dd7cdfdb49e4fcfc487b9ae2f423e7630246b8..1d7e9ab96ad2df2c19b682f49b0b73cf9963b114 100644 (file)
@@ -37,8 +37,9 @@
  */
 
 #include <map>
+#include <pcl/common/common.h> // for getMinMax3D
 #include <pcl/filters/voxel_grid_label.h>
-#include <pcl/filters/impl/voxel_grid.hpp>
+#include <boost/mpl/size.hpp> // for boost::mpl::size
 
 //////////////////////////////////////////////////////////////////////////////
 void
@@ -111,7 +112,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)
   int label_index = -1;
   label_index = pcl::getFieldIndex<PointXYZRGBL> ("label", fields);
 
-  std::vector<cloud_point_index_idx> index_vector;
+  std::vector<internal::cloud_point_index_idx> index_vector;
   index_vector.reserve(input_->size());
 
   // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
index cafc32e43bbb6a4bf33d079842e0134fc620a021..6f3d527c9cd24264bbd1a5311651372725703f49 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME geometry)
 set(SUBSYS_DESC "Point cloud geometry library")
 set(SUBSYS_DEPS common)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
@@ -14,7 +13,6 @@ endif()
 
 set(incs
   "include/pcl/${SUBSYS_NAME}/boost.h"
-  "include/pcl/${SUBSYS_NAME}/eigen.h"
   "include/pcl/${SUBSYS_NAME}/get_boundary.h"
   "include/pcl/${SUBSYS_NAME}/line_iterator.h"
   "include/pcl/${SUBSYS_NAME}/mesh_base.h"
@@ -36,12 +34,8 @@ set(impl_incs
   "include/pcl/${SUBSYS_NAME}/impl/polygon_operations.hpp"
 )
 
-
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
-add_library(${LIB_NAME} INTERFACE)
-target_include_directories(${LIB_NAME} INTERFACE "${CMAKE_CURRENT_SOURCE_DIR}/include")
+PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} INCLUDES ${incs} ${impl_incs})
 target_link_libraries(${LIB_NAME} INTERFACE Boost::boost pcl_common)
 
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} HEADER_ONLY)
diff --git a/geometry/include/pcl/geometry/eigen.h b/geometry/include/pcl/geometry/eigen.h
deleted file mode 100644 (file)
index 2f250e2..0000000
+++ /dev/null
@@ -1,49 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- * Point Cloud Library (PCL) - www.pointclouds.org
- * Copyright (c) 2009-2012, Willow Garage, Inc.
- * Copyright (c) 2012-, Open Perception, Inc.
- *
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of the copyright holder(s) nor the names of its
- *    contributors may be used to endorse or promote products derived
- *    from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-
-#pragma once
-
-#ifdef __GNUC__
-#pragma GCC system_header
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-
-#include <Eigen/Core>
-#include <Eigen/StdVector>
index f0437d2d5d35e59ec377f38e454a12031b21f9a8..014b8c862eb282808042d8b8450600f146cd2848 100644 (file)
@@ -1333,7 +1333,7 @@ protected:
                  HalfEdgeIndex& /*idx_free_half_edge*/,
                  std::true_type /*is_manifold*/) const
   {
-    return !(is_new_ab && is_new_bc && !is_isolated_b);
+    return (!is_new_ab || !is_new_bc || is_isolated_b);
   }
 
   /** \brief Check if the half-edge bc is the next half-edge of ab.
@@ -1804,14 +1804,14 @@ protected:
                                 typename IndexContainerT::value_type());
     Index ind_old(0), ind_new(0);
 
-    typename ElementContainerT::const_iterator it_e_old = elements.begin();
+    auto it_e_old = elements.cbegin();
     auto it_e_new = elements.begin();
 
-    typename DataContainerT::const_iterator it_d_old = data_cloud.begin();
+    auto it_d_old = data_cloud.cbegin();
     auto it_d_new = data_cloud.begin();
 
     auto it_ind_new = new_indices.begin();
-    typename IndexContainerT::const_iterator it_ind_new_end = new_indices.end();
+    auto it_ind_new_end = new_indices.cend();
 
     while (it_ind_new != it_ind_new_end) {
       if (!this->isDeleted(ind_old)) {
index 45daad5c6efbe54f6f3b112c927d478095c1abbf..a126cef8ac7e18ca4bc15d86a611115ed51ef3ca 100644 (file)
@@ -2,7 +2,7 @@ set(SUBSYS_NAME gpu)
 set(SUBSYS_DESC "Point cloud GPU libraries")
 set(SUBSYS_DEPS)
 
-option(BUILD_GPU "Build the GPU-related subsystems" ${DEFAULT})
+option(BUILD_GPU "Build the GPU-related subsystems" OFF)
 
 if(NOT (BUILD_GPU AND CUDA_FOUND))
   return()
index f25120bafc03d2f49bff7b2b25510df67d2214c9..a07418e0fd4e0373f2b90cc82019b4eb8e16642a 100644 (file)
@@ -1,9 +1,8 @@
 set(SUBSYS_NAME gpu_containers)
 set(SUBSYS_PATH gpu/containers)
 set(SUBSYS_DESC "Containers with reference counting for GPU memory. This module can be compiled without Cuda Toolkit.")
-set(SUBSYS_DEPS common)
+set(SUBSYS_DEPS common gpu_utils)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}")
@@ -13,19 +12,16 @@ if(NOT build)
   return()
 endif()
 
-file(GLOB srcs src/*.cpp src/*.hpp)
+file(GLOB srcs src/*.cpp src/*.cu src/*.hpp)
 file(GLOB incs include/pcl/gpu/containers/*.h)
 file(GLOB incs_impl include/pcl/gpu/containers/impl/*.hpp)
 
 source_group("Header Files\\impl" FILES ${incs_impl})
 list(APPEND incs ${incs_impl})
 
-get_filename_component(UTILS_INC "${CMAKE_CURRENT_SOURCE_DIR}/../utils/include" REALPATH)
-
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" ${UTILS_INC})
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
-target_link_libraries(${LIB_NAME} pcl_common)
+target_link_libraries(${LIB_NAME} pcl_common pcl_gpu_utils)
 
 #Ensures that CUDA is added and the project can compile as it uses cuda calls.
 set_source_files_properties(src/device_memory.cpp PROPERTIES LANGUAGE CUDA)
diff --git a/gpu/containers/include/pcl/gpu/containers/impl/repacks.hpp b/gpu/containers/include/pcl/gpu/containers/impl/repacks.hpp
new file mode 100644 (file)
index 0000000..db9c7f2
--- /dev/null
@@ -0,0 +1,154 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Copyright (c) 2011, Willow Garage, Inc.
+ *  All rights reserved.
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * Redistributions in binary form must reproduce the above
+ *     copyright notice, this list of conditions and the following
+ *     disclaimer in the documentation and/or other materials provided
+ *     with the distribution.
+ *   * Neither the name of Willow Garage, Inc. nor the names of its
+ *     contributors may be used to endorse or promote products derived
+ *     from this software without specific prior written permission.
+ *
+ *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ *  POSSIBILITY OF SUCH DAMAGE.
+ *
+ *  Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
+ */
+
+#ifndef __PCL_GPU_UTILS_REPACKS_HPP__
+#define __PCL_GPU_UTILS_REPACKS_HPP__
+
+#include <pcl/gpu/containers/device_array.h>
+#include <pcl/pcl_macros.h>
+#include <pcl/point_types.h>
+
+namespace pcl {
+namespace gpu {
+///////////////////////////////////////
+///  This is an experimental code   ///
+///////////////////////////////////////
+
+const int NoCP = 0xFFFFFFFF;
+
+/** \brief Returns field copy operation code. */
+inline int
+cp(int from, int to)
+{
+  return ((to & 0xF) << 4) + (from & 0xF);
+}
+
+/* Combines several field copy operations to one int (called rule) */
+inline int
+rule(int cp1, int cp2 = NoCP, int cp3 = NoCP, int cp4 = NoCP)
+{
+  return (cp1 & 0xFF) + ((cp2 & 0xFF) << 8) + ((cp3 & 0xFF) << 16) +
+         ((cp4 & 0xFF) << 24);
+}
+
+/* Combines performs all field copy operations in given rule array (can be 0, 1, or 16
+ * copies) */
+void
+copyFieldsImpl(
+    int in_size, int out_size, int rules[4], int size, const void* input, void* output);
+
+template <typename PointIn, typename PointOut>
+void
+copyFieldsEx(const DeviceArray<PointIn>& src,
+             DeviceArray<PointOut>& dst,
+             int rule1,
+             int rule2 = NoCP,
+             int rule3 = NoCP,
+             int rule4 = NoCP)
+{
+  int rules[4] = {rule1, rule2, rule3, rule4};
+  dst.create(src.size());
+  copyFieldsImpl(sizeof(PointIn) / sizeof(int),
+                 sizeof(PointOut) / sizeof(int),
+                 rules,
+                 (int)src.size(),
+                 src.ptr(),
+                 dst.ptr());
+}
+
+void
+copyFields(const DeviceArray<PointXYZ>& src, DeviceArray<PointNormal>& dst)
+{
+  // PointXYZ.x (0) -> PointNormal.x (0)
+  // PointXYZ.y (1) -> PointNormal.y (1)
+  // PointXYZ.z (2) -> PointNormal.z (2)
+  copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
+};
+
+void
+copyFields(const DeviceArray<Normal>& src, DeviceArray<PointNormal>& dst)
+{
+  // PointXYZ.normal_x (0)  -> PointNormal.normal_x (4)
+  // PointXYZ.normal_y (1)  -> PointNormal.normal_y (5)
+  // PointXYZ.normal_z (2)  -> PointNormal.normal_z (6)
+  // PointXYZ.curvature (4) -> PointNormal.curvature (8)
+  copyFieldsEx(src, dst, rule(cp(0, 4), cp(1, 5), cp(2, 6), cp(4, 8)));
+};
+
+void
+copyFields(const DeviceArray<PointXYZRGBL>& src, DeviceArray<PointXYZ>& dst)
+{
+  // PointXYZRGBL.x (0) -> PointXYZ.x (0)
+  // PointXYZRGBL.y (1) -> PointXYZ.y (1)
+  // PointXYZRGBL.z (2) -> PointXYZ.z (2)
+  copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
+};
+
+void
+copyFields(const DeviceArray<PointXYZRGB>& src, DeviceArray<PointXYZ>& dst)
+{
+  // PointXYZRGB.x (0) -> PointXYZ.x (0)
+  // PointXYZRGB.y (1) -> PointXYZ.y (1)
+  // PointXYZRGB.z (2) -> PointXYZ.z (2)
+  copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
+};
+
+void
+copyFields(const DeviceArray<PointXYZRGBA>& src, DeviceArray<PointXYZ>& dst)
+{
+  // PointXYZRGBA.x (0) -> PointXYZ.x (0)
+  // PointXYZRGBA.y (1) -> PointXYZ.y (1)
+  // PointXYZRGBA.z (2) -> PointXYZ.z (2)
+  copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
+};
+
+void
+copyFieldsZ(const DeviceArray<PointXYZ>& src, DeviceArray<float>& dst)
+{
+  // PointXYZRGBL.z (2) -> float (1)
+  copyFieldsEx(src, dst, rule(cp(2, 0)));
+};
+
+void
+copyFieldsZ(const DeviceArray<PointXYZRGB>& src, DeviceArray<float>& dst)
+{
+  // PointXYZRGBL.z (2) -> float (1)
+  copyFieldsEx(src, dst, rule(cp(2, 0)));
+};
+} // namespace gpu
+} // namespace pcl
+
+#endif /* __PCL_GPU_UTILS_REPACKS_HPP__ */
diff --git a/gpu/containers/include/pcl/gpu/containers/impl/texture_binder.hpp b/gpu/containers/include/pcl/gpu/containers/impl/texture_binder.hpp
new file mode 100644 (file)
index 0000000..16dede9
--- /dev/null
@@ -0,0 +1,93 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Copyright (c) 2011, Willow Garage, Inc.
+ *  All rights reserved.
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * Redistributions in binary form must reproduce the above
+ *     copyright notice, this list of conditions and the following
+ *     disclaimer in the documentation and/or other materials provided
+ *     with the distribution.
+ *   * Neither the name of Willow Garage, Inc. nor the names of its
+ *     contributors may be used to endorse or promote products derived
+ *     from this software without specific prior written permission.
+ *
+ *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ *  POSSIBILITY OF SUCH DAMAGE.
+ *
+ *  Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
+ */
+
+#ifndef PCL_GPU_UTILS_TEXTURE_BINDER_HPP_
+#define PCL_GPU_UTILS_TEXTURE_BINDER_HPP_
+
+#include <pcl/gpu/containers/device_array.h>
+#include <pcl/gpu/utils/safe_call.hpp>
+
+namespace pcl {
+namespace gpu {
+class TextureBinder {
+public:
+  template <class T, enum cudaTextureReadMode readMode>
+  TextureBinder(const DeviceArray2D<T>& arr, const struct texture<T, 2, readMode>& tex)
+  : texref(&tex)
+  {
+    cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();
+    cudaSafeCall(
+        cudaBindTexture2D(0, tex, arr.ptr(), desc, arr.cols(), arr.rows(), arr.step()));
+  }
+
+  template <class T, enum cudaTextureReadMode readMode>
+  TextureBinder(const DeviceArray<T>& arr, const struct texture<T, 1, readMode>& tex)
+  : texref(&tex)
+  {
+    cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();
+    cudaSafeCall(cudaBindTexture(0, tex, arr.ptr(), desc, arr.sizeBytes()));
+  }
+
+  template <class T, enum cudaTextureReadMode readMode>
+  TextureBinder(const PtrStepSz<T>& arr, const struct texture<T, 2, readMode>& tex)
+  : texref(&tex)
+  {
+    cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();
+    cudaSafeCall(
+        cudaBindTexture2D(0, tex, arr.data, desc, arr.cols, arr.rows, arr.step));
+  }
+
+  template <class T, enum cudaTextureReadMode readMode>
+  TextureBinder(const PtrSz<T>& arr, const struct texture<T, 1, readMode>& tex)
+  : texref(&tex)
+  {
+    cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();
+    cudaSafeCall(cudaBindTexture(0, tex, arr.data, desc, arr.size * arr.elemSize()));
+  }
+
+  ~TextureBinder() { cudaSafeCall(cudaUnbindTexture(texref)); }
+
+private:
+  const struct textureReference* texref;
+};
+} // namespace gpu
+
+namespace device {
+using pcl::gpu::TextureBinder;
+}
+} // namespace pcl
+
+#endif /* PCL_GPU_UTILS_TEXTURE_BINDER_HPP_*/
\ No newline at end of file
index 8bcc642884b34e41b3d10bac1d6bc5a91fdacedb..dbd4cadf88c8c866b69e25469bed5f20b9d606f1 100644 (file)
@@ -42,7 +42,9 @@
 #include <array> // replace c-style array with std::array
 #include <cstdio>
 
+#if !defined(HAVE_CUDA)
 #define HAVE_CUDA
+#endif
 //#include <pcl_config.h>
 
 #if !defined(HAVE_CUDA)
diff --git a/gpu/containers/src/repacks.cu b/gpu/containers/src/repacks.cu
new file mode 100644 (file)
index 0000000..e99956a
--- /dev/null
@@ -0,0 +1,120 @@
+#include <pcl/gpu/utils/safe_call.hpp>
+#include <pcl/pcl_exports.h>
+
+#include <algorithm>
+
+namespace pcl
+{
+    namespace device
+    {
+        struct Info
+        {
+            enum { SIZE = 4 };
+            int data[SIZE];
+        };
+
+        template<int n>
+        struct Point
+        {
+            int data[n];
+        };
+
+        template<int in, int out, typename Info>
+        __global__ void deviceCopyFields4B(const Info info, const int size, const void* input, void* output)
+        {
+            int idx = blockIdx.x * blockDim.x + threadIdx.x;
+
+            if (idx < size)
+            {
+                Point<in>  point_in  = reinterpret_cast<const  Point<in>* >( input)[idx];
+                Point<out> point_out = reinterpret_cast<      Point<out>* >(output)[idx];
+
+                for(int i = 0; i < Info::SIZE; ++i)
+                {
+                    int byte;
+                    int code = info.data[i];
+
+                    byte = ((code >> 0) & 0xFF);
+
+                    if (byte == 0xFF)
+                        break;
+                    else
+                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
+
+                    byte = ((code >> 8) & 0xFF);
+
+                    if (byte == 0xFF)
+                        break;
+                    else
+                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
+
+                    byte = ((code >> 16) & 0xFF);
+
+                    if (byte == 0xFF)
+                        break;
+                    else
+                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
+
+                    byte = ((code >> 24) & 0xFF);
+
+                    if (byte == 0xFF)
+                        break;
+                    else
+                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
+                }
+
+                reinterpret_cast< Point<out>* >(output)[idx] = point_out;
+            }
+        };
+
+        template<int in_size, int out_size>
+        void cf(int info[4], int size, const void* input, void* output)
+        {
+            Info i;
+            std::copy(info, info + 4, i.data);
+
+            dim3 block(256);
+            dim3 grid(divUp(size, block.x));
+
+            deviceCopyFields4B<in_size, out_size><<<grid, block>>>(i, size, input, output);
+            cudaSafeCall ( cudaGetLastError () );
+            cudaSafeCall (cudaDeviceSynchronize ());
+        }
+
+        using copy_fields_t = void (*)(int info[4], int size, const void* input, void* output);
+    }
+}
+
+namespace pcl
+{
+    namespace gpu
+    {
+        using namespace pcl::device;
+
+        PCL_EXPORTS void copyFieldsImpl(int in_size, int out_size, int rules[4], int size, const void* input, void* output)
+        {
+            pcl::device::copy_fields_t funcs[16][16] =
+            {
+                { /**/ cf<1,1>,  cf<1, 2>, cf<1, 3>, cf<1, 4>, /**/ cf<1, 5>, cf<1, 6>, cf<1, 7>, cf<1, 8>, /**/ cf<1, 9>, cf<1,10>, cf<1, 11>, cf<1, 12>, /**/ cf<1, 13>, cf<1, 14>, cf<1, 15>,  cf<1,16> },
+                { /**/ cf<2,1>,  cf<2, 2>, cf<2, 3>, cf<2, 4>, /**/ cf<2, 5>, cf<2, 6>, cf<2, 7>, cf<2, 8>, /**/ cf<2, 9>, cf<1,10>, cf<2, 11>, cf<2, 12>, /**/ cf<2, 13>, cf<2, 14>, cf<2, 15>,  cf<2,16> },
+                { /**/ cf<3,1>,  cf<3, 2>, cf<3, 3>, cf<3, 4>, /**/ cf<3, 5>, cf<3, 6>, cf<3, 7>, cf<3, 8>, /**/ cf<3, 9>, cf<1,10>, cf<3, 11>, cf<3, 12>, /**/ cf<3, 13>, cf<3, 14>, cf<3, 15>,  cf<3,16> },
+                { /**/ cf<4,1>,  cf<4, 2>, cf<4, 3>, cf<4, 4>, /**/ cf<4, 5>, cf<4, 6>, cf<4, 7>, cf<4, 8>, /**/ cf<4, 9>, cf<1,10>, cf<4, 11>, cf<4, 12>, /**/ cf<4, 13>, cf<4, 14>, cf<4, 15>,  cf<4,16> },
+                { /**/ cf<5,1>,  cf<5, 2>, cf<5, 3>, cf<5, 4>, /**/ cf<5, 5>, cf<5, 6>, cf<5, 7>, cf<5, 8>, /**/ cf<5, 9>, cf<1,10>, cf<5, 11>, cf<5, 12>, /**/ cf<5, 13>, cf<5, 14>, cf<5, 15>,  cf<5,16> },
+                { /**/ cf<6,1>,  cf<6, 2>, cf<6, 3>, cf<6, 4>, /**/ cf<6, 5>, cf<6, 6>, cf<6, 7>, cf<6, 8>, /**/ cf<6, 9>, cf<1,10>, cf<6, 11>, cf<6, 12>, /**/ cf<6, 13>, cf<6, 14>, cf<6, 15>,  cf<6,16> },
+                { /**/ cf<7,1>,  cf<7, 2>, cf<7, 3>, cf<7, 4>, /**/ cf<7, 5>, cf<7, 6>, cf<7, 7>, cf<7, 8>, /**/ cf<7, 9>, cf<1,10>, cf<7, 11>, cf<7, 12>, /**/ cf<7, 13>, cf<7, 14>, cf<7, 15>,  cf<7,16> },
+                { /**/ cf<8,1>,  cf<8, 2>, cf<8, 3>, cf<8, 4>, /**/ cf<8, 5>, cf<8, 6>, cf<8, 7>, cf<8, 8>, /**/ cf<8, 9>, cf<1,10>, cf<8, 11>, cf<8, 12>, /**/ cf<8, 13>, cf<8, 14>, cf<8, 15>,  cf<8,16> },
+                { /**/ cf<9,1>,  cf<9, 2>, cf<9, 3>, cf<9, 4>, /**/ cf<9, 5>, cf<9, 6>, cf<9, 7>, cf<9, 8>, /**/ cf<9, 9>, cf<1,10>, cf<9, 11>, cf<9, 12>, /**/ cf<9, 13>, cf<9, 14>, cf<9, 15>,  cf<9,16> },
+                { /**/ cf<10,1>, cf<10,2>, cf<10,3>, cf<10,4>, /**/ cf<10,5>, cf<10,6>, cf<10,7>, cf<10,8>, /**/ cf<10,9>, cf<1,10>, cf<10,11>, cf<10,12>, /**/ cf<10,13>, cf<10,14>, cf<10,15>, cf<10,16> },
+                { /**/ cf<11,1>, cf<11,2>, cf<11,3>, cf<11,4>, /**/ cf<11,5>, cf<11,6>, cf<11,7>, cf<11,8>, /**/ cf<11,9>, cf<1,10>, cf<11,11>, cf<11,12>, /**/ cf<11,13>, cf<11,14>, cf<11,15>, cf<11,16> },
+                { /**/ cf<12,1>, cf<12,2>, cf<12,3>, cf<12,4>, /**/ cf<12,5>, cf<12,6>, cf<12,7>, cf<12,8>, /**/ cf<12,9>, cf<1,10>, cf<12,11>, cf<12,12>, /**/ cf<12,13>, cf<12,14>, cf<12,15>, cf<12,16> },
+                { /**/ cf<13,1>, cf<13,2>, cf<13,3>, cf<13,4>, /**/ cf<13,5>, cf<13,6>, cf<13,7>, cf<13,8>, /**/ cf<13,9>, cf<1,10>, cf<13,11>, cf<13,12>, /**/ cf<13,13>, cf<13,14>, cf<13,15>, cf<13,16> },
+                { /**/ cf<14,1>, cf<14,2>, cf<14,3>, cf<14,4>, /**/ cf<14,5>, cf<14,6>, cf<14,7>, cf<14,8>, /**/ cf<14,9>, cf<1,10>, cf<14,11>, cf<14,12>, /**/ cf<14,13>, cf<14,14>, cf<14,15>, cf<14,16> },
+                { /**/ cf<15,1>, cf<15,2>, cf<15,3>, cf<15,4>, /**/ cf<15,5>, cf<15,6>, cf<15,7>, cf<15,8>, /**/ cf<15,9>, cf<1,10>, cf<15,11>, cf<15,12>, /**/ cf<15,13>, cf<15,14>, cf<15,15>, cf<15,16> },
+                { /**/ cf<16,1>, cf<16,2>, cf<16,3>, cf<16,4>, /**/ cf<16,5>, cf<16,6>, cf<16,7>, cf<16,8>, /**/ cf<16,9>, cf<1,10>, cf<16,11>, cf<16,12>, /**/ cf<16,13>, cf<16,14>, cf<16,15>, cf<16,16> }
+            };
+
+            funcs[in_size-1][out_size-1](rules, size, input, output);
+        }
+    }
+}
+
index 2d2954fe7fa0465d8ca0bfe70b7a6c5384b25d2e..4eecde02fc0041836013bc5ff1d7515e58846f37 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/features)
 set(SUBSYS_DESC "Temporary GPU_common module. Weak CUDA dependency: a code that use this module requires CUDA Toolkit installed, but should be compiled without nvcc")
 set(SUBSYS_DEPS common gpu_containers gpu_utils gpu_octree geometry)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}")
@@ -25,7 +24,6 @@ file(GLOB srcs_utils src/utils/*.hpp)
 source_group("Source Files\\utils" FILES ${srcs_utils})
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${cuda} ${srcs_utils}  ${dev_incs})
 target_link_libraries("${LIB_NAME}" pcl_gpu_utils pcl_gpu_containers pcl_gpu_octree)
 
index 5e73df35d806cf474e3b8f49f24f7493af03e62b..8ba0f80eefc41b1ba03217e46466eb386e2fe946 100644 (file)
@@ -36,6 +36,7 @@
 
 #include "internal.hpp"
 
+#include <thrust/tuple.h>
 #include <thrust/device_ptr.h>
 #include <thrust/transform_reduce.h>
 #include <thrust/iterator/permutation_iterator.h>
@@ -56,26 +57,26 @@ namespace pcl
 
         struct PlusFloat3
         {
-            __device__ __forceinline__ float3 operator()(const float3& e1, const float3& e2) const 
-            { 
-                return make_float3(e1.x + e2.x, e1.y + e2.y, e1.z + e2.z); 
+            __device__ __forceinline__ float3 operator()(const float3& e1, const float3& e2) const
+            {
+                return make_float3(e1.x + e2.x, e1.y + e2.y, e1.z + e2.z);
             }
         };
-        
+
         struct TupleDistCvt
         {
             float3 pivot_;
             TupleDistCvt(const float3& pivot) : pivot_(pivot) {}
-            __device__ __forceinline__ thrust::tuple<float, int> operator()(const thrust::tuple<float4, int>& t) const 
-            { 
-                float4 point = t.get<0>();
+            __device__ __forceinline__ thrust::tuple<float, int> operator()(const thrust::tuple<float4, int>& t) const
+            {
+                float4 point = thrust::get<0>(t);
 
                 float dx = pivot_.x - point.x;
                 float dy = pivot_.y - point.y;
                 float dz = pivot_.z - point.z;
                 float dist = sqrt(dx*dx + dy*dy + dz*dz);
 
-                return thrust::tuple<float, int>(dist, t.get<1>());                                
+                return thrust::tuple<float, int>(dist, thrust::get<1>(t));
             }
         };
 
@@ -87,7 +88,7 @@ void pcl::device::compute3DCentroid(const DeviceArray<PointT>& cloud, float3& ce
 {
     thrust::device_ptr<PointT> src_beg((PointT*)cloud.ptr());
     thrust::device_ptr<PointT> src_end = src_beg + cloud.size();
-                
+
     centroid = transform_reduce(src_beg, src_beg, PointT2float3<PointT>(), make_float3(0.f, 0.f, 0.f), PlusFloat3());
     centroid *= 1.f/cloud.size();
 }
@@ -99,13 +100,13 @@ void pcl::device::compute3DCentroid(const DeviceArray<PointT>& cloud, const Indi
         compute3DCentroid(cloud, centroid);
     else
     {
-        thrust::device_ptr<PointT> src_beg((PointT*)cloud.ptr());    
+        thrust::device_ptr<PointT> src_beg((PointT*)cloud.ptr());
         thrust::device_ptr<int> map_beg((int*)indices.ptr());
         thrust::device_ptr<int> map_end = map_beg + indices.size();
 
 
         centroid = transform_reduce(make_permutation_iterator(src_beg, map_beg),
-            make_permutation_iterator(src_beg, map_end), 
+            make_permutation_iterator(src_beg, map_end),
             PointT2float3<PointT>(), make_float3(0.f, 0.f, 0.f), PlusFloat3());
 
         centroid *= 1.f/indices.size();
@@ -114,7 +115,7 @@ void pcl::device::compute3DCentroid(const DeviceArray<PointT>& cloud, const Indi
 
 template<typename PointT>
 float3 pcl::device::getMaxDistance(const DeviceArray<PointT>& cloud, const float3& pivot)
-{   
+{
     thrust::device_ptr<PointT> src_beg((PointT*)cloud.ptr());
     thrust::device_ptr<PointT> src_end = src_beg + cloud.size();
 
@@ -123,14 +124,14 @@ float3 pcl::device::getMaxDistance(const DeviceArray<PointT>& cloud, const float
 
     thrust::tuple<float, int> init(0.f, 0);
     thrust::maximum<thrust::tuple<float, int>> op;
-    
+
     thrust::tuple<float, int> res =
         transform_reduce(
         make_zip_iterator(make_tuple( src_beg, cf )),
         make_zip_iterator(make_tuple( src_beg, ce )),
         TupleDistCvt(pivot), init, op);
 
-    float4 point = src_beg[res.get<1>()];
+    float4 point = src_beg[thrust::get<1>(res)];
 
     return make_float3(point.x, point.y, point.z);
 }
@@ -138,11 +139,11 @@ float3 pcl::device::getMaxDistance(const DeviceArray<PointT>& cloud, const float
 
 template<typename PointT>
 float3 pcl::device::getMaxDistance(const DeviceArray<PointT>& cloud, const Indices& indices, const float3& pivot)
-{   
+{
     if (indices.empty())
         return getMaxDistance(cloud, pivot);
 
-    thrust::device_ptr<PointT> src_beg((PointT*)cloud.ptr());    
+    thrust::device_ptr<PointT> src_beg((PointT*)cloud.ptr());
     thrust::device_ptr<int> map_beg((int*)indices.ptr());
     thrust::device_ptr<int> map_end = map_beg + indices.size();
 
@@ -151,13 +152,13 @@ float3 pcl::device::getMaxDistance(const DeviceArray<PointT>& cloud, const Indic
 
     thrust::tuple<float, int> init(0.f, 0);
     thrust::maximum<thrust::tuple<float, int>> op;
-    
+
     thrust::tuple<float, int> res = transform_reduce(
         make_zip_iterator(make_tuple( make_permutation_iterator(src_beg, map_beg), cf )),
         make_zip_iterator(make_tuple( make_permutation_iterator(src_beg, map_end), ce )),
         TupleDistCvt(pivot), init, op);
 
-    float4 point = src_beg[map_beg[res.get<1>()]];
+    float4 point = src_beg[map_beg[thrust::get<1>(res)]];
 
     return make_float3(point.x, point.y, point.z);
 }
index d2ae7fda43d416bdc5054c5a46f2885996b43656..211da113cc46f6946d70845fc1df8bcd3f7df62d 100644 (file)
@@ -297,7 +297,7 @@ namespace pcl
             template<int bins>
             __device__ __forceinline__ void normalizeFeature(volatile float *feature, volatile float *buffer, int lane) const
             {                                
-                //nomalize buns
+                //normalize buns
                 float value = (lane < bins) ? feature[lane] : 0.f;                
                 float sum = Warp::reduce(buffer, value, plus<volatile float>());
 
index 9dfaefd83f9883840b5c53f67e45797081ffe64e..9b510d257a22238163fa45781abeb8b7e006bef0 100644 (file)
@@ -55,7 +55,8 @@ namespace pcl
                 CTA_SIZE = 256,
                 WAPRS = CTA_SIZE / Warp::WARP_SIZE,
 
-                MIN_NEIGHBOORS = 1
+                // if there are fewer than 3 neighbors, the normal is definitely garbage
+                MIN_NEIGHBOORS = 3
             };
 
             struct plus 
@@ -86,6 +87,7 @@ namespace pcl
                 {
                     constexpr float NaN = std::numeric_limits<float>::quiet_NaN();
                     normals.data[idx] = make_float4(NaN, NaN, NaN, NaN);
+                    return;
                 }
 
                 const int *ibeg = indices.ptr(idx);
index 7d81b67e7998d87f89b833d1b70f1cdf28470fe7..3ae9e04f104711f5d5e473bc942b37128031e7ca 100644 (file)
@@ -2,26 +2,8 @@ if(NOT BUILD_TESTS)
   return()
 endif()
 
-include_directories(
-  "${PCL_SOURCE_DIR}/test/gtest-1.6.0/include"
-  "${PCL_SOURCE_DIR}/test/gtest-1.6.0"
-)
-
-set(pcl_gtest_sources "${PCL_SOURCE_DIR}/test/gtest-1.6.0/src/gtest-all.cc")
-
 set(the_test_target test_gpu_features)
 
-get_filename_component(DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)
-get_filename_component(INC1 "${DIR}/../../../io/include" REALPATH)
-get_filename_component(INC2 "${DIR}/../../../features/include" REALPATH)
-get_filename_component(INC3 "${DIR}/../../../kdtree/include" REALPATH)
-get_filename_component(INC4 "${DIR}/../../../visualization/include" REALPATH)
-get_filename_component(INC5 "${DIR}/../../../common/include" REALPATH)
-get_filename_component(INC6 "${DIR}/../../../search/include" REALPATH)
-get_filename_component(INC7 "${DIR}/../../../octree/include" REALPATH)
-
-
 file(GLOB test_src *.cpp *.hpp)
 list(APPEND test_src ${pcl_gtest_sources})
-include_directories("${INC1}" "${INC2}" "${INC3}" "${INC4}" "${INC5}" "${INC6}" "${INC7}")
-include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
+
index fbbd294fdbc2317002aa0ecba3e770d146ed84ee..2ba88e0c1d8f3bd64b3e3bf879add4d967a50e33 100644 (file)
@@ -1,7 +1,7 @@
 set(SUBSYS_NAME gpu_kinfu)
 set(SUBSYS_PATH gpu/kinfu)
 set(SUBSYS_DESC "Kinect Fusion implementation")
-set(SUBSYS_DEPS common io gpu_containers geometry search)
+set(SUBSYS_DEPS common io gpu_utils gpu_containers geometry search)
 if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0")
   set(DEFAULT FALSE)
   set(REASON "Kinfu uses textures which was removed in CUDA 12")
@@ -26,10 +26,10 @@ source_group("Source Files\\cuda" FILES ${cuda})
 source_group("Source Files" FILES ${srcs})
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src")
 
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${cuda})
-target_link_libraries(${LIB_NAME} pcl_cuda pcl_gpu_containers)
+target_link_libraries(${LIB_NAME} pcl_gpu_utils pcl_gpu_containers)
+target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src)
 
 target_compile_options(${LIB_NAME} PRIVATE $<$<COMPILE_LANGUAGE:CUDA>:--ftz=true;--prec-div=false;--prec-sqrt=false>)
 
index e1593b3800136238332404660501a45b01c2df7a..4a52d7833a12d8c64c72aecf6c1b03f384537e24 100644 (file)
@@ -2,7 +2,7 @@ set(SUBSUBSYS_NAME tools)
 set(SUBSUBSYS_DESC "Kinfu tools")
 set(SUBSUBSYS_DEPS gpu_kinfu visualization)
 set(SUBSUBSYS_OPT_DEPS opencv)
-set(EXT_DEPS openni)
+set(EXT_DEPS glew openni)
 set(DEFAULT TRUE)
 set(REASON "")
 
@@ -13,10 +13,7 @@ if(NOT build)
   return()
 endif()
 
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 file(GLOB hdrs "*.h*")
-include_directories(SYSTEM ${OPENNI_INCLUDE_DIRS})
 
 ## KINECT FUSION
 set(the_target pcl_kinfu_app)
index ffdb154ffaa336f59c3a36d27b94d41e675082d0..7564e62c88e20bfc18a0f4a25d0898b3e7d36e26 100644 (file)
 #include <iostream>
 #include <vector>
 
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 
-#include <boost/filesystem.hpp>
-
 #include <pcl/gpu/kinfu/kinfu.h>
 #include <pcl/gpu/kinfu/raycaster.h>
 #include <pcl/gpu/kinfu/marching_cubes.h>
@@ -173,19 +172,18 @@ namespace pcl
 ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 {
-  namespace fs = boost::filesystem;
-  fs::path dir(directory);
+  pcl_fs::path dir(directory);
  
   std::cout << "path: " << directory << std::endl;
-  if (directory.empty() || !fs::exists(dir) || !fs::is_directory(dir))
+  if (directory.empty() || !pcl_fs::exists(dir) || !pcl_fs::is_directory(dir))
     PCL_THROW_EXCEPTION (pcl::IOException, "No valid PCD directory given!\n");
     
   std::vector<std::string> result;
-  fs::directory_iterator pos(dir);
-  fs::directory_iterator end;           
+  pcl_fs::directory_iterator pos(dir);
+  pcl_fs::directory_iterator end;           
 
   for(; pos != end ; ++pos)
-    if (fs::is_regular_file(pos->status()) )
+    if (pcl_fs::is_regular_file(pos->status()) )
       if (pos->path().extension().string() == ".pcd")
       {
         result.push_back (pos->path ().string ());
@@ -1246,7 +1244,7 @@ main (int argc, char* argv[])
   pcl::gpu::printShortCudaDeviceInfo (device);
 
 //  if (checkIfPreFermiGPU(device))
-//    return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler arhitectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1;
+//    return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler architectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1;
   
   std::unique_ptr<pcl::Grabber> capture;
   
index 383ecb83758ca19608127fcbf6a774b9243ab43b..4d4bdd8bffd01941497e3ca6b1c57e28dbe3d82b 100644 (file)
@@ -1357,7 +1357,7 @@ print_cli_help ()
   std::cout << "";
   std::cout << " For RGBD benchmark (Requires OpenCV):" << std::endl;
   std::cout << "    -eval <eval_folder> [-match_file <associations_file_in_the_folder>]" << std::endl;
-  std::cout << " For Simuation (Requires pcl::simulation):" << std::endl;
+  std::cout << " For Simulation (Requires pcl::simulation):" << std::endl;
   std::cout << "    -plyfile                        : path to ply file for simulation testing " << std::endl;
 
   return 0;
index 0488fcb46aaf1ca23fa447139dc467f974f37924..da956a2770ece0ecde2ef272baec5c0f14082834 100644 (file)
@@ -2,6 +2,8 @@ set(SUBSYS_NAME gpu_kinfu_large_scale)
 set(SUBSYS_PATH gpu/kinfu_large_scale)
 set(SUBSYS_DESC "Kinect Fusion implementation, with volume shifting")
 set(SUBSYS_DEPS common io gpu_containers gpu_utils geometry search octree filters kdtree features surface)
+set(EXT_DEPS vtk) # Uses saveRgbPNGFile from png_io, which requires VTK to be present
+
 if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0")
   set(DEFAULT FALSE)
   set(REASON "Kinfu_large_scale uses textures which was removed in CUDA 12")
@@ -10,7 +12,7 @@ else()
 endif()
 
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
-PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS ${EXT_DEPS})
 PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}")
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 
@@ -27,15 +29,13 @@ source_group("Source Files\\cuda" FILES ${cuda})
 source_group("Source Files" FILES ${srcs})
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src")
-
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${cuda})
-
-target_link_libraries(${LIB_NAME} pcl_cuda pcl_common pcl_io pcl_gpu_utils pcl_gpu_containers pcl_gpu_octree pcl_octree pcl_filters)
+target_link_libraries(${LIB_NAME} pcl_common pcl_io pcl_gpu_utils pcl_gpu_containers pcl_gpu_octree pcl_octree pcl_filters)
+target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src)
 
 target_compile_options(${LIB_NAME} PRIVATE $<$<COMPILE_LANGUAGE:CUDA>:--ftz=true;--prec-div=false;--prec-sqrt=false>)
 
-PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${EXT_DEPS})
+PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS "")
 
 # Install include files
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_PATH}" ${incs})
index 35b0a1529253057a50f89fd2dc94fe6301a471ce..7ade37975ce8d3983acce699aa8ddd683ab56cd9 100644 (file)
 #include <pcl/gpu/containers/device_array.h>
 #include <pcl/gpu/containers/kernel_containers.h>
 #include <pcl/gpu/kinfu_large_scale/pixel_rgb.h> 
-#include <boost/filesystem.hpp> 
-//#include <boost/graph/buffer_concepts.hpp>
 
 #include <pcl/io/png_io.h>
 
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 
 
index 15e6a9a8dfdb8b1aafc9b6d383dfd70f9ece1991..755fc947130f835918327f75ae6b9313aebcd3fd 100644 (file)
@@ -48,8 +48,8 @@ namespace pcl
   {
       ScreenshotManager::ScreenshotManager()
       {
-        boost::filesystem::path p ("KinFuSnapshots"); 
-        boost::filesystem::create_directory (p);
+        pcl_fs::path p ("KinFuSnapshots"); 
+        pcl_fs::create_directory (p);
         screenshot_counter = 0;
         setCameraIntrinsics();
       }
index d8d654721bd63ee22e74ad6878c2cc5915eac259..30fbebe248dcdc40520689ea6a9dfa49eb491ad7 100644 (file)
@@ -2,7 +2,7 @@ set(SUBSUBSYS_NAME tools)
 set(SUBSUBSYS_DESC "Kinfu large scale tools")
 set(SUBSUBSYS_DEPS gpu_kinfu_large_scale visualization)
 set(SUBSUBSYS_OPT_DEPS )
-set(EXT_DEPS openni openni2)
+set(EXT_DEPS glew openni openni2)
 set(DEFAULT TRUE)
 set(REASON "")
 
@@ -13,10 +13,7 @@ if(NOT build)
   return()
 endif()
 
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 file(GLOB hdrs "*.h*")
-include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
 
 ## STANDALONE TEXTURE MAPPING
 set(the_target pcl_kinfu_largeScale_texture_output)
index 28278195e422ddeffaebf7aa9033dd1316da9b97..73c943e39414996b25746e6d128fd36339034b45 100644 (file)
@@ -53,10 +53,9 @@ Work in progress: patch by Marco (AUG,19th 2012)
 
 #include <pcl/memory.h>
 #include <pcl/pcl_macros.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 
-#include <boost/filesystem.hpp>
-
 #include <pcl/gpu/kinfu_large_scale/kinfu.h>
 #include <pcl/gpu/kinfu_large_scale/raycaster.h>
 #include <pcl/gpu/kinfu_large_scale/marching_cubes.h>
@@ -123,19 +122,18 @@ namespace pcl
 
 std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 {
-  namespace fs = boost::filesystem;
-  fs::path dir(directory);
+  pcl_fs::path dir(directory);
 
   std::cout << "path: " << directory << std::endl;
-  if (directory.empty() || !fs::exists(dir) || !fs::is_directory(dir))
+  if (directory.empty() || !pcl_fs::exists(dir) || !pcl_fs::is_directory(dir))
           PCL_THROW_EXCEPTION (pcl::IOException, "No valid PCD directory given!\n");
 
   std::vector<std::string> result;
-  fs::directory_iterator pos(dir);
-  fs::directory_iterator end;           
+  pcl_fs::directory_iterator pos(dir);
+  pcl_fs::directory_iterator end;           
 
   for(; pos != end ; ++pos)
-    if (fs::is_regular_file(pos->status()) )
+    if (pcl_fs::is_regular_file(pos->status()) )
       if (pos->path().extension().string() == ".pcd")
       {
         result.push_back (pos->path ().string ());
@@ -1330,7 +1328,7 @@ main (int argc, char* argv[])
   pcl::gpu::printShortCudaDeviceInfo (device);
 
   //  if (checkIfPreFermiGPU(device))
-  //    return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler arhitectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1;
+  //    return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler architectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1;
 
   pcl::shared_ptr<pcl::Grabber> capture;
   bool triggered_capture = false;
index b1ff4f56b9911d3bafa8209f0e7e09d20b1ad352..6ad7c1d60c3e12bb08236548b64d39f721e87693 100644 (file)
@@ -1382,7 +1382,7 @@ print_cli_help ()
   std::cout << "";
   std::cout << " For RGBD benchmark (Requires OpenCV):" << std::endl; 
   std::cout << "    -eval <eval_folder> [-match_file <associations_file_in_the_folder>]" << std::endl;
-  std::cout << " For Simuation (Requires pcl::simulation):" << std::endl; 
+  std::cout << " For Simulation (Requires pcl::simulation):" << std::endl; 
   std::cout << "    -plyfile                        : path to ply file for simulation testing " << std::endl;
     
   return 0;
index 6803bba3e3db0947dc324ea8d3dcd4612bfa438f..8a9f6faae23b25f5a26fd2140223ba193dfef98a 100644 (file)
  *  Author: Raphael Favier, Technical University Eindhoven, (r.mysurname <aT> tue.nl)
  */
 
-
-#include <boost/filesystem.hpp>
-
 #include <fstream>
 #include <iostream>
 #include <sstream>
 
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/transforms.h>
 #include <pcl/features/normal_3d.h>
 #include <pcl/visualization/pcl_visualizer.h>
@@ -432,11 +430,11 @@ main (int argc, char** argv)
   PCL_INFO ("\nLoading textures and camera poses...\n");
   pcl::texture_mapping::CameraVector my_cams;
   
-  const boost::filesystem::path base_dir (".");
+  const pcl_fs::path base_dir (".");
   std::string extension (".txt");
-  for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it)
+  for (pcl_fs::directory_iterator it (base_dir); it != pcl_fs::directory_iterator (); ++it)
   {
-    if(boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension)
+    if(pcl_fs::is_regular_file (it->status ()) && it->path ().extension ().string () == extension)
     {
       pcl::TextureMapping<pcl::PointXYZ>::Camera cam;
       readCamPoseFile(it->path ().string (), cam);
index 8477bb75ea393ac00744c68d876d72f66630c9fb..2c2f67e981309e0be9542938044d86619f559cc1 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/octree)
 set(SUBSYS_DESC "Octree GPU")
 set(SUBSYS_DEPS common gpu_containers gpu_utils)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
@@ -26,9 +25,9 @@ source_group("Source Files\\cuda" FILES ${cuda})
 list(APPEND srcs ${utils} ${cuda})
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src" "${CMAKE_CURRENT_SOURCE_DIR}/src/utils")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
 target_link_libraries("${LIB_NAME}" pcl_gpu_containers)
+target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
index e47d7f311e8562fca670e0a4ccf560ae59faabfb..1a7be92a9af3333fac407cb44ab8773a2d00b9ee 100644 (file)
@@ -58,7 +58,7 @@ namespace pcl
             void create(int query_number, int max_elements)
             {
                 max_elems = max_elements;
-                data.create (query_number * max_elems);
+                data.create (static_cast<std::size_t>(query_number) * static_cast<std::size_t>(max_elems));
 
                 if (max_elems != 1)
                     sizes.create(query_number);                
index 5e222a5c38ce3fb4a7d9f0eeb167a8a2a7580bd9..9f827e0f3a303b0a78786b8e81a7a41c20679d4f 100644 (file)
@@ -164,7 +164,7 @@ namespace pcl
               */
             void nearestKSearchBatch(const Queries& queries, int k, NeighborIndices& results, ResultSqrDists& sqr_distances) const;
 
-            /** \brief Desroys octree and release all resources */
+            /** \brief Destroys octree and release all resources */
             void clear();            
         private:
             void *impl;            
index 9616143695c925fceca1064667a65859a7bffcca..7ca1110e363c365515466a1b8c5a6355755e1221 100644 (file)
@@ -43,6 +43,7 @@
 #include "utils/scan_block.hpp"
 #include "utils/morton.hpp"
 
+#include <thrust/tuple.h>
 #include <thrust/device_ptr.h>
 #include <thrust/sequence.h>
 #include <thrust/sort.h>
@@ -51,7 +52,7 @@
 
 using namespace pcl::gpu;
 
-namespace pcl 
+namespace pcl
 {
     namespace device
     {
@@ -64,21 +65,21 @@ namespace pcl
                 result.x = fmin(e1.x, e2.x);
                 result.y = fmin(e1.y, e2.y);
                 result.z = fmin(e1.z, e2.z);
-                return result;                 
-               }       
+                return result;
+               }
         };
 
         template<typename PointType>
         struct SelectMaxPoint
         {
-               __host__ __device__ __forceinline__ PointType operator()(const PointType& e1, const PointType& e2) const 
-               {               
+               __host__ __device__ __forceinline__ PointType operator()(const PointType& e1, const PointType& e2) const
+               {
                 PointType result;
                 result.x = fmax(e1.x, e2.x);
                 result.y = fmax(e1.y, e2.y);
                 result.z = fmax(e1.z, e2.z);
-                return result;             
-               }       
+                return result;
+               }
         };
 
 
@@ -88,9 +89,9 @@ namespace pcl
             __device__ __forceinline__ thrust::tuple<float, float, float> operator()(const PointType& arg) const
             {
                 thrust::tuple<float, float, float> res;
-                res.get<0>() = arg.x;
-                res.get<1>() = arg.y;
-                res.get<2>() = arg.z;
+                thrust::get<0>(res) = arg.x;
+                thrust::get<1>(res) = arg.y;
+                thrust::get<2>(res) = arg.z;
                 return res;
             }
         };
@@ -102,8 +103,8 @@ namespace pcl
     {
         const static int max_points_per_leaf = 96;
 
-        enum 
-        { 
+        enum
+        {
             GRID_SIZE = 1,
             CTA_SIZE = 1024-32,
             STRIDE = CTA_SIZE,
@@ -116,7 +117,7 @@ namespace pcl
         __shared__ int tasks_beg;
         __shared__ int tasks_end;
         __shared__ int total_new;
-        __shared__ volatile int offsets[CTA_SIZE];                
+        __shared__ volatile int offsets[CTA_SIZE];
 
         struct SingleStepBuild
         {
@@ -127,14 +128,14 @@ namespace pcl
             static __device__ __forceinline__ int divUp(int total, int grain) { return (total + grain - 1) / grain; };
 
             __device__ __forceinline__ int FindCells(int task, int level, int cell_begs[], char cell_code[]) const
-            {               
+            {
                 int cell_count = 0;
 
                 int beg = octree.begs[task];
-                int end = octree.ends[task];                
+                int end = octree.ends[task];
 
                 if (end - beg < max_points_per_leaf)
-                {                        
+                {
                     //cell_count == 0;
                 }
                 else
@@ -142,13 +143,13 @@ namespace pcl
                     int cur_code = Morton::extractLevelCode(codes[beg], level);
 
                     cell_begs[cell_count] = beg;
-                    cell_code[cell_count] = cur_code;     
-                    ++cell_count;                        
+                    cell_code[cell_count] = cur_code;
+                    ++cell_count;
 
                     int last_code = Morton::extractLevelCode(codes[end - 1], level);
                     if (last_code == cur_code)
                     {
-                        cell_begs[cell_count] = end;                                         
+                        cell_begs[cell_count] = end;
                     }
                     else
                     {
@@ -162,7 +163,7 @@ namespace pcl
                             }
 
                             int morton_code = Morton::shiftLevelCode(search_code, level);
-                            int pos = lower_bound(codes + beg, codes + end, morton_code, CompareByLevelCode(level)) - codes; 
+                            int pos = lower_bound(codes + beg, codes + end, morton_code, CompareByLevelCode(level)) - codes;
 
                             if (pos == end)
                             {
@@ -175,7 +176,7 @@ namespace pcl
                             cell_code[cell_count] = cur_code;
                             ++cell_count;
                             beg = pos;
-                        }        
+                        }
                     }
                 }
                 return cell_count;
@@ -183,7 +184,7 @@ namespace pcl
 
 
             __device__  __forceinline__ void operator()() const
-            {             
+            {
                 //32 is a performance penalty step for search
                 static_assert((max_points_per_leaf % 32) == 0, "max_points_per_leaf must be a multiple of 32");
 
@@ -196,7 +197,7 @@ namespace pcl
                     octree. ends[0] = points_number;
                     octree.parent[0] = -1;
 
-                    //init shared                    
+                    //init shared
                     nodes_num = 1;
                     tasks_beg = 0;
                     tasks_end = 1;
@@ -211,8 +212,8 @@ namespace pcl
                 __syncthreads();
 
                 while (tasks_beg < tasks_end && level < Morton::levels)
-                {                  
-                    int task_count = tasks_end - tasks_beg;                    
+                {
+                    int task_count = tasks_end - tasks_beg;
                     int iters = divUp(task_count, CTA_SIZE);
 
                     int task = tasks_beg + threadIdx.x;
@@ -220,14 +221,14 @@ namespace pcl
                     //__syncthreads(); // extra??
 
                     for(int it = 0; it < iters; ++it, task += STRIDE)
-                    {   
+                    {
                         int cell_count = (task < tasks_end) ? FindCells(task, level, cell_begs, cell_code) : 0;
-                        
+
                         offsets[threadIdx.x] = cell_count;
                         __syncthreads();
 
                         scan_block<pcl::device::exclusive>(offsets);
-                        
+
                         //__syncthreads();  //because sync is inside the scan above
 
                         if (task < tasks_end)
@@ -255,24 +256,24 @@ namespace pcl
 
                         __syncthreads();
                         if (threadIdx.x == CTA_SIZE - 1)
-                        {                            
+                        {
                             total_new += cell_count + offsets[threadIdx.x];
                             nodes_num += cell_count + offsets[threadIdx.x];
-                        }    
-                        __syncthreads(); 
+                        }
+                        __syncthreads();
 
                     } /* for(int it = 0; it < iters; ++it, task += STRIDE) */
 
                     //__syncthreads(); //extra ??
 
                     if (threadIdx.x == CTA_SIZE - 1)
-                    {                       
+                    {
                         tasks_beg  = tasks_end;
-                        tasks_end += total_new;        
+                        tasks_end += total_new;
                         total_new = 0;
                     }
                     ++level;
-                    __syncthreads();                    
+                    __syncthreads();
                 }
 
                 if (threadIdx.x == CTA_SIZE - 1)
@@ -285,7 +286,7 @@ namespace pcl
 }
 
 void pcl::device::OctreeImpl::build()
-{       
+{
     using namespace pcl::device;
     host_octree.downloaded = false;
 
@@ -293,7 +294,7 @@ void pcl::device::OctreeImpl::build()
 
     //allocatations
     {
-        //ScopeTimer timer("new_allocs"); 
+        //ScopeTimer timer("new_allocs");
         //+1 codes               * points_num * sizeof(int)
         //+1 indices             * points_num * sizeof(int)
         //+1 octreeGlobal.nodes  * points_num * sizeof(int)
@@ -306,22 +307,22 @@ void pcl::device::OctreeImpl::build()
 
         //+3 points_sorted       * points_num * sizeof(float)
         //==
-        // 10 rows   
+        // 10 rows
 
-        //left 
-        //octreeGlobal.nodes_num * 1 * sizeof(int)          
+        //left
+        //octreeGlobal.nodes_num * 1 * sizeof(int)
         //==
-        // 3 * sizeof(int) => +1 row        
+        // 3 * sizeof(int) => +1 row
 
         const int transaction_size = 128 / sizeof(int);
         int cols = std::max<int>(points_num, transaction_size * 4);
         int rows = 10 + 1; // = 13
-            
+
         storage.create(rows, cols);
-        
+
         codes   = DeviceArray<int>(storage.ptr(0), points_num);
         indices = DeviceArray<int>(storage.ptr(1), points_num);
-        
+
         octreeGlobal.nodes   = storage.ptr(2);
         octreeGlobal.codes   = storage.ptr(3);
         octreeGlobal.begs    = storage.ptr(4);
@@ -332,10 +333,10 @@ void pcl::device::OctreeImpl::build()
 
         points_sorted = DeviceArray2D<float>(3, points_num, storage.ptr(8), storage.step());
     }
-    
+
     {
-        //ScopeTimer timer("reduce-morton-sort-permutations"); 
-       
+        //ScopeTimer timer("reduce-morton-sort-permutations");
+
         thrust::device_ptr<PointType> beg(points.ptr());
         thrust::device_ptr<PointType> end = beg + points.size();
 
@@ -345,49 +346,49 @@ void pcl::device::OctreeImpl::build()
             atmin.x = atmin.y = atmin.z = std::numeric_limits<float>::lowest();
             atmax.w = atmin.w = 0;
 
-            //ScopeTimer timer("reduce"); 
+            //ScopeTimer timer("reduce");
             PointType minp = thrust::reduce(beg, end, atmax, SelectMinPoint<PointType>());
             PointType maxp = thrust::reduce(beg, end, atmin, SelectMaxPoint<PointType>());
 
             octreeGlobal.minp = make_float3(minp.x, minp.y, minp.z);
             octreeGlobal.maxp = make_float3(maxp.x, maxp.y, maxp.z);
         }
-               
+
         thrust::device_ptr<int> codes_beg(codes.ptr());
         thrust::device_ptr<int> codes_end = codes_beg + codes.size();
         {
-            //ScopeTimer timer("morton"); 
+            //ScopeTimer timer("morton");
                thrust::transform(beg, end, codes_beg, CalcMorton(octreeGlobal.minp, octreeGlobal.maxp));
         }
 
         thrust::device_ptr<int> indices_beg(indices.ptr());
         thrust::device_ptr<int> indices_end = indices_beg + indices.size();
         {
-            //ScopeTimer timer("sort"); 
+            //ScopeTimer timer("sort");
             thrust::sequence(indices_beg, indices_end);
-            thrust::sort_by_key(codes_beg, codes_end, indices_beg );           
+            thrust::sort_by_key(codes_beg, codes_end, indices_beg );
         }
         {
-            ////ScopeTimer timer("perm"); 
+            ////ScopeTimer timer("perm");
             //thrust::copy(make_permutation_iterator(beg, indices_beg),
-            //                  make_permutation_iterator(end, indices_end), device_ptr<float3>(points_sorted.ptr()));    
+            //                  make_permutation_iterator(end, indices_end), device_ptr<float3>(points_sorted.ptr()));
+
 
-             
         }
 
         {
             thrust::device_ptr<float> xs(points_sorted.ptr(0));
             thrust::device_ptr<float> ys(points_sorted.ptr(1));
             thrust::device_ptr<float> zs(points_sorted.ptr(2));
-            //ScopeTimer timer("perm2"); 
+            //ScopeTimer timer("perm2");
             thrust::transform(make_permutation_iterator(beg, indices_beg),
-                              make_permutation_iterator(end, indices_end), 
+                              make_permutation_iterator(end, indices_end),
                               make_zip_iterator(make_tuple(xs, ys, zs)), PointType_to_tuple<PointType>());
 
-        
+
         }
     }
-    
+
     SingleStepBuild ssb;
     ssb.octree = octreeGlobal;
     ssb.codes  = codes;
index 2230ab3e2e2d9d4f6e8833bf6e020d0344fbd89e..8e8782c34f99d3d08abd03e15b43ba5304257679 100644 (file)
@@ -34,8 +34,8 @@
 *  Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
 */
 
-#include "pcl/gpu/utils/timers_cuda.hpp"
-#include "pcl/gpu/utils/safe_call.hpp"
+#include <pcl/gpu/utils/timers_cuda.hpp>
+#include <pcl/gpu/utils/safe_call.hpp>
 
 #include "internal.hpp"
 #include "utils/approx_nearest_utils.hpp"
index 63a7e7383608a15a759ccc2314b5bf0364710931..e5b06391aabf0cb5877c4a09b524133d6c94a975 100644 (file)
@@ -34,6 +34,7 @@
  *  Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
  */
 
+#include <pcl/gpu/containers/initialization.h>
 #include <pcl/gpu/octree/octree.hpp>
 #include <pcl/gpu/utils/timers_cuda.hpp>
 #include <pcl/gpu/utils/safe_call.hpp>
index 247eda0dc9b7fbdb646dff005f6333679987d82e..9bec17e74d678f0be7166cb42b47cde3b294e5bb 100644 (file)
@@ -12,6 +12,7 @@
 #include "morton.hpp"
 #include <assert.h>
 
+#include <cstdint>
 #include <limits>
 #include <tuple>
 #include <bitset>
index a3404263569e96b57d163a34e8b5db1c900d110b..6c9c3abad16f79258c8892dd59677b189b900262 100644 (file)
@@ -3,8 +3,14 @@ set(SUBSYS_PATH gpu/people)
 set(SUBSYS_DESC "Point cloud people library")
 set(SUBSYS_DEPS common features filters geometry gpu_containers gpu_utils io kdtree octree search segmentation surface visualization)
 
-set(build FALSE)
-PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} OFF)
+if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0")
+  set(DEFAULT FALSE)
+  set(REASON "gpu_people uses textures which was removed in CUDA 12")
+else()
+  set(DEFAULT TRUE)
+endif()
+
+PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ${DEFAULT} ${REASON})
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 mark_as_advanced("BUILD_${SUBSYS_NAME}")
 
@@ -14,19 +20,22 @@ if(NOT build)
   return()
 endif()
 
-#find NPP
-unset(CUDA_npp_LIBRARY CACHE)
-find_cuda_helper_libs(nppc)
-find_cuda_helper_libs(npps)
-if(CUDA_VERSION VERSION_GREATER "9.0" OR CUDA_VERSION VERSION_EQUAL "9.0")
-  find_cuda_helper_libs(nppim)
-  find_cuda_helper_libs(nppidei)
-  set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppim_LIBRARY} ${CUDA_nppidei_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library")
+if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.17)
+  set(CUDA_npp_LIBRARY CUDA::nppc CUDA::nppim CUDA::nppidei CUDA::npps CACHE STRING "npp library")
 else()
-  find_cuda_helper_libs(nppi)
-  set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppi_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library")
+  #find NPP
+  unset(CUDA_npp_LIBRARY CACHE)
+  find_cuda_helper_libs(nppc)
+  find_cuda_helper_libs(npps)
+  if(CUDA_VERSION VERSION_GREATER_EQUAL "9.0")
+    find_cuda_helper_libs(nppim)
+    find_cuda_helper_libs(nppidei)
+    set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppim_LIBRARY} ${CUDA_nppidei_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library")
+  else()
+    find_cuda_helper_libs(nppi)
+    set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppi_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library")
+  endif()
 endif()
-
 #Label_skeleton
 
 file(GLOB srcs src/*.cpp src/*.h*)
@@ -37,17 +46,18 @@ file(GLOB hdrs_cuda src/cuda/nvidia/*.h*)
 source_group("Source files\\cuda" FILES ${srcs_cuda})
 source_group("Source files" FILES ${srcs})
 
-include_directories(
-  "${CMAKE_CURRENT_SOURCE_DIR}/include"
-  "${CMAKE_CURRENT_SOURCE_DIR}/src"
-  "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda"
-  "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda/nvidia"
-)
-
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
 
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${hdrs} ${srcs_cuda})
-target_link_libraries(${LIB_NAME} pcl_cuda pcl_common pcl_search pcl_surface pcl_segmentation pcl_features pcl_sample_consensus pcl_gpu_utils pcl_gpu_containers "${CUDA_CUDART_LIBRARY}" ${CUDA_npp_LIBRARY})
+target_link_libraries(${LIB_NAME} pcl_common pcl_search pcl_surface pcl_segmentation pcl_features pcl_sample_consensus pcl_gpu_utils pcl_gpu_containers ${CUDA_CUDART_LIBRARY} ${CUDA_npp_LIBRARY})
+target_include_directories(
+    ${LIB_NAME} 
+    PRIVATE
+      ${CMAKE_CURRENT_SOURCE_DIR}/src 
+      ${CMAKE_CURRENT_SOURCE_DIR}/src/cuda
+    PUBLIC
+      ${CMAKE_CURRENT_SOURCE_DIR}/src/cuda/nvidia
+)
 
 if(UNIX OR APPLE)
   target_compile_options(${LIB_NAME} INTERFACE $<$<COMPILE_LANGUAGE:CUDA>:"-Xcompiler=-fPIC">)
index 417fd3c625e3559dc19d8c383dbf4d3b511aa6af..3391871107a2243fccd21c5634522bb21669b2be 100644 (file)
@@ -69,7 +69,7 @@ namespace pcl
       enum { XML_VERSION = 1};          /** \brief This indicates the current used xml file version (for people lib only) **/
 
       enum { NUM_ATTRIBS = 2000 };
-      enum { NUM_LABELS  = 32 };        /** \brief Our code is forseen to use maximal use 32 labels **/
+      enum { NUM_LABELS  = 32 };        /** \brief Our code is foreseen to use maximal use 32 labels **/
 
       /** @todo implement label 25 to 29 **/
       enum part_t
index 0cacdf9f0e15d84b0646a6051b68c0a5ac5a8695..2b3cd85a60b26d3f8a4c8f270ec409b276bd1c16 100644 (file)
@@ -1,6 +1,6 @@
 #include "internal.h"
 
-#include <pcl/gpu/utils/texture_binder.hpp>
+#include <pcl/gpu/containers/impl/texture_binder.hpp>
 #include <pcl/gpu/utils/device/block.hpp>
 
 #include <cassert>
index 5abc443d580dcf6554a9bb5154ead77ea6d5e259..df256264b1a998b24c1c10134c79888abe996c49 100644 (file)
@@ -41,7 +41,7 @@
 #include <pcl/gpu/people/tree.h>
 #include <pcl/gpu/people/label_common.h>
 #include <pcl/gpu/utils/safe_call.hpp>
-#include <pcl/gpu/utils/texture_binder.hpp>
+#include <pcl/gpu/containers/impl/texture_binder.hpp>
 #include <stdio.h>
 #include <limits>
 #include <assert.h>
index b9cf5524dfc21fafe1236979c599acfff13ecacf..52c89a5e62ef4c72f67fe19b7e50f4175d211b75 100644 (file)
@@ -41,7 +41,7 @@
 #include <pcl/gpu/people/tree.h>
 #include <pcl/gpu/people/label_common.h>
 #include <pcl/gpu/utils/safe_call.hpp>
-#include <pcl/gpu/utils/texture_binder.hpp>
+#include <pcl/gpu/containers/impl/texture_binder.hpp>
 #include <stdio.h>
 #include <limits>
 #include <assert.h>
index 834de9283d98cc757e641440ba0aae879c07dee0..5f29d5c61af505db671e6ba20ba9af4a65bff926 100644 (file)
@@ -2,7 +2,8 @@
 
 #include "internal.h"
 #include <pcl/gpu/utils/safe_call.hpp>
-#include <pcl/gpu/utils/texture_binder.hpp>
+#include <pcl/gpu/containers/initialization.h>
+#include <pcl/gpu/containers/impl/texture_binder.hpp>
 #include "npp.h"
 
 #include <stdio.h>
index 6cd7e7f9931c6b7859c7fa588217056e55ec5cc9..68e9b6e3ffe99c152a40a822cec6b102306df9a6 100644 (file)
@@ -6,13 +6,10 @@ if(NOT VTK_FOUND)
 else()
   set(DEFAULT TRUE)
   set(REASON)
-  include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 endif()
 
 set(the_target people_tracking)
 
-include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
-
 #PCL_ADD_EXECUTABLE(${the_target} "${SUBSYS_NAME}" people_tracking.cpp)
 #target_link_libraries("${the_target}" pcl_common pcl_kdtree pcl_gpu_people pcl_io pcl_visualization)
 
index 91308e4e26366693d20e0efc54ae093753e75844..109974ab73d6616fb373e67126364bca70a3f4a7 100644 (file)
@@ -41,6 +41,7 @@
 #include <pcl/pcl_base.h>
 #include <pcl/point_types.h>
 #include <pcl/point_cloud.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/time.h>
 #include <pcl/exceptions.h>
 #include <pcl/console/parse.h>
@@ -54,7 +55,6 @@
 #include <pcl/io/pcd_grabber.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/io/png_io.h>
-#include <boost/filesystem.hpp>
 
 #include <functional>
 #include <iostream>
@@ -66,18 +66,17 @@ using namespace std::chrono_literals;
 
 std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 {
-  namespace fs = boost::filesystem;
-  fs::path dir(directory);
+  pcl_fs::path dir(directory);
         
-  if (!fs::exists(dir) || !fs::is_directory(dir))
+  if (!pcl_fs::exists(dir) || !pcl_fs::is_directory(dir))
     PCL_THROW_EXCEPTION(pcl::IOException, "Wrong PCD directory");
     
   std::vector<std::string> result;
-  fs::directory_iterator pos(dir);
-  fs::directory_iterator end;           
+  pcl_fs::directory_iterator pos(dir);
+  pcl_fs::directory_iterator end;           
 
   for(; pos != end ; ++pos)
-    if (fs::is_regular_file(pos->status()) )
+    if (pcl_fs::is_regular_file(pos->status()) )
       if (pos->path().extension().string() == ".pcd")
         result.push_back(pos->path().string());
     
index 0c1838ec94b9a9da366ff3923601557cc06fe9ab..8bc3992c2986c3f22da1299c16533258112b8487 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/segmentation)
 set(SUBSYS_DESC "Point cloud GPU segmentation library")
 set(SUBSYS_DEPS common gpu_containers gpu_utils gpu_octree)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}")
@@ -32,7 +31,6 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_common pcl_gpu_octree pcl_gpu_utils pcl_gpu_containers)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
index 2e2be0de375d74918b3e595dbb4a39cbdd13be0a..1f4e28535c84b20b6e94f82c7f56adb712f953fc 100644 (file)
 #pragma once
 #include <pcl/common/copy_point.h>
 #include <pcl/gpu/segmentation/gpu_extract_clusters.h>
+#include <pcl/pcl_exports.h>
 
 namespace pcl {
 namespace detail {
 
 //// Downloads only the neccssary cluster indices from the device to the host.
-void
+PCL_EXPORTS void
 economical_download(const pcl::gpu::NeighborIndices& source_indices,
                     const pcl::Indices& buffer_indices,
                     std::size_t buffer_size,
index 6970f0e8cc66fc3b59921d4b066e1d3df64607f5..22a84d72a984da8c1b074765ebe03752e0363ee6 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/surface)
 set(SUBSYS_DESC "Surface algorithms with GPU")
 set(SUBSYS_DEPS common gpu_containers gpu_utils geometry)
 
-set(build FALSE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}")
@@ -26,9 +25,9 @@ source_group("Source Files\\cuda" FILES ${cuda})
 list(APPEND srcs ${utils} ${cuda})
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src" "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
-target_link_libraries("${LIB_NAME}" pcl_gpu_containers)
+target_link_libraries(${LIB_NAME} pcl_gpu_containers)
+target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
index c1f20234ebaa83f2710f944fa8848e5611111ac0..98e89cd703d82a75a9cc17977c3fa841a945bb5a 100644 (file)
 namespace pcl
 {
   namespace device
-  {      
+  {
          template<bool use_max>
          struct IndOp
          {
                  __device__ __forceinline__ thrust::tuple<float, int> operator()(const thrust::tuple<float, int>& e1, const thrust::tuple<float, int>& e2) const
-                 {     
+                 {
                          thrust::tuple<float, int> res;
-                         
+
                          if (use_max)
-                           res.get<0>() = fmax(e1.get<0>(), e2.get<0>());                                                
+                           thrust::get<0>(res) = fmax(thrust::get<0>(e1), thrust::get<0>(e2));
                          else
-                               res.get<0>() = fmin(e1.get<0>(), e2.get<0>());                                            
+                               thrust::get<0>(res) = fmin(thrust::get<0>(e1), thrust::get<0>(e2));
 
-                         res.get<1>()  = (res.get<0>() == e1.get<0>()) ? e1.get<1>() : e2.get<1>();
-                         return res;                     
-                 }              
+                         thrust::get<1>(res)  = (thrust::get<0>(res) == thrust::get<0>(e1)) ? thrust::get<1>(e1) : thrust::get<1>(e2);
+                         return res;
+                 }
          };
 
          struct X
-         {                       
-                 __device__ __forceinline__ 
-                 thrust::tuple<float, int> 
+         {
+                 __device__ __forceinline__
+                 thrust::tuple<float, int>
                  operator()(const thrust::tuple<PointType, int>& in) const
                  {
-                       return thrust::tuple<float, int>(in.get<0>().x, in.get<1>());                     
+                       return thrust::tuple<float, int>(thrust::get<0>(in).x, thrust::get<1>(in));
                  }
          };
 
          struct Y
-         {                       
+         {
                  __device__ __forceinline__  float operator()(const PointType& in) const { return in.y; }
          };
 
          struct Z
-         {                       
+         {
                  __device__ __forceinline__  float operator()(const PointType& in) const { return in.z; }
          };
-                 
+
          struct LineDist
          {
                  float3 x1, x2;
                  LineDist(const PointType& p1, const PointType& p2) : x1(tr(p1)), x2(tr(p2)) {}
-                 
+
                  __device__ __forceinline__
                  thrust::tuple<float, int> operator()(const thrust::tuple<PointType, int>& in) const
-                 {                       
-                         float3 x0 = tr(in.get<0>());
+                 {
+                         float3 x0 = tr(thrust::get<0>(in));
 
-                         float dist = norm(cross(x0 - x1, x0 - x2))/norm(x1 - x2);                       
-                         return thrust::tuple<float, int>(dist, in.get<1>());
-                 }           
+                         float dist = norm(cross(x0 - x1, x0 - x2))/norm(x1 - x2);
+                         return thrust::tuple<float, int>(dist, thrust::get<1>(in));
+                 }
          };
 
          struct PlaneDist
-         {               
+         {
                  float3 x1, n;
                  PlaneDist(const PointType& p1, const PointType& p2, const PointType& p3) : x1(tr(p1))
                  {
                          float3 x2 = tr(p2), x3 = tr(p3);
               n = normalized(cross(x2 - x1, x3 - x1));
                  }
-                 
+
                  __device__ __forceinline__
                  thrust::tuple<float, int> operator()(const thrust::tuple<PointType, int>& in) const
                  {
-                         float3 x0 = tr(in.get<0>());
+                         float3 x0 = tr(thrust::get<0>(in));
               float dist = std::abs(dot(n, x0 - x1));
-                         return thrust::tuple<float, int>(dist, in.get<1>());
+                         return thrust::tuple<float, int>(dist, thrust::get<1>(in));
                  }
          };
-         
+
          template<typename It, typename Unary, typename Init, typename Binary>
       int transform_reduce_index(It beg, It end, Unary unop, Init init, Binary binary)
          {
            thrust::counting_iterator<int> cbeg(0);
                thrust::counting_iterator<int> cend = cbeg + thrust::distance(beg, end);
-                                       
-           thrust::tuple<float, int> t = transform_reduce( 
-                 make_zip_iterator(thrust::make_tuple(beg, cbeg)), 
-                 make_zip_iterator(thrust::make_tuple(end, cend)), 
+
+           thrust::tuple<float, int> t = transform_reduce(
+                 make_zip_iterator(thrust::make_tuple(beg, cbeg)),
+                 make_zip_iterator(thrust::make_tuple(end, cend)),
                  unop, init, binary);
-               
-               return t.get<1>();
+
+               return thrust::get<1>(t);
          }
 
          template<typename It, typename Unary>
@@ -158,35 +158,35 @@ namespace pcl
          {
                thrust::tuple<float, int> max_tuple(std::numeric_limits<float>::min(), 0);
                return transform_reduce_index(beg, end, unop, max_tuple, IndOp<true>());
-         }      
+         }
   }
 }
 
 pcl::device::PointStream::PointStream(const Cloud& cloud_) : cloud(cloud_)
-{                              
+{
   cloud_size = cloud.size();
   facets_dists.create(cloud_size);
   perm.create(cloud_size);
 
-  thrust::device_ptr<int> pbeg(perm.ptr());  
+  thrust::device_ptr<int> pbeg(perm.ptr());
   thrust::sequence(pbeg, pbeg + cloud_size);
 }
 
 void pcl::device::PointStream::computeInitalSimplex()
 {
-  thrust::device_ptr<const PointType> beg(cloud.ptr());  
+  thrust::device_ptr<const PointType> beg(cloud.ptr());
   thrust::device_ptr<const PointType> end = beg + cloud_size;
-     
+
   int minx = transform_reduce_min_index(beg, end, X());
   int maxx = transform_reduce_max_index(beg, end, X());
 
   PointType p1 = *(beg + minx);
   PointType p2 = *(beg + maxx);
-               
+
   int maxl = transform_reduce_max_index(beg, end, LineDist(p1, p2));
 
   PointType p3 = *(beg + maxl);
-    
+
   int maxp = transform_reduce_max_index(beg, end, PlaneDist(p1, p2, p3));
 
   PointType p4 = *(beg + maxp);
@@ -194,12 +194,12 @@ void pcl::device::PointStream::computeInitalSimplex()
   simplex.x1 = tr(p1);  simplex.x2 = tr(p2);  simplex.x3 = tr(p3);  simplex.x4 = tr(p4);
   simplex.i1 = minx;    simplex.i2 = maxx;    simplex.i3 = maxl;    simplex.i4 = maxp;
 
-  float maxy = transform_reduce(beg, end, Y(), std::numeric_limits<float>::min(), thrust::maximum<float>()); 
-  float miny = transform_reduce(beg, end, Y(), std::numeric_limits<float>::max(), thrust::minimum<float>()); 
+  float maxy = transform_reduce(beg, end, Y(), std::numeric_limits<float>::min(), thrust::maximum<float>());
+  float miny = transform_reduce(beg, end, Y(), std::numeric_limits<float>::max(), thrust::minimum<float>());
+
+  float maxz = transform_reduce(beg, end, Z(), std::numeric_limits<float>::min(), thrust::maximum<float>());
+  float minz = transform_reduce(beg, end, Z(), std::numeric_limits<float>::max(), thrust::minimum<float>());
 
-  float maxz = transform_reduce(beg, end, Z(), std::numeric_limits<float>::min(), thrust::maximum<float>()); 
-  float minz = transform_reduce(beg, end, Z(), std::numeric_limits<float>::max(), thrust::minimum<float>()); 
-                 
   float dx = (p2.x - p1.x);
   float dy = (maxy - miny);
   float dz = (maxz - minz);
@@ -209,7 +209,7 @@ void pcl::device::PointStream::computeInitalSimplex()
   simplex.p1 = compute_plane(simplex.x4, simplex.x2, simplex.x3, simplex.x1);
   simplex.p2 = compute_plane(simplex.x3, simplex.x1, simplex.x4, simplex.x2);
   simplex.p3 = compute_plane(simplex.x2, simplex.x1, simplex.x4, simplex.x3);
-  simplex.p4 = compute_plane(simplex.x1, simplex.x2, simplex.x3, simplex.x4);  
+  simplex.p4 = compute_plane(simplex.x1, simplex.x2, simplex.x3, simplex.x4);
 }
 
 namespace pcl
@@ -217,7 +217,7 @@ namespace pcl
   namespace device
   {
     __global__ void init_fs(int i1, int i2, int i3, int i4, PtrStep<int> verts_inds)
-       {                         
+       {
       *(int4*)verts_inds.ptr(0) = make_int4(i2, i1, i1, i1);
       *(int4*)verts_inds.ptr(1) = make_int4(i3, i3, i2, i2);
       *(int4*)verts_inds.ptr(2) = make_int4(i4, i4, i4, i3);
@@ -227,10 +227,10 @@ namespace pcl
 }
 
 void pcl::device::FacetStream::setInitialFacets(const InitalSimplex& s)
-{  
-  init_fs<<<1, 1>>>(s.i1, s.i2, s.i3, s.i4, verts_inds);  
+{
+  init_fs<<<1, 1>>>(s.i1, s.i2, s.i3, s.i4, verts_inds);
   cudaSafeCall( cudaGetLastError() );
-  cudaSafeCall( cudaDeviceSynchronize() );  
+  cudaSafeCall( cudaDeviceSynchronize() );
   facet_count = 4;
 }
 
@@ -245,20 +245,20 @@ namespace pcl
        {
       float diag;
       float4 pl1, pl2, pl3, pl4;
-                 
-      InitalClassify(const float4& p1, const float4& p2, const float4& p3, const float4& p4, float diagonal) 
+
+      InitalClassify(const float4& p1, const float4& p2, const float4& p3, const float4& p4, float diagonal)
           : diag(diagonal), pl1(p1), pl2(p2), pl3(p3), pl4(p4)
-         {                             
+         {
         pl1 *= compue_inv_normal_norm(pl1);
         pl2 *= compue_inv_normal_norm(pl2);
         pl3 *= compue_inv_normal_norm(pl3);
         pl4 *= compue_inv_normal_norm(pl4);
          }
-                 
+
          __device__ __forceinline__
-         std::uint64_t 
+         std::uint64_t
          operator()(const PointType& p) const
-         {                   
+         {
                  float4 x = p;
                  x.w = 1;
 
@@ -270,7 +270,7 @@ namespace pcl
           float dists[] = { d0, d1, d2, d3 };
           int negs_inds[4];
           int neg_count = 0;
-          
+
           int idx = std::numeric_limits<int>::max();
           float dist = 0;
 
@@ -283,7 +283,7 @@ namespace pcl
           {
              int i1 = negs_inds[1];
              int i2 = negs_inds[2];
-             
+
              int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1;
              negs_inds[1] = ir;
              --neg_count;
@@ -293,10 +293,10 @@ namespace pcl
           {
              int i1 = negs_inds[0];
              int i2 = negs_inds[1];
-             
+
              int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1;
              negs_inds[0] = ir;
-             --neg_count;              
+             --neg_count;
           }
 
           if (neg_count == 1)
@@ -311,28 +311,28 @@ namespace pcl
                  std::uint64_t res = idx;
                  res <<= 32;
                  return res + *reinterpret_cast<unsigned int*>(&dist);
-         }             
-       };              
+         }
+       };
 
-    __global__ void initalClassifyKernel(const InitalClassify ic, const PointType* points, int cloud_size, std::uint64_t* output) 
-    { 
+    __global__ void initalClassifyKernel(const InitalClassify ic, const PointType* points, int cloud_size, std::uint64_t* output)
+    {
         int index = threadIdx.x + blockIdx.x * blockDim.x;
 
-        if (index < cloud_size)              
-          output[index] = ic(points[index]); 
+        if (index < cloud_size)
+          output[index] = ic(points[index]);
     }
   }
 }
 
 void pcl::device::PointStream::initalClassify()
-{        
+{
   //thrust::device_ptr<const PointType> beg(cloud.ptr());
   //thrust::device_ptr<const PointType> end = beg + cloud_size;
   thrust::device_ptr<std::uint64_t> out(facets_dists.ptr());
-  
+
   InitalClassify ic(simplex.p1, simplex.p2, simplex.p3, simplex.p4, cloud_diag);
   //thrust::transform(beg, end, out, ic);
-  
+
   //printFuncAttrib(initalClassifyKernel);
 
   initalClassifyKernel<<<divUp(cloud_size, 256), 256>>>(ic, cloud, cloud_size, facets_dists);
@@ -350,9 +350,9 @@ namespace pcl
 {
   namespace device
   {
-    __device__ int new_cloud_size;    
+    __device__ int new_cloud_size;
        struct SearchFacetHeads
-       {               
+       {
          std::uint64_t *facets_dists;
          int cloud_size;
          int facet_count;
@@ -361,25 +361,25 @@ namespace pcl
 
          mutable int* head_points;
       //bool logger;
-       
+
          __device__ __forceinline__
          void operator()(int facet) const
-         {                     
+         {
                const std::uint64_t* b = facets_dists;
                const std::uint64_t* e = b + cloud_size;
 
         bool last_thread = facet == facet_count;
 
-        int search_value = !last_thread ? facet : std::numeric_limits<int>::max();             
-               int index = lower_bound(b, e, search_value, LessThanByFacet()) - b;                     
-        
+        int search_value = !last_thread ? facet : std::numeric_limits<int>::max();
+               int index = lower_bound(b, e, search_value, LessThanByFacet()) - b;
+
         if (last_thread)
             new_cloud_size = index;
         else
         {
           bool not_found = index == cloud_size || (facet != (facets_dists[index] >> 32));
 
-          head_points[facet] = not_found ? -1 : perm[index];           
+          head_points[facet] = not_found ? -1 : perm[index];
         }
          }
        };
@@ -403,18 +403,18 @@ int pcl::device::PointStream::searchFacetHeads(std::size_t facet_count, DeviceAr
        sfh.facet_count = (int)facet_count;
        sfh.perm = perm;
        sfh.points = cloud.ptr();
-       sfh.head_points = head_points;  
-       
+       sfh.head_points = head_points;
+
     //thrust::counting_iterator<int> b(0);
-    //thrust::counting_iterator<int> e = b + facet_count + 1;          
+    //thrust::counting_iterator<int> e = b + facet_count + 1;
     //thrust::for_each(b, e, sfh);
 
     searchFacetHeadsKernel<<<divUp(facet_count+1, 256), 256>>>(sfh);
     cudaSafeCall( cudaGetLastError() );
-    cudaSafeCall( cudaDeviceSynchronize() );        
+    cudaSafeCall( cudaDeviceSynchronize() );
 
        int new_size;
-       cudaSafeCall( cudaMemcpyFromSymbol(     (void*)&new_size,  pcl::device::new_cloud_size, sizeof(new_size)) );    
+       cudaSafeCall( cudaMemcpyFromSymbol(     (void*)&new_size,  pcl::device::new_cloud_size, sizeof(new_size)) );
        return new_size;
 }
 
@@ -434,7 +434,7 @@ namespace pcl
 
        struct Compaction
        {
-               enum 
+               enum
                {
                        CTA_SIZE = 256,
 
@@ -443,18 +443,18 @@ namespace pcl
 
                int* head_points_in;
                PtrStep<int>  verts_inds_in;
-               
+
 
                int *scan_buffer;
                int facet_count;
 
                mutable int* head_points_out;
                mutable PtrStep<int>  verts_inds_out;
-               
+
 
                mutable PtrStep<int> empty_facets;
                mutable int *empty_count;
-                 
+
                __device__ __forceinline__
                void operator()() const
                {
@@ -473,16 +473,16 @@ namespace pcl
                                        int offset = scan_buffer[idx];
 
                                        head_points_out[offset] = head_idx;
-                                       
+
                                        verts_inds_out.ptr(0)[offset] = verts_inds_in.ptr(0)[idx];
                                        verts_inds_out.ptr(1)[offset] = verts_inds_in.ptr(1)[idx];
                                        verts_inds_out.ptr(2)[offset] = verts_inds_in.ptr(2)[idx];
 
-                    
-                                       
+
+
                                }
-                               else                
-                                 empty = 1;                
+                               else
+                                 empty = 1;
                        }
 
       int total = __popc (__ballot_sync (__activemask (), empty));
@@ -498,7 +498,7 @@ namespace pcl
                                if (laneid == 0)
                                {
                                        int old = atomicAdd(empty_count, total);
-                                       wapr_buffer[warpid] = old;                    
+                                       wapr_buffer[warpid] = old;
                                }
                                int old = wapr_buffer[warpid];
 
@@ -506,11 +506,11 @@ namespace pcl
                 {
                                  empty_facets.ptr(0)[old + offset] = verts_inds_in.ptr(0)[idx];
                                  empty_facets.ptr(1)[old + offset] = verts_inds_in.ptr(1)[idx];
-                                 empty_facets.ptr(2)[old + offset] = verts_inds_in.ptr(2)[idx];                                  
+                                 empty_facets.ptr(2)[old + offset] = verts_inds_in.ptr(2)[idx];
 
                   int a1 = verts_inds_in.ptr(0)[idx], a2 = verts_inds_in.ptr(1)[idx], a3 = verts_inds_in.ptr(2)[idx];
                 }
-                       }                                                       
+                       }
                }
        };
 
@@ -521,19 +521,19 @@ namespace pcl
 
 void pcl::device::FacetStream::compactFacets()
 {
-  int old_empty_count;  
-  empty_count.download(&old_empty_count); 
+  int old_empty_count;
+  empty_count.download(&old_empty_count);
 
   thrust::device_ptr<int> b(head_points.ptr());
   thrust::device_ptr<int> e = b + facet_count;
   thrust::device_ptr<int> o(scan_buffer.ptr());
-  
-  thrust::transform_exclusive_scan(b, e, o, NotMinus1(), 0, thrust::plus<int>());                                                                                    
-  
+
+  thrust::transform_exclusive_scan(b, e, o, NotMinus1(), 0, thrust::plus<int>());
+
   Compaction c;
 
   c.verts_inds_in   = verts_inds;
-  c.head_points_in  = head_points;    
+  c.head_points_in  = head_points;
 
   c.scan_buffer = scan_buffer;
   c.facet_count = facet_count;
@@ -543,20 +543,20 @@ void pcl::device::FacetStream::compactFacets()
 
   c.empty_facets = empty_facets;
   c.empty_count = empty_count;
+
   int block = Compaction::CTA_SIZE;
   int grid = divUp(facet_count, block);
 
-  compactionKernel<<<grid, block>>>(c);   
+  compactionKernel<<<grid, block>>>(c);
   cudaSafeCall( cudaGetLastError() );
   cudaSafeCall( cudaDeviceSynchronize() );
-    
+
   verts_inds.swap(verts_inds2);
   head_points.swap(head_points2);
 
-  int new_empty_count;  
-  empty_count.download(&new_empty_count); 
-  
+  int new_empty_count;
+  empty_count.download(&new_empty_count);
+
   facet_count -= new_empty_count - old_empty_count;
 }
 
@@ -583,11 +583,11 @@ namespace pcl
 
                int facet_count;
 
-               __device__ __forceinline__ 
+               __device__ __forceinline__
                void operator()(int point_idx) const
                {
           int perm_index = perm[point_idx];
-          
+
                  int facet = facets_dists[point_idx] >> 32;
                  facet = scan_buffer[facet];
 
@@ -596,10 +596,10 @@ namespace pcl
           if (hi == perm_index)
           {
             std::uint64_t res = std::numeric_limits<int>::max();
-                   res <<= 32;                               
+                   res <<= 32;
             facets_dists[point_idx] = res;
           }
-          else            
+          else
           {
 
                    int i1 = verts_inds.ptr(0)[facet];
@@ -610,16 +610,16 @@ namespace pcl
                    float3 v1 = tr( points[ i1 ] );
                    float3 v2 = tr( points[ i2 ] );
                    float3 v3 = tr( points[ i3 ] );
-               
+
                    float4 p0 = compute_plane(hp, v1, v2, /*opposite*/v3); // j
                    float4 p1 = compute_plane(hp, v2, v3, /*opposite*/v1); // facet_count + j
-                   float4 p2 = compute_plane(hp, v3, v1, /*opposite*/v2); // facet_count + j*2                 
+                   float4 p2 = compute_plane(hp, v3, v1, /*opposite*/v2); // facet_count + j*2
 
             p0 *= compue_inv_normal_norm(p0);
             p1 *= compue_inv_normal_norm(p1);
             p2 *= compue_inv_normal_norm(p2);
 
-          
+
                    float4 p = points[perm_index];
                    p.w = 1;
 
@@ -640,12 +640,12 @@ namespace pcl
             for(int i = 0; i < 3; ++i)
               if (dists[i] < 0)
                negs_inds[neg_count++] = i;
+
             if (neg_count == 3)
             {
               int i1 = negs_inds[1];
               int i2 = negs_inds[2];
-           
+
               int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1;
               negs_inds[1] = ir;
               --neg_count;
@@ -655,10 +655,10 @@ namespace pcl
             {
               int i1 = negs_inds[0];
               int i2 = negs_inds[1];
-           
+
               int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1;
               negs_inds[0] = ir;
-              --neg_count;              
+              --neg_count;
             }
 
             if (neg_count == 1)
@@ -670,16 +670,16 @@ namespace pcl
 
             // if (neg_count == 0)
             // new_idx = std::numeric_limits<int>::max() ==>> internal point
-                                          
+
             std::uint64_t res = new_idx;
                    res <<= 32;
                    res += *reinterpret_cast<unsigned int*>(&dist);
 
                    facets_dists[point_idx] = res;
 
-          } /* if (hi == perm_index) */            
+          } /* if (hi == perm_index) */
         }
-         };    
+         };
 
       __global__ void classifyKernel(const Classify c, int cloud_size)
       {
@@ -692,7 +692,7 @@ namespace pcl
 }
 
 void pcl::device::PointStream::classify(FacetStream& fs)
-{   
+{
   Classify c;
 
   c.facets_dists = facets_dists;
@@ -706,16 +706,16 @@ void pcl::device::PointStream::classify(FacetStream& fs)
   c.diag = cloud_diag;
   c.facet_count = fs.facet_count;
 
-  //thrust::counting_iterator<int> b(0);    
+  //thrust::counting_iterator<int> b(0);
   //thrust::for_each(b, b + cloud_size, c);
 
   classifyKernel<<<divUp(cloud_size, 256), 256>>>(c, cloud_size);
   cudaSafeCall( cudaGetLastError() );
   cudaSafeCall( cudaDeviceSynchronize() );
-  
+
   thrust::device_ptr<std::uint64_t> beg(facets_dists.ptr());
   thrust::device_ptr<std::uint64_t> end = beg + cloud_size;
-  
+
   thrust::device_ptr<int> pbeg(perm.ptr());
   thrust::sort_by_key(beg, end, pbeg);
 }
@@ -731,14 +731,14 @@ namespace pcl
 
       mutable PtrStep<int>  verts_inds;
 
-      __device__ __forceinline__ 
+      __device__ __forceinline__
       void operator()(int facet) const
       {
         int hi = head_points[facet];
         int i1 = verts_inds.ptr(0)[facet];
         int i2 = verts_inds.ptr(1)[facet];
         int i3 = verts_inds.ptr(2)[facet];
-        
+
         make_facet(hi, i1, i2, facet);
         make_facet(hi, i2, i3, facet + facet_count);
         make_facet(hi, i3, i1, facet + facet_count * 2);
@@ -757,8 +757,8 @@ namespace pcl
     {
       int facet = threadIdx.x + blockIdx.x * blockDim.x;
 
-      if (facet < sf.facet_count)        
-        sf(facet);        
+      if (facet < sf.facet_count)
+        sf(facet);
     }
   }
 }
@@ -769,9 +769,9 @@ void pcl::device::FacetStream::splitFacets()
   sf.head_points = head_points;
   sf.verts_inds = verts_inds;
   sf.facet_count = facet_count;
-    
 
-  //thrust::counting_iterator<int> b(0);    
+
+  //thrust::counting_iterator<int> b(0);
   //thrust::for_each(b, b + facet_count, sf);
 
   splitFacetsKernel<<<divUp(facet_count, 256), 256>>>(sf);
@@ -786,8 +786,8 @@ size_t pcl::device::remove_duplicates(DeviceArray<int>& indeces)
   thrust::device_ptr<int> beg(indeces.ptr());
   thrust::device_ptr<int> end = beg + indeces.size();
 
-  thrust::sort(beg, end);  
-  return (std::size_t)(thrust::unique(beg, end) - beg);  
+  thrust::sort(beg, end);
+  return (std::size_t)(thrust::unique(beg, end) - beg);
 }
 
 
@@ -810,15 +810,15 @@ void pcl::device::pack_hull(const DeviceArray<PointType>& points, const DeviceAr
 {
   output.create(indeces.size());
 
-  //thrust::device_ptr<const PointType> in(points.ptr());  
-  
+  //thrust::device_ptr<const PointType> in(points.ptr());
+
   //thrust::device_ptr<const int> mb(indeces.ptr());
   //thrust::device_ptr<const int> me = mb + indeces.size();
 
-  //thrust::device_ptr<PointType> out(output.ptr());  
+  //thrust::device_ptr<PointType> out(output.ptr());
 
   //thrust::gather(mb, me, in, out);
-  
+
   gatherKernel<<<divUp(indeces.size(), 256), 256>>>(indeces, points, output);
   cudaSafeCall( cudaGetLastError() );
   cudaSafeCall( cudaDeviceSynchronize() );
index 83f912d9310c1d50b9fa9c91862dc020f6f26786..96f6600d2476222e30cb9b892b02ff97f74afcc6 100644 (file)
@@ -4,18 +4,6 @@ endif()
 
 set(the_test_target test_gpu_surface)
 
-get_filename_component(DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)
-get_filename_component(INC_SURF "${DIR}/../../surface/include" REALPATH)
-get_filename_component(INC_IO "${DIR}/../../../io/include" REALPATH)
-get_filename_component(INC_VIZ "${DIR}/../../../visualization/include" REALPATH)
-get_filename_component(INC_GEO "${DIR}/../../../geometry/include" REALPATH)
-get_filename_component(INC_SURF_CPU "${DIR}/../../../surface/include" REALPATH)
-get_filename_component(INC_SEA "${DIR}/../../../search/include" REALPATH)
-get_filename_component(INC_KD "${DIR}/../../../kdtree/include" REALPATH)
-get_filename_component(INC_OCT "${DIR}/../../../octree/include" REALPATH)
-include_directories("${INC_SURF}" "${INC_IO}" "${INC_VIZ}" "${INC_GEO}" "${INC_SURF_CPU}" "${INC_SEA}" "${INC_KD}" "${INC_OCT}")
-include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
-
 file(GLOB test_src *.cpp *.hpp)
 #PCL_ADD_TEST(a_gpu_surface_test ${the_test_target} FILES ${test_src} LINK_WITH pcl_io pcl_gpu_containers pcl_gpu_surface pcl_visualization pcl_surface pcl_octree pcl_kdtree pcl_search)
 #add_dependencies(${the_test_target} pcl_io pcl_gpu_containes pcl_gpu_surface pcl_visualization)
index e464a9e8e266c5392a85713486a5017c1343f614..651c1718d9ca9aaadfefe9cb35fb4706b89bc55a 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/tracking)
 set(SUBSYS_DESC "Tracking with GPU")
 set(SUBSYS_DEPS common gpu_containers gpu_utils gpu_octree tracking search kdtree filters octree)
 
-set(build FALSE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}")
@@ -26,9 +25,9 @@ source_group("Source Files\\cuda" FILES ${cuda})
 list(APPEND srcs ${utils} ${cuda})
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src" "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
-target_link_libraries("${LIB_NAME}" pcl_gpu_containers)
+target_link_libraries(${LIB_NAME} pcl_gpu_containers)
+target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
index 8775067ccff32de7ae5465ef4f919ab153130cf5..e0f4ccfb020737f82d13cce7f8c9bcc6b2d56b6d 100644 (file)
@@ -1,9 +1,8 @@
 set(SUBSYS_NAME gpu_utils)
 set(SUBSYS_PATH gpu/utils)
 set(SUBSYS_DESC "Device layer functions.")
-set(SUBSYS_DEPS common gpu_containers)
+set(SUBSYS_DEPS common)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}")
@@ -20,9 +19,8 @@ source_group("Header Files\\device" FILES ${dev_incs})
 source_group("Source Files" FILES ${srcs})
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${dev_incs} ${incs} ${srcs})
-target_link_libraries("${LIB_NAME}" pcl_gpu_containers)
+target_link_libraries("${LIB_NAME}" pcl_common)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
index c4e8b1b5e4bb0b8fdb50cb8a819b571b7eaadd46..743c4cf942ce054aba93ea1e7f5be943ad533679 100644 (file)
@@ -46,7 +46,6 @@ namespace pcl
     {
         // Function Objects
 
-        using thrust::unary_function;
         using thrust::binary_function;
 
         // Arithmetic Operations
@@ -79,8 +78,10 @@ namespace pcl
         using thrust::bit_or;
         using thrust::bit_xor;
 
-        template <typename T> struct bit_not : unary_function<T, T>
+        template <typename T> struct bit_not
         {
+            typedef T argument_type;
+            typedef T result_type;
             __forceinline__ __device__ T operator ()(const T& v) const {return ~v;}
         };
 
diff --git a/gpu/utils/include/pcl/gpu/utils/device/static_check.hpp b/gpu/utils/include/pcl/gpu/utils/device/static_check.hpp
deleted file mode 100644 (file)
index fe153cf..0000000
+++ /dev/null
@@ -1,68 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011, Willow Garage, Inc.
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage, Inc. nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- *  Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
- */
-
-PCL_DEPRECATED_HEADER(1, 15, "pcl::device::Static will be removed at PCL release 1.15");
-
-#ifndef PCL_GPU_DEVICE_STATIC_CHECK_HPP_
-#define PCL_GPU_DEVICE_STATIC_CHECK_HPP_
-
-#if defined(__CUDACC__)
-#define __PCL_GPU_HOST_DEVICE__ __host__ __device__ __forceinline__
-#else
-#define __PCL_GPU_HOST_DEVICE__
-#endif
-
-namespace pcl {
-namespace device {
-template <bool expr>
-struct Static {};
-
-template <>
-struct [[deprecated("This class will be replaced at PCL release 1.15  by "
-                    "c++11's static_assert instead")]] Static<true>
-{
-  __PCL_GPU_HOST_DEVICE__ static void check(){};
-};
-} // namespace device
-
-namespace gpu {
-using pcl::device::Static;
-}
-} // namespace pcl
-
-#undef __PCL_GPU_HOST_DEVICE__
-
-#endif /* PCL_GPU_DEVICE_STATIC_CHECK_HPP_ */
index aee46375cae48155c659a823eaa1e253f6a57372..36647dcf7330e00468cdb258c8e69e76c3cb9899 100644 (file)
@@ -103,7 +103,7 @@ namespace pcl
 
 
         ////////////////////////////////
-        // tempalted operations vectors 
+        // templated operations vectors 
 
         template<typename T> __device__ __host__ __forceinline__ float norm(const T& val)
         {
index ce1e2d221ddda1c4c8cedb499b57724415675e31..217fa321db84200b27c7182ef64415f17908e686 100644 (file)
 #ifndef __PCL_GPU_UTILS_REPACKS_HPP__
 #define __PCL_GPU_UTILS_REPACKS_HPP__
 
-#include <pcl/pcl_macros.h>
-#include <pcl/point_types.h>
+PCL_DEPRECATED_HEADER(1, 17, "This has been deprecated, please include it from pcl/gpu/containers.")
 
-#include <pcl/gpu/containers/device_array.h>
-
-namespace pcl
-{
-    namespace gpu
-    {
-        ///////////////////////////////////////
-        ///  This is an experimental code   ///
-        ///////////////////////////////////////
-
-        const int NoCP = 0xFFFFFFFF;
-
-        /** \brief Returns field copy operation code. */
-        inline int cp(int from, int to) 
-        { 
-            return ((to & 0xF) << 4) + (from & 0xF); 
-        }
-
-        /* Combines several field copy operations to one int (called rule) */
-        inline int rule(int cp1, int cp2 = NoCP, int cp3 = NoCP, int cp4 = NoCP)
-        {
-            return (cp1 & 0xFF) + ((cp2 & 0xFF) << 8) + ((cp3 & 0xFF) << 16) + ((cp4 & 0xFF) << 24);
-        }
-
-        /* Combines performs all field copy operations in given rule array (can be 0, 1, or 16 copies) */
-        void copyFieldsImpl(int in_size, int out_size, int rules[4], int size, const void* input, void* output); 
-
-        template<typename PointIn, typename PointOut>
-        void copyFieldsEx(const DeviceArray<PointIn>& src, DeviceArray<PointOut>& dst, int rule1, int rule2 = NoCP, int rule3 = NoCP, int rule4 = NoCP)
-        {
-            int rules[4] = { rule1, rule2, rule3, rule4 };
-            dst.create(src.size());
-            copyFieldsImpl(sizeof(PointIn)/sizeof(int), sizeof(PointOut)/sizeof(int), rules, (int)src.size(), src.ptr(), dst.ptr());
-        }
-
-        void copyFields(const DeviceArray<PointXYZ>& src, DeviceArray<PointNormal>& dst)
-        {
-            //PointXYZ.x (0) -> PointNormal.x (0)
-            //PointXYZ.y (1) -> PointNormal.y (1)
-            //PointXYZ.z (2) -> PointNormal.z (2)
-            copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
-        };
-
-        void copyFields(const DeviceArray<Normal>& src, DeviceArray<PointNormal>& dst)
-        {
-            //PointXYZ.normal_x (0)  -> PointNormal.normal_x (4)
-            //PointXYZ.normal_y (1)  -> PointNormal.normal_y (5)
-            //PointXYZ.normal_z (2)  -> PointNormal.normal_z (6)
-            //PointXYZ.curvature (4) -> PointNormal.curvature (8)
-            copyFieldsEx(src, dst, rule(cp(0, 4), cp(1, 5), cp(2, 6), cp(4,8)));
-        };
-
-        void copyFields(const DeviceArray<PointXYZRGBL>& src, DeviceArray<PointXYZ>& dst)
-        {
-            //PointXYZRGBL.x (0) -> PointXYZ.x (0)
-            //PointXYZRGBL.y (1) -> PointXYZ.y (1)
-            //PointXYZRGBL.z (2) -> PointXYZ.z (2)
-            copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
-        };
-
-        void copyFields(const DeviceArray<PointXYZRGB>& src, DeviceArray<PointXYZ>& dst)
-        {
-            //PointXYZRGB.x (0) -> PointXYZ.x (0)
-            //PointXYZRGB.y (1) -> PointXYZ.y (1)
-            //PointXYZRGB.z (2) -> PointXYZ.z (2)
-            copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
-        };
-
-        void copyFields(const DeviceArray<PointXYZRGBA>& src, DeviceArray<PointXYZ>& dst)
-        {
-            //PointXYZRGBA.x (0) -> PointXYZ.x (0)
-            //PointXYZRGBA.y (1) -> PointXYZ.y (1)
-            //PointXYZRGBA.z (2) -> PointXYZ.z (2)
-            copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2)));
-        };
-
-        void copyFieldsZ(const DeviceArray<PointXYZ>& src, DeviceArray<float>& dst)
-        {
-            //PointXYZRGBL.z (2) -> float (1)
-            copyFieldsEx(src, dst, rule(cp(2, 0)));
-        };
-
-        void copyFieldsZ(const DeviceArray<PointXYZRGB>& src, DeviceArray<float>& dst)
-        {
-            //PointXYZRGBL.z (2) -> float (1)
-            copyFieldsEx(src, dst, rule(cp(2, 0)));
-        };
-    }
-}
 
 #endif /* __PCL_GPU_UTILS_REPACKS_HPP__ */
index 2a2e844d72e1c8ad4beaaa344ab66dbdcb62c4d0..0c0b83739565969cb08c0f4d121ce894ef17ebf6 100644 (file)
 #define __PCL_CUDA_SAFE_CALL_HPP__
 
 #include <cuda_runtime_api.h>
-#include <pcl/gpu/containers/initialization.h>
+
+#include <iostream>
 
 #if defined(__GNUC__)
-    #define cudaSafeCall(expr)  pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__, __func__)
+#define cudaSafeCall(expr) pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__, __func__)
 #else /* defined(__CUDACC__) || defined(__MSVC__) */
-    #define cudaSafeCall(expr)  pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__)    
+#define cudaSafeCall(expr) pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__)
 #endif
 
-namespace pcl
-{
-    namespace gpu
-    {
-        static inline void ___cudaSafeCall(cudaError_t err, const char *file, const int line, const char *func = "")
-        {
-            if (cudaSuccess != err)
-                error(cudaGetErrorString(err), file, line, func);
-        }        
+namespace pcl {
+namespace gpu {
 
-        static inline int divUp(int total, int grain) { return (total + grain - 1) / grain; }
-    }
+static inline void
+___cudaSafeCall(cudaError_t err,
+                const char* file,
+                const int line,
+                const char* func = "")
+{
+  if (cudaSuccess != err) {
+    std::cout << "Error: " << cudaGetErrorString(err) << "\t" << file << ":" << line
+              << ":" << func << std::endl;
+    exit(EXIT_FAILURE);
+  }
+}
 
-    namespace device
-    {
-        using pcl::gpu::divUp;        
-    }
+static inline int
+divUp(int total, int grain)
+{
+  return (total + grain - 1) / grain;
 }
+} // namespace gpu
 
+namespace device {
+using pcl::gpu::divUp;
+}
+} // namespace pcl
 
 #endif /* __PCL_CUDA_SAFE_CALL_HPP__ */
index 772392e042b8c5fd606d7e3c4a67e9c8028348a6..a52799fe3ab4f0fd6b2b22faf2306437580ef877 100644 (file)
 #ifndef PCL_GPU_UTILS_TEXTURE_BINDER_HPP_
 #define PCL_GPU_UTILS_TEXTURE_BINDER_HPP_
 
-#include <pcl/gpu/utils/safe_call.hpp>
-#include <pcl/gpu/containers/device_array.h>
+PCL_DEPRECATED_HEADER(1, 17, "This has been deprecated, please include it from pcl/gpu/containers.")
 
-namespace pcl
-{
-  namespace gpu
-  {
-    class TextureBinder
-    {
-    public:        
-      template<class T, enum cudaTextureReadMode readMode>
-      TextureBinder(const DeviceArray2D<T>& arr, const struct texture<T, 2, readMode>& tex) : texref(&tex)
-      {
-        cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();  
-        cudaSafeCall( cudaBindTexture2D(0, tex, arr.ptr(), desc, arr.cols(), arr.rows(), arr.step()) );        
-      }
-
-      template<class T, enum cudaTextureReadMode readMode>
-      TextureBinder(const DeviceArray<T>& arr, const struct texture<T, 1, readMode> &tex) : texref(&tex)
-      {
-        cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();  
-        cudaSafeCall( cudaBindTexture(0, tex, arr.ptr(), desc, arr.sizeBytes()) );
-      }
-
-      template<class T, enum cudaTextureReadMode readMode>
-      TextureBinder(const PtrStepSz<T>& arr, const struct texture<T, 2, readMode>& tex) : texref(&tex)
-      {
-        cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();  
-        cudaSafeCall( cudaBindTexture2D(0, tex, arr.data, desc, arr.cols, arr.rows, arr.step) );        
-      }
-
-      template<class T, enum cudaTextureReadMode readMode>
-      TextureBinder(const PtrSz<T>& arr, const struct texture<T, 1, readMode> &tex) : texref(&tex)
-      {
-        cudaChannelFormatDesc desc = cudaCreateChannelDesc<T>();  
-        cudaSafeCall( cudaBindTexture(0, tex, arr.data, desc, arr.size * arr.elemSize()) );
-      }
-
-      ~TextureBinder()
-      {
-        cudaSafeCall( cudaUnbindTexture(texref) );
-      }
-    private:
-      const struct textureReference *texref;    
-    };
-  }
-
-  namespace device
-  {
-      using pcl::gpu::TextureBinder;
-  }
-}
-
-#endif /* PCL_GPU_UTILS_TEXTURE_BINDER_HPP_*/
\ No newline at end of file
+#endif /* PCL_GPU_UTILS_TEXTURE_BINDER_HPP_*/
diff --git a/gpu/utils/src/empty.cu b/gpu/utils/src/empty.cu
new file mode 100644 (file)
index 0000000..1de3281
--- /dev/null
@@ -0,0 +1 @@
+// added empty file for Cmake to determine link language.
index 52245ca7f466aab898864c654dd8475e8f7d2c72..f1c2fbb6326924735c61ea118aa8e2511330a77f 100644 (file)
 #ifndef PCL_GPU_UTILS_INTERNAL_HPP_
 #define PCL_GPU_UTILS_INTERNAL_HPP_
 
+#include <pcl/pcl_macros.h>
+
+PCL_DEPRECATED_HEADER(1, 17, "This has been deprecated and will be removed.")
+
+
 namespace pcl
 {
     namespace device
@@ -45,4 +50,4 @@ namespace pcl
     }
 }
 
-#endif
\ No newline at end of file
+#endif
diff --git a/gpu/utils/src/repacks.cpp b/gpu/utils/src/repacks.cpp
deleted file mode 100644 (file)
index eae8e60..0000000
+++ /dev/null
@@ -1,41 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011, Willow Garage, Inc.
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage, Inc. nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- *  Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com)
- */
-
-#include <cassert>
-
-#include <pcl/gpu/utils/repacks.hpp>
-#include "internal.hpp"
-
diff --git a/gpu/utils/src/repacks.cu b/gpu/utils/src/repacks.cu
deleted file mode 100644 (file)
index 2467bf9..0000000
+++ /dev/null
@@ -1,120 +0,0 @@
-#include "internal.hpp"
-#include <algorithm>
-#include "pcl/gpu/utils/safe_call.hpp"
-#include "pcl/pcl_exports.h"
-
-namespace pcl
-{
-    namespace device
-    {
-        struct Info
-        {
-            enum { SIZE = 4 };
-            int data[SIZE];
-        };
-
-        template<int n>
-        struct Point
-        {
-            int data[n];
-        };
-
-        template<int in, int out, typename Info>
-        __global__ void deviceCopyFields4B(const Info info, const int size, const void* input, void* output)
-        {
-            int idx = blockIdx.x * blockDim.x + threadIdx.x;
-
-            if (idx < size)
-            {
-                Point<in>  point_in  = reinterpret_cast<const  Point<in>* >( input)[idx];
-                Point<out> point_out = reinterpret_cast<      Point<out>* >(output)[idx];
-
-                for(int i = 0; i < Info::SIZE; ++i)
-                {
-                    int byte;
-                    int code = info.data[i];
-
-                    byte = ((code >> 0) & 0xFF);
-
-                    if (byte == 0xFF)
-                        break;
-                    else
-                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
-
-                    byte = ((code >> 8) & 0xFF);
-
-                    if (byte == 0xFF)
-                        break;
-                    else
-                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
-
-                    byte = ((code >> 16) & 0xFF);
-
-                    if (byte == 0xFF)
-                        break;
-                    else
-                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
-
-                    byte = ((code >> 24) & 0xFF);
-
-                    if (byte == 0xFF)
-                        break;
-                    else
-                        point_out.data[byte >> 4] = point_in.data[byte & 0xF];
-                }
-
-                reinterpret_cast< Point<out>* >(output)[idx] = point_out;
-            }
-        };
-
-        template<int in_size, int out_size>
-        void cf(int info[4], int size, const void* input, void* output)
-        {
-            Info i;
-            std::copy(info, info + 4, i.data);
-
-            dim3 block(256);
-            dim3 grid(divUp(size, block.x));
-
-            deviceCopyFields4B<in_size, out_size><<<grid, block>>>(i, size, input, output);
-            cudaSafeCall ( cudaGetLastError () );
-            cudaSafeCall (cudaDeviceSynchronize ());
-        }
-
-        using copy_fields_t = void (*)(int info[4], int size, const void* input, void* output);
-    }
-}
-
-namespace pcl
-{
-    namespace gpu
-    {
-        using namespace pcl::device;
-
-        PCL_EXPORTS void copyFieldsImpl(int in_size, int out_size, int rules[4], int size, const void* input, void* output)
-        {
-            pcl::device::copy_fields_t funcs[16][16] =
-            {
-                { /**/ cf<1,1>,  cf<1, 2>, cf<1, 3>, cf<1, 4>, /**/ cf<1, 5>, cf<1, 6>, cf<1, 7>, cf<1, 8>, /**/ cf<1, 9>, cf<1,10>, cf<1, 11>, cf<1, 12>, /**/ cf<1, 13>, cf<1, 14>, cf<1, 15>,  cf<1,16> },
-                { /**/ cf<2,1>,  cf<2, 2>, cf<2, 3>, cf<2, 4>, /**/ cf<2, 5>, cf<2, 6>, cf<2, 7>, cf<2, 8>, /**/ cf<2, 9>, cf<1,10>, cf<2, 11>, cf<2, 12>, /**/ cf<2, 13>, cf<2, 14>, cf<2, 15>,  cf<2,16> },
-                { /**/ cf<3,1>,  cf<3, 2>, cf<3, 3>, cf<3, 4>, /**/ cf<3, 5>, cf<3, 6>, cf<3, 7>, cf<3, 8>, /**/ cf<3, 9>, cf<1,10>, cf<3, 11>, cf<3, 12>, /**/ cf<3, 13>, cf<3, 14>, cf<3, 15>,  cf<3,16> },
-                { /**/ cf<4,1>,  cf<4, 2>, cf<4, 3>, cf<4, 4>, /**/ cf<4, 5>, cf<4, 6>, cf<4, 7>, cf<4, 8>, /**/ cf<4, 9>, cf<1,10>, cf<4, 11>, cf<4, 12>, /**/ cf<4, 13>, cf<4, 14>, cf<4, 15>,  cf<4,16> },
-                { /**/ cf<5,1>,  cf<5, 2>, cf<5, 3>, cf<5, 4>, /**/ cf<5, 5>, cf<5, 6>, cf<5, 7>, cf<5, 8>, /**/ cf<5, 9>, cf<1,10>, cf<5, 11>, cf<5, 12>, /**/ cf<5, 13>, cf<5, 14>, cf<5, 15>,  cf<5,16> },
-                { /**/ cf<6,1>,  cf<6, 2>, cf<6, 3>, cf<6, 4>, /**/ cf<6, 5>, cf<6, 6>, cf<6, 7>, cf<6, 8>, /**/ cf<6, 9>, cf<1,10>, cf<6, 11>, cf<6, 12>, /**/ cf<6, 13>, cf<6, 14>, cf<6, 15>,  cf<6,16> },
-                { /**/ cf<7,1>,  cf<7, 2>, cf<7, 3>, cf<7, 4>, /**/ cf<7, 5>, cf<7, 6>, cf<7, 7>, cf<7, 8>, /**/ cf<7, 9>, cf<1,10>, cf<7, 11>, cf<7, 12>, /**/ cf<7, 13>, cf<7, 14>, cf<7, 15>,  cf<7,16> },
-                { /**/ cf<8,1>,  cf<8, 2>, cf<8, 3>, cf<8, 4>, /**/ cf<8, 5>, cf<8, 6>, cf<8, 7>, cf<8, 8>, /**/ cf<8, 9>, cf<1,10>, cf<8, 11>, cf<8, 12>, /**/ cf<8, 13>, cf<8, 14>, cf<8, 15>,  cf<8,16> },
-                { /**/ cf<9,1>,  cf<9, 2>, cf<9, 3>, cf<9, 4>, /**/ cf<9, 5>, cf<9, 6>, cf<9, 7>, cf<9, 8>, /**/ cf<9, 9>, cf<1,10>, cf<9, 11>, cf<9, 12>, /**/ cf<9, 13>, cf<9, 14>, cf<9, 15>,  cf<9,16> },
-                { /**/ cf<10,1>, cf<10,2>, cf<10,3>, cf<10,4>, /**/ cf<10,5>, cf<10,6>, cf<10,7>, cf<10,8>, /**/ cf<10,9>, cf<1,10>, cf<10,11>, cf<10,12>, /**/ cf<10,13>, cf<10,14>, cf<10,15>, cf<10,16> },
-                { /**/ cf<11,1>, cf<11,2>, cf<11,3>, cf<11,4>, /**/ cf<11,5>, cf<11,6>, cf<11,7>, cf<11,8>, /**/ cf<11,9>, cf<1,10>, cf<11,11>, cf<11,12>, /**/ cf<11,13>, cf<11,14>, cf<11,15>, cf<11,16> },
-                { /**/ cf<12,1>, cf<12,2>, cf<12,3>, cf<12,4>, /**/ cf<12,5>, cf<12,6>, cf<12,7>, cf<12,8>, /**/ cf<12,9>, cf<1,10>, cf<12,11>, cf<12,12>, /**/ cf<12,13>, cf<12,14>, cf<12,15>, cf<12,16> },
-                { /**/ cf<13,1>, cf<13,2>, cf<13,3>, cf<13,4>, /**/ cf<13,5>, cf<13,6>, cf<13,7>, cf<13,8>, /**/ cf<13,9>, cf<1,10>, cf<13,11>, cf<13,12>, /**/ cf<13,13>, cf<13,14>, cf<13,15>, cf<13,16> },
-                { /**/ cf<14,1>, cf<14,2>, cf<14,3>, cf<14,4>, /**/ cf<14,5>, cf<14,6>, cf<14,7>, cf<14,8>, /**/ cf<14,9>, cf<1,10>, cf<14,11>, cf<14,12>, /**/ cf<14,13>, cf<14,14>, cf<14,15>, cf<14,16> },
-                { /**/ cf<15,1>, cf<15,2>, cf<15,3>, cf<15,4>, /**/ cf<15,5>, cf<15,6>, cf<15,7>, cf<15,8>, /**/ cf<15,9>, cf<1,10>, cf<15,11>, cf<15,12>, /**/ cf<15,13>, cf<15,14>, cf<15,15>, cf<15,16> },
-                { /**/ cf<16,1>, cf<16,2>, cf<16,3>, cf<16,4>, /**/ cf<16,5>, cf<16,6>, cf<16,7>, cf<16,8>, /**/ cf<16,9>, cf<1,10>, cf<16,11>, cf<16,12>, /**/ cf<16,13>, cf<16,14>, cf<16,15>, cf<16,16> }
-            };
-
-            funcs[in_size-1][out_size-1](rules, size, input, output);
-        }
-    }
-}
-
index 7fc86b26e641df166a6e0e6d52df3085f4715c09..68c106704d51c171f5b24e617d3e89c8e6b81c58 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_DESC "Point cloud IO library")
 set(SUBSYS_DEPS common octree)
 set(SUBSYS_EXT_DEPS boost eigen3)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 if(WIN32)
   PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk rssdk rssdk2 pcap png vtk OpenMP EXT_DEPS ${SUBSYS_EXT_DEPS})
@@ -210,9 +209,10 @@ if(MINGW)
   target_link_libraries(pcl_io_ply ws2_32)
 endif()
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/ply" ${PLY_INCLUDES})
-target_include_directories(pcl_io_ply PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include")
 target_link_libraries(pcl_io_ply pcl_common Boost::boost)
 
+PCL_MAKE_PKGCONFIG(pcl_io_ply COMPONENT ${SUBSYS_NAME} DESC "${SUBSYS_DESC}, PLY" PCL_DEPS common)
+
 set(srcs
   src/debayer.cpp
   src/pcd_grabber.cpp
@@ -257,8 +257,6 @@ if(PCAP_FOUND)
 endif()
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
-  "include/pcl/${SUBSYS_NAME}/eigen.h"
   "include/pcl/${SUBSYS_NAME}/debayer.h"
   "include/pcl/${SUBSYS_NAME}/fotonic_grabber.h"
   "include/pcl/${SUBSYS_NAME}/file_io.h"
@@ -266,7 +264,6 @@ set(incs
   "include/pcl/${SUBSYS_NAME}/low_level_io.h"
   "include/pcl/${SUBSYS_NAME}/lzf.h"
   "include/pcl/${SUBSYS_NAME}/lzf_image_io.h"
-  "include/pcl/${SUBSYS_NAME}/io.h"
   "include/pcl/${SUBSYS_NAME}/grabber.h"
   "include/pcl/${SUBSYS_NAME}/file_grabber.h"
   "include/pcl/${SUBSYS_NAME}/timestamp.h"
@@ -341,9 +338,10 @@ add_definitions(${VTK_DEFINES})
 
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${compression_incs} ${impl_incs} ${OPENNI_INCLUDES} ${OPENNI2_INCLUDES})
 
-target_include_directories(${LIB_NAME} PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include")
-
-target_link_libraries("${LIB_NAME}" Boost::boost Boost::filesystem Boost::iostreams pcl_common pcl_io_ply)
+target_link_libraries("${LIB_NAME}" Boost::boost Boost::iostreams pcl_common pcl_io_ply pcl_octree)
+if(TARGET Boost::filesystem)
+  target_link_libraries("${LIB_NAME}" Boost::filesystem)
+endif()
 
 if(VTK_FOUND)
   if(${VTK_VERSION} VERSION_GREATER_EQUAL 9.0)
@@ -371,6 +369,7 @@ if(VTK_FOUND)
 endif()
 
 if(PNG_FOUND)
+  target_include_directories("${LIB_NAME}" SYSTEM PRIVATE ${PNG_INCLUDE_DIRS})
   target_link_libraries("${LIB_NAME}" ${PNG_LIBRARIES})
 endif()
 
@@ -431,6 +430,7 @@ endif()
 if(WITH_ENSENSO)
   list(APPEND EXT_DEPS ensenso)
 endif()
+list(APPEND EXT_DEPS pcl_io_ply)
 
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${EXT_DEPS})
 
index d2eae276364b43168887635acb8192c110d77e7c..4e2178fe634e55c97f90592470db72fce857b13f 100644 (file)
@@ -55,7 +55,7 @@ namespace pcl
   namespace io
   {
     /** \brief @b Octree pointcloud compression class
-     *  \note This class enables compression and decompression of point cloud data based on octree data structures.
+     *  \note This class enables compression and decompression of point cloud data based on octree data structures. It is a lossy compression. See also `PCDWriter` for another way to compress point cloud data.
      *  \note
      *  \note typename: PointT: type of point used in pointcloud
      *  \author Julius Kammerl (julius@kammerl.de)
diff --git a/io/include/pcl/io/boost.h b/io/include/pcl/io/boost.h
deleted file mode 100644 (file)
index a086779..0000000
+++ /dev/null
@@ -1,66 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2011-2012, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-#pragma once
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-#if defined __GNUC__
-#  pragma GCC system_header
-#endif
-//https://bugreports.qt-project.org/browse/QTBUG-22829
-#ifndef Q_MOC_RUN
-#ifndef __CUDACC__
-#include <boost/version.hpp>
-#include <boost/numeric/conversion/cast.hpp>
-#include <boost/filesystem.hpp>
-#include <boost/mpl/fold.hpp>
-#include <boost/mpl/inherit.hpp>
-#include <boost/mpl/inherit_linearly.hpp>
-#include <boost/mpl/joint_view.hpp>
-#include <boost/mpl/transform.hpp>
-#include <boost/mpl/vector.hpp>
-#include <boost/tokenizer.hpp>
-#include <boost/foreach.hpp>
-#include <boost/shared_array.hpp>
-#include <boost/interprocess/permissions.hpp>
-#include <boost/iostreams/device/mapped_file.hpp>
-#define BOOST_PARAMETER_MAX_ARITY 7
-#include <boost/signals2.hpp>
-#include <boost/signals2/slot.hpp>
-#endif
-#include <boost/algorithm/string.hpp>
-#include <boost/interprocess/sync/file_lock.hpp>
-#endif
diff --git a/io/include/pcl/io/eigen.h b/io/include/pcl/io/eigen.h
deleted file mode 100644 (file)
index 0979ece..0000000
+++ /dev/null
@@ -1,45 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2011-2012, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-
-#include <Eigen/Core>
index ce6f55a08904261059834a96b4384c5a372b4710..71f4df826f9362a59770942a43b64ec9c2ba5ad9 100644 (file)
@@ -300,7 +300,7 @@ namespace pcl
     boost::signals2::connection ret = signal->connect (callback);
 
     connections_[typeid (T).name ()].push_back (ret);
-    shared_connections_[typeid (T).name ()].push_back (boost::signals2::shared_connection_block (connections_[typeid (T).name ()].back (), false));
+    shared_connections_[typeid (T).name ()].emplace_back(connections_[typeid (T).name ()].back (), false);
     signalsChanged ();
     return (ret);
   }
index f149346b4a36ff66b7e4c1b44f9f2b6832e93f8d..233ff2642be402f75d93007bd8b90a6361e4ff03 100644 (file)
@@ -274,7 +274,7 @@ namespace pcl
       boost::asio::ip::udp::endpoint udp_listener_endpoint_;
       boost::asio::ip::address source_address_filter_;
       std::uint16_t source_port_filter_;
-      boost::asio::io_service hdl_read_socket_service_;
+      boost::asio::io_context hdl_read_socket_service_;
       boost::asio::ip::udp::socket *hdl_read_socket_;
       std::string pcap_file_name_;
       std::thread *queue_consumer_thread_;
index c45f8860c5cae77483ba0c6c5a405fe7d21c0e3e..f8fec231588f55b2412f26dd9da15fba52d908b9 100644 (file)
 #ifndef PCL_IO_AUTO_IO_IMPL_H_
 #define PCL_IO_AUTO_IO_IMPL_H_
 
+#include <pcl/common/pcl_filesystem.h>
+
 #include <pcl/io/obj_io.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/io/ply_io.h>
 #include <pcl/io/ifs_io.h>
-#include <boost/filesystem.hpp> // for path
 
 namespace pcl
 {
@@ -53,7 +54,7 @@ namespace pcl
     template<typename PointT> int
     load (const std::string& file_name, pcl::PointCloud<PointT>& cloud)
     {
-      boost::filesystem::path p (file_name.c_str ());
+      pcl_fs::path p (file_name.c_str ());
       std::string extension = p.extension ().string ();
       int result = -1;
       if (extension == ".pcd")
@@ -75,7 +76,7 @@ namespace pcl
     template<typename PointT> int
     save (const std::string& file_name, const pcl::PointCloud<PointT>& cloud)
     {
-      boost::filesystem::path p (file_name.c_str ());
+      pcl_fs::path p (file_name.c_str ());
       std::string extension = p.extension ().string ();
       int result = -1;
       if (extension == ".pcd")
@@ -94,4 +95,4 @@ namespace pcl
   }
 }
 
-#endif //PCL_IO_AUTO_IO_IMPL_H_
\ No newline at end of file
+#endif //PCL_IO_AUTO_IO_IMPL_H_
diff --git a/io/include/pcl/io/io.h b/io/include/pcl/io/io.h
deleted file mode 100644 (file)
index 62b3289..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-
-#pragma once
-#include <pcl/pcl_macros.h> // for PCL_DEPRECATED_HEADER
-PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/io.h directly.")
-#include <pcl/common/io.h>
index 7cc26fd95c9519bf6bee66f6b1162f0281d0f585..5d82ddf4083acb781a9a6af5b89c5b2f86787fe0 100644 (file)
@@ -181,6 +181,12 @@ namespace pcl
       // All other errors are passed up.
       if (errno != EINVAL)
         return -1;
+#  elif defined(__OpenBSD__)
+      // OpenBSD has neither posix_fallocate nor fallocate
+      if (::ftruncate(fd, length) == 0)
+        return 0;
+      if (errno != EINVAL)
+        return -1;
 #  else
       // Conforming POSIX systems have posix_fallocate.
       const int res = ::posix_fallocate(fd, 0, length);
index ddda24b0cdcee2ceda2c1feb36f9a90fb68720d0..739d24bd10118eb1f99e61fffdb8155a598924e2 100644 (file)
@@ -178,7 +178,7 @@ namespace openni_wrapper
       void 
       setDepthRegistration (bool on_off);
 
-      /** \return whether the depth stream is registered to the RGB camera fram or not. */
+      /** \return whether the depth stream is registered to the RGB camera frame or not. */
       bool 
       isDepthRegistered () const noexcept;
 
index 3023d566607e053f22a1f73b3f736c03fc44fbe9..244f3719506242f51edbd8051083a6f39dccd603 100644 (file)
@@ -49,6 +49,7 @@
 #include <string>
 #include <tuple>
 #include <vector>
+#include <functional>
 #include <boost/lexical_cast.hpp> // for lexical_cast
 #include <boost/mpl/fold.hpp> // for fold
 #include <boost/mpl/inherit.hpp> // for inherit
index 86e540771aed96879fef7aaa3ee04249cc857b37..dbad3424a3a1cc1165ef12090d37ceec024f82e2 100644 (file)
@@ -591,7 +591,19 @@ namespace pcl
                   const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
                   int precision = 8,
                   bool use_camera = true);
-
+         /** \brief Save point cloud data to a std::ostream containing n-D points, in BINARY format
+          * \param[in] os the output buffer
+          * \param[in] cloud the point cloud data message
+          * \param[in] origin the sensor data acquisition origin
+          * (translation) \param[in] orientation the sensor data acquisition origin
+          * (rotation) \param[in] use_camera if set to true then PLY file will use element
+          * camera else element range_grid will be used
+          */
+         int
+         writeBinary(std::ostream& os, const pcl::PCLPointCloud2& cloud,
+                                 const Eigen::Vector4f& origin = Eigen::Vector4f::Zero (), const Eigen::Quaternionf& orientation= Eigen::Quaternionf::Identity (),
+                                 bool use_camera=true);
+      
       /** \brief Save point cloud data to a PLY file containing n-D points, in BINARY format
         * \param[in] file_name the output file name
         * \param[in] cloud the point cloud data message
index 52485049d028be6f653b2d40dcf48eee289e14b7..4ed975d50e6e59e0e5830e94cb899a84bad544a1 100644 (file)
@@ -131,7 +131,7 @@ namespace pcl
 
       boost::asio::ip::address sensor_address_;
       boost::asio::ip::udp::endpoint sender_endpoint_;
-      boost::asio::io_service io_service_;
+      boost::asio::io_context io_service_;
       std::shared_ptr<boost::asio::ip::udp::socket> socket_;
       std::shared_ptr<std::thread> socket_thread_;
       std::shared_ptr<std::thread> consumer_thread_;
index 786e501b967e07a7fb8b71dd2ba3264d56ad3e80..91d8148c9a84f7955f49ebe4ee0d03fba911d631 100644 (file)
@@ -128,7 +128,7 @@ class PCL_EXPORTS TimGrabber : public Grabber
     std::vector<float> distances_;
 
     boost::asio::ip::tcp::endpoint tcp_endpoint_;
-    boost::asio::io_service tim_io_service_;
+    boost::asio::io_context tim_io_service_;
     boost::asio::ip::tcp::socket tim_socket_;
     //// wait time for receiving data (on the order of milliseconds)
     unsigned int wait_time_milliseconds_ = 0;
index a7a42ac95a3cb41c5e42dfd69ee1620063d81d74..de57bf20063d7506c087f2064c8b64d030202ef0 100644 (file)
@@ -92,6 +92,7 @@ namespace pcl
     /** \brief Load a \ref PolygonMesh object given an input file name, based on the file extension
       * \param[in] file_name the name of the file containing the polygon data
       * \param[out] mesh the object that we want to load the data in 
+      * \return Number of points in the point cloud of the mesh.
       * \ingroup io
       */ 
     PCL_EXPORTS int
@@ -113,6 +114,7 @@ namespace pcl
     /** \brief Load a VTK file into a \ref PolygonMesh object
       * \param[in] file_name the name of the file that contains the data
       * \param[out] mesh the object that we want to load the data in 
+      * \return Number of points in the point cloud of the mesh.
       * \ingroup io
       */
     PCL_EXPORTS int
@@ -122,6 +124,7 @@ namespace pcl
     /** \brief Load a PLY file into a \ref PolygonMesh object
       * \param[in] file_name the name of the file that contains the data
       * \param[out] mesh the object that we want to load the data in 
+      * \return Number of points in the point cloud of the mesh.
       * \ingroup io
       */
     PCL_EXPORTS int
@@ -131,6 +134,7 @@ namespace pcl
     /** \brief Load an OBJ file into a \ref PolygonMesh object
       * \param[in] file_name the name of the file that contains the data
       * \param[out] mesh the object that we want to load the data in 
+      * \return Number of points in the point cloud of the mesh.
       * \ingroup io
       */
     PCL_EXPORTS int
@@ -143,6 +147,7 @@ namespace pcl
       * load the material information.
       * \param[in] file_name the name of the file that contains the data
       * \param[out] mesh the object that we want to load the data in
+      * \return Number of points in the point cloud of the mesh.
       * \ingroup io
       */
     PCL_EXPORTS int
@@ -153,6 +158,7 @@ namespace pcl
     /** \brief Load an STL file into a \ref PolygonMesh object
       * \param[in] file_name the name of the file that contains the data
       * \param[out] mesh the object that we want to load the data in 
+      * \return Number of points in the point cloud of the mesh.
       * \ingroup io
       */
     PCL_EXPORTS int
index 486ef5aba186b8f1edfe75711b146a65da49b98c..efd6614df2cc4318b397675300f3edf4dd9ace68 100644 (file)
  */
 
 #include <pcl/common/io.h>  // for getFieldSize
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/utils.h> // pcl::utils::ignore
 #include <pcl/io/ascii_io.h>
 #include <istream>
 #include <fstream>
-#include <boost/filesystem.hpp>
+
 #include <boost/lexical_cast.hpp> // for lexical_cast
 #include <boost/algorithm/string.hpp> // for split
 #include <cstdint>
@@ -88,9 +89,9 @@ pcl::ASCIIReader::readHeader (const std::string& file_name,
 {
   pcl::utils::ignore(offset); //offset is not used for ascii file implementation
        
-  boost::filesystem::path fpath = file_name;
+  pcl_fs::path fpath = file_name;
 
-  if (!boost::filesystem::exists (fpath))
+  if (!pcl_fs::exists (fpath))
   {
     PCL_ERROR ("[%s] File %s does not exist.\n", name_.c_str (), file_name.c_str ());
     return (-1);
@@ -197,7 +198,7 @@ pcl::ASCIIReader::parse (
 #define ASSIGN_TOKEN(CASE_LABEL)                                                       \
   case CASE_LABEL: {                                                                   \
     *(reinterpret_cast<pcl::traits::asType_t<CASE_LABEL>*>(data_target)) =             \
-        boost::lexical_cast<pcl::traits::asType_t<CASE_LABEL>>(token);                 \
+        boost::lexical_cast<pcl::traits::asType_t<(CASE_LABEL)>>(token);               \
     return sizeof(pcl::traits::asType_t<CASE_LABEL>);                                  \
   }
   switch (field.datatype)
index 86a206bef82d7720fb84a40df78f517f3678af24..e5c09e05549511d09781570a6f4c2a109e5f3377 100644 (file)
@@ -46,7 +46,7 @@
 int
 pcl::io::load (const std::string& file_name, pcl::PCLPointCloud2& blob)
 {
-  boost::filesystem::path p (file_name.c_str ());
+  pcl_fs::path p (file_name.c_str ());
   std::string extension = p.extension ().string ();
   int result = -1;
   if (extension == ".pcd")
@@ -68,7 +68,7 @@ pcl::io::load (const std::string& file_name, pcl::PCLPointCloud2& blob)
 int
 pcl::io::load (const std::string& file_name, pcl::PolygonMesh& mesh)
 {
-  boost::filesystem::path p (file_name.c_str ());
+  pcl_fs::path p (file_name.c_str ());
   std::string extension = p.extension ().string ();
   int result = -1;
   if (extension == ".ply")
@@ -88,7 +88,7 @@ pcl::io::load (const std::string& file_name, pcl::PolygonMesh& mesh)
 int
 pcl::io::load (const std::string& file_name, pcl::TextureMesh& mesh)
 {
-  boost::filesystem::path p (file_name.c_str ());
+  pcl_fs::path p (file_name.c_str ());
   std::string extension = p.extension ().string ();
   int result = -1;
   if (extension == ".obj")
@@ -104,7 +104,7 @@ pcl::io::load (const std::string& file_name, pcl::TextureMesh& mesh)
 int
 pcl::io::save (const std::string& file_name, const pcl::PCLPointCloud2& blob, unsigned precision)
 {
-  boost::filesystem::path p (file_name.c_str ());
+  pcl_fs::path p (file_name.c_str ());
   std::string extension = p.extension ().string ();
   int result = -1;
   if (extension == ".pcd")
@@ -134,7 +134,7 @@ pcl::io::save (const std::string& file_name, const pcl::PCLPointCloud2& blob, un
 int
 pcl::io::save (const std::string &file_name, const pcl::TextureMesh &tex_mesh, unsigned precision)
 {
-  boost::filesystem::path p (file_name.c_str ());
+  pcl_fs::path p (file_name.c_str ());
   std::string extension = p.extension ().string ();
   int result = -1;
   if (extension == ".obj")
@@ -150,7 +150,7 @@ pcl::io::save (const std::string &file_name, const pcl::TextureMesh &tex_mesh, u
 int
 pcl::io::save (const std::string &file_name, const pcl::PolygonMesh &poly_mesh, unsigned precision)
 {
-  boost::filesystem::path p (file_name.c_str ());
+  pcl_fs::path p (file_name.c_str ());
   std::string extension = p.extension ().string ();
   int result = -1;
   if (extension == ".ply")
index c54f68edf3709975b4e6a5c7ac85f7192b22c360..adce104ad0a12da18465a18dcc08e48c469b25e3 100644 (file)
@@ -287,7 +287,7 @@ pcl::HDLGrabber::loadHDL32Corrections ()
 boost::asio::ip::address
 pcl::HDLGrabber::getDefaultNetworkAddress ()
 {
-  return (boost::asio::ip::address::from_string ("192.168.3.255"));
+  return (boost::asio::ip::make_address ("192.168.3.255"));
 }
 
 /////////////////////////////////////////////////////////////////////////////
index d3bc8c7a1e4cb6229c8817786ed04a1f6a80df85..8f9884fd2926be4cabd7678ecb47b9f8897d74e8 100644 (file)
@@ -42,7 +42,6 @@
 
 #include <cstring>
 #include <cerrno>
-#include <boost/filesystem.hpp> // for exists
 #include <boost/iostreams/device/mapped_file.hpp> // for mapped_file_source
 
 ///////////////////////////////////////////////////////////////////////////////////////////
@@ -60,15 +59,22 @@ pcl::IFSReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
   //cloud.is_dense = true;
 
   std::uint32_t nr_points = 0;
+
+  if (file_name.empty ())
+  {
+    PCL_ERROR ("[pcl::IFSReader::readHeader] No file name given!\n");
+    return (-1);
+  }
+
   std::ifstream fs;
+  fs.open (file_name.c_str (), std::ios::binary);
 
-  if (file_name.empty() || !boost::filesystem::exists (file_name))
+  if (!fs.good ())
   {
     PCL_ERROR ("[pcl::IFSReader::readHeader] Could not find file '%s'.\n", file_name.c_str ());
     return (-1);
   }
 
-  fs.open (file_name.c_str (), std::ios::binary);
   if (!fs.is_open () || fs.fail ())
   {
     PCL_ERROR ("[pcl::IFSReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror(errno));
index de32f1f20deb69ed8e1ffa6488003ede3708f278..780b9fa525583136087741a6b235f0d8b30ed604 100644 (file)
@@ -35,6 +35,7 @@
  *
  */
 // Looking for PCL_BUILT_WITH_VTK
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/for_each_type.h>
 #include <pcl/io/timestamp.h>
 #include <pcl/io/image_grabber.h>
@@ -42,7 +43,7 @@
 #include <pcl/memory.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
-#include <boost/filesystem.hpp> // for exists, basename, is_directory, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 #ifdef PCL_BUILT_WITH_VTK
@@ -255,7 +256,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::trigger ()
 void
 pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string &dir)
 {
-  if (!boost::filesystem::exists (dir) || !boost::filesystem::is_directory (dir))
+  if (!pcl_fs::exists (dir) || !pcl_fs::is_directory (dir))
   {
     PCL_ERROR ("[pcl::ImageGrabber::loadDepthAndRGBFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which"
                " is not a directory: %s\n", dir.c_str ());
@@ -264,13 +265,13 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
   std::string pathname;
   std::string extension;
   std::string basename;
-  boost::filesystem::directory_iterator end_itr;
-  for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr)
+  pcl_fs::directory_iterator end_itr;
+  for (pcl_fs::directory_iterator itr (dir); itr != end_itr; ++itr)
   {
     extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
     basename = itr->path ().stem ().string ();
-    if (!boost::filesystem::is_directory (itr->status ())
+    if (!pcl_fs::is_directory (itr->status ())
         && isValidExtension (extension))
     {
       if (basename.find ("rgb") < std::string::npos)
@@ -291,13 +292,13 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
 void
 pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string &depth_dir, const std::string &rgb_dir)
 {
-  if (!boost::filesystem::exists (depth_dir) || !boost::filesystem::is_directory (depth_dir))
+  if (!pcl_fs::exists (depth_dir) || !pcl_fs::is_directory (depth_dir))
   {
     PCL_ERROR ("[pcl::ImageGrabber::loadDepthAndRGBFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which"
                " is not a directory: %s\n", depth_dir.c_str ());
     return;
   }
-  if (!boost::filesystem::exists (rgb_dir) || !boost::filesystem::is_directory (rgb_dir))
+  if (!pcl_fs::exists (rgb_dir) || !pcl_fs::is_directory (rgb_dir))
   {
     PCL_ERROR ("[pcl::ImageGrabber::loadDepthAndRGBFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which"
                " is not a directory: %s\n", rgb_dir.c_str ());
@@ -306,14 +307,14 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
   std::string pathname;
   std::string extension;
   std::string basename;
-  boost::filesystem::directory_iterator end_itr;
+  pcl_fs::directory_iterator end_itr;
   // First iterate over depth images
-  for (boost::filesystem::directory_iterator itr (depth_dir); itr != end_itr; ++itr)
+  for (pcl_fs::directory_iterator itr (depth_dir); itr != end_itr; ++itr)
   {
     extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
     basename = itr->path ().stem ().string ();
-    if (!boost::filesystem::is_directory (itr->status ())
+    if (!pcl_fs::is_directory (itr->status ())
         && isValidExtension (extension))
     {
       if (basename.find ("depth") < std::string::npos)
@@ -323,12 +324,12 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
     }
   }
   // Then iterate over RGB images
-  for (boost::filesystem::directory_iterator itr (rgb_dir); itr != end_itr; ++itr)
+  for (pcl_fs::directory_iterator itr (rgb_dir); itr != end_itr; ++itr)
   {
     extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
     basename = itr->path ().stem ().string ();
-    if (!boost::filesystem::is_directory (itr->status ())
+    if (!pcl_fs::is_directory (itr->status ())
         && isValidExtension (extension))
     {
       if (basename.find ("rgb") < std::string::npos)
@@ -354,7 +355,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
 void
 pcl::ImageGrabberBase::ImageGrabberImpl::loadPCLZFFiles (const std::string &dir)
 {
-  if (!boost::filesystem::exists (dir) || !boost::filesystem::is_directory (dir))
+  if (!pcl_fs::exists (dir) || !pcl_fs::is_directory (dir))
   {
     PCL_ERROR ("[pcl::ImageGrabber::loadPCLZFFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which"
                " is not a directory: %s\n", dir.c_str ());
@@ -363,13 +364,13 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadPCLZFFiles (const std::string &dir)
   std::string pathname;
   std::string extension;
   std::string basename;
-  boost::filesystem::directory_iterator end_itr;
-  for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr)
+  pcl_fs::directory_iterator end_itr;
+  for (pcl_fs::directory_iterator itr (dir); itr != end_itr; ++itr)
   {
     extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
     basename = itr->path ().stem ().string ();
-    if (!boost::filesystem::is_directory (itr->status ())
+    if (!pcl_fs::is_directory (itr->status ())
         && isValidExtension (extension))
     {
       if (basename.find ("rgb") < std::string::npos)
@@ -429,7 +430,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getTimestampFromFilepath (
 {
   // For now, we assume the file is of the form frame_[22-char POSIX timestamp]_*
   char timestamp_str[256];
-  int result = std::sscanf (boost::filesystem::path (filepath).stem ().string ().c_str (),
+  int result = std::sscanf (pcl_fs::path (filepath).stem ().string ().c_str (),
                             "frame_%22s_%*s",
                             timestamp_str);
   if (result > 0)
@@ -611,7 +612,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getCloudPCLZF (std::size_t idx,
                                                         double &cx,
                                                         double &cy) const
 {
-  if (idx > depth_pclzf_files_.size ())
+  if (idx >= depth_pclzf_files_.size ())
   {
     return (false);
   }
@@ -971,7 +972,7 @@ pcl::ImageGrabberBase::getCurrentDepthFileName () const
     pathname = impl_->depth_pclzf_files_[impl_->cur_frame_];
   else
     pathname = impl_->depth_image_files_[impl_->cur_frame_];
-  std::string basename = boost::filesystem::path (pathname).stem ().string ();
+  std::string basename = pcl_fs::path (pathname).stem ().string ();
   return (basename);
 }
 //////////////////////////////////////////////////////////////////////////////////////////
@@ -983,7 +984,7 @@ pcl::ImageGrabberBase::getPrevDepthFileName () const
     pathname = impl_->depth_pclzf_files_[impl_->cur_frame_-1];
   else
     pathname = impl_->depth_image_files_[impl_->cur_frame_-1];
-  std::string basename = boost::filesystem::path (pathname).stem ().string ();
+  std::string basename = pcl_fs::path (pathname).stem ().string ();
   return (basename);
 }
 
@@ -996,7 +997,7 @@ pcl::ImageGrabberBase::getDepthFileNameAtIndex (std::size_t idx) const
     pathname = impl_->depth_pclzf_files_[idx];
   else
     pathname = impl_->depth_image_files_[idx];
-  std::string basename = boost::filesystem::path (pathname).stem ().string ();
+  std::string basename = pcl_fs::path (pathname).stem ().string ();
   return (basename);
 }
 
index c666f234cd3d85f3aa61c2e5bac0d50fc4c8ae3a..2d6443f39475b9eaf2010ae66c6183a530efb92a 100644 (file)
@@ -75,7 +75,7 @@ using LZF_STATE = unsigned int[1 << (HLOG)];
 
 // IDX works because it is very similar to a multiplicative hash, e.g.
 // ((h * 57321 >> (3*8 - HLOG)) & ((1 << (HLOG)) - 1))
-#define IDX(h) ((( h >> (3*8 - HLOG)) - h  ) & ((1 << (HLOG)) - 1))
+#define IDX(h) ((( (h) >> (3*8 - HLOG)) - (h)  ) & ((1 << (HLOG)) - 1))
 
 ///////////////////////////////////////////////////////////////////////////////////////////
 //
index ab59a6eeb110cac9f065865f56fb40c7263e4ed5..5c01cfbd8afca75247b092ba6ada3cb25f6d42da 100644 (file)
 #include <pcl/io/low_level_io.h>
 #include <pcl/io/lzf_image_io.h>
 #include <pcl/io/lzf.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <fcntl.h>
 #include <cstring>
-#include <boost/filesystem.hpp>
+
 #include <boost/property_tree/ptree.hpp>
 #include <boost/property_tree/xml_parser.hpp>
 
@@ -357,7 +358,7 @@ pcl::io::LZFImageReader::loadImageBlob (const std::string &filename,
                                         std::vector<char> &data,
                                         std::uint32_t &uncompressed_size)
 {
-  if (filename.empty() || !boost::filesystem::exists (filename))
+  if (filename.empty() || !pcl_fs::exists (filename))
   {
     PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Could not find file '%s'.\n", filename.c_str ());
     return (false);
index 9cc1fdc68f769a85b69479ea4aa66b95d83cf140..095b81e483d9bdd228720611f9f608a6628c1af0 100644 (file)
 #include <pcl/io/obj_io.h>
 #include <fstream>
 #include <pcl/common/io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/time.h>
 #include <pcl/io/split.h>
 
 #include <boost/lexical_cast.hpp> // for lexical_cast
-#include <boost/filesystem.hpp> // for exists
 #include <boost/algorithm/string.hpp> // for trim
 
 pcl::MTLReader::MTLReader ()
@@ -146,21 +146,27 @@ int
 pcl::MTLReader::read (const std::string& obj_file_name,
                       const std::string& mtl_file_name)
 {
-  if (obj_file_name.empty() || !boost::filesystem::exists (obj_file_name))
+  if (obj_file_name.empty ())
+  {
+    PCL_ERROR ("[pcl::MTLReader::read] No OBJ file name given!\n");
+    return (-1);
+  }
+
+  if (!pcl_fs::exists (obj_file_name))
   {
     PCL_ERROR ("[pcl::MTLReader::read] Could not find file '%s'!\n",
                obj_file_name.c_str ());
     return (-1);
   }
 
-  if (mtl_file_name.empty())
+  if (mtl_file_name.empty ())
   {
     PCL_ERROR ("[pcl::MTLReader::read] MTL file name is empty!\n");
     return (-1);
   }
 
-  boost::filesystem::path obj_file_path (obj_file_name.c_str ());
-  boost::filesystem::path mtl_file_path = obj_file_path.parent_path ();
+  pcl_fs::path obj_file_path (obj_file_name.c_str ());
+  pcl_fs::path mtl_file_path = obj_file_path.parent_path ();
   mtl_file_path /=  mtl_file_name;
   return (read (mtl_file_path.string ()));
 }
@@ -168,14 +174,23 @@ pcl::MTLReader::read (const std::string& obj_file_name,
 int
 pcl::MTLReader::read (const std::string& mtl_file_path)
 {
-  if (mtl_file_path.empty() || !boost::filesystem::exists (mtl_file_path))
+  if (mtl_file_path.empty ())
   {
-    PCL_ERROR ("[pcl::MTLReader::read] Could not find file '%s'.\n", mtl_file_path.c_str ());
+    PCL_ERROR ("[pcl::MTLReader::read] No file name given!\n");
     return (-1);
   }
 
+  // Open file in binary mode to avoid problem of
+  // std::getline() corrupting the result of ifstream::tellg()
   std::ifstream mtl_file;
   mtl_file.open (mtl_file_path.c_str (), std::ios::binary);
+
+  if (!mtl_file.good ())
+  {
+    PCL_ERROR ("[pcl::MTLReader::read] Could not find file '%s'.\n", mtl_file_path.c_str ());
+    return (-1);
+  }
+
   if (!mtl_file.is_open () || mtl_file.fail ())
   {
     PCL_ERROR ("[pcl::MTLReader::read] Could not open file '%s'! Error : %s\n",
@@ -186,7 +201,7 @@ pcl::MTLReader::read (const std::string& mtl_file_path)
 
   std::string line;
   std::vector<std::string> st;
-  boost::filesystem::path parent_path = mtl_file_path.c_str ();
+  pcl_fs::path parent_path = mtl_file_path.c_str ();
   parent_path = parent_path.parent_path ();
 
   try
@@ -200,8 +215,8 @@ pcl::MTLReader::read (const std::string& mtl_file_path)
 
       // Tokenize the line
       pcl::split (st, line, "\t\r ");
-      // Ignore comments
-      if (st[0] == "#")
+      // Ignore comments and lines with only whitespace
+      if (st.empty() || st[0] == "#")
         continue;
 
       if (st[0] == "newmtl")
@@ -307,7 +322,7 @@ pcl::MTLReader::read (const std::string& mtl_file_path)
 
       if (st[0] == "map_Kd")
       {
-        boost::filesystem::path full_path = parent_path;
+        pcl_fs::path full_path = parent_path;
         full_path/= st.back ().c_str ();
         materials_.back ().tex_file = full_path.string ();
         continue;
@@ -340,18 +355,25 @@ pcl::OBJReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
   data_type = 0;
   data_idx = offset;
 
-  std::ifstream fs;
   std::string line;
 
-  if (file_name.empty() || !boost::filesystem::exists (file_name))
+  if (file_name.empty ())
   {
-    PCL_ERROR ("[pcl::OBJReader::readHeader] Could not find file '%s'.\n", file_name.c_str ());
+    PCL_ERROR ("[pcl::OBJReader::readHeader] No file name given!\n");
     return (-1);
   }
 
   // Open file in binary mode to avoid problem of
   // std::getline() corrupting the result of ifstream::tellg()
+  std::ifstream fs;
   fs.open (file_name.c_str (), std::ios::binary);
+
+  if (!fs.good ())
+  {
+    PCL_ERROR ("[pcl::OBJReader::readHeader] Could not find file '%s'.\n", file_name.c_str ());
+    return (-1);
+  }
+
   if (!fs.is_open () || fs.fail ())
   {
     PCL_ERROR ("[pcl::OBJReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror(errno));
@@ -524,10 +546,18 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
 
   // Get normal_x and rgba fields indices
   int normal_x_field = -1;
+  std::vector<Eigen::Vector3f> normals;
+
+  //vector[idx of vertex]<accumulated normals{x, y, z}>
+  std::vector<Eigen::Vector3f> normal_mapping;
+  bool normal_mapping_used = false;
+
   // std::size_t rgba_field = 0;
   for (std::size_t i = 0; i < cloud.fields.size (); ++i)
     if (cloud.fields[i].name == "normal_x")
     {
+      normals.reserve(cloud.width);
+      normal_mapping.resize(cloud.width, Eigen::Vector3f::Zero());
       normal_x_field = i;
       break;
     }
@@ -551,8 +581,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
       // Tokenize the line
       pcl::split (st, line, "\t\r ");
 
-      // Ignore comments
-      if (st[0] == "#")
+      // Ignore comments and lines with only whitespace
+      if (st.empty() || st[0] == "#")
         continue;
 
       // Vertex
@@ -580,22 +610,13 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
       // Vertex normal
       if (st[0] == "vn")
       {
-        if (normal_idx >= cloud.width) 
-        {
-          if (normal_idx == cloud.width)
-            PCL_WARN ("[pcl:OBJReader] Too many vertex normals (expected %d), skipping remaining normals.\n", cloud.width, normal_idx + 1);
-          ++normal_idx;
-          continue;
-        }
         try
         {
-          for (int i = 1, f = normal_x_field; i < 4; ++i, ++f)
-          {
-            float value = boost::lexical_cast<float> (st[i]);
-            memcpy (&cloud.data[normal_idx * cloud.point_step + cloud.fields[f].offset],
-                &value,
-                sizeof (float));
-          }
+          normals.emplace_back(
+            boost::lexical_cast<float> (st[1]),
+            boost::lexical_cast<float> (st[2]),
+            boost::lexical_cast<float> (st[3])
+          );
           ++normal_idx;
         }
         catch (const boost::bad_lexical_cast&)
@@ -605,6 +626,48 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
         }
         continue;
       }
+
+      // Face
+      if (st[0] == "f")
+      {
+        std::vector<std::string> f_st;
+        std::string n_st;
+
+        pcl::Vertices face_vertices; face_vertices.vertices.resize(st.size() - 1);
+        for (std::size_t i = 1; i < st.size (); ++i)
+        {
+          if (st[i].find("//") != std::string::npos)
+          {
+            //covers format v//vn
+            pcl::split(f_st, st[i], "//");
+            n_st = f_st[1];
+          }
+          else if (st[i].find('/') != std::string::npos)
+          {
+            //covers format v/vt/vn and v/vt
+            pcl::split(f_st, st[i], "/");
+            if (f_st.size() > 2)
+              n_st = f_st[2];
+          }
+          else
+            f_st = { st[i] };
+
+          int v = std::stoi(f_st[0]);
+          v = (v < 0) ? point_idx + v : v - 1;
+          face_vertices.vertices[i - 1] = v;
+
+          //handle normals
+          if (!n_st.empty())
+          {
+            int n = std::stoi(n_st);
+            n = (n < 0) ? normal_idx + n : n - 1;
+
+            normal_mapping[v] += normals[n];
+            normal_mapping_used = true;
+          }
+        }
+        continue;
+      }
     }
   }
   catch (const char *exception)
@@ -614,6 +677,27 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
     return (-1);
   }
 
+  if (normal_mapping_used && !normal_mapping.empty())
+  {
+    for (uindex_t i = 0, main_offset = 0; i < cloud.width; ++i, main_offset += cloud.point_step)
+    {
+      normal_mapping[i].normalize();
+
+      for (int j = 0, f = normal_x_field; j < 3; ++j, ++f)
+        memcpy(&cloud.data[main_offset + cloud.fields[f].offset], &normal_mapping[i][j], sizeof(float));
+    }
+  }
+  else if (cloud.width == normals.size())
+  {
+    // if obj file contains vertex normals (same number as vertices), but does not define faces,
+    // then associate vertices and vertex normals one-to-one
+    for (uindex_t i = 0, main_offset = 0; i < cloud.width; ++i, main_offset += cloud.point_step)
+    {
+      for (int j = 0, f = normal_x_field; j < 3; ++j, ++f)
+        memcpy(&cloud.data[main_offset + cloud.fields[f].offset], &normals[i][j], sizeof(float));
+    }
+  }
+
   double total_time = tt.toc ();
   PCL_DEBUG ("[pcl::OBJReader::read] Loaded %s as a dense cloud in %g ms with %d points. Available dimensions: %s.\n",
              file_name.c_str (), total_time,
@@ -662,16 +746,24 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
 
   // Get normal_x and rgba fields indices
   int normal_x_field = -1;
+  std::vector<Eigen::Vector3f> normals;
+
+  //vector[idx of vertex]<accumulated normals{x, y, z}>
+  std::vector<Eigen::Vector3f> normal_mapping;
+
   // std::size_t rgba_field = 0;
   for (std::size_t i = 0; i < mesh.cloud.fields.size (); ++i)
     if (mesh.cloud.fields[i].name == "normal_x")
     {
+      normals.reserve(mesh.cloud.width);
+      normal_mapping.resize(mesh.cloud.width, Eigen::Vector3f::Zero());
       normal_x_field = i;
       break;
     }
 
   std::size_t v_idx = 0;
   std::size_t f_idx = 0;
+  std::size_t vt_idx = 0;
   std::string line;
   std::vector<std::string> st;
   std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > coordinates;
@@ -689,8 +781,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
       // Tokenize the line
       pcl::split (st, line, "\t\r ");
 
-      // Ignore comments
-      if (st[0] == "#")
+      // Ignore comments and lines with only whitespace
+      if (st.empty() || st[0] == "#")
         continue;
       // Vertex
       if (st[0] == "v")
@@ -718,13 +810,11 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
       {
         try
         {
-          for (int i = 1, f = normal_x_field; i < 4; ++i, ++f)
-          {
-            float value = boost::lexical_cast<float> (st[i]);
-            memcpy (&mesh.cloud.data[vn_idx * mesh.cloud.point_step + mesh.cloud.fields[f].offset],
-                &value,
-                sizeof (float));
-          }
+          normals.emplace_back(
+            boost::lexical_cast<float> (st[1]),
+            boost::lexical_cast<float> (st[2]),
+            boost::lexical_cast<float> (st[3])
+          );
           ++vn_idx;
         }
         catch (const boost::bad_lexical_cast&)
@@ -746,6 +836,7 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
             coordinates.emplace_back(c[0], c[1]);
           else
             coordinates.emplace_back(c[0]/c[2], c[1]/c[2]);
+          ++vt_idx;
         }
         catch (const boost::bad_lexical_cast&)
         {
@@ -779,23 +870,55 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
       // Face
       if (st[0] == "f")
       {
-        // TODO read in normal indices properly
-        pcl::Vertices face_v; face_v.vertices.resize (st.size () - 1);
+        std::vector<std::string> f_st;
+        std::string n_st;
+        std::string vt_st;
+
+        pcl::Vertices face_vertices; face_vertices.vertices.resize (st.size () - 1);
         pcl::Vertices tex_indices; tex_indices.vertices.reserve (st.size () - 1);
         for (std::size_t i = 1; i < st.size (); ++i)
         {
-          char* str_end;
-          int v = std::strtol(st[i].c_str(), &str_end, 10);
+          if (st[i].find("//") != std::string::npos)
+          {
+            //covers format v//vn
+            pcl::split(f_st, st[i], "//");
+            n_st = f_st[1];
+          }
+          else if (st[i].find('/') != std::string::npos)
+          {
+            //covers format v/vt/vn and v/vt
+            pcl::split(f_st, st[i], "/");
+            if (f_st.size() > 1)
+              vt_st = f_st[1];
+
+            if (f_st.size() > 2)
+              n_st = f_st[2];
+          }
+          else
+            f_st = { st[i] };
+
+          int v = std::stoi(f_st[0]);
           v = (v < 0) ? v_idx + v : v - 1;
-          face_v.vertices[i-1] = v;
-          if (str_end[0] == '/' && str_end[1] != '/' && str_end[1] != '\0')
+          face_vertices.vertices[i - 1] = v;
+
+          //handle normals
+          if (!n_st.empty())
           {
-            // texture coordinate indices are optional
-            int tex_index = std::strtol(str_end+1, &str_end, 10);
-            tex_indices.vertices.push_back (tex_index - 1);
+            int n = std::stoi(n_st);
+            n = (n < 0) ? vn_idx + n : n - 1;
+
+            normal_mapping[v] += normals[n];
+          }
+
+          if (!vt_st.empty())
+          {
+            int vt = std::stoi(vt_st);
+            vt = (vt < 0) ? vt_idx + vt : vt - 1;
+
+            tex_indices.vertices.push_back(vt);
           }
         }
-        mesh.tex_polygons.back ().push_back (face_v);
+        mesh.tex_polygons.back ().push_back (face_vertices);
         mesh.tex_coord_indices.back ().push_back (tex_indices);
         ++f_idx;
         continue;
@@ -809,6 +932,17 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
     return (-1);
   }
 
+  if (!normal_mapping.empty())
+  {
+    for (uindex_t i = 0, main_offset = 0; i < mesh.cloud.width; ++i, main_offset += mesh.cloud.point_step)
+    {
+      normal_mapping[i].normalize();
+
+      for (int j = 0, f = normal_x_field; j < 3; ++j, ++f)
+        memcpy(&mesh.cloud.data[main_offset + mesh.cloud.fields[f].offset], &normal_mapping[i][j], sizeof(float));
+    }
+  }
+
   double total_time = tt.toc ();
   PCL_DEBUG ("[pcl::OBJReader::read] Loaded %s as a TextureMesh in %g ms with %zu points, %zu texture materials, %zu polygons.\n",
              file_name.c_str (), total_time,
@@ -857,10 +991,18 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
 
   // Get normal_x and rgba fields indices
   int normal_x_field = -1;
+  std::vector<Eigen::Vector3f> normals;
+
+  //vector[idx of vertex]<accumulated normals{x, y, z}>
+  std::vector<Eigen::Vector3f> normal_mapping;
+  bool normal_mapping_used = false;
+
   // std::size_t rgba_field = 0;
   for (std::size_t i = 0; i < mesh.cloud.fields.size (); ++i)
     if (mesh.cloud.fields[i].name == "normal_x")
     {
+      normals.reserve(mesh.cloud.width);
+      normal_mapping.resize(mesh.cloud.width, Eigen::Vector3f::Zero());
       normal_x_field = i;
       break;
     }
@@ -882,8 +1024,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
       // Tokenize the line
       pcl::split (st, line, "\t\r ");
 
-      // Ignore comments
-      if (st[0] == "#")
+      // Ignore comments and lines with only whitespace
+      if (st.empty() || st[0] == "#")
         continue;
 
       // Vertex
@@ -913,13 +1055,11 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
       {
         try
         {
-          for (int i = 1, f = normal_x_field; i < 4; ++i, ++f)
-          {
-            float value = boost::lexical_cast<float> (st[i]);
-            memcpy (&mesh.cloud.data[vn_idx * mesh.cloud.point_step + mesh.cloud.fields[f].offset],
-                &value,
-                sizeof (float));
-          }
+          normals.emplace_back(
+            boost::lexical_cast<float> (st[1]),
+            boost::lexical_cast<float> (st[2]),
+            boost::lexical_cast<float> (st[3])
+          );
           ++vn_idx;
         }
         catch (const boost::bad_lexical_cast&)
@@ -933,13 +1073,41 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
       // Face
       if (st[0] == "f")
       {
+        std::vector<std::string> f_st;
+        std::string n_st;
+
         pcl::Vertices face_vertices; face_vertices.vertices.resize (st.size () - 1);
         for (std::size_t i = 1; i < st.size (); ++i)
         {
-          int v;
-          sscanf (st[i].c_str (), "%d", &v);
+          if (st[i].find("//") != std::string::npos)
+          {
+            //covers format v//vn
+            pcl::split(f_st, st[i], "//");
+            n_st = f_st[1];
+          }
+          else if (st[i].find('/') != std::string::npos)
+          {
+            //covers format v/vt/vn and v/vt
+            pcl::split(f_st, st[i], "/");
+            if (f_st.size() > 2)
+              n_st = f_st[2];
+          }
+          else
+            f_st = { st[i] };
+
+          int v = std::stoi(f_st[0]);
           v = (v < 0) ? v_idx + v : v - 1;
           face_vertices.vertices[i - 1] = v;
+
+          //handle normals
+          if (!n_st.empty())
+          {
+            int n = std::stoi(n_st);
+            n = (n < 0) ? vn_idx + n : n - 1;
+              
+            normal_mapping[v] += normals[n];
+            normal_mapping_used = true;
+          }
         }
         mesh.polygons.push_back (face_vertices);
         continue;
@@ -953,6 +1121,27 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
     return (-1);
   }
 
+  if (normal_mapping_used && !normal_mapping.empty())
+  {
+    for (uindex_t i = 0, main_offset = 0; i < mesh.cloud.width; ++i, main_offset += mesh.cloud.point_step)
+    {
+      normal_mapping[i].normalize();
+
+      for (int j = 0, f = normal_x_field; j < 3; ++j, ++f)
+        memcpy(&mesh.cloud.data[main_offset + mesh.cloud.fields[f].offset], &normal_mapping[i][j], sizeof(float));
+    }
+  }
+  else if (mesh.cloud.width == normals.size())
+  {
+    // if obj file contains vertex normals (same number as vertices), but does not define faces,
+    // then associate vertices and vertex normals one-to-one
+    for (uindex_t i = 0, main_offset = 0; i < mesh.cloud.width; ++i, main_offset += mesh.cloud.point_step)
+    {
+      for (int j = 0, f = normal_x_field; j < 3; ++j, ++f)
+        memcpy(&mesh.cloud.data[main_offset + mesh.cloud.fields[f].offset], &normals[i][j], sizeof(float));
+    }
+  }
+
   double total_time = tt.toc ();
   PCL_DEBUG ("[pcl::OBJReader::read] Loaded %s as a PolygonMesh in %g ms with %zu points and %zu polygons.\n",
              file_name.c_str (), total_time,
index 8d460471360ca9b717e60e78f8cf30cc8e0d188c..a029e532aa48b0d084c06d2aed3cb72686acda36 100644 (file)
@@ -56,7 +56,7 @@ pcl::io::openni2::OpenNI2Device::OpenNI2Device (const std::string& device_URI)
 
   openni_device_.reset (new openni::Device);
 
-  if (device_URI.length () > 0)
+  if (!device_URI.empty())
     status = openni_device_->open (device_URI.c_str ());
   else
     status = openni_device_->open (openni::ANY_DEVICE);
@@ -215,8 +215,8 @@ pcl::io::openni2::OpenNI2Device::isIRVideoModeSupported (const OpenNI2VideoMode&
 
   bool supported = false;
 
-  std::vector<OpenNI2VideoMode>::const_iterator it = ir_video_modes_.begin ();
-  std::vector<OpenNI2VideoMode>::const_iterator it_end = ir_video_modes_.end ();
+  auto it = ir_video_modes_.cbegin ();
+  auto it_end = ir_video_modes_.cend ();
 
   while (it != it_end && !supported)
   {
@@ -234,8 +234,8 @@ pcl::io::openni2::OpenNI2Device::isColorVideoModeSupported (const OpenNI2VideoMo
 
   bool supported = false;
 
-  std::vector<OpenNI2VideoMode>::const_iterator it = color_video_modes_.begin ();
-  std::vector<OpenNI2VideoMode>::const_iterator it_end = color_video_modes_.end ();
+  auto it = color_video_modes_.cbegin ();
+  auto it_end = color_video_modes_.cend ();
 
   while (it != it_end && !supported)
   {
@@ -253,8 +253,8 @@ pcl::io::openni2::OpenNI2Device::isDepthVideoModeSupported (const OpenNI2VideoMo
 
   bool supported = false;
 
-  std::vector<OpenNI2VideoMode>::const_iterator it = depth_video_modes_.begin ();
-  std::vector<OpenNI2VideoMode>::const_iterator it_end = depth_video_modes_.end ();
+  auto it = depth_video_modes_.cbegin ();
+  auto it_end = depth_video_modes_.cend ();
 
   while (it != it_end && !supported)
   {
index 932ff0a2a1444d7294b4fd2ea9d651ef283bf642..538c521196f8d788971babd49a60d17d7a677f7e 100644 (file)
@@ -73,8 +73,8 @@ namespace pcl
         {
           double sum = 0;
 
-          std::deque<double>::const_iterator it = buffer_.begin ();
-          std::deque<double>::const_iterator it_end = buffer_.end ();
+          auto it = buffer_.cbegin ();
+          auto it_end = buffer_.cend ();
 
           while (it != it_end)
           {
index 2ce1b6036206bf75fa2a687321a6c4f7b9081e44..0cdaa947ff24c0bc00451d6f673a716e6f86e59b 100644 (file)
 #include <pcl/io/openni2/openni2_device.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/time.h>
 #include <pcl/console/print.h>
 #include <pcl/exceptions.h>
 #include <iostream>
-#include <boost/filesystem.hpp> // for exists
 
 using namespace pcl::io::openni2;
 
@@ -292,7 +292,7 @@ pcl::io::OpenNI2Grabber::setupDevice (const std::string& device_id, const Mode&
 
   try
   {
-    if (boost::filesystem::exists (device_id))
+    if (pcl_fs::exists (device_id))
     {
       device_ = deviceManager->getFileDevice (device_id);      // Treat as file path
     }
index 11e50769a2a9d03ad4e4dbd22f5de1f416a373c8..5b58936b1276f557d211867ec0c4d3edfcea1a49 100644 (file)
@@ -348,7 +348,7 @@ openni_wrapper::OpenNIDriver::getDeviceInfos () noexcept
   {
     libusb_device* device = devices[devIdx];
     std::uint8_t busId = libusb_get_bus_number (device);
-    std::map<unsigned char, std::map<unsigned char, unsigned> >::const_iterator busIt = bus_map_.find (busId);
+    auto busIt = bus_map_.find (busId);
     if (busIt == bus_map_.end ())
       continue;
 
index 04d43c765d583c552970a8b4b629aa679e2eb398..1ff5887aadd31493415547a6327496261b8b6fd8 100644 (file)
 #include <pcl/io/openni_grabber.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/common/time.h>
 #include <pcl/console/print.h>
 #include <pcl/exceptions.h>
 #include <iostream>
 #include <thread>
-#include <boost/filesystem.hpp> // for exists
 
 using namespace std::chrono_literals;
 
@@ -303,7 +303,7 @@ pcl::OpenNIGrabber::setupDevice (const std::string& device_id, const Mode& depth
 
   try
   {
-    if (boost::filesystem::exists (device_id))
+    if (pcl_fs::exists (device_id))
     {
       device_ = driver.createVirtualDevice (device_id, true, true);
     }
index 2a90664c841b3465b99b9195ff7edeb70cee0a7f..b811da80f6bf20b3fd21d42a3655e9b546008358 100644 (file)
@@ -43,6 +43,7 @@
 #include <cstdlib>
 #include <pcl/common/utils.h> // pcl::utils::ignore
 #include <pcl/common/io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/io/low_level_io.h>
 #include <pcl/io/lzf.h>
 #include <pcl/io/pcd_io.h>
@@ -51,7 +52,6 @@
 
 #include <cstring>
 #include <cerrno>
-#include <boost/filesystem.hpp> // for permissions
 
 ///////////////////////////////////////////////////////////////////////////////////////////
 void
@@ -69,10 +69,13 @@ pcl::PCDWriter::setLockingPermissions (const std::string &file_name,
   else
     PCL_DEBUG ("[pcl::PCDWriter::setLockingPermissions] File %s could not be locked!\n", file_name.c_str ());
 
-  namespace fs = boost::filesystem;
   try
   {
-    fs::permissions (fs::path (file_name), fs::add_perms | fs::set_gid_on_exe);
+#ifdef PCL_USING_STD_FILESYSTEM
+    pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::perms::set_gid, pcl_fs::perm_options::add);
+#else
+    pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::add_perms | pcl_fs::set_gid_on_exe);
+#endif
   }
   catch (const std::exception &e)
   {
@@ -90,10 +93,13 @@ pcl::PCDWriter::resetLockingPermissions (const std::string &file_name,
   pcl::utils::ignore(file_name, lock);
 #ifndef _WIN32
 #ifndef NO_MANDATORY_LOCKING
-  namespace fs = boost::filesystem;
   try
   {
-    fs::permissions (fs::path (file_name), fs::remove_perms | fs::set_gid_on_exe);
+#ifdef PCL_USING_STD_FILESYSTEM
+    pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::perms::set_gid, pcl_fs::perm_options::remove);
+#else
+    pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::remove_perms | pcl_fs::set_gid_on_exe);
+#endif
   }
   catch (const std::exception &e)
   {
@@ -319,15 +325,19 @@ pcl::PCDReader::readHeader (std::istream &fs, pcl::PCLPointCloud2 &cloud,
       // Read the header + comments line by line until we get to <DATA>
       if (line_type.substr (0, 4) == "DATA")
       {
-        data_idx = static_cast<int> (fs.tellg ());
         if (st.at (1).substr (0, 17) == "binary_compressed")
-         data_type = 2;
-        else
-          if (st.at (1).substr (0, 6) == "binary")
-            data_type = 1;
-        continue;
+          data_type = 2;
+        else if (st.at (1).substr (0, 6) == "binary")
+          data_type = 1;
+        else if (st.at (1).substr (0, 5) == "ascii")
+          data_type = 0;
+        else {
+          PCL_WARN("[pcl::PCDReader::readHeader] Unknown DATA format: %s\n", line.c_str());
+          continue;
+        }
+        data_idx = static_cast<int> (fs.tellg ());
       }
-      break;
+      break;  // DATA is the last header entry, everything after it will be interpreted as point cloud data
     }
   }
   catch (const char *exception)
@@ -385,9 +395,9 @@ pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
                             Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, 
                             int &pcd_version, int &data_type, unsigned int &data_idx, const int offset)
 {
-  if (file_name.empty() || !boost::filesystem::exists (file_name))
+  if (file_name.empty ())
   {
-    PCL_ERROR ("[pcl::PCDReader::readHeader] Could not find file '%s'.\n", file_name.c_str ());
+    PCL_ERROR ("[pcl::PCDReader::readHeader] No file name given!\n");
     return (-1);
   }
 
@@ -395,6 +405,13 @@ pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
   // std::getline() corrupting the result of ifstream::tellg()
   std::ifstream fs;
   fs.open (file_name.c_str (), std::ios::binary);
+
+  if (!fs.good ())
+  {
+    PCL_ERROR ("[pcl::PCDReader::readHeader] Could not find file '%s'.\n", file_name.c_str ());
+    return (-1);
+  }
+
   if (!fs.is_open () || fs.fail ())
   {
     PCL_ERROR ("[pcl::PCDReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror (errno));
@@ -496,7 +513,7 @@ pcl::PCDReader::readBodyASCII (std::istream &fs, pcl::PCLPointCloud2 &cloud, int
         {
 #define COPY_STRING(CASE_LABEL)                                                        \
   case CASE_LABEL: {                                                                   \
-    copyStringValue<pcl::traits::asType_t<CASE_LABEL>>(                                \
+    copyStringValue<pcl::traits::asType_t<(CASE_LABEL)>>(                              \
         st.at(total + c), cloud, idx, d, c, is);                                       \
     break;                                                                             \
   }
@@ -627,11 +644,11 @@ pcl::PCDReader::readBodyBinary (const unsigned char *map, pcl::PCLPointCloud2 &c
     {
       for (uindex_t c = 0; c < cloud.fields[d].count; ++c)
       {
-#define SET_CLOUD_DENSE(CASE_LABEL)                                                    \
-  case CASE_LABEL: {                                                                   \
-    if (!isValueFinite<pcl::traits::asType_t<CASE_LABEL>>(cloud, i, point_size, d, c)) \
-      cloud.is_dense = false;                                                          \
-    break;                                                                             \
+#define SET_CLOUD_DENSE(CASE_LABEL)                                                      \
+  case CASE_LABEL: {                                                                     \
+    if (!isValueFinite<pcl::traits::asType_t<(CASE_LABEL)>>(cloud, i, point_size, d, c)) \
+      cloud.is_dense = false;                                                            \
+    break;                                                                               \
   }
         switch (cloud.fields[d].datatype)
         {
@@ -664,7 +681,13 @@ pcl::PCDReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
   pcl::console::TicToc tt;
   tt.tic ();
 
-  if (file_name.empty() || !boost::filesystem::exists (file_name))
+  if (file_name.empty ())
+  {
+    PCL_ERROR ("[pcl::PCDReader::read] No file name given!\n");
+    return (-1);
+  }
+
+  if (!pcl_fs::exists (file_name))
   {
     PCL_ERROR ("[pcl::PCDReader::read] Could not find file '%s'.\n", file_name.c_str ());
     return (-1);
@@ -1137,7 +1160,7 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PCLPointClo
       {
 #define COPY_VALUE(CASE_LABEL)                                                         \
   case CASE_LABEL: {                                                                   \
-    copyValueString<pcl::traits::asType_t<CASE_LABEL>>(                                \
+    copyValueString<pcl::traits::asType_t<(CASE_LABEL)>>(                              \
         cloud, i, point_size, d, c, stream);                                           \
     break;                                                                             \
   }
index aaedca8f39d122b061bfeb0b5b3e738172e0cf86..936e836fb0d91e1e9448523e78f3c0298d8a29d5 100644 (file)
@@ -37,6 +37,7 @@
 
 #include <pcl/point_types.h>
 #include <pcl/common/io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/io/ply_io.h>
 
 #include <algorithm>
 #include <string>
 #include <tuple>
 
-// https://www.boost.org/doc/libs/1_70_0/libs/filesystem/doc/index.htm#Coding-guidelines
-#define BOOST_FILESYSTEM_NO_DEPRECATED
-#include <boost/filesystem.hpp>
 #include <boost/algorithm/string.hpp> // for split
 
-namespace fs = boost::filesystem;
-
 std::tuple<std::function<void ()>, std::function<void ()> >
 pcl::PLYReader::elementDefinitionCallback (const std::string& element_name, std::size_t count)
 {
@@ -413,8 +409,16 @@ void
 pcl::PLYReader::vertexIntensityCallback (pcl::io::ply::uint8 intensity)
 {
   pcl::io::ply::float32 intensity_ (intensity);
-  cloud_->at<pcl::io::ply::float32>(vertex_count_, vertex_offset_before_) = intensity_;
-  vertex_offset_before_ += static_cast<int> (sizeof (pcl::io::ply::float32));
+  try
+  {
+    cloud_->at<pcl::io::ply::float32>(vertex_count_, vertex_offset_before_) = intensity_;
+    vertex_offset_before_ += static_cast<int> (sizeof (pcl::io::ply::float32));
+  }
+  catch(const std::out_of_range&)
+  {
+    PCL_WARN ("[pcl::PLYReader::vertexIntensityCallback] Incorrect data index specified (%lu)!\n", vertex_count_ * cloud_->point_step + vertex_offset_before_);
+    assert(false);
+  }
 }
 
 void
@@ -439,7 +443,7 @@ pcl::PLYReader::vertexEndCallback ()
 void
 pcl::PLYReader::rangeGridBeginCallback ()
 {
-  range_grid_->push_back (std::vector <int> ());
+  range_grid_->emplace_back();
 }
 
 void
@@ -463,7 +467,7 @@ pcl::PLYReader::rangeGridEndCallback () {}
 void
 pcl::PLYReader::faceBeginCallback ()
 {
-  polygons_->push_back (pcl::Vertices ());
+  polygons_->emplace_back();
 }
 
 void
@@ -582,7 +586,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
   int data_type;
   unsigned int data_idx;
 
-  if (!fs::exists (file_name))
+  if (!pcl_fs::exists (file_name))
   {
     PCL_ERROR ("[pcl::PLYReader::read] File (%s) not found!\n",file_name.c_str ());
     return (-1);
@@ -682,7 +686,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
   unsigned int data_idx;
   polygons_ = &(mesh.polygons);
 
-  if (!fs::exists (file_name))
+  if (!pcl_fs::exists (file_name))
   {
     PCL_ERROR ("[pcl::PLYReader::read] File (%s) not found!\n",file_name.c_str ());
     return (-1);
@@ -1200,10 +1204,10 @@ pcl::PLYWriter::writeContentWithRangeGridASCII (int nr_points,
 
 ////////////////////////////////////////////////////////////////////////////////////////
 int
-pcl::PLYWriter::writeBinary (const std::string &file_name,
-                             const pcl::PCLPointCloud2 &cloud,
-                             const Eigen::Vector4f &origin,
-                             const Eigen::Quaternionf &orientation,
+pcl::PLYWriter::writeBinary (const std::stringfile_name,
+                             const pcl::PCLPointCloud2cloud,
+                             const Eigen::Vector4forigin,
+                             const Eigen::Quaternionforientation,
                              bool use_camera)
 {
   if (cloud.data.empty ())
@@ -1213,14 +1217,36 @@ pcl::PLYWriter::writeBinary (const std::string &file_name,
   }
 
   std::ofstream fs;
-  fs.open (file_name.c_str ());      // Open file
+  fs.open (file_name.c_str (),
+           std::ios::out | std::ios::binary |
+               std::ios::trunc); // Open file in binary mode and erase current contents
+                                 // if any
   if (!fs)
   {
-    PCL_ERROR ("[pcl::PLYWriter::writeBinary] Error during opening (%s)!\n", file_name.c_str ());
+    PCL_ERROR ("[pcl::PLYWriter::writeBinary] Error during opening (%s)!\n",
+               file_name.c_str ());
     return (-1);
   }
 
-  unsigned int nr_points  = cloud.width * cloud.height;
+  if (!(writeBinary (fs, cloud, origin, orientation, use_camera) == 0))
+  {
+    fs.close();
+    return -1;
+  }
+  fs.close();
+  return 0;
+}
+
+int
+pcl::PLYWriter::writeBinary (std::ostream& os,
+                             const pcl::PCLPointCloud2& cloud,
+                             const Eigen::Vector4f& origin,
+                             const Eigen::Quaternionf& orientation,
+                             bool use_camera)
+{
+  os.imbue(std::locale::classic());
+  
+  unsigned int nr_points = cloud.width * cloud.height;
 
   // Compute the range_grid, if necessary, and then write out the PLY header
   bool doRangeGrid = !use_camera && cloud.height > 1;
@@ -1237,17 +1263,17 @@ pcl::PLYWriter::writeBinary (const std::string &file_name,
     // If no x-coordinate field exists, then assume all points are valid
     if (xfield < 0)
     {
-      for (unsigned int i=0; i < nr_points; ++i)
+      for (unsigned int i = 0; i < nr_points; ++i)
         rangegrid[i] = i;
       valid_points = nr_points;
     }
     // Otherwise, look at their x-coordinates to determine if points are valid
     else
     {
-      for (std::size_t i=0; i < nr_points; ++i)
+      for (std::size_t i = 0; i < nr_points; ++i)
       {
-        const float& value = cloud.at<float>(i, cloud.fields[xfield].offset);
-        if (std::isfinite(value))
+        const float& value = cloud.at<float> (i, cloud.fields[xfield].offset);
+        if (std::isfinite (value))
         {
           rangegrid[i] = valid_points;
           ++valid_points;
@@ -1256,21 +1282,11 @@ pcl::PLYWriter::writeBinary (const std::string &file_name,
           rangegrid[i] = -1;
       }
     }
-    fs << generateHeader (cloud, origin, orientation, true, use_camera, valid_points);
+    os << generateHeader (cloud, origin, orientation, true, use_camera, valid_points);
   }
   else
   {
-    fs << generateHeader (cloud, origin, orientation, true, use_camera, nr_points);
-  }
-
-  // Close the file
-  fs.close ();
-  // Open file in binary appendable
-  std::ofstream fpout (file_name.c_str (), std::ios::app | std::ios::binary);
-  if (!fpout)
-  {
-    PCL_ERROR ("[pcl::PLYWriter::writeBinary] Error during reopening (%s)!\n", file_name.c_str ());
-    return (-1);
+    os << generateHeader (cloud, origin, orientation, true, use_camera, nr_points);
   }
 
   // Iterate through the points
@@ -1285,16 +1301,17 @@ pcl::PLYWriter::writeBinary (const std::string &file_name,
     {
       int count = cloud.fields[d].count;
       if (count == 0)
-        count = 1; //workaround
+        count = 1; // workaround
       if (count > 1)
       {
         static unsigned int ucount (count);
-        fpout.write (reinterpret_cast<const char*> (&ucount), sizeof (unsigned int));
+        os.write (reinterpret_cast<const char*> (&ucount), sizeof (unsigned int));
       }
       // Ignore invalid padded dimensions that are inherited from binary data
       if (cloud.fields[d].name == "_")
       {
-        total += cloud.fields[d].count; // jump over this many elements in the string token
+        total +=
+            cloud.fields[d].count; // jump over this many elements in the string token
         continue;
       }
 
@@ -1302,70 +1319,93 @@ pcl::PLYWriter::writeBinary (const std::string &file_name,
       {
         switch (cloud.fields[d].datatype)
         {
-          case pcl::PCLPointField::INT8:
-          {
-            fpout.write (&cloud.at<char>(i, cloud.fields[d].offset + (total + c) * sizeof (char)), sizeof (char));
-            break;
-          }
-          case pcl::PCLPointField::UINT8:
-          {
-            fpout.write (reinterpret_cast<const char*> (&cloud.at<unsigned char>(i, cloud.fields[d].offset + (total + c) * sizeof (unsigned char))), sizeof (unsigned char));
-            break;
-          }
-          case pcl::PCLPointField::INT16:
-          {
-            fpout.write (reinterpret_cast<const char*> (&cloud.at<short>(i, cloud.fields[d].offset + (total + c) * sizeof (short))), sizeof (short));
-            break;
-          }
-          case pcl::PCLPointField::UINT16:
-          {
-            fpout.write (reinterpret_cast<const char*> (&cloud.at<unsigned short>(i, cloud.fields[d].offset + (total + c) * sizeof (unsigned short))), sizeof (unsigned short));
-            break;
-          }
-          case pcl::PCLPointField::INT32:
+        case pcl::PCLPointField::INT8:
+        {
+          os.write (
+              &cloud.at<char> (i, cloud.fields[d].offset + (total + c) * sizeof (char)),
+              sizeof (char));
+          break;
+        }
+        case pcl::PCLPointField::UINT8:
+        {
+          os.write (
+              reinterpret_cast<const char*> (&cloud.at<unsigned char> (
+                  i, cloud.fields[d].offset + (total + c) * sizeof (unsigned char))),
+              sizeof (unsigned char));
+          break;
+        }
+        case pcl::PCLPointField::INT16:
+        {
+          os.write (reinterpret_cast<const char*> (&cloud.at<short> (
+                        i, cloud.fields[d].offset + (total + c) * sizeof (short))),
+                    sizeof (short));
+          break;
+        }
+        case pcl::PCLPointField::UINT16:
+        {
+          os.write (
+              reinterpret_cast<const char*> (&cloud.at<unsigned short> (
+                  i, cloud.fields[d].offset + (total + c) * sizeof (unsigned short))),
+              sizeof (unsigned short));
+          break;
+        }
+        case pcl::PCLPointField::INT32:
+        {
+          os.write (reinterpret_cast<const char*> (&cloud.at<int> (
+                        i, cloud.fields[d].offset + (total + c) * sizeof (int))),
+                    sizeof (int));
+          break;
+        }
+        case pcl::PCLPointField::UINT32:
+        {
+          if (cloud.fields[d].name.find ("rgba") == std::string::npos)
           {
-            fpout.write (reinterpret_cast<const char*> (&cloud.at<int>(i, cloud.fields[d].offset + (total + c) * sizeof (int))), sizeof (int));
-            break;
+            os.write (
+                reinterpret_cast<const char*> (&cloud.at<unsigned int> (
+                    i, cloud.fields[d].offset + (total + c) * sizeof (unsigned int))),
+                sizeof (unsigned int));
           }
-          case pcl::PCLPointField::UINT32:
+          else
           {
-            if (cloud.fields[d].name.find ("rgba") == std::string::npos)
-            {
-              fpout.write (reinterpret_cast<const char*> (&cloud.at<unsigned int>(i, cloud.fields[d].offset + (total + c) * sizeof (unsigned int))), sizeof (unsigned int));
-            }
-            else
-            {
-              const auto& color = cloud.at<pcl::RGB>(i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB));
-              fpout.write (reinterpret_cast<const char*> (&color.r), sizeof (unsigned char));
-              fpout.write (reinterpret_cast<const char*> (&color.g), sizeof (unsigned char));
-              fpout.write (reinterpret_cast<const char*> (&color.b), sizeof (unsigned char));
-              fpout.write (reinterpret_cast<const char*> (&color.a), sizeof (unsigned char));
-            }
-            break;
+            const auto& color = cloud.at<pcl::RGB> (
+                i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB));
+            os.write (reinterpret_cast<const char*> (&color.r), sizeof (unsigned char));
+            os.write (reinterpret_cast<const char*> (&color.g), sizeof (unsigned char));
+            os.write (reinterpret_cast<const char*> (&color.b), sizeof (unsigned char));
+            os.write (reinterpret_cast<const char*> (&color.a), sizeof (unsigned char));
           }
-          case pcl::PCLPointField::FLOAT32:
+          break;
+        }
+        case pcl::PCLPointField::FLOAT32:
+        {
+          if (cloud.fields[d].name.find ("rgb") == std::string::npos)
           {
-            if (cloud.fields[d].name.find ("rgb") == std::string::npos)
-            {
-              fpout.write (reinterpret_cast<const char*> (&cloud.at<float>(i, cloud.fields[d].offset + (total + c) * sizeof (float))), sizeof (float));
-            }
-            else
-            {
-              const auto& color = cloud.at<pcl::RGB>(i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB));
-              fpout.write (reinterpret_cast<const char*> (&color.r), sizeof (unsigned char));
-              fpout.write (reinterpret_cast<const char*> (&color.g), sizeof (unsigned char));
-              fpout.write (reinterpret_cast<const char*> (&color.b), sizeof (unsigned char));
-            }
-            break;
+            os.write (reinterpret_cast<const char*> (&cloud.at<float> (
+                          i, cloud.fields[d].offset + (total + c) * sizeof (float))),
+                      sizeof (float));
           }
-          case pcl::PCLPointField::FLOAT64:
+          else
           {
-            fpout.write (reinterpret_cast<const char*> (&cloud.at<double>(i, cloud.fields[d].offset + (total + c) * sizeof (double))), sizeof (double));
-            break;
+            const auto& color = cloud.at<pcl::RGB> (
+                i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB));
+            os.write (reinterpret_cast<const char*> (&color.r), sizeof (unsigned char));
+            os.write (reinterpret_cast<const char*> (&color.g), sizeof (unsigned char));
+            os.write (reinterpret_cast<const char*> (&color.b), sizeof (unsigned char));
           }
-          default:
-            PCL_WARN ("[pcl::PLYWriter::writeBinary] Incorrect field data type specified (%d)!\n", cloud.fields[d].datatype);
-            break;
+          break;
+        }
+        case pcl::PCLPointField::FLOAT64:
+        {
+          os.write (reinterpret_cast<const char*> (&cloud.at<double> (
+                        i, cloud.fields[d].offset + (total + c) * sizeof (double))),
+                    sizeof (double));
+          break;
+        }
+        default:
+          PCL_WARN ("[pcl::PLYWriter::writeBinary] Incorrect field data type specified "
+                    "(%d)!\n",
+                    cloud.fields[d].datatype);
+          break;
         }
       }
     }
@@ -1378,17 +1418,17 @@ pcl::PLYWriter::writeBinary (const std::string &file_name,
     for (int i = 0; i < 3; ++i)
     {
       if (origin[3] != 0)
-        t = origin[i]/origin[3];
+        t = origin[i] / origin[3];
       else
         t = origin[i];
-      fpout.write (reinterpret_cast<const char*> (&t), sizeof (float));
+      os.write (reinterpret_cast<const char*> (&t), sizeof (float));
     }
     Eigen::Matrix3f R = orientation.toRotationMatrix ();
     for (int i = 0; i < 3; ++i)
       for (int j = 0; j < 3; ++j)
-    {
-      fpout.write (reinterpret_cast<const char*> (&R (i, j)),sizeof (float));
-    }
+      {
+        os.write (reinterpret_cast<const char*> (&R (i, j)), sizeof (float));
+      }
 
     /////////////////////////////////////////////////////
     // Append those properties directly.               //
@@ -1406,41 +1446,44 @@ pcl::PLYWriter::writeBinary (const std::string &file_name,
 
     const float zerof = 0;
     for (int i = 0; i < 5; ++i)
-      fpout.write (reinterpret_cast<const char*> (&zerof), sizeof (float));
+      os.write (reinterpret_cast<const char*> (&zerof), sizeof (float));
 
     // width and height
     int width = cloud.width;
-    fpout.write (reinterpret_cast<const char*> (&width), sizeof (int));
+    os.write (reinterpret_cast<const char*> (&width), sizeof (int));
 
     int height = cloud.height;
-    fpout.write (reinterpret_cast<const char*> (&height), sizeof (int));
+    os.write (reinterpret_cast<const char*> (&height), sizeof (int));
 
     for (int i = 0; i < 2; ++i)
-      fpout.write (reinterpret_cast<const char*> (&zerof), sizeof (float));
+      os.write (reinterpret_cast<const char*> (&zerof), sizeof (float));
   }
   else if (doRangeGrid)
   {
     // Write out range_grid
-    for (std::size_t i=0; i < nr_points; ++i)
+    for (std::size_t i = 0; i < nr_points; ++i)
     {
       pcl::io::ply::uint8 listlen;
 
       if (rangegrid[i] >= 0)
       {
         listlen = 1;
-        fpout.write (reinterpret_cast<const char*> (&listlen), sizeof (pcl::io::ply::uint8));
-        fpout.write (reinterpret_cast<const char*> (&rangegrid[i]), sizeof (pcl::io::ply::int32));
+        os.write (reinterpret_cast<const char*> (&listlen),
+                  sizeof (pcl::io::ply::uint8));
+        os.write (reinterpret_cast<const char*> (&rangegrid[i]),
+                  sizeof (pcl::io::ply::int32));
       }
       else
       {
         listlen = 0;
-        fpout.write (reinterpret_cast<const char*> (&listlen), sizeof (pcl::io::ply::uint8));
+        os.write (reinterpret_cast<const char*> (&listlen),
+                  sizeof (pcl::io::ply::uint8));
       }
     }
   }
 
   // Close file
-  fpout.close ();
+  
   return (0);
 }
 
index b034501bab4aee12dae951ecdeab660b67421a1d..798b6cd904a24c59e8998ad03ee37e992bc54332 100644 (file)
@@ -86,6 +86,10 @@ namespace pcl
       signal_PointXYZRGBA->num_slots () == 0)
       return;
 
+    // cache stream options
+    const bool color_requested = signal_PointXYZRGB->num_slots () > 0 || signal_PointXYZRGBA->num_slots () > 0;
+    const bool ir_requested = signal_PointXYZI->num_slots () > 0;
+
     running_ = true;
     quit_ = false;
 
@@ -96,30 +100,30 @@ namespace pcl
     {
       cfg.enable_device_from_file ( file_name_or_serial_number_, repeat_playback_ );
     }
+    // capture from camera
     else
     {
+      // find by serial number if provided
       if (!file_name_or_serial_number_.empty ())
         cfg.enable_device ( file_name_or_serial_number_ );
 
-      if (signal_PointXYZRGB->num_slots () > 0 || signal_PointXYZRGBA->num_slots () > 0)
-      {
+      // enable camera streams as requested
+      if (color_requested)
         cfg.enable_stream ( RS2_STREAM_COLOR, device_width_, device_height_, RS2_FORMAT_RGB8, target_fps_ );
-      }
 
       cfg.enable_stream ( RS2_STREAM_DEPTH, device_width_, device_height_, RS2_FORMAT_Z16, target_fps_ );
 
-      if (signal_PointXYZI->num_slots () > 0)
-      {
+      if (ir_requested)
         cfg.enable_stream ( RS2_STREAM_INFRARED, device_width_, device_height_, RS2_FORMAT_Y8, target_fps_ );
-      }
 
     }
 
     rs2::pipeline_profile prof = pipe_.start ( cfg );
 
-    if ( prof.get_stream ( RS2_STREAM_COLOR ).format ( ) != RS2_FORMAT_RGB8 ||
+    // check all requested streams started properly
+    if ( (color_requested && prof.get_stream ( RS2_STREAM_COLOR ).format ( ) != RS2_FORMAT_RGB8) ||
       prof.get_stream ( RS2_STREAM_DEPTH ).format ( ) != RS2_FORMAT_Z16 ||
-      prof.get_stream ( RS2_STREAM_INFRARED ).format ( ) != RS2_FORMAT_Y8 )
+      (ir_requested && prof.get_stream (RS2_STREAM_INFRARED ).format ( ) != RS2_FORMAT_Y8) )
       THROW_IO_EXCEPTION ( "This stream type or format not supported." );
 
     thread_ = std::thread ( &RealSense2Grabber::threadFunction, this );
index 2db6da1790680acd9950f92b7069a5d7d243f908..22574a2bd234510ff6cf4c29d39ab733171063eb 100644 (file)
@@ -269,7 +269,7 @@ void
 pcl::RobotEyeGrabber::socketThreadLoop ()
 {
   asyncSocketReceive();
-  io_service_.reset();
+  io_service_.restart();
   io_service_.run();
 }
 
index a97b9e374da466f97663824bc570c9670c35efa1..953f7bc3e9a95d6b89bf03dfa90320ae8bb27975 100644 (file)
@@ -184,8 +184,8 @@ pcl::TimGrabber::start ()
 
   try {
     boost::asio::ip::tcp::resolver resolver (tim_io_service_);
-    tcp_endpoint_ = *resolver.resolve (tcp_endpoint_);
-    tim_socket_.connect (tcp_endpoint_);
+    boost::asio::ip::tcp::resolver::results_type endpoints = resolver.resolve (tcp_endpoint_);
+    boost::asio::connect(tim_socket_, endpoints);
   }
   catch (std::exception& e)
   {
index b35087b74b95b947d8d4a46a1bfbe00cb0fc3eda..8e95b98189db76b97626b0ce6fd2057b362cef4d 100644 (file)
@@ -92,7 +92,7 @@ pcl::VLPGrabber::loadVLP16Corrections ()
 boost::asio::ip::address
 pcl::VLPGrabber::getDefaultNetworkAddress ()
 {
-  return (boost::asio::ip::address::from_string ("255.255.255.255"));
+  return (boost::asio::ip::make_address ("255.255.255.255"));
 }
 
 /////////////////////////////////////////////////////////////////////////////
index bb5a5cfe0416555f75d40caed9c573e84ad219ed..9c1bc5190fc1acf6778ca72047b69b2ac0f0c148 100644 (file)
@@ -252,7 +252,7 @@ pcl::io::vtk2mesh (const vtkSmartPointer<vtkPolyData>& poly_data, pcl::PolygonMe
 
   if (poly_data->GetPoints () == nullptr)
   {
-    PCL_ERROR ("[pcl::io::vtk2mesh] Given vtkPolyData is misformed (contains nullpointer instead of points).\n");
+    PCL_ERROR ("[pcl::io::vtk2mesh] Given vtkPolyData is malformed (contains nullpointer instead of points).\n");
     return (0);
   }
   vtkSmartPointer<vtkPoints> mesh_points = poly_data->GetPoints ();
@@ -410,7 +410,7 @@ pcl::io::vtk2mesh (const vtkSmartPointer<vtkPolyData>& poly_data, pcl::TextureMe
     {
       float tex[2];
       texture_coords->GetTupleValue (i, tex);
-      mesh.tex_coordinates.front ().push_back (Eigen::Vector2f (tex[0], tex[1]));
+      mesh.tex_coordinates.front ().emplace_back(tex[0], tex[1]);
     }
   }
   else
@@ -531,7 +531,7 @@ pcl::io::saveRangeImagePlanarFilePNG (
     for (int x = 0; x < dims[0]; x++)
       {
       float* pixel = static_cast<float*>(image->GetScalarPointer(x,y,0));
-      pixel[0] = range_image(y,x).range;
+      *pixel = range_image(x,y).range;
       }
     }
 
index d9c94bbe45bcdcd3e1325adf7a71f876f4f0ddda..9487af14e4afd8939477863bc0328816c6d42ed8 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME kdtree)
 set(SUBSYS_DESC "Point cloud kd-tree library")
 set(SUBSYS_DEPS common)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS flann)
 
@@ -28,7 +27,6 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_common FLANN::FLANN)
 set(EXT_DEPS flann)
index fd5e357fb09d9562cb757fff591419f2ecd19cef..5638c76e3e67a34d0348b6f012d8061ffe967b17 100644 (file)
@@ -332,6 +332,15 @@ namespace pcl
         return (min_pts_);
       }
 
+      /** \brief Gets whether the results should be sorted (ascending in the distance) or not
+        * Otherwise the results may be returned in any order.
+        */
+      inline bool
+      getSortedResults () const
+      {
+        return (sorted_);
+      }
+
     protected:
       /** \brief The input point cloud dataset containing the points we need to use. */
       PointCloudConstPtr input_;
index 4396cb8b71757a68f6a5c5bf3a635784bff23229..73a84d4dc3e967bf64b45215e664800f18816420 100644 (file)
@@ -70,7 +70,7 @@ using NotCompatWithFlann = std::enable_if_t<!compat_with_flann<IndexT>::value, b
 } // namespace detail
 
 /**
- * @brief Comaptibility template function to allow use of various types of indices with
+ * @brief Compatibility template function to allow use of various types of indices with
  * FLANN
  * @details Template is used for all params to not constrain any FLANN side capability
  * @param[in,out] index A index searcher, of type ::flann::Index<Dist> or similar, where
@@ -96,7 +96,7 @@ radius_search(const FlannIndex& index,
               const SearchParams& params);
 
 /**
- * @brief Comaptibility template function to allow use of various types of indices with
+ * @brief Compatibility template function to allow use of various types of indices with
  * FLANN
  * @details Template is used for all params to not constrain any FLANN side capability
  * @param[in,out] index A index searcher, of type ::flann::Index<Dist> or similar, where
index 480e022f253b8a7d7fa07ae5af140fbbb20fd8b9..30419d7c6f4715962f6193070ff856d727640181 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME keypoints)
 set(SUBSYS_DESC "Point cloud keypoints library")
 set(SUBSYS_DEPS common search kdtree octree features filters)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
@@ -30,7 +29,6 @@ set(incs
   "include/pcl/${SUBSYS_NAME}/keypoint.h"
   "include/pcl/${SUBSYS_NAME}/narf_keypoint.h"
   "include/pcl/${SUBSYS_NAME}/sift_keypoint.h"
-  "include/pcl/${SUBSYS_NAME}/uniform_sampling.h"
   "include/pcl/${SUBSYS_NAME}/smoothed_surfaces_keypoint.h"
   "include/pcl/${SUBSYS_NAME}/agast_2d.h"
   "include/pcl/${SUBSYS_NAME}/harris_2d.h"
@@ -59,7 +57,6 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_features pcl_filters)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
diff --git a/keypoints/include/pcl/keypoints/uniform_sampling.h b/keypoints/include/pcl/keypoints/uniform_sampling.h
deleted file mode 100644 (file)
index 6659627..0000000
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage, Inc. nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-
-#pragma once
-
-PCL_DEPRECATED_HEADER(1, 15, "UniformSampling is not a Keypoint anymore, use <pcl/filters/uniform_sampling.h> instead.")
-
-#include <pcl/filters/uniform_sampling.h>
index 4b3d52c903176876aafe8fc1c8e0be4c6e58e021..3c58354f6d852dcc1e7f9f41a48f3cf1fdda0448 100644 (file)
@@ -1192,7 +1192,7 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D (
     return (static_cast<float>(coeff6) / 18.0f);
   }
 
-  if (!(H_det > 0 && coeff1 < 0))
+  if (H_det <= 0 || coeff1 >= 0)
   {
     // The maximum must be at the one of the 4 patch corners.
     int tmp_max = coeff3 + coeff4 + coeff5;
index 35d5811d34ae1b350a64894bb011f2f1edc3c857..c8073cf6314e89aca4b46d6a25280dfe19917370 100644 (file)
@@ -555,7 +555,7 @@ NarfKeypoint::calculateSparseInterestImage ()
                                        static_cast<int> (pcl_lrint (std::floor ( (angle+deg2rad (90.0f))/deg2rad (180.0f) * angle_histogram_size))));
       float& histogram_value = angle_histogram[histogram_cell];
       histogram_value = (std::max) (histogram_value, surface_change_score);
-      angle_elements[histogram_cell].push_back (std::make_pair(index2, surface_change_score));
+      angle_elements[histogram_cell].emplace_back(index2, surface_change_score);
     }
     
     // Reset was_touched to false
index 98209bea91e12abd0329ecadcd8aa57c8a3e4838..7c4c112acf1cbb0d4a5cc6b715c823dec7867d49 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME ml)
 set(SUBSYS_DESC "Point cloud machine learning library")
 set(SUBSYS_DEPS common)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
@@ -75,7 +74,6 @@ set(srcs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 SET_TARGET_PROPERTIES("${LIB_NAME}" PROPERTIES LINKER_LANGUAGE CXX)
 target_link_libraries("${LIB_NAME}" pcl_common)
index b125b700798417f8678e84abfa216d4acda1e20d..8190cc221b12dc465f942d7e8d19ff0a9f7d7264 100644 (file)
@@ -47,6 +47,7 @@
 #include <limits> // for numeric_limits
 #include <string> // for string
 #include <vector>
+// NOLINTNEXTLINE(bugprone-macro-parentheses)
 #define Malloc(type, n) static_cast<type*>(malloc((n) * sizeof(type)))
 
 namespace pcl {
index 1a27bf9a99fa14baf457a2a443ad3162475d198f..59e8dfcf450dbf84aa680cff019f6802231511d5 100644 (file)
@@ -104,8 +104,10 @@ powi(double base, int times)
 
 #define INF HUGE_VAL
 #define TAU 1e-12
+// NOLINTBEGIN(bugprone-macro-parentheses)
 #define Malloc(type, n) static_cast<type*>(malloc((n) * sizeof(type)))
 #define Realloc(var, type, n) static_cast<type*>(realloc(var, (n) * sizeof(type)))
+// NOLINTEND(bugprone-macro-parentheses)
 
 static void
 print_string_stdout(const char* s)
index b5c58434fe82361991963d092b3f89333bc52623..43e07b9a53fc17ebc915e3f544af21de9a32f82f 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME octree)
 set(SUBSYS_DESC "Point cloud octree library")
 set(SUBSYS_DEPS common)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
@@ -17,7 +16,6 @@ set(srcs
 )
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
   "include/pcl/${SUBSYS_NAME}/octree_base.h"
   "include/pcl/${SUBSYS_NAME}/octree_container.h"
   "include/pcl/${SUBSYS_NAME}/octree_impl.h"
@@ -51,7 +49,6 @@ set(impl_incs
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_common)
-target_include_directories(${LIB_NAME} PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
 
 # Install include files
diff --git a/octree/include/pcl/octree/boost.h b/octree/include/pcl/octree/boost.h
deleted file mode 100644 (file)
index b3680aa..0000000
+++ /dev/null
@@ -1,48 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- *
- */
-
-#pragma once
-
-#ifdef __GNUC__
-#pragma GCC system_header
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-
-// Marking all Boost headers as system headers to remove warnings
-#include <boost/graph/adjacency_list.hpp>
index b91b03baf01688a3da5903880e51bf3ea1e9ab2a..f56fa2d2826ffa1afa87ad1856a3fabbb2e73bcb 100644 (file)
@@ -279,8 +279,8 @@ Octree2BufBase<LeafContainerT, BranchContainerT>::deserializeTree(
   leaf_count_ = 0;
 
   // iterator for binary tree structure vector
-  std::vector<char>::const_iterator binary_tree_in_it = binary_tree_in_arg.begin();
-  std::vector<char>::const_iterator binary_tree_in_it_end = binary_tree_in_arg.end();
+  auto binary_tree_in_it = binary_tree_in_arg.cbegin();
+  auto binary_tree_in_it_end = binary_tree_in_arg.cend();
 
   deserializeTreeRecursive(root_node_,
                            depth_mask_,
@@ -307,19 +307,17 @@ Octree2BufBase<LeafContainerT, BranchContainerT>::deserializeTree(
   OctreeKey new_key;
 
   // set data iterator to first element
-  typename std::vector<LeafContainerT*>::const_iterator leaf_container_vector_it =
-      leaf_container_vector_arg.begin();
+  auto leaf_container_vector_it = leaf_container_vector_arg.cbegin();
 
   // set data iterator to last element
-  typename std::vector<LeafContainerT*>::const_iterator leaf_container_vector_it_end =
-      leaf_container_vector_arg.end();
+  auto leaf_container_vector_it_end = leaf_container_vector_arg.cend();
 
   // we will rebuild an octree -> reset leafCount
   leaf_count_ = 0;
 
   // iterator for binary tree structure vector
-  std::vector<char>::const_iterator binary_tree_in_it = binary_tree_in_arg.begin();
-  std::vector<char>::const_iterator binary_tree_in_it_end = binary_tree_in_arg.end();
+  auto binary_tree_in_it = binary_tree_in_arg.cbegin();
+  auto binary_tree_in_it_end = binary_tree_in_arg.cend();
 
   deserializeTreeRecursive(root_node_,
                            depth_mask_,
index 92b0489ef1e64cc9230afc7943baa1a23af99181..ab440f67359c9633b7c7c95311d096866d8b0e1b 100644 (file)
@@ -244,8 +244,8 @@ OctreeBase<LeafContainerT, BranchContainerT>::deserializeTree(
   deleteTree();
 
   // iterator for binary tree structure vector
-  std::vector<char>::const_iterator binary_tree_out_it = binary_tree_out_arg.begin();
-  std::vector<char>::const_iterator binary_tree_out_it_end = binary_tree_out_arg.end();
+  auto binary_tree_out_it = binary_tree_out_arg.cbegin();
+  auto binary_tree_out_it_end = binary_tree_out_arg.cend();
 
   deserializeTreeRecursive(root_node_,
                            depth_mask_,
@@ -266,19 +266,17 @@ OctreeBase<LeafContainerT, BranchContainerT>::deserializeTree(
   OctreeKey new_key;
 
   // set data iterator to first element
-  typename std::vector<LeafContainerT*>::const_iterator leaf_vector_it =
-      leaf_container_vector_arg.begin();
+  auto leaf_vector_it = leaf_container_vector_arg.cbegin();
 
   // set data iterator to last element
-  typename std::vector<LeafContainerT*>::const_iterator leaf_vector_it_end =
-      leaf_container_vector_arg.end();
+  auto leaf_vector_it_end = leaf_container_vector_arg.cend();
 
   // free existing tree before tree rebuild
   deleteTree();
 
   // iterator for binary tree structure vector
-  std::vector<char>::const_iterator binary_tree_input_it = binary_tree_in_arg.begin();
-  std::vector<char>::const_iterator binary_tree_input_it_end = binary_tree_in_arg.end();
+  auto binary_tree_input_it = binary_tree_in_arg.cbegin();
+  auto binary_tree_input_it_end = binary_tree_in_arg.cend();
 
   deserializeTreeRecursive(root_node_,
                            depth_mask_,
index ae37008105929462f5f51a1f31be9786842da7ed..fcabeca1f0f9067cf39b4133ac2050dcb1a7a83b 100644 (file)
@@ -886,12 +886,9 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
   min_pt(2) = static_cast<float>(static_cast<double>(key_arg.z) * voxel_side_len +
                                  this->min_z_);
 
-  max_pt(0) = static_cast<float>(static_cast<double>(key_arg.x + 1) * voxel_side_len +
-                                 this->min_x_);
-  max_pt(1) = static_cast<float>(static_cast<double>(key_arg.y + 1) * voxel_side_len +
-                                 this->min_y_);
-  max_pt(2) = static_cast<float>(static_cast<double>(key_arg.z + 1) * voxel_side_len +
-                                 this->min_z_);
+  max_pt(0) = min_pt(0) + voxel_side_len;
+  max_pt(1) = min_pt(1) + voxel_side_len;
+  max_pt(2) = min_pt(2) + voxel_side_len;
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
index b0b5b54baa36015196a55ceb67e252e5b00090df..31a846568f5ab00b3f802f3b3ff12ed87c049b48 100644 (file)
@@ -97,6 +97,7 @@ OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT>::nearestKSearch
 
   prioPointQueueEntry point_entry;
   std::vector<prioPointQueueEntry> point_candidates;
+  point_candidates.reserve(k);
 
   OctreeKey key;
   key.x = key.y = key.z = 0;
@@ -305,21 +306,26 @@ OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT>::
         // calculate point distance to search point
         float squared_dist = pointSquaredDist(candidate_point, point);
 
-        // check if a closer match is found
-        if (squared_dist < smallest_squared_dist) {
-          prioPointQueueEntry point_entry;
-
-          point_entry.point_distance_ = squared_dist;
-          point_entry.point_idx_ = point_index;
-          point_candidates.push_back(point_entry);
+        const auto insert_into_queue = [&] {
+          point_candidates.emplace(
+              std::upper_bound(point_candidates.begin(),
+                               point_candidates.end(),
+                               squared_dist,
+                               [](float dist, const prioPointQueueEntry& ent) {
+                                 return dist < ent.point_distance_;
+                               }),
+              point_index,
+              squared_dist);
+        };
+        if (point_candidates.size() < K) {
+          insert_into_queue();
+        }
+        else if (point_candidates.back().point_distance_ > squared_dist) {
+          point_candidates.pop_back();
+          insert_into_queue();
         }
       }
 
-      std::sort(point_candidates.begin(), point_candidates.end());
-
-      if (point_candidates.size() > K)
-        point_candidates.resize(K);
-
       if (point_candidates.size() == K)
         smallest_squared_dist = point_candidates.back().point_distance_;
     }
@@ -342,9 +348,6 @@ OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT>::
                                       std::vector<float>& k_sqr_distances,
                                       uindex_t max_nn) const
 {
-  // get spatial voxel information
-  double voxel_squared_diameter = this->getVoxelSquaredDiameter(tree_depth);
-
   // iterate over all children
   for (unsigned char child_idx = 0; child_idx < 8; child_idx++) {
     if (!this->branchHasChild(*node, child_idx))
@@ -354,7 +357,6 @@ OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT>::
     child_node = this->getBranchChildPtr(*node, child_idx);
 
     OctreeKey new_key;
-    PointT voxel_center;
     float squared_dist;
 
     // generate new key for current branch voxel
@@ -362,17 +364,24 @@ OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT>::
     new_key.y = (key.y << 1) + (!!(child_idx & (1 << 1)));
     new_key.z = (key.z << 1) + (!!(child_idx & (1 << 0)));
 
-    // generate voxel center point for voxel at key
-    this->genVoxelCenterFromOctreeKey(new_key, tree_depth, voxel_center);
-
-    // calculate distance to search point
-    squared_dist = pointSquaredDist(static_cast<const PointT&>(voxel_center), point);
-
-    // if distance is smaller than search radius
-    if (squared_dist + this->epsilon_ <=
-        voxel_squared_diameter / 4.0 + radiusSquared +
-            sqrt(voxel_squared_diameter * radiusSquared)) {
-
+    // compute min distance between query point and any point in this child node, to
+    // decide whether we can skip it
+    Eigen::Vector3f min_pt, max_pt;
+    this->genVoxelBoundsFromOctreeKey(new_key, tree_depth, min_pt, max_pt);
+    squared_dist = 0.0f;
+    if (point.x < min_pt.x())
+      squared_dist += std::pow(point.x - min_pt.x(), 2);
+    else if (point.x > max_pt.x())
+      squared_dist += std::pow(point.x - max_pt.x(), 2);
+    if (point.y < min_pt.y())
+      squared_dist += std::pow(point.y - min_pt.y(), 2);
+    else if (point.y > max_pt.y())
+      squared_dist += std::pow(point.y - max_pt.y(), 2);
+    if (point.z < min_pt.z())
+      squared_dist += std::pow(point.z - min_pt.z(), 2);
+    else if (point.z > max_pt.z())
+      squared_dist += std::pow(point.z - max_pt.z(), 2);
+    if (squared_dist < (radiusSquared + this->epsilon_)) {
       if (child_node->getNodeType() == BRANCH_NODE) {
         // we have not reached maximum tree depth
         getNeighborsWithinRadiusRecursive(point,
@@ -548,9 +557,9 @@ OctreePointCloudSearch<PointT, LeafContainerT, BranchContainerT>::boxSearchRecur
 
     // test if search region overlap with voxel space
 
-    if (!((lower_voxel_corner(0) > max_pt(0)) || (min_pt(0) > upper_voxel_corner(0)) ||
-          (lower_voxel_corner(1) > max_pt(1)) || (min_pt(1) > upper_voxel_corner(1)) ||
-          (lower_voxel_corner(2) > max_pt(2)) || (min_pt(2) > upper_voxel_corner(2)))) {
+    if ((lower_voxel_corner(0) <= max_pt(0)) && (min_pt(0) <= upper_voxel_corner(0)) &&
+        (lower_voxel_corner(1) <= max_pt(1)) && (min_pt(1) <= upper_voxel_corner(1)) &&
+        (lower_voxel_corner(2) <= max_pt(2)) && (min_pt(2) <= upper_voxel_corner(2))) {
 
       if (child_node->getNodeType() == BRANCH_NODE) {
         // we have not reached maximum tree depth
index c22fa85473e9ff374faa687ad35b26d2556c7836..da69f80c6ba3e0a866e06003fe38bd590636e1c2 100644 (file)
@@ -159,7 +159,6 @@ public:
    * \param[in] query_index the index in \a cloud representing the query point
    * \param[out] result_index the resultant index of the neighbor point
    * \param[out] sqr_distance the resultant squared distance to the neighboring point
-   * \return number of neighbors found
    */
   inline void
   approxNearestSearch(const PointCloud& cloud,
@@ -184,7 +183,6 @@ public:
    * position in the indices vector.
    * \param[out] result_index the resultant index of the neighbor point
    * \param[out] sqr_distance the resultant squared distance to the neighboring point
-   * \return number of neighbors found
    */
   void
   approxNearestSearch(uindex_t query_index, index_t& result_index, float& sqr_distance);
index a68de5461c70444860fb6c3955343de861bd211b..9083ed4319ab8be1cdafb4d725f4e3884a21208a 100644 (file)
@@ -14,7 +14,7 @@ The <b>pcl_octree</b> implementation provides efficient nearest neighbor search
 such as "Neighbors within Voxel Search”, “K Nearest Neighbor Search” and 
 “Neighbors within Radius Search”. It automatically adjusts its dimension to the point 
 data set. A set of leaf node classes provide additional functionality, such as 
-spacial "occupancy" and "point density per voxel" checks. Functions for serialization 
+spatial "occupancy" and "point density per voxel" checks. Functions for serialization 
 and deserialization enable to efficiently encode the octree structure into a binary format.
 Furthermore, a memory pool implementation reduces expensive memory allocation and 
 deallocation operations in scenarios where octrees needs to be created at high rate. 
index fbc515d0da8bdaf6538bc6f705728993f68205d8..416669b8d98da5ff89f22da93dc1030e67ad7881 100644 (file)
@@ -2,8 +2,14 @@ set(SUBSYS_NAME outofcore)
 set(SUBSYS_DESC "Point cloud outofcore library")
 set(SUBSYS_DEPS common io filters octree visualization)
 
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
+if(NOT TARGET Boost::filesystem)
+  set(DEFAULT FALSE)
+  set(REASON "Boost filesystem is not available.")
+else()
+  set(DEFAULT TRUE)
+endif()
+
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
@@ -13,7 +19,6 @@ if(NOT build)
 endif()
 
 set(srcs
-  src/cJSON.cpp
   src/outofcore_node_data.cpp
   src/outofcore_base_data.cpp
 )
@@ -26,7 +31,6 @@ set(incs
   "include/pcl/${SUBSYS_NAME}/outofcore_breadth_first_iterator.h"
   "include/pcl/${SUBSYS_NAME}/outofcore_depth_first_iterator.h"
   "include/pcl/${SUBSYS_NAME}/boost.h"
-  "include/pcl/${SUBSYS_NAME}/cJSON.h"
   "include/pcl/${SUBSYS_NAME}/octree_base.h"
   "include/pcl/${SUBSYS_NAME}/octree_base_node.h"
   "include/pcl/${SUBSYS_NAME}/octree_abstract_node_container.h"
@@ -59,12 +63,19 @@ set(visualization_incs
   "include/pcl/${SUBSYS_NAME}/visualization/viewport.h"
 )
 
+if(NOT HAVE_CJSON)
+  list(APPEND srcs  src/cJSON.cpp)
+  list(APPEND incs "include/pcl/${SUBSYS_NAME}/cJSON.h")
+endif()
+
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
 
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${visualization_incs})
 #PCL_ADD_SSE_FLAGS("${LIB_NAME}")
 target_link_libraries("${LIB_NAME}" pcl_common pcl_visualization ${Boost_SYSTEM_LIBRARY})
+if(HAVE_CJSON)
+  target_link_libraries("${LIB_NAME}" ${CJSON_LIBRARIES})
+endif()
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
 
 # Install include files
diff --git a/outofcore/include/pcl/outofcore/cJSON.h b/outofcore/include/pcl/outofcore/cJSON.h
deleted file mode 100644 (file)
index ba75a01..0000000
+++ /dev/null
@@ -1,133 +0,0 @@
-/*
-  Copyright (c) 2009 Dave Gamble
-  Permission is hereby granted, free of charge, to any person obtaining a copy
-  of this software and associated documentation files (the "Software"), to deal
-  in the Software without restriction, including without limitation the rights
-  to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-  copies of the Software, and to permit persons to whom the Software is
-  furnished to do so, subject to the following conditions:
-  The above copyright notice and this permission notice shall be included in
-  all copies or substantial portions of the Software.
-  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-  IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-  FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-  AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-  LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-  OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
-  THE SOFTWARE.
-*/
-
-#pragma once
-
-#include <pcl/pcl_macros.h>
-
-//make interop with c++ string easier
-#include <string>
-
-#ifdef __cplusplus
-extern "C"
-{
-#endif
-
-/* cJSON Types: */
-#define cJSON_False 0
-#define cJSON_True 1
-#define cJSON_NULL 2
-#define cJSON_Number 3
-#define cJSON_String 4
-#define cJSON_Array 5
-#define cJSON_Object 6
-       
-#define cJSON_IsReference 256
-
-/* The cJSON structure: */
-typedef struct cJSON { // NOLINT
-       struct cJSON *next,*prev;       /* next/prev allow you to walk array/object chains. Alternatively, use GetArraySize/GetArrayItem/GetObjectItem */
-       struct cJSON *child;            /* An array or object item will have a child pointer pointing to a chain of the items in the array/object. */
-
-       int type;                                       /* The type of the item, as above. */
-
-       char *valuestring;                      /* The item's string, if type==cJSON_String */
-       int valueint;                           /* The item's number, if type==cJSON_Number */
-       double valuedouble;                     /* The item's number, if type==cJSON_Number */
-
-       char *string;                           /* The item's name string, if this item is the child of, or is in the list of subitems of an object. */
-} cJSON;
-
-typedef struct cJSON_Hooks {   // NOLINT
-      void *(*malloc_fn)(std::size_t sz);
-      void (*free_fn)(void *ptr);
-} cJSON_Hooks;
-
-/* Supply malloc, realloc and free functions to cJSON */
-PCLAPI(void) cJSON_InitHooks(cJSON_Hooks* hooks);
-
-
-/* Supply a block of JSON, and this returns a cJSON object you can interrogate. Call cJSON_Delete when finished. */
-PCLAPI(cJSON *) cJSON_Parse(const char *value);
-/* Render a cJSON entity to text for transfer/storage. Free the char* when finished. */
-PCLAPI(char  *) cJSON_Print(cJSON *item);
-/* Render a cJSON entity to text for transfer/storage without any formatting. Free the char* when finished. */
-PCLAPI(char  *) cJSON_PrintUnformatted(cJSON *item);
-/* Delete a cJSON entity and all subentities. */
-PCLAPI(void)   cJSON_Delete(cJSON *c);
-/* Render a cJSON entity to text for transfer/storage. */
-PCLAPI(void) cJSON_PrintStr(cJSON *item, std::string& s);
-/* Render a cJSON entity to text for transfer/storage without any formatting. */
-PCLAPI(void) cJSON_PrintUnformattedStr(cJSON *item, std::string& s);
-
-/* Returns the number of items in an array (or object). */
-PCLAPI(int)      cJSON_GetArraySize(cJSON *array);
-/* Retrieve item number "item" from array "array". Returns NULL if unsuccessful. */
-PCLAPI(cJSON *) cJSON_GetArrayItem(cJSON *array,int item);
-/* Get item "string" from object. Case insensitive. */
-PCLAPI(cJSON *) cJSON_GetObjectItem(cJSON *object,const char *string);
-
-/* For analysing failed parses. This returns a pointer to the parse error. You'll probably need to look a few chars back to make sense of it. Defined when cJSON_Parse() returns 0. 0 when cJSON_Parse() succeeds. */
-PCLAPI(const char *) cJSON_GetErrorPtr();
-       
-/* These calls create a cJSON item of the appropriate type. */
-PCLAPI(cJSON *) cJSON_CreateNull();
-PCLAPI(cJSON *) cJSON_CreateTrue();
-PCLAPI(cJSON *) cJSON_CreateFalse();
-PCLAPI(cJSON *) cJSON_CreateBool(int b);
-PCLAPI(cJSON *) cJSON_CreateNumber(double num);
-PCLAPI(cJSON *) cJSON_CreateString(const char *string);
-PCLAPI(cJSON *) cJSON_CreateArray();
-PCLAPI(cJSON *) cJSON_CreateObject();
-
-/* These utilities create an Array of count items. */
-PCLAPI(cJSON *) cJSON_CreateIntArray(int *numbers,int count);
-PCLAPI(cJSON *) cJSON_CreateFloatArray(float *numbers,int count);
-PCLAPI(cJSON *) cJSON_CreateDoubleArray(double *numbers,int count);
-PCLAPI(cJSON *) cJSON_CreateStringArray(const char **strings,int count);
-
-/* Append item to the specified array/object. */
-PCLAPI(void) cJSON_AddItemToArray(cJSON *array, cJSON *item);
-PCLAPI(void) cJSON_AddItemToObject(cJSON *object,const char *string,cJSON *item);
-/* Append reference to item to the specified array/object. Use this when you want to add an existing cJSON to a new cJSON, but don't want to corrupt your existing cJSON. */
-PCLAPI(void) cJSON_AddItemReferenceToArray(cJSON *array, cJSON *item);
-PCLAPI(void) cJSON_AddItemReferenceToObject(cJSON *object,const char *string,cJSON *item);
-
-/* Remove/Detach items from Arrays/Objects. */
-PCLAPI(cJSON *) cJSON_DetachItemFromArray(cJSON *array,int which);
-PCLAPI(void)    cJSON_DeleteItemFromArray(cJSON *array,int which);
-PCLAPI(cJSON *) cJSON_DetachItemFromObject(cJSON *object,const char *string);
-PCLAPI(void)    cJSON_DeleteItemFromObject(cJSON *object,const char *string);
-       
-/* Update array items. */
-PCLAPI(void) cJSON_ReplaceItemInArray(cJSON *array,int which,cJSON *newitem);
-PCLAPI(void) cJSON_ReplaceItemInObject(cJSON *object,const char *string,cJSON *newitem);
-
-#define cJSON_AddNullToObject(object,name)     cJSON_AddItemToObject(object, name, cJSON_CreateNull())
-#define cJSON_AddTrueToObject(object,name)     cJSON_AddItemToObject(object, name, cJSON_CreateTrue())
-#define cJSON_AddFalseToObject(object,name)            cJSON_AddItemToObject(object, name, cJSON_CreateFalse())
-#define cJSON_AddNumberToObject(object,name,n) cJSON_AddItemToObject(object, name, cJSON_CreateNumber(n))
-#define cJSON_AddStringToObject(object,name,s) cJSON_AddItemToObject(object, name, cJSON_CreateString(s))
-
-#ifdef __cplusplus
-}
-#endif
index f3a8e6f3f0b197ac6338e3773e1efd0079fec36e..6ae31492bdc4908417f388cf25c335efcd0fe6f0 100644 (file)
 #include <pcl/outofcore/octree_base.h>
 
 // JSON
+#include <pcl/pcl_config.h> // for HAVE_CJSON
+#if defined(HAVE_CJSON)
+#include <cjson/cJSON.h>
+#else
 #include <pcl/outofcore/cJSON.h>
+#endif
 
 #include <pcl/filters/random_sample.h>
 #include <pcl/filters/extract_indices.h>
index 53778768ac8b8fefcb8e574102565cb6b376508e..b86c7d79a021502884ad92741b36058293956240 100644 (file)
 #include <pcl/filters/extract_indices.h>
 
 // JSON
+#include <pcl/pcl_config.h> // for HAVE_CJSON
+#if defined(HAVE_CJSON)
+#include <cjson/cJSON.h>
+#else
 #include <pcl/outofcore/cJSON.h>
+#endif
 
 namespace pcl
 {
index 28b25de7f51bc2379ba0c8142b111fb2039057fa..642aced2853e2d23151caf56f0325b59e70dddb0 100644 (file)
@@ -48,6 +48,7 @@
 // Boost
 #include <boost/random/bernoulli_distribution.hpp>
 #include <boost/random/uniform_int.hpp>
+#include <boost/random/variate_generator.hpp> // for boost::variate_generator
 #include <boost/uuid/uuid_io.hpp>
 
 // PCL
index a7d15386619fcb0b07124f5249c1f17f5f0c054a..b5744d525038114ea95119c4f3802efbcd947b5d 100644 (file)
@@ -107,10 +107,10 @@ namespace pcl
           if (!stack_.empty ())
           {
             std::pair<OutofcoreOctreeBaseNode<ContainerT, PointT>*, unsigned char>& stackEntry = stack_.back ();
-            stack_.pop_back ();
               
             this->currentNode_ = stackEntry.first;
             currentChildIdx_ = stackEntry.second;
+            stack_.pop_back (); // stackEntry is a reference, so pop_back after accessing it!
               
             //don't do anything with the keys here...
             this->currentOctreeDepth_--;
index e3c5368068ff888a64125b33588dcb263be5fd62..1a7c8778c1046921af3ae6d5ef8bb5e45e9feb1a 100644 (file)
@@ -63,6 +63,7 @@
 #include <pcl/PCLPointCloud2.h>
 
 #include <shared_mutex>
+#include <list>
 
 namespace pcl
 {
@@ -93,7 +94,7 @@ namespace pcl
      *  recursively in this state. This class provides an the interface
      *  for: 
      *               -# Point/Region insertion methods 
-     *               -# Frustrum/box/region queries
+     *               -# Frustum/box/region queries
      *               -# Parameterization of resolution, container type, etc...
      *
      *  For lower-level node access, there is a Depth-First iterator
@@ -294,7 +295,7 @@ namespace pcl
         std::uint64_t
         addDataToLeaf_and_genLOD (AlignedPointTVector &p);
 
-        // Frustrum/Box/Region REQUESTS/QUERIES: DB Accessors
+        // Frustum/Box/Region REQUESTS/QUERIES: DB Accessors
         // -----------------------------------------------------------------------
         void
         queryFrustum (const double *planes, std::list<std::string>& file_names) const;
@@ -347,7 +348,7 @@ namespace pcl
         
         /** \brief Returns a random subsample of points within the given bounding box at \c query_depth.
          *
-         * \param[in] min The minimum corner of the boudning box to query.
+         * \param[in] min The minimum corner of the bounding box to query.
          * \param[out] max The maximum corner of the bounding box to query.
          * \param[in] query_depth The depth in the tree at which to look for the points. Only returns points within the given bounding box at the specified \c query_depth.
          * \param percent
index 7085d530227da76bb441a73ee13508bf60c2d720..dba76d4f04ff2b7536525ae56d2699f479cf8d6f 100644 (file)
@@ -42,6 +42,7 @@
 #include <memory>
 #include <mutex>
 #include <random>
+#include <list>
 
 #include <pcl/common/io.h>
 #include <pcl/PCLPointCloud2.h>
index 0f9c0acf31004e646aef9bb72fb8768abe0d7469..9ca3d5d99e0d8f853004549069a172833defdf60 100644 (file)
@@ -44,6 +44,7 @@
 #include <string>
 
 // Boost
+#include <boost/random/mersenne_twister.hpp> // for boost::mt19937
 #include <boost/uuid/random_generator.hpp>
 
 #include <pcl/common/utils.h> // pcl::utils::ignore
index 67f41e43134241f8d2cabe125cdf7d3fe5e6694e..16ef0a84ba483f3810bd64433296a906e9d6109b 100644 (file)
 
 #include <pcl/memory.h>
 #include <pcl/pcl_macros.h>
+#include <pcl/pcl_config.h> // for HAVE_CJSON
+#if defined(HAVE_CJSON)
+#include <cjson/cJSON.h>
+#else
 #include <pcl/outofcore/cJSON.h>
+#endif
 
 #include <pcl/outofcore/metadata.h>
 
index 09a85876e83c06f475b07d21540eb30eb810d15b..26997a96ec1dfd0c92710a6350c30aceb4a3a5cb 100644 (file)
 
 #include <pcl/memory.h>
 #include <pcl/pcl_macros.h>
+#include <pcl/pcl_config.h> // for HAVE_CJSON
+#if defined(HAVE_CJSON)
+#include <cjson/cJSON.h>
+#else
 #include <pcl/outofcore/cJSON.h>
+#endif
 
 #include <pcl/common/eigen.h>
 
diff --git a/outofcore/src/cJSON.cpp b/outofcore/src/cJSON.cpp
deleted file mode 100644 (file)
index f60e870..0000000
+++ /dev/null
@@ -1,556 +0,0 @@
-/*
-  Copyright (c) 2009 Dave Gamble
-
-  Permission is hereby granted, free of charge, to any person obtaining a copy
-  of this software and associated documentation files (the "Software"), to deal
-  in the Software without restriction, including without limitation the rights
-  to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-  copies of the Software, and to permit persons to whom the Software is
-  furnished to do so, subject to the following conditions:
-
-  The above copyright notice and this permission notice shall be included in
-  all copies or substantial portions of the Software.
-
-  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-  IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-  FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-  AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-  LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-  OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
-  THE SOFTWARE.
-*/
-
-/* cJSON */
-/* JSON parser in C. */
-
-#include <pcl/outofcore/cJSON.h>
-#include <pcl/pcl_macros.h>
-
-#include <algorithm>
-#include <cstdio>
-#include <cmath>
-#include <cstdlib>
-#include <cstring>
-#include <cctype>
-#include <limits>
-
-static const char *ep;
-
-const char *cJSON_GetErrorPtr() {return ep;}
-
-static int cJSON_strcasecmp(const char *s1,const char *s2)
-{
-       if (!s1) return (s1==s2)?0:1;
-       if (!s2) return 1;
-       for(; tolower(*s1) == tolower(*s2); ++s1, ++s2) if(*s1 == 0)    return 0;
-       return tolower(* reinterpret_cast<const unsigned char *> (s1) ) - tolower(* reinterpret_cast<const unsigned char *> (s2) );
-}
-
-static void *(*cJSON_malloc)(std::size_t sz) = malloc;
-static void (*cJSON_free)(void *ptr) = free;
-
-static char* cJSON_strdup(const char* str)
-{
-      std::size_t len;
-      char* copy;
-
-      len = strlen(str) + 1;
-      if (!(copy = static_cast<char*> ( cJSON_malloc(len))))
-      {
-        return (nullptr);
-      }
-
-      std::copy(str, str + len, copy);
-      return (copy);
-}
-
-void cJSON_InitHooks(cJSON_Hooks* hooks)
-{
-    if (!hooks) { /* Reset hooks */
-        cJSON_malloc = malloc;
-        cJSON_free = free;
-        return;
-    }
-
-       cJSON_malloc = (hooks->malloc_fn)?hooks->malloc_fn:malloc;
-       cJSON_free       = (hooks->free_fn)?hooks->free_fn:free;
-}
-
-/* Internal constructor. */
-static cJSON *cJSON_New_Item()
-{
-       cJSON* node = static_cast<cJSON*> (cJSON_malloc(sizeof(cJSON)));
-       if (node) {
-           *node = cJSON{};
-    }
-       return node;
-}
-
-/* Delete a cJSON structure. */
-void cJSON_Delete(cJSON *c)
-{
-       cJSON *next;
-       while (c)
-       {
-               next=c->next;
-               if (!(c->type&cJSON_IsReference) && c->child) cJSON_Delete(c->child);
-               if (!(c->type&cJSON_IsReference) && c->valuestring) cJSON_free(c->valuestring);
-               if (c->string) cJSON_free(c->string);
-               cJSON_free(c);
-               c=next;
-       }
-}
-
-/* Parse the input text to generate a number, and populate the result into item. */
-static const char *parse_number(cJSON *item,const char *num)
-{
-       double n=0,sign=1,scale=0;int subscale=0,signsubscale=1;
-
-       /* Could use sscanf for this? */
-       if (*num=='-') sign=-1,num++;   /* Has sign? */
-       if (*num=='0') num++;                   /* is zero */
-       if (*num>='1' && *num<='9')     do      n=(n*10.0)+(*num++ -'0');       while (*num>='0' && *num<='9'); /* Number? */
-       if (*num=='.') {num++;          do      n=(n*10.0)+(*num++ -'0'),scale--; while (*num>='0' && *num<='9');}      /* Fractional part? */
-       if (*num=='e' || *num=='E')             /* Exponent? */
-       {       num++;if (*num=='+') num++;     else if (*num=='-') signsubscale=-1,num++;              /* With sign? */
-               while (*num>='0' && *num<='9') subscale=(subscale*10)+(*num++ - '0');   /* Number? */
-       }
-
-       n=sign*n*pow(10.0,(scale+subscale*signsubscale));       /* number = +/- number.fraction * 10^+/- exponent */
-       
-       item->valuedouble=n;
-       item->valueint=static_cast<int> (n);
-       item->type=cJSON_Number;
-       return num;
-}
-
-/* Render the number nicely from the given item into a string. */
-static char *print_number(cJSON *item)
-{
-       char *str;
-       double d=item->valuedouble;
-       if (std::abs((static_cast<double>(item->valueint)-d))<=std::numeric_limits<double>::epsilon() &&
-                       d <= std::numeric_limits<int>::max() && d >= std::numeric_limits<int>::min())
-       {
-               str=static_cast<char*>(cJSON_malloc(21));       /* 2^64+1 can be represented in 21 chars. */
-               if (str) sprintf(str,"%d",item->valueint);
-       }
-       else
-       {
-               str=static_cast<char*>(cJSON_malloc(64));       /* This is a nice tradeoff. */
-               if (str)
-               {
-                       if (std::abs(std::floor(d)-d)<=std::numeric_limits<double>::epsilon())                  sprintf(str,"%.0f",d);
-                       else sprintf(str,"%.16g",d);
-               }
-       }
-       return str;
-}
-
-/* Parse the input text into an unescaped cstring, and populate item. */
-static const unsigned char firstByteMark[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC };
-static const char *parse_string(cJSON *item,const char *str)
-{
-       const char *ptr=str+1; char *ptr2; char *out; int len=0; unsigned uc;
-       if (*str!='\"') {ep=str;return nullptr;}        /* not a string! */
-       
-       while (*ptr!='\"' && *ptr && ++len) if (*ptr++ == '\\') ptr++;  /* Skip escaped quotes. */
-       
-       out=static_cast<char*> (cJSON_malloc(len+1));   /* This is how long we need for the string, roughly. */
-       if (!out) return nullptr;
-       
-       ptr=str+1;ptr2=out;
-       while (*ptr!='\"' && *ptr)
-       {
-               if (*ptr!='\\') *ptr2++=*ptr++;
-               else
-               {
-                       ptr++;
-                       switch (*ptr)
-                       {
-                               case 'b': *ptr2++='\b'; break;
-                               case 'f': *ptr2++='\f'; break;
-                               case 'n': *ptr2++='\n'; break;
-                               case 'r': *ptr2++='\r'; break;
-                               case 't': *ptr2++='\t'; break;
-                               case 'u':        /* transcode utf16 to utf8. DOES NOT SUPPORT SURROGATE PAIRS CORRECTLY. */
-                                       sscanf(ptr+1,"%4x",&uc);        /* get the unicode char. */
-                                       len=3;if (uc<0x80) len=1;else if (uc<0x800) len=2;ptr2+=len;
-                                       
-                                       switch (len) {
-                                               case 3: *--ptr2 = static_cast<char>(( (uc) | 0x80) & 0xBF );
-              uc >>= 6;
-              PCL_FALLTHROUGH
-                                               case 2: *--ptr2 = static_cast<char>(( (uc) | 0x80) & 0xBF );
-              uc >>= 6;
-              PCL_FALLTHROUGH
-                                               case 1: *--ptr2 = static_cast<char>( (uc) | firstByteMark[len] );
-                                       }
-                                       ptr2+=len;ptr+=4;
-                                       break;
-                               default:  *ptr2++=*ptr; break;
-                       }
-                       ptr++;
-               }
-       }
-       *ptr2=0;
-       if (*ptr=='\"') ptr++;
-       item->valuestring=out;
-       item->type=cJSON_String;
-       return ptr;
-}
-
-/* Render the cstring provided to an escaped version that can be printed. */
-static char *print_string_ptr(const char *str)
-{
-       const char *ptr;char *ptr2,*out;int len=0;unsigned char token;
-       
-       if (!str) return cJSON_strdup("");
-       ptr=str;while ((token=*ptr) && ++len) {if (strchr("\"\\\b\f\n\r\t",token)) len++; else if (token<32) len+=5;ptr++;}
-       
-       out=static_cast<char*>(cJSON_malloc(len+3));
-       if (!out) return nullptr;
-
-       ptr2=out;ptr=str;
-       *ptr2++='\"';
-       while (*ptr)
-       {
-               if (static_cast<unsigned char>(*ptr)>31 && *ptr!='\"' && *ptr!='\\') *ptr2++=*ptr++;
-               else
-               {
-                       *ptr2++='\\';
-                       switch (token=*ptr++)
-                       {
-                               case '\\':      *ptr2++='\\';   break;
-                               case '\"':      *ptr2++='\"';   break;
-                               case '\b':      *ptr2++='b';    break;
-                               case '\f':      *ptr2++='f';    break;
-                               case '\n':      *ptr2++='n';    break;
-                               case '\r':      *ptr2++='r';    break;
-                               case '\t':      *ptr2++='t';    break;
-                               default: sprintf(ptr2,"u%04x",token);ptr2+=5;   break;  /* escape and print */
-                       }
-               }
-       }
-       *ptr2++='\"';*ptr2++=0;
-       return out;
-}
-/* Invote print_string_ptr (which is useful) on an item. */
-static char *print_string(cJSON *item) {return print_string_ptr(item->valuestring);}
-
-/* Predeclare these prototypes. */
-static const char *parse_value(cJSON *item,const char *value);
-static char *print_value(cJSON *item,int depth,int fmt);
-static const char *parse_array(cJSON *item,const char *value);
-static char *print_array(cJSON *item,int depth,int fmt);
-static const char *parse_object(cJSON *item,const char *value);
-static char *print_object(cJSON *item,int depth,int fmt);
-
-/* Utility to jump whitespace and cr/lf */
-static const char *skip(const char *in) {while (in && *in && static_cast<unsigned char>(*in)<=32) in++; return in;}
-
-/* Parse an object - create a new root, and populate. */
-cJSON *cJSON_Parse(const char *value)
-{
-       cJSON *c=cJSON_New_Item();
-       ep=nullptr;
-       if (!c) return nullptr;       /* memory fail */
-
-       if (!parse_value(c,skip(value))) {cJSON_Delete(c);return nullptr;}
-       return c;
-}
-
-/* Render a cJSON item/entity/structure to text. */
-char *cJSON_Print(cJSON *item)                         {return print_value(item,0,1);}
-char *cJSON_PrintUnformatted(cJSON *item)      {return print_value(item,0,0);}
-
-void cJSON_PrintStr(cJSON *item, std::string& s)
-{
-       char* c = cJSON_Print(item);
-       s.assign(c);
-       free(c);
-}
-
-void cJSON_PrintUnformattedStr(cJSON *item, std::string& s)
-{
-       char* c = cJSON_PrintUnformatted(item);
-       s.assign(c);
-       free(c);
-}
-
-/* Parser core - when encountering text, process appropriately. */
-static const char *parse_value(cJSON *item,const char *value)
-{
-       if (!value)                                             return nullptr; /* Fail on null. */
-       if (!strncmp(value,"null",4))   { item->type=cJSON_NULL;  return value+4; }
-       if (!strncmp(value,"false",5))  { item->type=cJSON_False; return value+5; }
-       if (!strncmp(value,"true",4))   { item->type=cJSON_True; item->valueint=1;      return value+4; }
-       if (*value=='\"')                               { return parse_string(item,value); }
-       if (*value=='-' || (*value>='0' && *value<='9'))        { return parse_number(item,value); }
-       if (*value=='[')                                { return parse_array(item,value); }
-       if (*value=='{')                                { return parse_object(item,value); }
-
-       ep=value;return nullptr;        /* failure. */
-}
-
-/* Render a value to text. */
-static char *print_value(cJSON *item,int depth,int fmt)
-{
-       char *out=nullptr;
-       if (!item) return nullptr;
-       switch ((item->type)&255)
-       {
-               case cJSON_NULL:        out=cJSON_strdup("null");       break;
-               case cJSON_False:       out=cJSON_strdup("false");break;
-               case cJSON_True:        out=cJSON_strdup("true"); break;
-               case cJSON_Number:      out=print_number(item);break;
-               case cJSON_String:      out=print_string(item);break;
-               case cJSON_Array:       out=print_array(item,depth,fmt);break;
-               case cJSON_Object:      out=print_object(item,depth,fmt);break;
-       }
-       return out;
-}
-
-/* Build an array from input text. */
-static const char *parse_array(cJSON *item,const char *value)
-{
-       cJSON *child;
-       if (*value!='[')        {ep=value;return nullptr;}      /* not an array! */
-
-       item->type=cJSON_Array;
-       value=skip(value+1);
-       if (*value==']') return value+1;        /* empty array. */
-
-       item->child=child=cJSON_New_Item();
-       if (!item->child) return nullptr;                /* memory fail */
-       value=skip(parse_value(child,skip(value)));     /* skip any spacing, get the value. */
-       if (!value) return nullptr;
-
-       while (*value==',')
-       {
-               cJSON *new_item;
-               if (!(new_item=cJSON_New_Item())) return nullptr;       /* memory fail */
-               child->next=new_item;new_item->prev=child;child=new_item;
-               value=skip(parse_value(child,skip(value+1)));
-               if (!value) return nullptr;     /* memory fail */
-       }
-
-       if (*value==']') return value+1;        /* end of array */
-       ep=value;return nullptr;        /* malformed. */
-}
-
-/* Render an array to text */
-static char *print_array(cJSON *item,int depth,int fmt)
-{
-       char **entries;
-       char *out=nullptr,*ptr,*ret;std::size_t len=5;
-       cJSON *child=item->child;
-       int numentries=0,i=0,fail=0;
-       
-       /* How many entries in the array? */
-       while (child) numentries++,child=child->next;
-       /* Allocate an array to hold the values for each */
-       entries=static_cast<char**>(cJSON_malloc(numentries*sizeof(char*)));
-       if (!entries) return nullptr;
-  std::fill_n(entries, numentries, nullptr);
-       /* Retrieve all the results: */
-       child=item->child;
-       while (child && !fail)
-       {
-               ret=print_value(child,depth+1,fmt);
-               entries[i++]=ret;
-               if (ret) len+=strlen(ret)+2+(fmt?1:0); else fail=1;
-               child=child->next;
-       }
-       
-       /* If we didn't fail, try to malloc the output string */
-       if (!fail) out=static_cast<char*>(cJSON_malloc(len));
-       /* If that fails, we fail. */
-       if (!out) fail=1;
-
-       /* Handle failure. */
-       if (fail)
-       {
-               for (i=0;i<numentries;i++) if (entries[i]) cJSON_free(entries[i]);
-               cJSON_free(entries);
-               return nullptr;
-       }
-       
-       /* Compose the output array. */
-       *out='[';
-       ptr=out+1;*ptr=0;
-       for (i=0;i<numentries;i++)
-       {
-               strcpy(ptr,entries[i]);ptr+=strlen(entries[i]);
-               if (i!=numentries-1) {*ptr++=',';if(fmt)*ptr++=' ';*ptr=0;}
-               cJSON_free(entries[i]);
-       }
-       cJSON_free(entries);
-       *ptr++=']';*ptr++=0;
-       return out;     
-}
-
-/* Build an object from the text. */
-static const char *parse_object(cJSON *item,const char *value)
-{
-       cJSON *child;
-       if (*value!='{')        {ep=value;return nullptr;}      /* not an object! */
-       
-       item->type=cJSON_Object;
-       value=skip(value+1);
-       if (*value=='}') return value+1;        /* empty array. */
-       
-       item->child=child=cJSON_New_Item();
-       if (!item->child) return nullptr;
-       value=skip(parse_string(child,skip(value)));
-       if (!value) return nullptr;
-       child->string=child->valuestring;child->valuestring=nullptr;
-       if (*value!=':') {ep=value;return nullptr;}     /* fail! */
-       value=skip(parse_value(child,skip(value+1)));   /* skip any spacing, get the value. */
-       if (!value) return nullptr;
-       
-       while (*value==',')
-       {
-               cJSON *new_item;
-               if (!(new_item=cJSON_New_Item()))       return nullptr; /* memory fail */
-               child->next=new_item;new_item->prev=child;child=new_item;
-               value=skip(parse_string(child,skip(value+1)));
-               if (!value) return nullptr;
-               child->string=child->valuestring;child->valuestring=nullptr;
-               if (*value!=':') {ep=value;return nullptr;}     /* fail! */
-               value=skip(parse_value(child,skip(value+1)));   /* skip any spacing, get the value. */
-               if (!value) return nullptr;
-       }
-       
-       if (*value=='}') return value+1;        /* end of array */
-       ep=value;return nullptr;        /* malformed. */
-}
-
-/* Render an object to text. */
-static char *print_object(cJSON *item,int depth,int fmt)
-{
-       char *out=nullptr;
-       std::size_t len=7;
-       cJSON *child=item->child;
-       std::size_t numentries=0,fail=0;
-       /* Count the number of entries. */
-       while (child) numentries++,child=child->next;
-       /* Allocate space for the names and the objects */
-       char **entries = static_cast<char**>(cJSON_malloc(numentries*sizeof(char*)));
-       if (!entries) return nullptr;
-       char **names=static_cast<char**>(cJSON_malloc(numentries*sizeof(char*)));
-       if (!names) {cJSON_free(entries);return nullptr;}
-  std::fill_n(entries, numentries, nullptr);
-  std::fill_n(names, numentries, nullptr);
-
-       /* Collect all the results into our arrays: */
-       child=item->child;depth++;if (fmt) len+=depth;
-       int childId = 0;
-       while (child)
-       {
-               char *str = print_string_ptr(child->string);
-               names[childId] = str;
-               char *ret = print_value(child,depth,fmt);
-               entries[childId++] = ret;
-               if (str && ret) len+=strlen(ret)+strlen(str)+2+(fmt?2+depth:0); else fail=1;
-               child=child->next;
-       }
-       
-       /* Try to allocate the output string */
-       if (!fail) out=static_cast<char*> (cJSON_malloc(len));
-       if (!out) fail=1;
-
-       /* Handle failure */
-       if (fail)
-       {
-               for (std::size_t i=0;i<numentries;i++) {if (names[i]) cJSON_free(names[i]);if (entries[i]) cJSON_free(entries[i]);}
-               cJSON_free(names);cJSON_free(entries);
-               return nullptr;
-       }
-       
-       /* Compose the output: */
-       *out='{';
-       char *ptr = out+1;
-       if (fmt)*ptr++='\n';
-       *ptr=0;
-       for (std::size_t i=0;i<numentries;i++)
-       {
-               if (fmt) for (int j=0; j < depth; j++) *ptr++='\t';
-               strcpy(ptr,names[i]);ptr+=strlen(names[i]);
-               *ptr++=':';if (fmt) *ptr++='\t';
-               strcpy(ptr,entries[i]);ptr+=strlen(entries[i]);
-               if (i!=numentries-1) *ptr++=',';
-               if (fmt) *ptr++='\n';
-               *ptr=0;
-               cJSON_free(names[i]);cJSON_free(entries[i]);
-       }
-       
-       cJSON_free(names);cJSON_free(entries);
-       if (fmt) for (int i=0; i < depth-1; i++) *ptr++='\t';
-       *ptr++='}';*ptr++=0;
-       return out;     
-}
-
-/* Get Array size/item / object item. */
-int    cJSON_GetArraySize(cJSON *array)                                                        {cJSON *c=array->child;int i=0;while(c)i++,c=c->next;return i;}
-cJSON *cJSON_GetArrayItem(cJSON *array,int item)                               {cJSON *c=array->child;  while (c && item>0) item--,c=c->next; return c;}
-cJSON *cJSON_GetObjectItem(cJSON *object,const char *string)   {cJSON *c=object->child; while (c && cJSON_strcasecmp(c->string,string)) c=c->next; return c;}
-
-/* Utility for array list handling. */
-static void suffix_object(cJSON *prev,cJSON *item) {prev->next=item;item->prev=prev;}
-/* Utility for handling references. */
-static cJSON*
-create_reference(cJSON* item)
-{
-  cJSON* ref = cJSON_New_Item();
-  if (!ref) {
-    return nullptr;
-  }
-  *ref = *item;
-  ref->string = nullptr;
-  ref->type |= cJSON_IsReference;
-  ref->next = ref->prev = nullptr;
-  return ref;
-}
-
-/* Add item to array/object. */
-void   cJSON_AddItemToArray(cJSON *array, cJSON *item)                                         {cJSON *c=array->child;if (!item) return; if (!c) {array->child=item;} else {while (c && c->next) c=c->next; suffix_object(c,item);}}
-void   cJSON_AddItemToObject(cJSON *object,const char *string,cJSON *item)     {if (!item) return; if (item->string) cJSON_free(item->string);item->string=cJSON_strdup(string);cJSON_AddItemToArray(object,item);}
-void   cJSON_AddItemReferenceToArray(cJSON *array, cJSON *item)                                                {cJSON_AddItemToArray(array,create_reference(item));}
-void   cJSON_AddItemReferenceToObject(cJSON *object,const char *string,cJSON *item)    {cJSON_AddItemToObject(object,string,create_reference(item));}
-
-cJSON *cJSON_DetachItemFromArray(cJSON *array,int which)                       {
-       cJSON *c=array->child;
-       while (c && which>0) c=c->next,which--;
-       if (!c) return nullptr;
-       if (c->prev) c->prev->next=c->next;
-       if (c->next) c->next->prev=c->prev;
-       if (c==array->child) array->child=c->next;
-       c->prev=c->next=nullptr;
-       return c;
-}
-void   cJSON_DeleteItemFromArray(cJSON *array,int which)                       {cJSON_Delete(cJSON_DetachItemFromArray(array,which));}
-cJSON *cJSON_DetachItemFromObject(cJSON *object,const char *string) {int i=0;cJSON *c=object->child;while (c && cJSON_strcasecmp(c->string,string)) i++,c=c->next;if (c) return cJSON_DetachItemFromArray(object,i);return nullptr;}
-void   cJSON_DeleteItemFromObject(cJSON *object,const char *string) {cJSON_Delete(cJSON_DetachItemFromObject(object,string));}
-
-/* Replace array/object items with new ones. */
-void   cJSON_ReplaceItemInArray(cJSON *array,int which,cJSON *newitem)         {cJSON *c=array->child;while (c && which>0) c=c->next,which--;if (!c) return;
-       newitem->next=c->next;newitem->prev=c->prev;if (newitem->next) newitem->next->prev=newitem;
-       if (c==array->child) array->child=newitem; else newitem->prev->next=newitem;c->next=c->prev=nullptr;cJSON_Delete(c);}
-void   cJSON_ReplaceItemInObject(cJSON *object,const char *string,cJSON *newitem){int i=0;cJSON *c=object->child;while(c && cJSON_strcasecmp(c->string,string))i++,c=c->next;if(c){newitem->string=cJSON_strdup(string);cJSON_ReplaceItemInArray(object,i,newitem);}}
-
-/* Create basic types: */
-cJSON *cJSON_CreateNull()                                              {cJSON *item=cJSON_New_Item();if(item)item->type=cJSON_NULL;return item;}
-cJSON *cJSON_CreateTrue()                                              {cJSON *item=cJSON_New_Item();if(item)item->type=cJSON_True;return item;}
-cJSON *cJSON_CreateFalse()                                             {cJSON *item=cJSON_New_Item();if(item)item->type=cJSON_False;return item;}
-cJSON *cJSON_CreateBool(int b)                                 {cJSON *item=cJSON_New_Item();if(item)item->type=b?cJSON_True:cJSON_False;return item;}
-cJSON *cJSON_CreateNumber(double num)                  {cJSON *item=cJSON_New_Item();if(item){item->type=cJSON_Number;item->valuedouble=num;item->valueint=static_cast<int>(num);}return item;}
-cJSON *cJSON_CreateString(const char *string)  {cJSON *item=cJSON_New_Item();if(item){item->type=cJSON_String;item->valuestring=cJSON_strdup(string);}return item;}
-cJSON *cJSON_CreateArray()                                             {cJSON *item=cJSON_New_Item();if(item)item->type=cJSON_Array;return item;}
-cJSON *cJSON_CreateObject()                                            {cJSON *item=cJSON_New_Item();if(item)item->type=cJSON_Object;return item;}
-
-/* Create Arrays: */
-cJSON *cJSON_CreateIntArray(int *numbers,int count)                            {cJSON *p=nullptr,*a=cJSON_CreateArray();for(int i=0;a && i<count;i++){cJSON *n=cJSON_CreateNumber(numbers[i]);if(!i)a->child=n;else suffix_object(p,n);p=n;}return a;}
-cJSON *cJSON_CreateFloatArray(float *numbers,int count)                        {cJSON *p=nullptr,*a=cJSON_CreateArray();for(int i=0;a && i<count;i++){cJSON *n=cJSON_CreateNumber(numbers[i]);if(!i)a->child=n;else suffix_object(p,n);p=n;}return a;}
-cJSON *cJSON_CreateDoubleArray(double *numbers,int count)              {cJSON *p=nullptr,*a=cJSON_CreateArray();for(int i=0;a && i<count;i++){cJSON *n=cJSON_CreateNumber(numbers[i]);if(!i)a->child=n;else suffix_object(p,n);p=n;}return a;}
-cJSON *cJSON_CreateStringArray(const char **strings,int count) {cJSON *p=nullptr,*a=cJSON_CreateArray();for(int i=0;a && i<count;i++){cJSON *n=cJSON_CreateString(strings[i]);if(!i)a->child=n;else suffix_object(p,n);p=n;}return a;}
index f33e8b4475d1baa21065d4e2139d6687a2f33b83..8f353c84c54e88993d8a59f1eb74c8e076f37eb3 100644 (file)
@@ -13,7 +13,6 @@ if(NOT VTK_FOUND)
 else()
   set(DEFAULT TRUE)
   set(REASON)
-  include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 
   set(srcs outofcore_viewer.cpp
          ../src/visualization/camera.cpp
index 13d04c3fbfc54032d1f7a4b6ba5b1d8fcb340313..5b07e0d7ca04e9a554bc580252ed10ae93686d80 100644 (file)
@@ -3,18 +3,19 @@
 // Ensure the compiler is meeting the minimum C++ standard
 // MSVC is not checked via __cplusplus due to
 // https://developercommunity.visualstudio.com/content/problem/120156/-cplusplus-macro-still-defined-as-pre-c11-value.html
-#if (!defined(_MSC_VER) && __cplusplus < 201402L) || (defined(_MSC_VER) && _MSC_VER < 1900)
-  #error PCL requires C++14 or above
+#if defined(__cplusplus) && ((!defined(_MSC_VER) && __cplusplus < ${PCL__cplusplus}) || (defined(_MSC_VER) && _MSC_VER < ${PCL_REQUIRES_MSC_VER}) || (defined(_MSVC_LANG) && _MSVC_LANG < ${PCL__cplusplus}))
+  #error C++ standard too low (PCL requires ${PCL__cplusplus} or above)
 #endif
 
 #define BUILD_@CMAKE_BUILD_TYPE@
+#cmakedefine PCL_SYMBOL_VISIBILITY_HIDDEN
 /* PCL version information */
 #define PCL_MAJOR_VERSION ${PCL_VERSION_MAJOR}
 #define PCL_MINOR_VERSION ${PCL_VERSION_MINOR}
 #define PCL_REVISION_VERSION ${PCL_VERSION_PATCH}
 #define PCL_DEV_VERSION ${PCL_DEV_VERSION}
 #define PCL_VERSION_PRETTY "${PCL_VERSION_PRETTY}"
-#define PCL_VERSION_CALC(MAJ, MIN, PATCH) (MAJ*100000+MIN*100+PATCH)
+#define PCL_VERSION_CALC(MAJ, MIN, PATCH) ((MAJ)*100000+(MIN)*100+(PATCH))
 #define PCL_VERSION \
     PCL_VERSION_CALC(PCL_MAJOR_VERSION, PCL_MINOR_VERSION, PCL_REVISION_VERSION)
 #define PCL_VERSION_COMPARE(OP, MAJ, MIN, PATCH) \
@@ -34,6 +35,8 @@
   #endif //PCL_MINOR_VERSION
 #endif 
 
+#define PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC ${PCL_USES_EIGEN_HANDMADE_ALIGNED_MALLOC}
+
 #cmakedefine HAVE_OPENNI 1
 
 #cmakedefine HAVE_OPENNI2 1
 
 #cmakedefine HAVE_ZLIB
 
+#cmakedefine HAVE_CJSON
+
+#cmakedefine PCL_PREFER_BOOST_FILESYSTEM
+
 /* Precompile for a minimal set of point types instead of all. */
 #cmakedefine PCL_ONLY_CORE_POINT_TYPES
 
+#define PCL_XYZ_POINT_TYPES @PCL_XYZ_POINT_TYPES@
+
+#define PCL_NORMAL_POINT_TYPES @PCL_NORMAL_POINT_TYPES@
+
 /* Do not precompile for any point types at all. */
 #cmakedefine PCL_NO_PRECOMPILE
 
index dca32d662beb6cb69378d06f71879a923178bcad..f2b11e838e6ca3c75bc7f2ef134343d774eb8c76 100644 (file)
@@ -2,16 +2,6 @@ set(SUBSYS_NAME people)
 set(SUBSYS_DESC "Point cloud people library")
 set(SUBSYS_DEPS common kdtree search sample_consensus filters io visualization geometry segmentation octree)
 
-if(NOT VTK_FOUND)
-  set(DEFAULT FALSE)
-  set(REASON "VTK was not found.")
-else()
-  set(DEFAULT TRUE)
-  set(REASON)
-  include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-endif()
-
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
@@ -43,8 +33,6 @@ set(srcs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries(${LIB_NAME} pcl_common pcl_filters pcl_kdtree pcl_sample_consensus pcl_segmentation pcl_visualization)
 
@@ -53,8 +41,6 @@ PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs})
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs})
 
-#SET_TARGET_PROPERTIES("${LIB_NAME}" PROPERTIES LINKER_LANGUAGE CXX)
-
 if(WITH_OPENNI)
   PCL_ADD_EXECUTABLE(pcl_ground_based_rgbd_people_detector COMPONENT ${SUBSYS_NAME} SOURCES apps/main_ground_based_people_detection.cpp BUNDLE)
   target_link_libraries(pcl_ground_based_rgbd_people_detector pcl_common pcl_kdtree pcl_search pcl_sample_consensus pcl_filters pcl_io pcl_visualization pcl_segmentation pcl_people)
index 7c9866fcf2788e2198cd22151fe1a3d8cd65ee89..950f56854dedcbccc868b90c00f4aa22cc73d03c 100644 (file)
@@ -136,7 +136,7 @@ pcl::people::HeadBasedSubclustering<PointT>::mergeClustersCloseInFloorCoordinate
 {
   float min_distance_between_cluster_centers = 0.4;                   // meters
   float normalize_factor = std::pow(sqrt_ground_coeffs_, 2);          // sqrt_ground_coeffs ^ 2 (precomputed for speed)
-  Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3);        // ground plane normal (precomputed for speed)
+  Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head<3>();        // ground plane normal (precomputed for speed)
   std::vector <std::vector<int> > connected_clusters;
   connected_clusters.resize(input_clusters.size());
   std::vector<bool> used_clusters;          // 0 in correspondence of clusters remained to process, 1 for already used clusters
@@ -196,7 +196,7 @@ pcl::people::HeadBasedSubclustering<PointT>::createSubClusters (pcl::people::Per
 {
   // create new clusters from the current cluster and put corresponding indices into sub_clusters_indices:
   float normalize_factor = std::pow(sqrt_ground_coeffs_, 2);          // sqrt_ground_coeffs ^ 2 (precomputed for speed)
-  Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3);        // ground plane normal (precomputed for speed)
+  Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head<3>();        // ground plane normal (precomputed for speed)
   Eigen::Matrix3Xf maxima_projected(3,maxima_number);                 // matrix containing the projection of maxima onto the ground plane
   Eigen::VectorXi subclusters_number_of_points(maxima_number);        // subclusters number of points
   std::vector <pcl::Indices> sub_clusters_indices;                    // vector of vectors with the cluster indices for every maximum
index e8640ebd768d71856876face3f4b33010da41df6..df93b822c608e4febcf5826f407fb4271b13f701 100644 (file)
@@ -213,16 +213,16 @@ pcl::people::HeightMap2D<PointT>::filterMaxima ()
 
       PointT* p_current = &(*cloud_)[maxima_cloud_indices_[i]];  // pointcloud point referring to the current maximum
       Eigen::Vector3f p_current_eigen(p_current->x, p_current->y, p_current->z);  // conversion to eigen
-      float t = p_current_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
-      p_current_eigen -= ground_coeffs_.head(3) * t;       // projection of the point on the groundplane
+      float t = p_current_eigen.dot(ground_coeffs_.head<3>()) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
+      p_current_eigen -= ground_coeffs_.head<3>() * t;       // projection of the point on the groundplane
 
       int j = i-1;
       while ((j >= 0) && (good_maximum))
       {
         PointT* p_previous = &(*cloud_)[maxima_cloud_indices_[j]];         // pointcloud point referring to an already validated maximum
         Eigen::Vector3f p_previous_eigen(p_previous->x, p_previous->y, p_previous->z);  // conversion to eigen
-        float t = p_previous_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
-        p_previous_eigen -= ground_coeffs_.head(3) * t;         // projection of the point on the groundplane
+        float t = p_previous_eigen.dot(ground_coeffs_.head<3>()) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
+        p_previous_eigen -= ground_coeffs_.head<3>() * t;         // projection of the point on the groundplane
 
         // distance of the projection of the points on the groundplane:
         float distance = (p_current_eigen-p_previous_eigen).norm();
index 84158dc605f3af046f2b69daf40de596e3e52cc1..db1de1bf6cd2d653ebb0bad1dc464148c6baf884 100644 (file)
@@ -2,8 +2,9 @@ set(SUBSYS_NAME recognition)
 set(SUBSYS_DESC "Point cloud recognition library")
 set(SUBSYS_DEPS common io search kdtree octree features filters registration sample_consensus ml)
 
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
+set(DEFAULT ON)
+
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
@@ -21,7 +22,6 @@ set(LINEMOD_IMPLS
 )
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
   "include/pcl/${SUBSYS_NAME}/color_gradient_dot_modality.h"
   "include/pcl/${SUBSYS_NAME}/color_gradient_modality.h"
   "include/pcl/${SUBSYS_NAME}/color_modality.h"
@@ -38,20 +38,7 @@ set(incs
   "include/pcl/${SUBSYS_NAME}/dense_quantized_multi_mod_template.h"
   "include/pcl/${SUBSYS_NAME}/sparse_quantized_multi_mod_template.h"
   "include/pcl/${SUBSYS_NAME}/surface_normal_modality.h"
-  "include/pcl/${SUBSYS_NAME}/line_rgbd.h"
   "include/pcl/${SUBSYS_NAME}/implicit_shape_model.h"
-  "include/pcl/${SUBSYS_NAME}/auxiliary.h"
-  "include/pcl/${SUBSYS_NAME}/hypothesis.h"
-  "include/pcl/${SUBSYS_NAME}/model_library.h"
-  "include/pcl/${SUBSYS_NAME}/rigid_transform_space.h"
-  "include/pcl/${SUBSYS_NAME}/obj_rec_ransac.h"
-  "include/pcl/${SUBSYS_NAME}/orr_graph.h"
-  "include/pcl/${SUBSYS_NAME}/orr_octree_zprojection.h"
-  "include/pcl/${SUBSYS_NAME}/trimmed_icp.h"
-  "include/pcl/${SUBSYS_NAME}/orr_octree.h"
-  "include/pcl/${SUBSYS_NAME}/simple_octree.h"
-  "include/pcl/${SUBSYS_NAME}/voxel_structure.h"
-  "include/pcl/${SUBSYS_NAME}/bvh.h"
 )
 
 set(ransac_based_incs
@@ -91,9 +78,6 @@ set(cg_incs
 )
 
 set(impl_incs
-  "include/pcl/${SUBSYS_NAME}/impl/line_rgbd.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/simple_octree.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/voxel_structure.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/implicit_shape_model.hpp"
 )
 
@@ -135,24 +119,19 @@ set(srcs
   src/implicit_shape_model.cpp
 )
 
-if(HAVE_METSLIB)
-  set(metslib_incs "")
-else()
-  set(metslib_incs
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/abstract-search.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/local-search.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/mets.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/metslib_config.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/model.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/observer.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/simulated-annealing.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/tabu-search.hh"
-    "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/termination-criteria.hh"
-  )
-endif()
+set(metslib_incs
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/abstract-search.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/local-search.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/mets.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/metslib_config.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/model.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/observer.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/simulated-annealing.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/tabu-search.hh"
+  "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/termination-criteria.hh"
+)
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${face_detection_incs} ${ransac_based_incs} ${ransac_based_impl_incs} ${hv_incs} ${hv_impl_incs} ${cg_incs} ${cg_impl_incs} ${metslib_incs})
 target_link_libraries("${LIB_NAME}" pcl_common pcl_kdtree pcl_octree pcl_search pcl_features pcl_registration pcl_sample_consensus pcl_filters pcl_ml pcl_io)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
@@ -169,7 +148,4 @@ PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl/hv" ${hv_impl_incs})
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl/cg" ${cg_impl_incs})
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/linemod" ${LINEMOD_INCLUDES})
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl/linemod" ${LINEMOD_IMPLS})
-
-if(NOT HAVE_METSLIB)
-  PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/3rdparty/metslib" ${metslib_incs})
-endif()
+PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/3rdparty/metslib" ${metslib_incs})
diff --git a/recognition/include/pcl/recognition/auxiliary.h b/recognition/include/pcl/recognition/auxiliary.h
deleted file mode 100644 (file)
index 0e364ad..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/auxiliary.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/auxiliary.h> instead")
diff --git a/recognition/include/pcl/recognition/boost.h b/recognition/include/pcl/recognition/boost.h
deleted file mode 100644 (file)
index 44e705b..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-
-#include <boost/graph/graph_traits.hpp>
diff --git a/recognition/include/pcl/recognition/bvh.h b/recognition/include/pcl/recognition/bvh.h
deleted file mode 100644 (file)
index 12374a2..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/bvh.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/bvh.h> instead")
index 89ca02cb49cbd880905e8717c7f237506cc50047..986b22b98aa523e2195b21b016edcdfba4815b22 100644 (file)
@@ -368,7 +368,7 @@ processInputData ()
 
        convolution.setInputCloud (rgb_input_);
        convolution.setKernel (gaussian_kernel);
-
+  convolution.setBordersPolicy(pcl::filters::Convolution<pcl::RGB, pcl::RGB>::BORDERS_POLICY_DUPLICATE);
   convolution.convolve (*smoothed_input_);
 
   // extract color gradients
index b1c6451997fcdbf3b5df2e35722db8e7260cf796..be0e5661dfeb08912393ed665800038977ede331 100644 (file)
@@ -59,6 +59,7 @@ namespace pcl
   /**
     * \brief Template matching using the DOTMOD approach.
     * \author Stefan Holzer, Stefan Hinterstoisser
+    * \ingroup recognition
     */
   class PCL_EXPORTS DOTMOD
   {
index 7b4a929df52604a269fde377850ac55930074faa..6bf66dc9abe5564496465fe6edab4f3ba817ac85 100644 (file)
@@ -7,19 +7,17 @@
 
 #pragma once
 
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/memory.h>
 #include <pcl/ml/dt/decision_tree_data_provider.h>
 #include <pcl/recognition/face_detection/face_common.h>
 
 #include <boost/algorithm/string.hpp>
-#include <boost/filesystem/operations.hpp>
 
 #include <fstream>
 #include <string>
 
 
-namespace bf = boost::filesystem;
-
 namespace pcl
 {
   namespace face_detection
@@ -35,15 +33,15 @@ namespace pcl
         int patches_per_image_;
         int min_images_per_bin_;
 
-        void getFilesInDirectory(bf::path & dir, std::string & rel_path_so_far, std::vector<std::string> & relative_paths, std::string & ext)
+        void getFilesInDirectory(pcl_fs::path & dir, std::string & rel_path_so_far, std::vector<std::string> & relative_paths, std::string & ext)
         {
-          for (const auto& dir_entry : bf::directory_iterator(dir))
+          for (const auto& dir_entry : pcl_fs::directory_iterator(dir))
           {
             //check if its a directory, then get models in it
-            if (bf::is_directory (dir_entry))
+            if (pcl_fs::is_directory (dir_entry))
             {
               std::string so_far = rel_path_so_far + (dir_entry.path ().filename ()).string () + "/";
-              bf::path curr_path = dir_entry.path ();
+              pcl_fs::path curr_path = dir_entry.path ();
               getFilesInDirectory (curr_path, so_far, relative_paths, ext);
             } else
             {
index 40c874d77c69994d9a8c463a28824c73d86e8b39..fb7f0e952052f9a417a6c1987b46ba0005b3335c 100644 (file)
@@ -47,6 +47,7 @@ namespace pcl
   /**
    * \brief A greedy hypothesis verification method
    * \author Aitor Aldoma
+   * \ingroup recognition
    */
 
   template<typename ModelT, typename SceneT>
diff --git a/recognition/include/pcl/recognition/hypothesis.h b/recognition/include/pcl/recognition/hypothesis.h
deleted file mode 100644 (file)
index ad8f5b6..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/hypothesis.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/hypothesis.h> instead")
index 4783f7018d5e84dda21670035b866e6423c8e94d..3db2df822db3bfbf0d0fcc64aeaa506b5a1330b5 100644 (file)
@@ -61,6 +61,8 @@ inline void extractEuclideanClustersSmooth(const typename pcl::PointCloud<PointT
     PCL_ERROR("[pcl::extractEuclideanClusters] Number of points in the input point cloud different than normals!\n");
     return;
   }
+  // If tree gives sorted results, we can skip the first one because it is the query point itself
+  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
 
   // Create a bool vector of processed point indices, and initialize it to false
   std::vector<bool> processed (cloud.size (), false);
@@ -96,7 +98,7 @@ inline void extractEuclideanClustersSmooth(const typename pcl::PointCloud<PointT
         continue;
       }
 
-      for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx
+      for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
       {
         if (processed[nn_indices[j]]) // Has this point been processed before ?
           continue;
@@ -635,7 +637,7 @@ bool pcl::GlobalHypothesesVerification<ModelT, SceneT>::addModel(typename pcl::P
     Eigen::Vector3f scene_p_normal = (*scene_normals_)[it->first].getNormalVector3fMap ();
     Eigen::Vector3f model_p_normal =
         (*recog_model->normals_)[it->second->at(closest).first].getNormalVector3fMap();
-    float dotp = scene_p_normal.dot (model_p_normal) * 1.f; //[-1,1] from antiparallel trough perpendicular to parallel
+    float dotp = scene_p_normal.dot (model_p_normal) * 1.f; //[-1,1] from antiparallel through perpendicular to parallel
 
     if (dotp < 0.f)
       dotp = 0.f;
@@ -725,7 +727,7 @@ void pcl::GlobalHypothesesVerification<ModelT, SceneT>::computeClutterCue(Recogn
           //using normals to weight clutter points
           Eigen::Vector3f scene_p_normal = (*scene_normals_)[neighborhood_index.first].getNormalVector3fMap ();
           Eigen::Vector3f model_p_normal = (*scene_normals_)[recog_model->explained_[neighborhood_index.second]].getNormalVector3fMap ();
-          float dotp = scene_p_normal.dot (model_p_normal); //[-1,1] from antiparallel trough perpendicular to parallel
+          float dotp = scene_p_normal.dot (model_p_normal); //[-1,1] from antiparallel through perpendicular to parallel
 
           if (dotp < 0)
             dotp = 0.f;
index 3830bdbe9b110fece484350712d40e14620cb75a..fdd87b780e96513a594cd5acf63a4c5d05998ae4 100644 (file)
@@ -32,7 +32,7 @@
  *  POSSIBILITY OF SUCH DAMAGE.
  *
  *
- * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication"
+ * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classification"
  * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool
  *
  * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov
diff --git a/recognition/include/pcl/recognition/impl/line_rgbd.hpp b/recognition/include/pcl/recognition/impl/line_rgbd.hpp
deleted file mode 100644 (file)
index 53d6711..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/impl/linemod/line_rgbd.hpp>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/impl/linemod/line_rgbd.hpp> instead")
diff --git a/recognition/include/pcl/recognition/impl/simple_octree.hpp b/recognition/include/pcl/recognition/impl/simple_octree.hpp
deleted file mode 100644 (file)
index 0c8c0cc..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/impl/ransac_based/simple_octree.hpp>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/impl/ransac_based/simple_octree.hpp> instead")
diff --git a/recognition/include/pcl/recognition/impl/voxel_structure.hpp b/recognition/include/pcl/recognition/impl/voxel_structure.hpp
deleted file mode 100644 (file)
index 44697e8..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/impl/ransac_based/voxel_structure.hpp>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/impl/ransac_based/voxel_structure.hpp> instead")
index 0347eff922af06fe47d2703af9f6be7a06eb31c9..ea02007e1f5328ca475cb3a53c790ac3bf59f71f 100644 (file)
@@ -226,12 +226,12 @@ namespace pcl
   namespace ism
   {
     /** \brief This class implements Implicit Shape Model algorithm described in
-      * "Hough Transforms and 3D SURF for robust three dimensional classication"
+      * "Hough Transforms and 3D SURF for robust three dimensional classification"
       * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool.
       * It has two main member functions. One for training, using the data for which we know
       * which class it belongs to. And second for investigating a cloud for the presence
       * of the class of interest.
-      * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication"
+      * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classification"
       * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool
       *
       * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov
diff --git a/recognition/include/pcl/recognition/line_rgbd.h b/recognition/include/pcl/recognition/line_rgbd.h
deleted file mode 100644 (file)
index 5d526ad..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/linemod/line_rgbd.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/linemod/line_rgbd.h> instead")
index d9f9cd5dec82eeb95fb983cd407436004bbb5f0b..b955f38554f083a2a4151ecca8392544e612ced9 100644 (file)
@@ -67,6 +67,7 @@ namespace pcl
 
   /** \brief High-level class for template matching using the LINEMOD approach based on RGB and Depth data.
     * \author Stefan Holzer
+    * \ingroup recognition
     */
   template <typename PointXYZT, typename PointRGBT=PointXYZT>
   class PCL_EXPORTS LineRGBD
diff --git a/recognition/include/pcl/recognition/model_library.h b/recognition/include/pcl/recognition/model_library.h
deleted file mode 100644 (file)
index 4b4ee33..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/model_library.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/model_library.h> instead")
diff --git a/recognition/include/pcl/recognition/obj_rec_ransac.h b/recognition/include/pcl/recognition/obj_rec_ransac.h
deleted file mode 100644 (file)
index 52b9636..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/obj_rec_ransac.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/obj_rec_ransac.h> instead")
diff --git a/recognition/include/pcl/recognition/orr_graph.h b/recognition/include/pcl/recognition/orr_graph.h
deleted file mode 100644 (file)
index a43e35c..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/orr_graph.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/orr_graph.h> instead")
diff --git a/recognition/include/pcl/recognition/orr_octree.h b/recognition/include/pcl/recognition/orr_octree.h
deleted file mode 100644 (file)
index b0f43fc..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/orr_octree.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/orr_octree.h> instead")
diff --git a/recognition/include/pcl/recognition/orr_octree_zprojection.h b/recognition/include/pcl/recognition/orr_octree_zprojection.h
deleted file mode 100644 (file)
index 536f8a5..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/orr_octree_zprojection.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/orr_octree_zprojection.h> instead")
index 1ca6ef3448e5e0345266c3233d36ec05e9fd4038..43276a248c7bc07439c653e5abf8ac3ac20a67c8 100644 (file)
@@ -190,8 +190,8 @@ namespace pcl
             inline bool
             intersect(const float box[6]) const
             {
-              return !(box[1] < bounds_[0] || box[3] < bounds_[2] || box[5] < bounds_[4] ||
-                   box[0] > bounds_[1] || box[2] > bounds_[3] || box[4] > bounds_[5]);
+              return (box[1] >= bounds_[0] && box[3] >= bounds_[2] && box[5] >= bounds_[4] &&
+                      box[0] <= bounds_[1] && box[2] <= bounds_[3] && box[4] <= bounds_[5]);
             }
 
             /** \brief Computes and returns the volume of the bounding box of this node. */
diff --git a/recognition/include/pcl/recognition/rigid_transform_space.h b/recognition/include/pcl/recognition/rigid_transform_space.h
deleted file mode 100644 (file)
index 2cc3043..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/rigid_transform_space.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/rigid_transform_space.h> instead")
diff --git a/recognition/include/pcl/recognition/simple_octree.h b/recognition/include/pcl/recognition/simple_octree.h
deleted file mode 100644 (file)
index aa47e0d..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/simple_octree.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/simple_octree.h> instead")
diff --git a/recognition/include/pcl/recognition/trimmed_icp.h b/recognition/include/pcl/recognition/trimmed_icp.h
deleted file mode 100644 (file)
index cabf17b..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/trimmed_icp.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/trimmed_icp.h> instead")
diff --git a/recognition/include/pcl/recognition/voxel_structure.h b/recognition/include/pcl/recognition/voxel_structure.h
deleted file mode 100644 (file)
index a78e541..0000000
+++ /dev/null
@@ -1,2 +0,0 @@
-#include <pcl/recognition/ransac_based/voxel_structure.h>
-PCL_DEPRECATED_HEADER(1, 15, "Please use <pcl/recognition/ransac_based/voxel_structure.h> instead")
index 558c7f10773665f6f502aa14a4137f72f18b3aab..c6baab4b911c47a9687d63ca787b554a90c524c4 100644 (file)
@@ -50,7 +50,7 @@ void pcl::face_detection::FaceDetectorDataProvider<FeatureType, DataSet, LabelTy
 {
   std::string start;
   std::string ext = std::string ("pcd");
-  bf::path dir = data_dir;
+  pcl_fs::path dir = data_dir;
 
   std::vector < std::string > files;
   getFilesInDirectory (dir, start, files, ext);
@@ -93,7 +93,7 @@ void pcl::face_detection::FaceDetectorDataProvider<FeatureType, DataSet, LabelTy
 
     if (readMatrixFromFile (pose_file, pose_mat))
     {
-      Eigen::Vector3f ea = pose_mat.block<3, 3> (0, 0).eulerAngles (0, 1, 2);
+      Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2);
       ea *= 57.2957795f; //transform it to degrees to do the binning
       int y = static_cast<int>(pcl_round ((ea[0] + static_cast<float>(std::abs (min_yaw))) / res_yaw));
       int p = static_cast<int>(pcl_round ((ea[1] + static_cast<float>(std::abs (min_pitch))) / res_pitch));
@@ -354,7 +354,7 @@ void pcl::face_detection::FaceDetectorDataProvider<FeatureType, DataSet, LabelTy
     pose_mat.setIdentity (4, 4);
     readMatrixFromFile (pose_file, pose_mat);
 
-    Eigen::Vector3f ea = pose_mat.block<3, 3> (0, 0).eulerAngles (0, 1, 2);
+    Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2);
     Eigen::Vector3f trans_vector = Eigen::Vector3f (pose_mat (0, 3), pose_mat (1, 3), pose_mat (2, 3));
 
     pcl::PointXYZ center_point;
index e4a447b4d81c98acd4029676178ce1a9ec89aeb1..327c132c47a568d2b1f86550aff121eb588129ea 100644 (file)
@@ -479,7 +479,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces()
 
       Eigen::Matrix4f guess;
       guess.setIdentity ();
-      guess.block<3, 3> (0, 0) = matrixxx;
+      guess.topLeftCorner<3, 3> () = matrixxx;
       guess (0, 3) = head_clusters_centers_[i][0];
       guess (1, 3) = head_clusters_centers_[i][1];
       guess (2, 3) = head_clusters_centers_[i][2];
@@ -519,7 +519,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces()
       head_clusters_centers_[i][1] = icp_trans (1, 3);
       head_clusters_centers_[i][2] = icp_trans (2, 3);
 
-      Eigen::Vector3f ea = icp_trans.block<3, 3> (0, 0).eulerAngles (0, 1, 2);
+      Eigen::Vector3f ea = icp_trans.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2);
       head_clusters_rotation_[i][0] = ea[0];
       head_clusters_rotation_[i][1] = ea[1];
       head_clusters_rotation_[i][2] = ea[2];
index ed851c35009bc2e1e5001cbee8725481d33f1289..9efa48f4cb8ea68bde949a49ae3e30b9bd17e9a4 100644 (file)
@@ -43,6 +43,6 @@
 #include <pcl/recognition/impl/implicit_shape_model.hpp>
 
 // Instantiations of specific point types
-template class pcl::features::ISMVoteList<pcl::PointXYZ>;
+template class PCL_EXPORTS pcl::features::ISMVoteList<pcl::PointXYZ>;
 
-template class pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>;
+template class PCL_EXPORTS pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>;
index dd3d3efdabcbfcdacf201e9bac8cb15ec932b1e2..6efba154c12b10455039ec4a8a5b0e3062c24da4 100644 (file)
@@ -173,7 +173,7 @@ ModelLibrary::addToHashTable (Model* model, const ORROctree::Node::Data* data1,
   HashTableCell* cell = hash_table_.getVoxel (key);
 
   // Insert the pair (data1,data2) belonging to 'model'
-  (*cell)[model].push_back (std::pair<const ORROctree::Node::Data*, const ORROctree::Node::Data*> (data1, data2));
+  (*cell)[model].emplace_back(data1, data2);
 
   return (true);
 }
index a57b2d4bc6f9120fa6cce64c0e776a73e0f7ddf0..25aba5c0cb37c1b56ba11bd46027c6cf35d8e36d 100644 (file)
@@ -420,7 +420,7 @@ pcl::recognition::ObjRecRANSAC::buildGraphOfCloseHypotheses (HypothesisOctree& h
   i = 0;
 
   // Now create the graph connectivity such that each two neighboring rotation spaces are neighbors in the graph
-  for ( std::vector<HypothesisOctree::Node*>::const_iterator hypo = hypo_leaves.begin () ; hypo != hypo_leaves.end () ; ++hypo, ++i )
+  for ( auto hypo = hypo_leaves.cbegin () ; hypo != hypo_leaves.cend () ; ++hypo, ++i )
   {
     // Compute the fitness of the graph node
     graph.getNodes ()[i]->setFitness (static_cast<int> ((*hypo)->getData ().explained_pixels_.size ()));
index 7dce51a2f9117cc1bfee1cb3760e654e1ac9e7ab..ab15ffc2cc2e2f3610628205417e950243ce0975 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME registration)
 set(SUBSYS_DESC "Point cloud registration library")
 set(SUBSYS_DEPS common octree kdtree search sample_consensus features filters)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
@@ -13,8 +12,6 @@ if(NOT build)
 endif()
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/eigen.h"
-  "include/pcl/${SUBSYS_NAME}/boost.h"
   "include/pcl/${SUBSYS_NAME}/boost_graph.h"
   "include/pcl/${SUBSYS_NAME}/convergence_criteria.h"
   "include/pcl/${SUBSYS_NAME}/default_convergence_criteria.h"
@@ -52,7 +49,6 @@ set(incs
 
   "include/pcl/${SUBSYS_NAME}/pyramid_feature_matching.h"
   "include/pcl/${SUBSYS_NAME}/registration.h"
-  "include/pcl/${SUBSYS_NAME}/transforms.h"
   "include/pcl/${SUBSYS_NAME}/transformation_estimation.h"
   "include/pcl/${SUBSYS_NAME}/transformation_estimation_2D.h"
   "include/pcl/${SUBSYS_NAME}/transformation_estimation_svd.h"
@@ -87,17 +83,10 @@ set(impl_incs
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_estimation_normal_shooting.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_estimation_backprojection.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_estimation_organized_projection.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_distance.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_median_distance.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_surface_normal.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_features.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_one_to_one.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_poly.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_sample_consensus.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_sample_consensus_2d.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_trimmed.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_var_trimmed.hpp"
-  "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_organized_boundary.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/correspondence_types.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/ia_ransac.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/icp.hpp"
@@ -173,7 +162,6 @@ set(srcs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_kdtree pcl_search pcl_sample_consensus pcl_features pcl_filters)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
diff --git a/registration/include/pcl/registration/boost.h b/registration/include/pcl/registration/boost.h
deleted file mode 100644 (file)
index 6a6f17d..0000000
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-
-#pragma once
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-#if defined __GNUC__
-#pragma GCC system_header
-#endif
-
-//#include <boost/graph/adjacency_list.hpp>
-#include <boost/graph/dijkstra_shortest_paths.hpp>
-#include <boost/graph/graph_traits.hpp>
-#include <boost/noncopyable.hpp>
-#include <boost/property_map/property_map.hpp>
index bb1db6aab3ab871cbd1c7d9705597460882980d4..7dcffc258cffb02582af77fb40d5e865ad437e13 100644 (file)
@@ -137,6 +137,23 @@ public:
     return (target_);
   }
 
+  /** \brief Set the number of threads to use.
+   * \param nr_threads the number of hardware threads to use (0 sets the value back to
+   * automatic)
+   */
+  void
+  setNumberOfThreads(unsigned int nr_threads)
+  {
+#ifdef _OPENMP
+    num_threads_ = nr_threads != 0 ? nr_threads : omp_get_num_procs();
+#else
+    if (nr_threads != 1) {
+      PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
+    }
+    num_threads_ = 1;
+#endif
+  }
+
   /** \brief See if this rejector requires source normals */
   virtual bool
   requiresSourceNormals() const
@@ -362,11 +379,13 @@ protected:
   /** \brief A flag which, if set, means the tree operating on the source cloud
    * will never be recomputed*/
   bool force_no_recompute_reciprocal_{false};
+
+  unsigned int num_threads_{1};
 };
 
-/** \brief @b CorrespondenceEstimation represents the base class for
+/** \brief @b CorrespondenceEstimation represents a simple class for
  * determining correspondences between target and query point
- * sets/features.
+ * sets/features, using nearest neighbor search.
  *
  * Code example:
  *
@@ -479,6 +498,9 @@ public:
     Ptr copy(new CorrespondenceEstimation<PointSource, PointTarget, Scalar>(*this));
     return (copy);
   }
+
+protected:
+  using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::num_threads_;
 };
 } // namespace registration
 } // namespace pcl
index 44835c379fce0d4cd3c45f9886d7f4898b7b8d88..f3bab8fef014743590ff45b60951b2dc3c131286 100644 (file)
@@ -269,9 +269,9 @@ protected:
       // Check if the representations are valid
       if (!feature_representation_->isValid(feat_src) ||
           !feature_representation_->isValid(feat_tgt)) {
-        PCL_ERROR("[pcl::registration::%s::getCorrespondenceScore] Invalid feature "
-                  "representation given!\n",
-                  this->getClassName().c_str());
+        PCL_ERROR(
+            "[pcl::registration::CorrespondenceRejectorFeatures::FeatureContainer::"
+            "getCorrespondenceScore] Invalid feature representation given!\n");
         return (std::numeric_limits<double>::max());
       }
 
diff --git a/registration/include/pcl/registration/eigen.h b/registration/include/pcl/registration/eigen.h
deleted file mode 100644 (file)
index 5712e8f..0000000
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#pragma GCC system_header
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-
-#include <Eigen/Core>
-#include <Eigen/Dense>
-#include <Eigen/Geometry>
-#include <unsupported/Eigen/Polynomials>
index 4084c6444e02cca60a060e7d7f42d2f7ad909caf..99a9288250e99583dad7af62548fdda9d1dab879 100644 (file)
@@ -52,6 +52,22 @@ namespace pcl {
  * The original code uses GSL and ANN while in ours we use FLANN and Newton's method
  * for optimization (call `useBFGS` to switch to BFGS optimizer, however Newton
  * is usually faster and more accurate).
+ * Basic usage example:
+ * \code
+ * pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> reg;
+ * reg.setInputSource(src);
+ * reg.setInputTarget(tgt);
+ * // use default parameters or set them yourself, for example:
+ * // reg.setMaximumIterations(...);
+ * // reg.setTransformationEpsilon(...);
+ * // reg.setRotationEpsilon(...);
+ * // reg.setCorrespondenceRandomness(...);
+ * pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
+ * // supply a better guess, if possible:
+ * Eigen::Matrix4f guess = Eigen::Matrix4f::Identity();
+ * reg.align(*output, guess);
+ * std::cout << reg.getFinalTransformation() << std::endl;
+ * \endcode
  * \author Nizar Sallem
  * \ingroup registration
  */
@@ -125,6 +141,7 @@ public:
     max_iterations_ = 200;
     transformation_epsilon_ = 5e-4;
     corr_dist_threshold_ = 5.;
+    setNumberOfThreads(0);
     rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src,
                                               const pcl::Indices& indices_src,
                                               const PointCloudTarget& cloud_tgt,
@@ -355,6 +372,13 @@ public:
     return rotation_gradient_tolerance_;
   }
 
+  /** \brief Initialize the scheduler and set the number of threads to use.
+   * \param nr_threads the number of hardware threads to use (0 sets the value back to
+   * automatic)
+   */
+  void
+  setNumberOfThreads(unsigned int nr_threads = 0);
+
 protected:
   /** \brief The number of neighbors used for covariances computation.
    * default: 20
@@ -508,6 +532,9 @@ private:
                      Eigen::Matrix3d& ddR_dTheta_dTheta,
                      Eigen::Matrix3d& ddR_dTheta_dPsi,
                      Eigen::Matrix3d& ddR_dPsi_dPsi) const;
+
+  /** \brief The number of threads the scheduler should use. */
+  unsigned int threads_;
 };
 } // namespace pcl
 
index abff434f52711113725b3045c993f6d2119536c0..afb9f25280558480620f5b370b2c5d58eb1fe921 100644 (file)
@@ -415,6 +415,7 @@ protected:
    * \param[in] match_indices indices of match M
    * \param[out] correspondences resulting correspondences
    */
+  PCL_DEPRECATED(1, 18, "this function has a bug and is generally not needed")
   virtual void
   linkMatchWithBase(const pcl::Indices& base_indices,
                     pcl::Indices& match_indices,
@@ -427,7 +428,7 @@ protected:
    *
    * \param[in] base_indices indices of base B
    * \param[in] match_indices indices of match M
-   * \param[in] correspondences corresondences between source and target
+   * \param[in] correspondences correspondences between source and target
    * \param[out] transformation resulting transformation matrix
    * \return
    * * < 0 MSE bigger than max_mse_
index ac32c58b4807197ee717959c0d7b397162722a47..8f3136c07acd4b62849fd626d3a46e878cf60acb 100644 (file)
@@ -44,8 +44,18 @@ namespace registration {
  * on keypoints as described in: "Markerless point cloud registration with
  * keypoint-based 4-points congruent sets", Pascal Theiler, Jan Dirk Wegner, Konrad
  * Schindler. ISPRS Annals II-5/W2, 2013. Presented at ISPRS Workshop Laser Scanning,
- * Antalya, Turkey, 2013. \note Method has since been improved and some variations to
- * the paper exist. \author P.W.Theiler \ingroup registration
+ * Antalya, Turkey, 2013.
+ * \note Method has since been improved and some variations to the paper exist.
+ *
+ * The main differences to FPCSInitialAlignment are:
+ * <ol>
+ *   <li> KFPCSInitialAlignment stores all solution candidates instead of only the best
+ * one
+ *   <li> KFPCSInitialAlignment uses an MSAC approach to score candidates instead of
+ * counting inliers
+ * </ol>
+ * \author P.W.Theiler
+ * \ingroup registration
  */
 template <typename PointSource,
           typename PointTarget,
@@ -187,8 +197,6 @@ protected:
   using FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::fitness_score_;
   using FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::
       score_threshold_;
-  using FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::
-      linkMatchWithBase;
   using FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::validateMatch;
 
   /** \brief Internal computation initialization. */
index 8127b10d0293ae8e07a35d1d587ca0eb3c960456..dbba310952ab54ea5da1484e3afc1045f238f9bb 100644 (file)
@@ -261,6 +261,16 @@ public:
     return (use_reciprocal_correspondence_);
   }
 
+  /** \brief Set the number of threads to use.
+   * \param nr_threads the number of hardware threads to use (0 sets the value back to
+   * automatic)
+   */
+  void
+  setNumberOfThreads(unsigned int nr_threads)
+  {
+    correspondence_estimation_->setNumberOfThreads(nr_threads);
+  }
+
 protected:
   /** \brief Apply a rigid transform to a given dataset. Here we check whether
    * the dataset has surface normals in addition to XYZ, and rotate normals as well.
index 50eb5b0fc66076fa740590e4121b8612b0c67110..676c17876cff9128b18f3757fd6a9bc8f8363656 100644 (file)
@@ -43,6 +43,7 @@
 
 #include <pcl/common/copy_point.h>
 #include <pcl/common/io.h>
+#include <pcl/common/point_tests.h> // for isXYZFinite
 
 namespace pcl {
 
@@ -153,27 +154,66 @@ CorrespondenceEstimation<PointSource, PointTarget, Scalar>::determineCorresponde
 
   pcl::Indices index(1);
   std::vector<float> distance(1);
-  pcl::Correspondence corr;
-  unsigned int nr_valid_correspondences = 0;
+  std::vector<pcl::Correspondences> per_thread_correspondences(num_threads_);
+  for (auto& corrs : per_thread_correspondences) {
+    corrs.reserve(2 * indices_->size() / num_threads_);
+  }
   double max_dist_sqr = max_distance * max_distance;
 
+#pragma omp parallel for default(none)                                                 \
+    shared(max_dist_sqr, per_thread_correspondences) firstprivate(index, distance)     \
+        num_threads(num_threads_)
   // Iterate over the input set of source indices
-  for (const auto& idx : (*indices_)) {
+  for (int i = 0; i < static_cast<int>(indices_->size()); i++) {
+    const auto& idx = (*indices_)[i];
     // Check if the template types are the same. If true, avoid a copy.
     // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT
     // macro!
     const auto& pt = detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx);
+    if (!input_->is_dense && !pcl::isXYZFinite(pt))
+      continue;
     tree_->nearestKSearch(pt, 1, index, distance);
     if (distance[0] > max_dist_sqr)
       continue;
 
+    pcl::Correspondence corr;
     corr.index_query = idx;
     corr.index_match = index[0];
     corr.distance = distance[0];
-    correspondences[nr_valid_correspondences++] = corr;
+
+#ifdef _OPENMP
+    const int thread_num = omp_get_thread_num();
+#else
+    const int thread_num = 0;
+#endif
+
+    per_thread_correspondences[thread_num].emplace_back(corr);
   }
 
-  correspondences.resize(nr_valid_correspondences);
+  if (num_threads_ == 1) {
+    correspondences = std::move(per_thread_correspondences.front());
+  }
+  else {
+    const unsigned int nr_correspondences = std::accumulate(
+        per_thread_correspondences.begin(),
+        per_thread_correspondences.end(),
+        static_cast<unsigned int>(0),
+        [](const auto sum, const auto& corr) { return sum + corr.size(); });
+    correspondences.resize(nr_correspondences);
+
+    // Merge per-thread correspondences while keeping them ordered
+    auto insert_loc = correspondences.begin();
+    for (const auto& corrs : per_thread_correspondences) {
+      const auto new_insert_loc = std::move(corrs.begin(), corrs.end(), insert_loc);
+      std::inplace_merge(correspondences.begin(),
+                         insert_loc,
+                         insert_loc + corrs.size(),
+                         [](const auto& lhs, const auto& rhs) {
+                           return lhs.index_query < rhs.index_query;
+                         });
+      insert_loc = new_insert_loc;
+    }
+  }
   deinitCompute();
 }
 
@@ -197,23 +237,30 @@ CorrespondenceEstimation<PointSource, PointTarget, Scalar>::
   std::vector<float> distance(1);
   pcl::Indices index_reciprocal(1);
   std::vector<float> distance_reciprocal(1);
-  pcl::Correspondence corr;
-  unsigned int nr_valid_correspondences = 0;
-  int target_idx = 0;
+  std::vector<pcl::Correspondences> per_thread_correspondences(num_threads_);
+  for (auto& corrs : per_thread_correspondences) {
+    corrs.reserve(2 * indices_->size() / num_threads_);
+  }
 
+#pragma omp parallel for default(none)                                                 \
+    shared(max_dist_sqr, per_thread_correspondences)                                   \
+        firstprivate(index, distance, index_reciprocal, distance_reciprocal)           \
+            num_threads(num_threads_)
   // Iterate over the input set of source indices
-  for (const auto& idx : (*indices_)) {
+  for (int i = 0; i < static_cast<int>(indices_->size()); i++) {
+    const auto& idx = (*indices_)[i];
     // Check if the template types are the same. If true, avoid a copy.
     // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT
     // macro!
 
     const auto& pt_src = detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx);
-
+    if (!input_->is_dense && !pcl::isXYZFinite(pt_src))
+      continue;
     tree_->nearestKSearch(pt_src, 1, index, distance);
     if (distance[0] > max_dist_sqr)
       continue;
 
-    target_idx = index[0];
+    const auto target_idx = index[0];
     const auto& pt_tgt =
         detail::pointCopyOrRef<PointSource, PointTarget>(target_, target_idx);
 
@@ -221,12 +268,45 @@ CorrespondenceEstimation<PointSource, PointTarget, Scalar>::
     if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0])
       continue;
 
+    pcl::Correspondence corr;
     corr.index_query = idx;
     corr.index_match = index[0];
     corr.distance = distance[0];
-    correspondences[nr_valid_correspondences++] = corr;
+
+#ifdef _OPENMP
+    const int thread_num = omp_get_thread_num();
+#else
+    const int thread_num = 0;
+#endif
+
+    per_thread_correspondences[thread_num].emplace_back(corr);
   }
-  correspondences.resize(nr_valid_correspondences);
+
+  if (num_threads_ == 1) {
+    correspondences = std::move(per_thread_correspondences.front());
+  }
+  else {
+    const unsigned int nr_correspondences = std::accumulate(
+        per_thread_correspondences.begin(),
+        per_thread_correspondences.end(),
+        static_cast<unsigned int>(0),
+        [](const auto sum, const auto& corr) { return sum + corr.size(); });
+    correspondences.resize(nr_correspondences);
+
+    // Merge per-thread correspondences while keeping them ordered
+    auto insert_loc = correspondences.begin();
+    for (const auto& corrs : per_thread_correspondences) {
+      const auto new_insert_loc = std::move(corrs.begin(), corrs.end(), insert_loc);
+      std::inplace_merge(correspondences.begin(),
+                         insert_loc,
+                         insert_loc + corrs.size(),
+                         [](const auto& lhs, const auto& rhs) {
+                           return lhs.index_query < rhs.index_query;
+                         });
+      insert_loc = new_insert_loc;
+    }
+  }
+
   deinitCompute();
 }
 
diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_distance.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_distance.hpp
deleted file mode 100644 (file)
index 680ed69..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_
-#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_
-PCL_DEPRECATED_HEADER(1, 15, "")
-#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_ */
diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_median_distance.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_median_distance.hpp
deleted file mode 100644 (file)
index eaa5364..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_
-#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_
-PCL_DEPRECATED_HEADER(1, 15, "")
-#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_
diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_one_to_one.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_one_to_one.hpp
deleted file mode 100644 (file)
index 3f25683..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_
-#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_
-PCL_DEPRECATED_HEADER(1, 15, "")
-#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_ */
diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp
deleted file mode 100644 (file)
index c70ea72..0000000
+++ /dev/null
@@ -1,42 +0,0 @@
-/*
- *  Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2009-2012, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *  Copyright (c) Alexandru-Eugen Ichim
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of the copyright holder(s) nor the names of its
- *    contributors may be used to endorse or promote products derived
- *    from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_
-#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_
-PCL_DEPRECATED_HEADER(1, 15, "")
-#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_ */
diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_surface_normal.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_surface_normal.hpp
deleted file mode 100644 (file)
index 65e8bbc..0000000
+++ /dev/null
@@ -1,42 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_
-#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_
-PCL_DEPRECATED_HEADER(1, 15, "")
-#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_ */
diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_trimmed.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_trimmed.hpp
deleted file mode 100644 (file)
index 9aee8cd..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_
-#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_
-PCL_DEPRECATED_HEADER(1, 15, "")
-#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_ */
diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp
deleted file mode 100644 (file)
index 201c6d4..0000000
+++ /dev/null
@@ -1,42 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_
-#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_
-PCL_DEPRECATED_HEADER(1, 15, "")
-#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_ */
index 9b4c940bc796f1b09f1e8f0ec4046b4621dd2707..d7eb1353b9303b701ab624762fb3a1220e7eabdd 100644 (file)
@@ -91,10 +91,17 @@ DefaultConvergenceCriteria<Scalar>::hasConverged()
   }
 
   correspondences_cur_mse_ = calculateMSE(correspondences_);
-  PCL_DEBUG("[pcl::DefaultConvergenceCriteria::hasConverged] Previous / Current MSE "
-            "for correspondences distances is: %f / %f.\n",
-            correspondences_prev_mse_,
-            correspondences_cur_mse_);
+  if (std::numeric_limits<double>::max() == correspondences_prev_mse_) {
+    PCL_DEBUG("[pcl::DefaultConvergenceCriteria::hasConverged] Previous / Current MSE "
+              "for correspondences distances is: INIT / %f.\n",
+              correspondences_cur_mse_);
+  }
+  else {
+    PCL_DEBUG("[pcl::DefaultConvergenceCriteria::hasConverged] Previous / Current MSE "
+              "for correspondences distances is: %f / %f.\n",
+              correspondences_prev_mse_,
+              correspondences_cur_mse_);
+  }
 
   // 3. The relative sum of Euclidean squared errors is smaller than a user defined
   // threshold Absolute
index 647386cf8808618b6fab491089efa0c2ecf84746..b1dc7535c53520b88b3aba90fe4eeec8c3ccf33b 100644 (file)
@@ -192,7 +192,7 @@ pcl::registration::ELCH<PointT>::initCompute()
 
     PointCloudPtr tmp(new PointCloud);
     // Eigen::Vector4f diff = pose_start - pose_end;
-    // Eigen::Translation3f translation (diff.head (3));
+    // Eigen::Translation3f translation (diff.head<3> ());
     // Eigen::Affine3f trans = translation * Eigen::Quaternionf::Identity ();
     // pcl::transformPointCloud (*(*loop_graph_)[loop_end_].cloud, *tmp, trans);
 
@@ -240,7 +240,7 @@ pcl::registration::ELCH<PointT>::compute()
   // TODO use pose
   // Eigen::Vector4f cend;
   // pcl::compute3DCentroid (*((*loop_graph_)[loop_end_].cloud), cend);
-  // Eigen::Translation3f tend (cend.head (3));
+  // Eigen::Translation3f tend (cend.head<3> ());
   // Eigen::Affine3f aend (tend);
   // Eigen::Affine3f aendI = aend.inverse ();
 
index 3e1bcb62ed6acd88aea00ce216b3e081683ccff8..93fb7c8198bd860a7f356a3725ba568b4a71dd45 100644 (file)
 
 namespace pcl {
 
+template <typename PointSource, typename PointTarget, typename Scalar>
+void
+GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::setNumberOfThreads(
+    unsigned int nr_threads)
+{
+#ifdef _OPENMP
+  if (nr_threads == 0)
+    threads_ = omp_get_num_procs();
+  else
+    threads_ = nr_threads;
+  PCL_DEBUG("[pcl::GeneralizedIterativeClosestPoint::setNumberOfThreads] Setting "
+            "number of threads to %u.\n",
+            threads_);
+#else
+  threads_ = 1;
+  if (nr_threads != 1)
+    PCL_WARN("[pcl::GeneralizedIterativeClosestPoint::setNumberOfThreads] "
+             "Parallelization is requested, but OpenMP is not available! Continuing "
+             "without parallelization.\n");
+#endif // _OPENMP
+}
+
 template <typename PointSource, typename PointTarget, typename Scalar>
 template <typename PointT>
 void
@@ -62,6 +84,7 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
   }
 
   Eigen::Vector3d mean;
+  Eigen::Matrix3d cov;
   pcl::Indices nn_indices(k_correspondences_);
   std::vector<float> nn_dist_sq(k_correspondences_);
 
@@ -69,11 +92,10 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
   if (cloud_covariances.size() < cloud->size())
     cloud_covariances.resize(cloud->size());
 
-  auto matrices_iterator = cloud_covariances.begin();
-  for (auto points_iterator = cloud->begin(); points_iterator != cloud->end();
-       ++points_iterator, ++matrices_iterator) {
-    const PointT& query_point = *points_iterator;
-    Eigen::Matrix3d& cov = *matrices_iterator;
+#pragma omp parallel for num_threads(threads_) schedule(dynamic, 32)                   \
+    shared(cloud, cloud_covariances) firstprivate(mean, cov, nn_indices, nn_dist_sq)
+  for (std::ptrdiff_t i = 0; i < static_cast<std::ptrdiff_t>(cloud->size()); ++i) {
+    const PointT& query_point = (*cloud)[i];
     // Zero out the cov and mean
     cov.setZero();
     mean.setZero();
@@ -124,6 +146,7 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
         v = gicp_epsilon_;
       cov += v * col * col.transpose();
     }
+    cloud_covariances[i] = cov;
   }
 }
 
@@ -635,9 +658,9 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
                             p_trans_src[1] - p_tgt[1],
                             p_trans_src[2] - p_tgt[2]);
     const Eigen::Matrix3d& M = gicp_->mahalanobis(src_idx);
-    const Eigen::Vector3d Md(M * d); // Md = M*d
-    gradient.head<3>() += Md;        // translation gradient
-    hessian.block<3, 3>(0, 0) += M;  // translation-translation hessian
+    const Eigen::Vector3d Md(M * d);    // Md = M*d
+    gradient.head<3>() += Md;           // translation gradient
+    hessian.topLeftCorner<3, 3>() += M; // translation-translation hessian
     p_trans_src = base_transformation_float * p_src;
     const Eigen::Vector3d p_base_src(p_trans_src[0], p_trans_src[1], p_trans_src[2]);
     dCost_dR_T.noalias() += p_base_src * Md.transpose();
@@ -657,7 +680,7 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
   gradient.head<3>() *= 2.0 / m; // translation gradient
   dCost_dR_T *= 2.0 / m;
   gicp_->computeRDerivative(x, dCost_dR_T, gradient); // rotation gradient
-  hessian.block<3, 3>(0, 0) *= 2.0 / m;               // translation-translation hessian
+  hessian.topLeftCorner<3, 3>() *= 2.0 / m;           // translation-translation hessian
   // translation-rotation hessian
   dCost_dR_T1.row(0) = dCost_dR_T1b.col(0);
   dCost_dR_T1.row(1) = dCost_dR_T2b.col(0);
index d73e56c3c3d1fbfa1d02fd24d79f2b413f002cc3..31533621a82a8c44698e88217978695f64072b7b 100644 (file)
@@ -41,6 +41,7 @@
 #include <pcl/common/distances.h>
 #include <pcl/common/time.h>
 #include <pcl/common/utils.h>
+#include <pcl/filters/random_sample.h>
 #include <pcl/registration/ia_fpcs.h>
 #include <pcl/registration/transformation_estimation_3point.h>
 #include <pcl/sample_consensus/sac_model_plane.h>
@@ -189,9 +190,19 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
         }
 
         // check terminate early (time or fitness_score threshold reached)
-        abort = (!candidates.empty() ? candidates[0].fitness_score < score_threshold_
-                                     : abort);
-        abort = (abort ? abort : timer.getTimeSeconds() > max_runtime_);
+        if (!candidates.empty() && candidates[0].fitness_score < score_threshold_) {
+          PCL_DEBUG("[%s::computeTransformation] Terminating because fitness score "
+                    "(%g) is below threshold (%g).\n",
+                    reg_name_.c_str(),
+                    candidates[0].fitness_score,
+                    score_threshold_);
+          abort = true;
+        }
+        else if (timer.getTimeSeconds() > max_runtime_) {
+          PCL_DEBUG("[%s::computeTransformation] Terminating because time exceeded.\n",
+                    reg_name_.c_str());
+          abort = true;
+        }
 
 #pragma omp flush(abort)
       }
@@ -238,14 +249,14 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
 
   // if a sample size for the point clouds is given; preferably no sampling of target
   // cloud
-  if (nr_samples_ != 0) {
-    const int ss = static_cast<int>(indices_->size());
-    const int sample_fraction_src = std::max(1, static_cast<int>(ss / nr_samples_));
-
+  if (nr_samples_ > 0 && static_cast<std::size_t>(nr_samples_) < indices_->size()) {
     source_indices_ = pcl::IndicesPtr(new pcl::Indices);
-    for (int i = 0; i < ss; i++)
-      if (rand() % sample_fraction_src == 0)
-        source_indices_->push_back((*indices_)[i]);
+    pcl::RandomSample<PointSource> random_sampling;
+    random_sampling.setInputCloud(input_);
+    random_sampling.setIndices(indices_);
+    random_sampling.setSample(nr_samples_);
+    random_sampling.setSeed(seed);
+    random_sampling.filter(*source_indices_);
   }
   else
     source_indices_ = indices_;
@@ -274,6 +285,15 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
   float max_base_diameter = diameter_ * approx_overlap_ * 2.f;
   max_base_diameter_sqr_ = max_base_diameter * max_base_diameter;
 
+#ifdef _OPENMP
+  if (nr_threads_ < 1) {
+    nr_threads_ = omp_get_num_procs();
+    PCL_DEBUG("[%s::initCompute] Setting number of threads to %i.\n",
+              reg_name_.c_str(),
+              nr_threads_);
+  }
+#endif // _OPENMP
+
   // normalize the delta
   if (normalize_delta_) {
     float mean_dist = getMeanPointDensity<PointTarget>(
@@ -289,6 +309,9 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
                                               static_cast<double>(min_iterations)));
     max_iterations_ =
         static_cast<int>(first_est / (diameter_fraction * approx_overlap_ * 2.f));
+    PCL_DEBUG("[%s::initCompute] Estimated max iterations as %i\n",
+              reg_name_.c_str(),
+              max_iterations_);
   }
 
   // set further parameter
@@ -307,6 +330,14 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
   coincidation_limit_ = delta_ * 2.f; // EDITED: originally std::sqrt (delta_ * 2.f)
   max_mse_ = powf(delta_ * 2.f, 2.f);
   max_inlier_dist_sqr_ = powf(delta_ * 2.f, 2.f);
+  PCL_DEBUG("[%s::initCompute] delta_=%g, max_inlier_dist_sqr_=%g, "
+            "coincidation_limit_=%g, max_edge_diff_=%g, max_pair_diff_=%g\n",
+            reg_name_.c_str(),
+            delta_,
+            max_inlier_dist_sqr_,
+            coincidation_limit_,
+            max_edge_diff_,
+            max_pair_diff_);
 
   // reset fitness_score
   fitness_score_ = std::numeric_limits<float>::max();
@@ -350,7 +381,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
       float d1 = pcl::squaredEuclideanDistance(*pt4, *pt1);
       float d2 = pcl::squaredEuclideanDistance(*pt4, *pt2);
       float d3 = pcl::squaredEuclideanDistance(*pt4, *pt3);
-      float d4 = (pt4->getVector3fMap() - centre_pt.head(3)).squaredNorm();
+      float d4 = (pt4->getVector3fMap() - centre_pt.head<3>()).squaredNorm();
 
       // check distance between points w.r.t minimum sampling distance; EDITED -> 4th
       // point now also limited by max base line
@@ -590,8 +621,8 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
             continue;
         }
 
-        pairs.push_back(pcl::Correspondence(*it_in, *it_out, dist));
-        pairs.push_back(pcl::Correspondence(*it_out, *it_in, dist));
+        pairs.emplace_back(*it_in, *it_out, dist);
+        pairs.emplace_back(*it_out, *it_in, dist);
       }
     }
   }
@@ -668,6 +699,11 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
             pairs_a[static_cast<int>(std::floor((id / 2.f)))].index_query;
         match_indices[2] = pair.index_match;
         match_indices[3] = pair.index_query;
+        if (match_indices[0] == match_indices[2] ||
+            match_indices[0] == match_indices[3] ||
+            match_indices[1] == match_indices[2] ||
+            match_indices[1] == match_indices[3])
+          continue;
 
         // EDITED: added coarse check of match based on edge length (due to rigid-body )
         if (checkBaseMatch(match_indices, dist_base) < 0)
@@ -679,7 +715,16 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
   }
 
   // return unsuccessful if no match was found
-  return (!matches.empty() ? 0 : -1);
+  if (matches.empty()) {
+    PCL_DEBUG("[%s::determineBaseMatches] no matches found\n", reg_name_.c_str());
+    return -1;
+  }
+  else {
+    PCL_DEBUG("[%s::determineBaseMatches] found %zu matches\n",
+              reg_name_.c_str(),
+              matches.size());
+    return 0;
+  }
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////
@@ -721,10 +766,10 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
   for (auto& match : matches) {
     Eigen::Matrix4f transformation_temp;
     pcl::Correspondences correspondences_temp;
-
-    // determine corresondences between base and match according to their distance to
-    // centroid
-    linkMatchWithBase(base_indices, match, correspondences_temp);
+    correspondences_temp.emplace_back(match[0], base_indices[0], 0.0);
+    correspondences_temp.emplace_back(match[1], base_indices[1], 0.0);
+    correspondences_temp.emplace_back(match[2], base_indices[2], 0.0);
+    correspondences_temp.emplace_back(match[3], base_indices[3], 0.0);
 
     // check match based on residuals of the corresponding points after
     if (validateMatch(base_indices, match, correspondences_temp, transformation_temp) <
@@ -792,7 +837,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
     }
 
     // assign new correspondence and update indices of matched targets
-    correspondences.push_back(pcl::Correspondence(best_index, *it_base, best_diff_sqr));
+    correspondences.emplace_back(best_index, *it_base, best_diff_sqr);
     *it_match_orig = best_index;
   }
 }
@@ -846,8 +891,8 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
                         : static_cast<std::size_t>((1.f - fitness_score) * nr_points);
 
   float inlier_score_temp = 0;
-  pcl::Indices ids;
-  std::vector<float> dists_sqr;
+  pcl::Indices ids(1);
+  std::vector<float> dists_sqr(1);
   auto it = source_transformed.begin();
 
   for (std::size_t i = 0; i < nr_points; it++, i++) {
@@ -888,6 +933,12 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
       best_index = i;
     }
   }
+  PCL_DEBUG(
+      "[%s::finalCompute] best score is %g (iteration %i), out of %zu iterations.\n",
+      reg_name_.c_str(),
+      best_score,
+      best_index,
+      candidates.size());
 
   // check if a valid candidate was available
   if (!(best_index < 0)) {
index 93a9bc570eeb91f97f850de8fb80981db5264ec4..42241d3c3817224e4b5d4b8f1e2a1feb7413cf78 100644 (file)
@@ -90,13 +90,26 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::initCompute()
 
   // generate a subset of indices of size ransac_iterations_ on which to evaluate
   // candidates on
-  std::size_t nr_indices = indices_->size();
-  if (nr_indices < static_cast<std::size_t>(ransac_iterations_))
+  if (indices_->size() <= static_cast<std::size_t>(ransac_iterations_) ||
+      ransac_iterations_ <= 0)
     indices_validation_ = indices_;
-  else
-    for (int i = 0; i < ransac_iterations_; i++)
-      indices_validation_->push_back((*indices_)[rand() % nr_indices]);
+  else {
+    indices_validation_.reset(new pcl::Indices);
+    pcl::RandomSample<PointSource> random_sampling;
+    random_sampling.setInputCloud(input_);
+    random_sampling.setIndices(indices_);
+    random_sampling.setSample(ransac_iterations_);
+    random_sampling.filter(*indices_validation_);
+  }
 
+  PCL_DEBUG("[%s::initCompute] delta_=%g, max_inlier_dist_sqr_=%g, "
+            "coincidation_limit_=%g, max_edge_diff_=%g, max_pair_diff_=%g\n",
+            reg_name_.c_str(),
+            delta_,
+            max_inlier_dist_sqr_,
+            coincidation_limit_,
+            max_edge_diff_,
+            max_pair_diff_);
   return (true);
 }
 
@@ -117,9 +130,10 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::handleMatches(
         std::numeric_limits<float>::max(); // reset to std::numeric_limits<float>::max()
                                            // to accept all candidates and not only best
 
-    // determine corresondences between base and match according to their distance to
-    // centroid
-    linkMatchWithBase(base_indices, match, correspondences_temp);
+    correspondences_temp.emplace_back(match[0], base_indices[0], 0.0);
+    correspondences_temp.emplace_back(match[1], base_indices[1], 0.0);
+    correspondences_temp.emplace_back(match[2], base_indices[2], 0.0);
+    correspondences_temp.emplace_back(match[3], base_indices[3], 0.0);
 
     // check match based on residuals of the corresponding points after transformation
     if (validateMatch(base_indices, match, correspondences_temp, transformation_temp) <
@@ -131,8 +145,17 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::handleMatches(
     validateTransformation(transformation_temp, fitness_score);
 
     // store all valid match as well as associated score and transformation
-    candidates.push_back(
-        MatchingCandidate(fitness_score, correspondences_temp, transformation_temp));
+    candidates.emplace_back(fitness_score, correspondences_temp, transformation_temp);
+  }
+  // make sure that candidate with best fitness score is at the front, for early
+  // termination check
+  if (!candidates.empty()) {
+    auto best_candidate = candidates.begin();
+    for (auto iter = candidates.begin(); iter < candidates.end(); ++iter)
+      if (iter->fitness_score < best_candidate->fitness_score)
+        best_candidate = iter;
+    if (best_candidate != candidates.begin())
+      std::swap(*best_candidate, *candidates.begin());
   }
 }
 
@@ -150,8 +173,8 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::
   float score_a = 0.f, score_b = 0.f;
 
   // residual costs based on mse
-  pcl::Indices ids;
-  std::vector<float> dists_sqr;
+  pcl::Indices ids(1);
+  std::vector<float> dists_sqr(1);
   for (const auto& source : source_transformed) {
     // search for nearest point using kd tree search
     tree_->nearestKSearch(source, 1, ids, dists_sqr);
@@ -166,7 +189,7 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::
   // translation score (solutions with small translation are down-voted)
   float scale = 1.f;
   if (use_trl_score_) {
-    float trl = transformation.rightCols<1>().head(3).norm();
+    float trl = transformation.rightCols<1>().head<3>().norm();
     float trl_ratio =
         (trl - lower_trl_boundary_) / (upper_trl_boundary_ - lower_trl_boundary_);
 
@@ -220,6 +243,10 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::finalCompute(
   fitness_score_ = candidates_[0].fitness_score;
   final_transformation_ = candidates_[0].transformation;
   *correspondences_ = candidates_[0].correspondences;
+  PCL_DEBUG("[%s::finalCompute] best score is %g, out of %zu candidate solutions.\n",
+            reg_name_.c_str(),
+            fitness_score_,
+            candidates_.size());
 
   // here we define convergence if resulting score is above threshold
   converged_ = fitness_score_ < score_threshold_;
@@ -244,7 +271,7 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::getNBestCandid
     for (const auto& c2 : candidates) {
       Eigen::Matrix4f diff =
           candidate.transformation.colPivHouseholderQr().solve(c2.transformation);
-      const float angle3d = Eigen::AngleAxisf(diff.block<3, 3>(0, 0)).angle();
+      const float angle3d = Eigen::AngleAxisf(diff.topLeftCorner<3, 3>()).angle();
       const float translation3d = diff.block<3, 1>(0, 3).norm();
       unique = angle3d > min_angle3d && translation3d > min_translation3d;
       if (!unique) {
@@ -281,7 +308,7 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::getTBestCandid
     for (const auto& c2 : candidates) {
       Eigen::Matrix4f diff =
           candidate.transformation.colPivHouseholderQr().solve(c2.transformation);
-      const float angle3d = Eigen::AngleAxisf(diff.block<3, 3>(0, 0)).angle();
+      const float angle3d = Eigen::AngleAxisf(diff.topLeftCorner<3, 3>()).angle();
       const float translation3d = diff.block<3, 1>(0, 3).norm();
       unique = angle3d > min_angle3d && translation3d > min_translation3d;
       if (!unique) {
index 3e01b9810a62fcb01a38d039fb9055774a463cb7..b735738502256f268a63927667683cf7d7af806d 100644 (file)
@@ -37,7 +37,4 @@
  * $Id$
  *
  */
-#ifndef PCL_REGISTRATION_ICP_NL_HPP_
-#define PCL_REGISTRATION_ICP_NL_HPP_
-
-#endif /* PCL_REGISTRATION_ICP_NL_HPP_ */
+PCL_DEPRECATED_HEADER(1, 18, "Do not include icp_nl.hpp, it is empty.")
index faa1d6f575de421593353535ca123795d56c5038..852759ee75c687e4361f9144ccd6f7e79f5f421a 100644 (file)
@@ -254,8 +254,8 @@ LUM<PointT>::compute()
 
         // Fill in elements of G and B
         if (vj > 0)
-          G.block(6 * (vi - 1), 6 * (vj - 1), 6, 6) = -(*slam_graph_)[e].cinv_;
-        G.block(6 * (vi - 1), 6 * (vi - 1), 6, 6) += (*slam_graph_)[e].cinv_;
+          G.block<6, 6>(6 * (vi - 1), 6 * (vj - 1)) = -(*slam_graph_)[e].cinv_;
+        G.block<6, 6>(6 * (vi - 1), 6 * (vi - 1)) += (*slam_graph_)[e].cinv_;
         B.segment(6 * (vi - 1), 6) += (present1 ? 1 : -1) * (*slam_graph_)[e].cinvd_;
       }
     }
@@ -268,7 +268,7 @@ LUM<PointT>::compute()
     // Update the poses
     float sum = 0.0;
     for (int vi = 1; vi != n; ++vi) {
-      Eigen::Vector6f difference_pose = static_cast<Eigen::Vector6f>(
+      auto difference_pose = static_cast<Eigen::Vector6f>(
           -incidenceCorrection(getPose(vi)).inverse() * X.segment(6 * (vi - 1), 6));
       sum += difference_pose.norm();
       setPose(vi, getPose(vi) + difference_pose);
index 15ac5d68e4bcc0cf098c35fb9c1c592674ae14e5..b6df6802115a9fcb855a24d7f647480601271cc0 100644 (file)
@@ -730,8 +730,8 @@ NormalDistributionsTransform<PointSource, PointTarget, Scalar>::computeStepLengt
   // the sufficient decrease, Equation 1.1, and curvature condition, Equation 1.2 [More,
   // Thuente 1994]
   while (!interval_converged && step_iterations < max_step_iterations &&
-         !(psi_t <= 0 /*Sufficient Decrease*/ &&
-           d_phi_t <= -nu * d_phi_0 /*Curvature Condition*/)) {
+         (psi_t > 0 /*Sufficient Decrease*/ ||
+          d_phi_t > -nu * d_phi_0 /*Curvature Condition*/)) {
     // Use auxiliary function if interval I is not closed
     if (open_interval) {
       a_t = trialValueSelectionMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t);
index ba7b4eebd0a7d8bcc105c4b86e1fbafc1f6ccaa2..4ced722e45a4b2e071336887c581b3dac943cd8f 100644 (file)
@@ -299,8 +299,8 @@ PyramidFeatureHistogram<PointFeature>::compute()
   if (!initializeHistogram())
     return;
 
+  std::vector<float> feature_vector; // put here to reuse memory
   for (const auto& point : *input_) {
-    std::vector<float> feature_vector;
     // NaN is converted to very high number that gives out of bound exception.
     if (!pcl::isFinite(point))
       continue;
index 24a454efabd394958f01cafc342d987fa3e50d65..db0faef597f28e9997c242b52915559abec63a0e 100644 (file)
@@ -145,6 +145,8 @@ Registration<PointSource, PointTarget, Scalar>::getFitnessScore(double max_range
   // For each point in the source dataset
   int nr = 0;
   for (const auto& point : input_transformed) {
+    if (!input_->is_dense && !pcl::isXYZFinite(point))
+      continue;
     // Find its nearest neighbor in the target
     tree_->nearestKSearch(point, 1, nn_indices, nn_dists);
 
@@ -214,4 +216,4 @@ Registration<PointSource, PointTarget, Scalar>::align(PointCloudSource& output,
   deinitCompute();
 }
 
-} // namespace pcl
+} // namespace pcl
\ No newline at end of file
index 6f853a06be7c5b39937a3010c79a2697838fe689..5a84f870489a459e23f53639877b6ae5cb607dce 100644 (file)
@@ -94,7 +94,7 @@ SampleConsensusPrerejective<PointSource, PointTarget, FeatureT>::selectSamples(
     // Select a random number
     sample_indices[i] = getRandomIndex(static_cast<int>(cloud.size()) - i);
 
-    // Run trough list of numbers, starting at the lowest, to avoid duplicates
+    // Run through list of numbers, starting at the lowest, to avoid duplicates
     for (int j = 0; j < i; j++) {
       // Move value up if it is higher than previous selections to ensure true
       // randomness
index c2aae92c16642c07224f1435f07eadc82fb07ac6..1140880b547853745cc920823e1521513c078e2c 100644 (file)
@@ -166,7 +166,7 @@ TransformationEstimation2D<PointSource, PointTarget, Scalar>::
 
   // Assemble the correlation matrix H = source * target'
   Eigen::Matrix<Scalar, 3, 3> H =
-      (cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3);
+      (cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>();
 
   float angle = std::atan2((H(0, 1) - H(1, 0)), (H(0, 0) + H(1, 1)));
 
@@ -176,9 +176,10 @@ TransformationEstimation2D<PointSource, PointTarget, Scalar>::
   R(1, 0) = std::sin(angle);
 
   // Return the correct transformation
-  transformation_matrix.topLeftCorner(3, 3).matrix() = R;
-  const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.head(3).matrix());
-  transformation_matrix.block(0, 3, 3, 1).matrix() = centroid_tgt.head(3) - Rc;
+  transformation_matrix.template topLeftCorner<3, 3>().matrix() = R;
+  const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.template head<3>().matrix());
+  transformation_matrix.template block<3, 1>(0, 3).matrix() =
+      centroid_tgt.template head<3>() - Rc;
 }
 
 } // namespace registration
index cceac5530db9a5d42956568805fa5bec1114db91..c4cf1671aee6df12ff3331144debee42c2e0f90a 100644 (file)
@@ -155,11 +155,11 @@ pcl::registration::TransformationEstimation3Point<PointSource, PointTarget, Scal
   target_it.reset();
 
   Eigen::Matrix<Scalar, 3, 1> s1 =
-      source_demean.col(1).head(3) - source_demean.col(0).head(3);
+      source_demean.col(1).template head<3>() - source_demean.col(0).template head<3>();
   s1.normalize();
 
   Eigen::Matrix<Scalar, 3, 1> s2 =
-      source_demean.col(2).head(3) - source_demean.col(0).head(3);
+      source_demean.col(2).template head<3>() - source_demean.col(0).template head<3>();
   s2 -= s2.dot(s1) * s1;
   s2.normalize();
 
@@ -169,11 +169,11 @@ pcl::registration::TransformationEstimation3Point<PointSource, PointTarget, Scal
   source_rot.col(2) = s1.cross(s2);
 
   Eigen::Matrix<Scalar, 3, 1> t1 =
-      target_demean.col(1).head(3) - target_demean.col(0).head(3);
+      target_demean.col(1).template head<3>() - target_demean.col(0).template head<3>();
   t1.normalize();
 
   Eigen::Matrix<Scalar, 3, 1> t2 =
-      target_demean.col(2).head(3) - target_demean.col(0).head(3);
+      target_demean.col(2).template head<3>() - target_demean.col(0).template head<3>();
   t2 -= t2.dot(t1) * t1;
   t2.normalize();
 
@@ -184,11 +184,11 @@ pcl::registration::TransformationEstimation3Point<PointSource, PointTarget, Scal
 
   // Eigen::Matrix <Scalar, 3, 3> R = source_rot * target_rot.transpose ();
   Eigen::Matrix<Scalar, 3, 3> R = target_rot * source_rot.transpose();
-  transformation_matrix.topLeftCorner(3, 3) = R;
-  // transformation_matrix.block (0, 3, 3, 1) = source_mean.head (3) - R *
-  // target_mean.head (3);
-  transformation_matrix.block(0, 3, 3, 1) =
-      target_mean.head(3) - R * source_mean.head(3);
+  transformation_matrix.template topLeftCorner<3, 3>() = R;
+  // transformation_matrix.block<3, 1>(0, 3) = source_mean.head<3>() - R *
+  // target_mean.head<3>();
+  transformation_matrix.template block<3, 1>(0, 3) =
+      target_mean.template head<3>() - R * source_mean.template head<3>();
 }
 
 //#define PCL_INSTANTIATE_TransformationEstimation3Point(T,U) template class PCL_EXPORTS
diff --git a/registration/include/pcl/registration/impl/transformation_estimation_dq.hpp b/registration/include/pcl/registration/impl/transformation_estimation_dq.hpp
deleted file mode 100644 (file)
index fce6079..0000000
+++ /dev/null
@@ -1,225 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- *
- */
-
-#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_HPP_
-#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_HPP_
-
-#include <pcl/common/eigen.h>
-PCL_DEPRECATED_HEADER(1,
-                      15,
-                      "TransformationEstimationDQ has been renamed to "
-                      "TransformationEstimationDualQuaternion.");
-
-namespace pcl {
-
-namespace registration {
-
-template <typename PointSource, typename PointTarget, typename Scalar>
-inline void
-TransformationEstimationDQ<PointSource, PointTarget, Scalar>::
-    estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                                const pcl::PointCloud<PointTarget>& cloud_tgt,
-                                Matrix4& transformation_matrix) const
-{
-  const auto nr_points = cloud_src.size();
-  if (cloud_tgt.size() != nr_points) {
-    PCL_ERROR("[pcl::TransformationEstimationDQ::estimateRigidTransformation] Number "
-              "or points in source (%zu) differs than target (%zu)!\n",
-              static_cast<std::size_t>(nr_points),
-              static_cast<std::size_t>(cloud_tgt.size()));
-    return;
-  }
-
-  ConstCloudIterator<PointSource> source_it(cloud_src);
-  ConstCloudIterator<PointTarget> target_it(cloud_tgt);
-  estimateRigidTransformation(source_it, target_it, transformation_matrix);
-}
-
-template <typename PointSource, typename PointTarget, typename Scalar>
-void
-TransformationEstimationDQ<PointSource, PointTarget, Scalar>::
-    estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                                const pcl::Indices& indices_src,
-                                const pcl::PointCloud<PointTarget>& cloud_tgt,
-                                Matrix4& transformation_matrix) const
-{
-  if (indices_src.size() != cloud_tgt.size()) {
-    PCL_ERROR("[pcl::TransformationDQ::estimateRigidTransformation] Number or points "
-              "in source (%zu) differs than target (%zu)!\n",
-              indices_src.size(),
-              static_cast<std::size_t>(cloud_tgt.size()));
-    return;
-  }
-
-  ConstCloudIterator<PointSource> source_it(cloud_src, indices_src);
-  ConstCloudIterator<PointTarget> target_it(cloud_tgt);
-  estimateRigidTransformation(source_it, target_it, transformation_matrix);
-}
-
-template <typename PointSource, typename PointTarget, typename Scalar>
-inline void
-TransformationEstimationDQ<PointSource, PointTarget, Scalar>::
-    estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                                const pcl::Indices& indices_src,
-                                const pcl::PointCloud<PointTarget>& cloud_tgt,
-                                const pcl::Indices& indices_tgt,
-                                Matrix4& transformation_matrix) const
-{
-  if (indices_src.size() != indices_tgt.size()) {
-    PCL_ERROR("[pcl::TransformationEstimationDQ::estimateRigidTransformation] Number "
-              "or points in source (%zu) differs than target (%zu)!\n",
-              indices_src.size(),
-              indices_tgt.size());
-    return;
-  }
-
-  ConstCloudIterator<PointSource> source_it(cloud_src, indices_src);
-  ConstCloudIterator<PointTarget> target_it(cloud_tgt, indices_tgt);
-  estimateRigidTransformation(source_it, target_it, transformation_matrix);
-}
-
-template <typename PointSource, typename PointTarget, typename Scalar>
-void
-TransformationEstimationDQ<PointSource, PointTarget, Scalar>::
-    estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                                const pcl::PointCloud<PointTarget>& cloud_tgt,
-                                const pcl::Correspondences& correspondences,
-                                Matrix4& transformation_matrix) const
-{
-  ConstCloudIterator<PointSource> source_it(cloud_src, correspondences, true);
-  ConstCloudIterator<PointTarget> target_it(cloud_tgt, correspondences, false);
-  estimateRigidTransformation(source_it, target_it, transformation_matrix);
-}
-
-template <typename PointSource, typename PointTarget, typename Scalar>
-inline void
-TransformationEstimationDQ<PointSource, PointTarget, Scalar>::
-    estimateRigidTransformation(ConstCloudIterator<PointSource>& source_it,
-                                ConstCloudIterator<PointTarget>& target_it,
-                                Matrix4& transformation_matrix) const
-{
-  const int npts = static_cast<int>(source_it.size());
-
-  transformation_matrix.setIdentity();
-
-  // dual quaternion optimization
-  Eigen::Matrix<Scalar, 4, 4> C1 = Eigen::Matrix<Scalar, 4, 4>::Zero();
-  Eigen::Matrix<Scalar, 4, 4> C2 = Eigen::Matrix<Scalar, 4, 4>::Zero();
-  Scalar* c1 = C1.data();
-  Scalar* c2 = C2.data();
-
-  for (int i = 0; i < npts; i++) {
-    const PointSource& a = *source_it;
-    const PointTarget& b = *target_it;
-    const Scalar axbx = a.x * b.x;
-    const Scalar ayby = a.y * b.y;
-    const Scalar azbz = a.z * b.z;
-    const Scalar axby = a.x * b.y;
-    const Scalar aybx = a.y * b.x;
-    const Scalar axbz = a.x * b.z;
-    const Scalar azbx = a.z * b.x;
-    const Scalar aybz = a.y * b.z;
-    const Scalar azby = a.z * b.y;
-    c1[0] += axbx - azbz - ayby;
-    c1[5] += ayby - azbz - axbx;
-    c1[10] += azbz - axbx - ayby;
-    c1[15] += axbx + ayby + azbz;
-    c1[1] += axby + aybx;
-    c1[2] += axbz + azbx;
-    c1[3] += aybz - azby;
-    c1[6] += azby + aybz;
-    c1[7] += azbx - axbz;
-    c1[11] += axby - aybx;
-
-    c2[1] += a.z + b.z;
-    c2[2] -= a.y + b.y;
-    c2[3] += a.x - b.x;
-    c2[6] += a.x + b.x;
-    c2[7] += a.y - b.y;
-    c2[11] += a.z - b.z;
-    source_it++;
-    target_it++;
-  }
-
-  c1[4] = c1[1];
-  c1[8] = c1[2];
-  c1[9] = c1[6];
-  c1[12] = c1[3];
-  c1[13] = c1[7];
-  c1[14] = c1[11];
-  c2[4] = -c2[1];
-  c2[8] = -c2[2];
-  c2[12] = -c2[3];
-  c2[9] = -c2[6];
-  c2[13] = -c2[7];
-  c2[14] = -c2[11];
-
-  C1 *= -2.0f;
-  C2 *= 2.0f;
-
-  const Eigen::Matrix<Scalar, 4, 4> A =
-      (0.25f / float(npts)) * C2.transpose() * C2 - C1;
-
-  const Eigen::EigenSolver<Eigen::Matrix<Scalar, 4, 4>> es(A);
-
-  ptrdiff_t i;
-  es.eigenvalues().real().maxCoeff(&i);
-  const Eigen::Matrix<Scalar, 4, 1> qmat = es.eigenvectors().col(i).real();
-  const Eigen::Matrix<Scalar, 4, 1> smat = -(0.5f / float(npts)) * C2 * qmat;
-
-  const Eigen::Quaternion<Scalar> q(qmat(3), qmat(0), qmat(1), qmat(2));
-  const Eigen::Quaternion<Scalar> s(smat(3), smat(0), smat(1), smat(2));
-
-  const Eigen::Quaternion<Scalar> t = s * q.conjugate();
-
-  const Eigen::Matrix<Scalar, 3, 3> R(q.toRotationMatrix());
-
-  for (int i = 0; i < 3; ++i)
-    for (int j = 0; j < 3; ++j)
-      transformation_matrix(i, j) = R(i, j);
-
-  transformation_matrix(0, 3) = -t.x();
-  transformation_matrix(1, 3) = -t.y();
-  transformation_matrix(2, 3) = -t.z();
-}
-
-} // namespace registration
-} // namespace pcl
-
-#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_HPP_ */
index 6e62bd92f4fd204e57c08001ea0a1a677d2e2a21..8ebb59b57702fe6a91b9052d2ea4c328bb7e3ff7 100644 (file)
@@ -194,7 +194,7 @@ TransformationEstimationSVD<PointSource, PointTarget, Scalar>::
 
   // Assemble the correlation matrix H = source * target'
   Eigen::Matrix<Scalar, 3, 3> H =
-      (cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3);
+      (cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>();
 
   // Compute the Singular Value Decomposition
   Eigen::JacobiSVD<Eigen::Matrix<Scalar, 3, 3>> svd(
@@ -211,9 +211,10 @@ TransformationEstimationSVD<PointSource, PointTarget, Scalar>::
   Eigen::Matrix<Scalar, 3, 3> R = v * u.transpose();
 
   // Return the correct transformation
-  transformation_matrix.topLeftCorner(3, 3) = R;
-  const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.head(3));
-  transformation_matrix.block(0, 3, 3, 1) = centroid_tgt.head(3) - Rc;
+  transformation_matrix.template topLeftCorner<3, 3>() = R;
+  const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.template head<3>());
+  transformation_matrix.template block<3, 1>(0, 3) =
+      centroid_tgt.template head<3>() - Rc;
 
   if (pcl::console::isVerbosityLevelEnabled(pcl::console::L_DEBUG)) {
     size_t N = cloud_src_demean.cols();
index 51a5b2174f72770881c8183d5ddb29abc52af8ed..9b2035af77e84067e78467abea3f6f23aa8712fb 100644 (file)
@@ -58,7 +58,7 @@ TransformationEstimationSVDScale<PointSource, PointTarget, Scalar>::
 
   // Assemble the correlation matrix H = source * target'
   Eigen::Matrix<Scalar, 3, 3> H =
-      (cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3);
+      (cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>();
 
   // Compute the Singular Value Decomposition
   Eigen::JacobiSVD<Eigen::Matrix<Scalar, 3, 3>> svd(
@@ -76,7 +76,7 @@ TransformationEstimationSVDScale<PointSource, PointTarget, Scalar>::
 
   // rotated cloud
   Eigen::Matrix<Scalar, 4, 4> R4;
-  R4.block(0, 0, 3, 3) = R;
+  R4.template topLeftCorner<3, 3>() = R;
   R4(0, 3) = 0;
   R4(1, 3) = 0;
   R4(2, 3) = 0;
@@ -96,9 +96,10 @@ TransformationEstimationSVDScale<PointSource, PointTarget, Scalar>::
   }
 
   float scale = sum_tt / sum_ss;
-  transformation_matrix.topLeftCorner(3, 3) = scale * R;
-  const Eigen::Matrix<Scalar, 3, 1> Rc(scale * R * centroid_src.head(3));
-  transformation_matrix.block(0, 3, 3, 1) = centroid_tgt.head(3) - Rc;
+  transformation_matrix.template topLeftCorner<3, 3>() = scale * R;
+  const Eigen::Matrix<Scalar, 3, 1> Rc(scale * R * centroid_src.template head<3>());
+  transformation_matrix.template block<3, 1>(0, 3) =
+      centroid_tgt.template head<3>() - Rc;
 }
 
 } // namespace registration
index 7fbb6403b32b69acd447610a1cdbba7764e225cc..26115717bd7e28837bb1ab5d5fe8563175ed4f1d 100644 (file)
@@ -126,7 +126,7 @@ public:
     // Prevents unnecessary voxel initiations
     if (resolution_ != resolution) {
       resolution_ = resolution;
-      if (input_) {
+      if (target_) { // init() needs target_
         init();
       }
     }
@@ -175,11 +175,37 @@ public:
    * \return outlier ratio
    */
   inline double
+  getOutlierRatio() const
+  {
+    return outlier_ratio_;
+  }
+
+  /** \brief Get the point cloud outlier ratio.
+   * \return outlier ratio
+   */
+  PCL_DEPRECATED(1,
+                 18,
+                 "The method `getOulierRatio` has been renamed to "
+                 "`getOutlierRatio`.")
+  inline double
   getOulierRatio() const
   {
     return outlier_ratio_;
   }
 
+  /** \brief Set/change the point cloud outlier ratio.
+   * \param[in] outlier_ratio outlier ratio
+   */
+  inline void
+  setOutlierRatio(double outlier_ratio)
+  {
+    outlier_ratio_ = outlier_ratio;
+  }
+
+  PCL_DEPRECATED(1,
+                 18,
+                 "The method `setOulierRatio` has been renamed to "
+                 "`setOutlierRatio`.")
   /** \brief Set/change the point cloud outlier ratio.
    * \param[in] outlier_ratio outlier ratio
    */
@@ -220,6 +246,20 @@ public:
     return nr_iterations_;
   }
 
+  /** \brief Get access to the `VoxelGridCovariance` generated from target cloud
+   * containing point means and covariances. Set the input target cloud before calling
+   * this. Useful for debugging, e.g.
+   * \code
+   * pcl::PointCloud<PointXYZ> visualize_cloud;
+   * ndt.getTargetCells().getDisplayCloud(visualize_cloud);
+   * \endcode
+   */
+  inline const TargetGrid&
+  getTargetCells() const
+  {
+    return target_cells_;
+  }
+
   /** \brief Convert 6 element transformation vector to affine transformation.
    * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw]
    * \param[out] trans affine transform corresponding to given transformation
@@ -292,6 +332,10 @@ protected:
     target_cells_.setInputCloud(target_);
     // Initiate voxel structure.
     target_cells_.filter(true);
+    PCL_DEBUG("[pcl::%s::init] Computed voxel structure, got %zu voxels with valid "
+              "normal distributions.\n",
+              getClassName().c_str(),
+              target_cells_.getCentroids()->size());
   }
 
   /** \brief Compute derivatives of likelihood function w.r.t. the
@@ -363,24 +407,6 @@ protected:
   computeHessian(Eigen::Matrix<double, 6, 6>& hessian,
                  const PointCloudSource& trans_cloud);
 
-  /** \brief Compute hessian of likelihood function w.r.t. the transformation
-   * vector.
-   * \note Equation 6.13 [Magnusson 2009].
-   * \param[out] hessian the hessian matrix of the likelihood function
-   * w.r.t. the transformation vector
-   * \param[in] trans_cloud transformed point cloud
-   * \param[in] transform the current transform vector
-   */
-  PCL_DEPRECATED(1, 15, "Parameter `transform` is not required")
-  void
-  computeHessian(Eigen::Matrix<double, 6, 6>& hessian,
-                 const PointCloudSource& trans_cloud,
-                 const Eigen::Matrix<double, 6, 1>& transform)
-  {
-    pcl::utils::ignore(transform);
-    computeHessian(hessian, trans_cloud);
-  }
-
   /** \brief Compute individual point contributions to hessian of likelihood
    * function w.r.t. the transformation vector.
    * \note Equation 6.13 [Magnusson 2009].
index fbb5ed39f93a23b8246b22d8926c324687ef4de6..7962d0368b5ed9575278dd0cdef9fd1b324580a6 100644 (file)
@@ -67,11 +67,18 @@ public:
     std::size_t
     operator()(const HashKeyStruct& s) const noexcept
     {
-      const std::size_t h1 = std::hash<int>{}(s.first);
-      const std::size_t h2 = std::hash<int>{}(s.second.first);
-      const std::size_t h3 = std::hash<int>{}(s.second.second.first);
-      const std::size_t h4 = std::hash<int>{}(s.second.second.second);
-      return h1 ^ (h2 << 1) ^ (h3 << 2) ^ (h4 << 3);
+      /// RS hash function https://www.partow.net/programming/hashfunctions/index.html
+      std::size_t b_ = 378551;
+      std::size_t a_ = 63689;
+      std::size_t hash = 0;
+      hash = hash * a_ + s.first;
+      a_ = a_ * b_;
+      hash = hash * a_ + s.second.first;
+      a_ = a_ * b_;
+      hash = hash * a_ + s.second.second.first;
+      a_ = a_ * b_;
+      hash = hash * a_ + s.second.second.second;
+      return hash;
     }
   };
   using FeatureHashMapType =
diff --git a/registration/include/pcl/registration/transformation_estimation_dq.h b/registration/include/pcl/registration/transformation_estimation_dq.h
deleted file mode 100644 (file)
index 5ad76cc..0000000
+++ /dev/null
@@ -1,138 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- *
- */
-
-#pragma once
-
-#include <pcl/registration/transformation_estimation.h>
-#include <pcl/cloud_iterator.h>
-PCL_DEPRECATED_HEADER(1,
-                      15,
-                      "TransformationEstimationDQ has been renamed to "
-                      "TransformationEstimationDualQuaternion.");
-
-namespace pcl {
-namespace registration {
-/** @b TransformationEstimationDQ implements dual quaternion based estimation of
- * the transformation aligning the given correspondences.
- *
- * \note The class is templated on the source and target point types as well as on the
- * output scalar of the transformation matrix (i.e., float or double). Default: float.
- * \author Sergey Zagoruyko
- * \ingroup registration
- */
-template <typename PointSource, typename PointTarget, typename Scalar = float>
-class TransformationEstimationDQ
-: public TransformationEstimation<PointSource, PointTarget, Scalar> {
-public:
-  using Ptr = shared_ptr<TransformationEstimationDQ<PointSource, PointTarget, Scalar>>;
-  using ConstPtr =
-      shared_ptr<const TransformationEstimationDQ<PointSource, PointTarget, Scalar>>;
-
-  using Matrix4 =
-      typename TransformationEstimation<PointSource, PointTarget, Scalar>::Matrix4;
-
-  TransformationEstimationDQ(){};
-
-  /** \brief Estimate a rigid rotation transformation between a source and a target
-   * point cloud using dual quaternion optimization \param[in] cloud_src the source
-   * point cloud dataset \param[in] cloud_tgt the target point cloud dataset \param[out]
-   * transformation_matrix the resultant transformation matrix
-   */
-  inline void
-  estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                              const pcl::PointCloud<PointTarget>& cloud_tgt,
-                              Matrix4& transformation_matrix) const;
-
-  /** \brief Estimate a rigid rotation transformation between a source and a target
-   * point cloud using dual quaternion optimization \param[in] cloud_src the source
-   * point cloud dataset \param[in] indices_src the vector of indices describing the
-   * points of interest in \a cloud_src
-   * \param[in] cloud_tgt the target point cloud dataset
-   * \param[out] transformation_matrix the resultant transformation matrix
-   */
-  inline void
-  estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                              const pcl::Indices& indices_src,
-                              const pcl::PointCloud<PointTarget>& cloud_tgt,
-                              Matrix4& transformation_matrix) const;
-
-  /** \brief Estimate a rigid rotation transformation between a source and a target
-   * point cloud using dual quaternion optimization \param[in] cloud_src the source
-   * point cloud dataset \param[in] indices_src the vector of indices describing the
-   * points of interest in \a cloud_src
-   * \param[in] cloud_tgt the target point cloud dataset
-   * \param[in] indices_tgt the vector of indices describing the correspondences of the
-   * interest points from \a indices_src
-   * \param[out] transformation_matrix the resultant transformation matrix
-   */
-  inline void
-  estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                              const pcl::Indices& indices_src,
-                              const pcl::PointCloud<PointTarget>& cloud_tgt,
-                              const pcl::Indices& indices_tgt,
-                              Matrix4& transformation_matrix) const;
-
-  /** \brief Estimate a rigid rotation transformation between a source and a target
-   * point cloud using dual quaternion optimization \param[in] cloud_src the source
-   * point cloud dataset \param[in] cloud_tgt the target point cloud dataset \param[in]
-   * correspondences the vector of correspondences between source and target point cloud
-   * \param[out] transformation_matrix the resultant transformation matrix
-   */
-  void
-  estimateRigidTransformation(const pcl::PointCloud<PointSource>& cloud_src,
-                              const pcl::PointCloud<PointTarget>& cloud_tgt,
-                              const pcl::Correspondences& correspondences,
-                              Matrix4& transformation_matrix) const;
-
-protected:
-  /** \brief Estimate a rigid rotation transformation between a source and a target
-   * \param[in] source_it an iterator over the source point cloud dataset
-   * \param[in] target_it an iterator over the target point cloud dataset
-   * \param[out] transformation_matrix the resultant transformation matrix
-   */
-  void
-  estimateRigidTransformation(ConstCloudIterator<PointSource>& source_it,
-                              ConstCloudIterator<PointTarget>& target_it,
-                              Matrix4& transformation_matrix) const;
-};
-
-} // namespace registration
-} // namespace pcl
-
-#include <pcl/registration/impl/transformation_estimation_dq.hpp>
diff --git a/registration/include/pcl/registration/transforms.h b/registration/include/pcl/registration/transforms.h
deleted file mode 100644 (file)
index 2f4bfb7..0000000
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id$
- *
- */
-
-#pragma once
-PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/transforms.h directly.")
-#include <pcl/common/transforms.h>
index 2aa6dec1603ab6899a80fb42cd34ff4fd6534dfc..228ea9c90929d16717d9592373181f94022e48b0 100644 (file)
@@ -95,9 +95,9 @@ public:
     pnt_out.z = static_cast<float>(
         transform_matrix_(2, 0) * pnt_in.x + transform_matrix_(2, 1) * pnt_in.y +
         transform_matrix_(2, 2) * pnt_in.z + transform_matrix_(2, 3));
-    // pnt_out.getVector3fMap () = transform_matrix_.topLeftCorner (3, 3) *
+    // pnt_out.getVector3fMap () = transform_matrix_.topLeftCorner<3, 3> () *
     //                            pnt_in.getVector3fMap () +
-    //                            transform_matrix_.block (0, 3, 3, 1);
+    //                            transform_matrix_.block<3, 1> (0, 3);
     // pnt_out.data[3] = pnt_in.data[3];
   }
 
index 459681ccae280c23eb83a738f5717a3894dc7284..03f2cae9188af4f2610546285a127731832312ef 100644 (file)
@@ -82,11 +82,11 @@ public:
     trans(2, 2) = 1; // Rotation around the Z-axis
 
     // Copy the rotation and translation components
-    trans.block(0, 3, 4, 1) = Eigen::Matrix<Scalar, 4, 1>(p[0], p[1], 0, 1.0);
+    trans.template block<4, 1>(0, 3) = Eigen::Matrix<Scalar, 4, 1>(p[0], p[1], 0, 1.0);
 
     // Compute w from the unit quaternion
     Eigen::Rotation2D<Scalar> r(p[2]);
-    trans.topLeftCorner(2, 2) = r.toRotationMatrix();
+    trans.template topLeftCorner<2, 2>() = r.toRotationMatrix();
   }
 };
 } // namespace registration
index 30b07d7c21696dfd7a8c5e939a935b25474c0e97..ec1302acf1acacacb15fff1cc09435c9678ea097 100644 (file)
@@ -89,7 +89,7 @@ public:
     Eigen::Quaternion<Scalar> q(0, p[3], p[4], p[5]);
     q.w() = static_cast<Scalar>(std::sqrt(1 - q.dot(q)));
     q.normalize();
-    transform_matrix_.topLeftCorner(3, 3) = q.toRotationMatrix();
+    transform_matrix_.template topLeftCorner<3, 3>() = q.toRotationMatrix();
   }
 };
 } // namespace registration
index eb49a954f94a7a0039a074b1c15792d6ccccf1d1..bc15c427cf7e0280803d0fbf7b54af19a5a42b70 100644 (file)
@@ -15,6 +15,8 @@ The <b>pcl_registration</b> library implements a plethora of point cloud
 registration algorithms for both organized and unorganized (general purpose)
 datasets.
 
+PCL's methods to register one point cloud to another can be divided into two groups: the first group needs an initial guess of the transformation (pcl::IterativeClosestPoint, pcl::IterativeClosestPointWithNormals, pcl::IterativeClosestPointNonLinear, pcl::GeneralizedIterativeClosestPoint, pcl::GeneralizedIterativeClosestPoint6D, pcl::NormalDistributionsTransform, pcl::NormalDistributionsTransform2D), and the second group does not need a guess but is usually slower and less accurate (pcl::registration::FPCSInitialAlignment, pcl::registration::KFPCSInitialAlignment, pcl::SampleConsensusInitialAlignment, pcl::SampleConsensusPrerejective, pcl::PPFRegistration). Many parts of the registration process can be configured and swapped out, like the correspondence estimation, correspondence rejection, or the transformation estimation. And finally, PCL also has methods if there are more than two point clouds to align (pcl::registration::ELCH, pcl::registration::LUM, pcl::PairwiseGraphRegistration, pcl::registration::IncrementalRegistration, pcl::registration::MetaRegistration).
+
 \image html http://www.pointclouds.org/assets/images/contents/documentation/registration_outdoor.png
 \image html http://www.pointclouds.org/assets/images/contents/documentation/registration_closeup.png
 
index c06bc2c2664d8ed5fb8df616cb0f8d886c5cdf60..513c4ef796f2355bb2ad9dc72ad27dcfb0ea9e74 100644 (file)
@@ -225,12 +225,8 @@ GeneralizedIterativeClosestPoint6D::computeTransformation(PointCloudSource& outp
       PCL_DEBUG("[pcl::%s::computeTransformation] Convergence failed\n",
                 getClassName().c_str());
   }
-  // for some reason the static equivalent method raises an error
-  // final_transformation_.block<3,3> (0,0) = (transformation_.block<3,3> (0,0)) *
-  // (guess.block<3,3> (0,0)); final_transformation_.block <3, 1> (0, 3) =
-  // transformation_.block <3, 1> (0, 3) + guess.rightCols<1>.block <3, 1> (0, 3);
-  final_transformation_.topLeftCorner(3, 3) =
-      previous_transformation_.topLeftCorner(3, 3) * guess.topLeftCorner(3, 3);
+  final_transformation_.topLeftCorner<3, 3>() =
+      previous_transformation_.topLeftCorner<3, 3>() * guess.topLeftCorner<3, 3>();
   final_transformation_(0, 3) = previous_transformation_(0, 3) + guess(0, 3);
   final_transformation_(1, 3) = previous_transformation_(1, 3) + guess(1, 3);
   final_transformation_(2, 3) = previous_transformation_(2, 3) + guess(2, 3);
diff --git a/registration/src/transformation_estimation_dq.cpp b/registration/src/transformation_estimation_dq.cpp
deleted file mode 100644 (file)
index a6d388f..0000000
+++ /dev/null
@@ -1,39 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011, Alexandru-Eugen Ichim
- *                      Willow Garage, Inc
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage, Inc. nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: transformation_estimation_svd.cpp 7153 2012-09-16 22:24:29Z aichim $
- *
- */
-
-#include <pcl/registration/transformation_estimation_dq.h>
index 8552beed7a7e1c13773ab3bc7779ed99403305b8..ab8b539786d42a7aa0f8ea449589652ae086be44 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME sample_consensus)
 set(SUBSYS_DESC "Point cloud sample consensus library")
 set(SUBSYS_DEPS common search)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
@@ -14,6 +13,7 @@ endif()
 
 set(srcs
   src/sac.cpp
+  src/sac_model_ellipse3d.cpp
   src/sac_model_circle.cpp
   src/sac_model_circle3d.cpp
   src/sac_model_cylinder.cpp
@@ -27,12 +27,10 @@ set(srcs
   src/sac_model_plane.cpp
   src/sac_model_registration.cpp
   src/sac_model_sphere.cpp
-  src/sac_model_ellipse3d.cpp
+  src/sac_model_torus.cpp
 )
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
-  "include/pcl/${SUBSYS_NAME}/eigen.h"
   "include/pcl/${SUBSYS_NAME}/lmeds.h"
   "include/pcl/${SUBSYS_NAME}/method_types.h"
   "include/pcl/${SUBSYS_NAME}/mlesac.h"
@@ -61,6 +59,7 @@ set(incs
   "include/pcl/${SUBSYS_NAME}/sac_model_registration_2d.h"
   "include/pcl/${SUBSYS_NAME}/sac_model_sphere.h"
   "include/pcl/${SUBSYS_NAME}/sac_model_ellipse3d.h"
+  "include/pcl/${SUBSYS_NAME}/sac_model_torus.h"
 )
 
 set(impl_incs
@@ -88,12 +87,12 @@ set(impl_incs
   "include/pcl/${SUBSYS_NAME}/impl/sac_model_registration_2d.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/sac_model_sphere.hpp"
   "include/pcl/${SUBSYS_NAME}/impl/sac_model_ellipse3d.hpp"
+  "include/pcl/${SUBSYS_NAME}/impl/sac_model_torus.hpp"
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
-target_link_libraries("${LIB_NAME}" pcl_common)
+target_link_libraries("${LIB_NAME}" pcl_common pcl_search)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
 
 # Install include files
diff --git a/sample_consensus/include/pcl/sample_consensus/boost.h b/sample_consensus/include/pcl/sample_consensus/boost.h
deleted file mode 100644 (file)
index ea42ca4..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-
-#include <boost/random.hpp>
diff --git a/sample_consensus/include/pcl/sample_consensus/eigen.h b/sample_consensus/include/pcl/sample_consensus/eigen.h
deleted file mode 100644 (file)
index 63d7333..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-
-#include <Eigen/Core>
-#include <unsupported/Eigen/NonLinearOptimization>
index 5f5cab7151cbe2201dc66c5ef409a6aeac5270ee..b2b0f5809a2057e4644a0ee1780783cbafbf740f 100644 (file)
@@ -72,7 +72,8 @@ pcl::RandomizedMEstimatorSampleConsensus<PointT>::computeModel (int debug_verbos
   const unsigned max_skip = max_iterations_ * 10;
   
   // Number of samples to try randomly
-  std::size_t fraction_nr_points = pcl_lrint (static_cast<double>(sac_model_->getIndices ()->size ()) * fraction_nr_pretest_ / 100.0);
+  const std::size_t fraction_nr_points = (fraction_nr_pretest_ < 0.0 ? nr_samples_pretest_ : pcl_lrint (static_cast<double>(sac_model_->getIndices ()->size ()) * fraction_nr_pretest_ / 100.0));
+  PCL_DEBUG ("[pcl::RandomizedMEstimatorSampleConsensus::computeModel] Using %lu points for RMSAC pre-test.\n", fraction_nr_points);
 
   // Iterate
   while (iterations_ < k && skipped_count < max_skip)
index 08751e41a29c04ff44c9d1bb53927afd5807a5bc..b259a1495de47ec7bd731fca57354f89f2b1d1c5 100644 (file)
@@ -71,7 +71,8 @@ pcl::RandomizedRandomSampleConsensus<PointT>::computeModel (int debug_verbosity_
   const unsigned max_skip = max_iterations_ * 10;
 
   // Number of samples to try randomly
-  const std::size_t fraction_nr_points = pcl_lrint (static_cast<double>(sac_model_->getIndices ()->size ()) * fraction_nr_pretest_ / 100.0);
+  const std::size_t fraction_nr_points = (fraction_nr_pretest_ < 0.0 ? nr_samples_pretest_ : pcl_lrint (static_cast<double>(sac_model_->getIndices ()->size ()) * fraction_nr_pretest_ / 100.0));
+  PCL_DEBUG ("[pcl::RandomizedRandomSampleConsensus::computeModel] Using %lu points for RRANSAC pre-test.\n", fraction_nr_points);
 
   // Iterate
   while (iterations_ < k)
index 435e5d2c3f07adf09c6cdd58a4a9cd9f66909339..8fd9458a26bda19974eb0c0520808dc7526d943c 100644 (file)
@@ -65,7 +65,7 @@ pcl::SampleConsensusModelCircle3D<PointT>::isSampleGood (
   // Check if the squared norm of the cross-product is non-zero, otherwise
   // common_helper_vec, which plays an important role in computeModelCoefficients,
   // would likely be ill-formed.
-  if ((p1 - p0).cross(p1 - p2).squaredNorm() < Eigen::NumTraits<float>::dummy_precision ())
+  if ((p1 - p0).cross(p1 - p2).squaredNorm() < Eigen::NumTraits<double>::dummy_precision ())
   {
     PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::isSampleGood] Sample points too similar or collinear!\n");
     return (false);
@@ -102,7 +102,7 @@ pcl::SampleConsensusModelCircle3D<PointT>::computeModelCoefficients (const Indic
 
   // The same check is implemented in isSampleGood, so be sure to look there too
   // if you find the need to change something here.
-  if (common_helper_vec.squaredNorm() < Eigen::NumTraits<float>::dummy_precision ())
+  if (common_helper_vec.squaredNorm() < Eigen::NumTraits<double>::dummy_precision ())
   {
     PCL_ERROR ("[pcl::SampleConsensusModelCircle3D::computeModelCoefficients] Sample points too similar or collinear!\n");
     return (false);
@@ -194,7 +194,9 @@ pcl::SampleConsensusModelCircle3D<PointT>::selectWithinDistance (
     return;
   }
   inliers.clear ();
+  error_sqr_dists_.clear ();
   inliers.reserve (indices_->size ());
+  error_sqr_dists_.reserve (indices_->size ());
 
   const auto squared_threshold = threshold * threshold;
   // Iterate through the 3d points and calculate the distances from them to the sphere
@@ -221,10 +223,12 @@ pcl::SampleConsensusModelCircle3D<PointT>::selectWithinDistance (
     Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized ();
     Eigen::Vector3d distanceVector =  P - K;
 
-    if (distanceVector.squaredNorm () < squared_threshold)
+    const double sqr_dist = distanceVector.squaredNorm ();
+    if (sqr_dist < squared_threshold)
     {
       // Returns the indices of the points whose distances are smaller than the threshold
       inliers.push_back ((*indices_)[i]);
+      error_sqr_dists_.push_back (sqr_dist);
     }
   }
 }
@@ -297,8 +301,9 @@ pcl::SampleConsensusModelCircle3D<PointT>::optimizeModelCoefficients (
   OptimizationFunctor functor (this, inliers);
   Eigen::NumericalDiff<OptimizationFunctor> num_diff (functor);
   Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, double> lm (num_diff);
-  Eigen::VectorXd coeff;
+  Eigen::VectorXd coeff = optimized_coefficients.cast<double>();
   int info = lm.minimize (coeff);
+  coeff.tail(3).normalize(); // normalize the cylinder axis
   for (Eigen::Index i = 0; i < coeff.size (); ++i)
     optimized_coefficients[i] = static_cast<float> (coeff[i]);
 
@@ -338,11 +343,11 @@ pcl::SampleConsensusModelCircle3D<PointT>::projectPoints (
       pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> ((*input_)[i], projected_points[i]));
 
     // Iterate through the 3d points and calculate the distances from them to the plane
-    for (std::size_t i = 0; i < inliers.size (); ++i)
+    for (const auto &inlier : inliers)
     {
       // what i have:
       // P : Sample Point
-      Eigen::Vector3d P ((*input_)[inliers[i]].x, (*input_)[inliers[i]].y, (*input_)[inliers[i]].z);
+      Eigen::Vector3d P ((*input_)[inlier].x, (*input_)[inlier].y, (*input_)[inlier].z);
       // C : Circle Center
       Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]);
       // N : Circle (Plane) Normal
@@ -361,9 +366,9 @@ pcl::SampleConsensusModelCircle3D<PointT>::projectPoints (
       // K : Point on Circle
       Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized ();
 
-      projected_points[i].x = static_cast<float> (K[0]);
-      projected_points[i].y = static_cast<float> (K[1]);
-      projected_points[i].z = static_cast<float> (K[2]);
+      projected_points[inlier].x = static_cast<float> (K[0]);
+      projected_points[inlier].y = static_cast<float> (K[1]);
+      projected_points[inlier].z = static_cast<float> (K[2]);
     }
   }
   else
index e0be7718f0d6613087b7c1c2e0fada8853d28e72..c3d3cd835e9ac0659b26c056db65eb1489303cd5 100644 (file)
@@ -87,6 +87,11 @@ pcl::SampleConsensusModelCone<PointT, PointNT>::computeModelCoefficients (
   Eigen::Vector4f ortho31 = n3.cross3(n1);
 
   float denominator = n1.dot(ortho23);
+  if (std::abs(denominator) < Eigen::NumTraits<float>::dummy_precision ())
+  {
+    PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] Impossible to compute stable model with these points.\n");
+    return (false);
+  }
 
   float d1 = p1.dot (n1);
   float d2 = p2.dot (n2);
index 247a58e3d1f0b0f752a61f2052b62449035d19eb..abb0d32c9c4700622b49e9abdeb6214e38903b30 100644 (file)
@@ -235,7 +235,7 @@ pcl::SampleConsensusModelEllipse3D<PointT>::computeModelCoefficients (const Indi
   model_coefficients[10] = static_cast<float>(x_axis[2]);
 
 
-  PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::computeModelCoefficients] Model is (%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g).\n",
+  PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::computeModelCoefficients] Model is (%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g).\n",
              model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3],
              model_coefficients[4], model_coefficients[5], model_coefficients[6], model_coefficients[7],
              model_coefficients[8], model_coefficients[9], model_coefficients[10]);
@@ -312,12 +312,14 @@ pcl::SampleConsensusModelEllipse3D<PointT>::selectWithinDistance (
     Indices &inliers)
 {
   inliers.clear();
+  error_sqr_dists_.clear();
   // Check if the model is valid given the user constraints
   if (!isModelValid (model_coefficients))
   {
     return;
   }
   inliers.reserve (indices_->size ());
+  error_sqr_dists_.reserve (indices_->size ());
 
   // c : Ellipse Center
   const Eigen::Vector3f c(model_coefficients[0], model_coefficients[1], model_coefficients[2]);
@@ -358,10 +360,12 @@ pcl::SampleConsensusModelEllipse3D<PointT>::selectWithinDistance (
     float th_opt;
     const Eigen::Vector2f distanceVector = dvec2ellipse(params, p_(0), p_(1), th_opt);
 
-    if (distanceVector.squaredNorm() < squared_threshold)
+    const double sqr_dist = distanceVector.squaredNorm();
+    if (sqr_dist < squared_threshold)
     {
       // Returns the indices of the points whose distances are smaller than the threshold
       inliers.push_back ((*indices_)[i]);
+      error_sqr_dists_.push_back (sqr_dist);
     }
   }
 }
@@ -447,13 +451,12 @@ pcl::SampleConsensusModelEllipse3D<PointT>::optimizeModelCoefficients (
   OptimizationFunctor functor(this, inliers);
   Eigen::NumericalDiff<OptimizationFunctor> num_diff(functor);
   Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, double> lm(num_diff);
-  Eigen::VectorXd coeff;
+  Eigen::VectorXd coeff = model_coefficients.cast<double>();
   int info = lm.minimize(coeff);
-  for (Eigen::Index i = 0; i < coeff.size (); ++i)
-    optimized_coefficients[i] = static_cast<float> (coeff[i]);
+  optimized_coefficients = coeff.cast<float>();
 
   // Compute the L2 norm of the residuals
-  PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g %g %g %g %g %g %g\n",
+  PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g %g %g %g %g\nFinal solution: %g %g %g %g %g %g %g %g %g %g %g\n",
             info, lm.fvec.norm (),
 
             model_coefficients[0],
index 0cd94ff80ee37ac0f5724dfe60c9825fc7a158dc..dc96852c2477caca52a443a5120056b1be42c47a 100644 (file)
@@ -42,7 +42,6 @@
 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PLANE_H_
 
 #include <pcl/sample_consensus/sac_model_normal_plane.h>
-#include <pcl/sample_consensus/impl/sac_model_plane.hpp> // for dist4, dist8
 #include <pcl/common/common.h> // for getAngle3D
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
index a9a6800bbd85fb6b51c29dd7efd396adacac5056..be51ff89bae2d37fd9f6598bc7b2ae458a33e096 100644 (file)
@@ -117,36 +117,6 @@ pcl::SampleConsensusModelPlane<PointT>::computeModelCoefficients (
   return (true);
 }
 
-#define AT(POS) ((*input_)[(*indices_)[(POS)]])
-
-#ifdef __AVX__
-// This function computes the distances of 8 points to the plane
-template <typename PointT> inline __m256 pcl::SampleConsensusModelPlane<PointT>::dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const
-{
-  // The andnot-function realizes an abs-operation: the sign bit is removed
-  return _mm256_andnot_ps (abs_help,
-        _mm256_add_ps (_mm256_add_ps (_mm256_mul_ps (a_vec, _mm256_set_ps (AT(i  ).x, AT(i+1).x, AT(i+2).x, AT(i+3).x, AT(i+4).x, AT(i+5).x, AT(i+6).x, AT(i+7).x)),
-                                      _mm256_mul_ps (b_vec, _mm256_set_ps (AT(i  ).y, AT(i+1).y, AT(i+2).y, AT(i+3).y, AT(i+4).y, AT(i+5).y, AT(i+6).y, AT(i+7).y))),
-                       _mm256_add_ps (_mm256_mul_ps (c_vec, _mm256_set_ps (AT(i  ).z, AT(i+1).z, AT(i+2).z, AT(i+3).z, AT(i+4).z, AT(i+5).z, AT(i+6).z, AT(i+7).z)),
-                                      d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
-}
-#endif // ifdef __AVX__
-
-#ifdef __SSE__
-// This function computes the distances of 4 points to the plane
-template <typename PointT> inline __m128 pcl::SampleConsensusModelPlane<PointT>::dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const
-{
-  // The andnot-function realizes an abs-operation: the sign bit is removed
-  return _mm_andnot_ps (abs_help,
-        _mm_add_ps (_mm_add_ps (_mm_mul_ps (a_vec, _mm_set_ps (AT(i  ).x, AT(i+1).x, AT(i+2).x, AT(i+3).x)),
-                                _mm_mul_ps (b_vec, _mm_set_ps (AT(i  ).y, AT(i+1).y, AT(i+2).y, AT(i+3).y))),
-                    _mm_add_ps (_mm_mul_ps (c_vec, _mm_set_ps (AT(i  ).z, AT(i+1).z, AT(i+2).z, AT(i+3).z)),
-                                d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
-}
-#endif // ifdef __SSE__
-
-#undef AT
-
 //////////////////////////////////////////////////////////////////////////
 template <typename PointT> void
 pcl::SampleConsensusModelPlane<PointT>::getDistancesToModel (
diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_torus.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_torus.hpp
new file mode 100644 (file)
index 0000000..81cd107
--- /dev/null
@@ -0,0 +1,581 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2009-2010, Willow Garage, Inc.
+ *  Copyright (c) 2012-, Open Perception, Inc.
+ *
+ *  All rights reserved.
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * Redistributions in binary form must reproduce the above
+ *     copyright notice, this list of conditions and the following
+ *     disclaimer in the documentation and/or other materials provided
+ *     with the distribution.
+ *   * Neither the name of the copyright holder(s) nor the names of its
+ *     contributors may be used to endorse or promote products derived
+ *     from this software without specific prior written permission.
+ *
+ *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ *  POSSIBILITY OF SUCH DAMAGE.
+ *
+ * $Id$
+ *
+ */
+
+#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_TORUS_H_
+#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_TORUS_H_
+
+// clang-format off
+#include <pcl/sample_consensus/sac_model_torus.h>
+#include <pcl/common/concatenate.h>
+// clang-format on
+
+#include <unsupported/Eigen/NonLinearOptimization> // for LevenbergMarquardt
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+bool
+pcl::SampleConsensusModelTorus<PointT, PointNT>::isSampleGood(
+    const Indices& samples) const
+{
+  if (samples.size() != sample_size_) {
+    PCL_ERROR("[pcl::SampleConsensusTorus::isSampleGood] Wrong number of samples (is "
+              "%lu, should be %lu)!\n",
+              samples.size(),
+              sample_size_);
+    return (false);
+  }
+
+  Eigen::Vector3f n0 = Eigen::Vector3f((*normals_)[samples[0]].getNormalVector3fMap());
+  Eigen::Vector3f n1 = Eigen::Vector3f((*normals_)[samples[1]].getNormalVector3fMap());
+  Eigen::Vector3f n2 = Eigen::Vector3f((*normals_)[samples[2]].getNormalVector3fMap());
+  Eigen::Vector3f n3 = Eigen::Vector3f((*normals_)[samples[3]].getNormalVector3fMap());
+
+  // Required for numeric stability on computeModelCoefficients
+  if (std::abs((n0).cross(n1).squaredNorm()) <
+          Eigen::NumTraits<float>::dummy_precision() ||
+      std::abs((n0).cross(n2).squaredNorm()) <
+          Eigen::NumTraits<float>::dummy_precision() ||
+      std::abs((n0).cross(n3).squaredNorm()) <
+          Eigen::NumTraits<float>::dummy_precision() ||
+      std::abs((n1).cross(n2).squaredNorm()) <
+          Eigen::NumTraits<float>::dummy_precision() ||
+      std::abs((n1).cross(n3).squaredNorm()) <
+          Eigen::NumTraits<float>::dummy_precision()) {
+    PCL_ERROR("[pcl::SampleConsensusModelEllipse3D::isSampleGood] Sample points "
+              "normals too similar or collinear!\n");
+    return (false);
+  }
+  return (true);
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+float
+crossDot(const Eigen::Vector3f& v1, const Eigen::Vector3f& v2, const Eigen::Vector3f& v3)
+{
+  return v1.cross(v2).dot(v3);
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+bool
+pcl::SampleConsensusModelTorus<PointT, PointNT>::computeModelCoefficients(
+    const Indices& samples, Eigen::VectorXf& model_coefficients) const
+{
+
+  // Make sure that the samples are valid
+  if (!isSampleGood(samples)) {
+    PCL_ERROR("[pcl::SampleConsensusModelTorus::computeModelCoefficients] Invalid set "
+              "of samples given!\n");
+    return (false);
+  }
+
+  if (!normals_) {
+    PCL_ERROR("[pcl::SampleConsensusModelTorus::computeModelCoefficients] No input "
+              "dataset containing normals was given!\n");
+    return (false);
+  }
+  // Find axis using:
+
+  // @article{article,
+  // author = {Lukacs, G. and Marshall, David and Martin, R.},
+  // year = {2001},
+  // month = {09},
+  // pages = {},
+  // title = {Geometric Least-Squares Fitting of Spheres, Cylinders, Cones and Tori}
+  //}
+
+  const Eigen::Vector3f n0 = Eigen::Vector3f((*normals_)[samples[0]].getNormalVector3fMap());
+  const Eigen::Vector3f n1 = Eigen::Vector3f((*normals_)[samples[1]].getNormalVector3fMap());
+  const Eigen::Vector3f n2 = Eigen::Vector3f((*normals_)[samples[2]].getNormalVector3fMap());
+  const Eigen::Vector3f n3 = Eigen::Vector3f((*normals_)[samples[3]].getNormalVector3fMap());
+
+  const Eigen::Vector3f p0 = Eigen::Vector3f((*input_)[samples[0]].getVector3fMap());
+  const Eigen::Vector3f p1 = Eigen::Vector3f((*input_)[samples[1]].getVector3fMap());
+  const Eigen::Vector3f p2 = Eigen::Vector3f((*input_)[samples[2]].getVector3fMap());
+  const Eigen::Vector3f p3 = Eigen::Vector3f((*input_)[samples[3]].getVector3fMap());
+
+  const float a01 = crossDot(n0, n1, n2);
+  const float b01 = crossDot(n0, n1, n3);
+  const float a0 = crossDot(p2 - p1, n0, n2);
+  const float a1 = crossDot(p0 - p2, n1, n2);
+  const float b0 = crossDot(p3 - p1, n0, n3);
+  const float b1 = crossDot(p0 - p3, n1, n3);
+  const float a = crossDot(p0 - p2, p1 - p0, n2);
+  const float b = crossDot(p0 - p3, p1 - p0, n3);
+
+  // a10*t0*t1 + a0*t0 + a1*t1 + a = 0
+  // b10*t0*t1 + b0*t0 + b1*t1 + b = 0
+  //
+  // (a0 - b0*a10/b10)* t0 + (a1-b1*a10/b10) *t1 + a - b*a10/b10
+  // t0 = k * t1 + p
+
+  const float k = -(a1 - b1 * a01 / b01) / (a0 - b0 * a01 / b01);
+  const float p = -(a - b * a01 / b01) / (a0 - b0 * a01 / b01);
+
+  // Second deg eqn.
+  //
+  // b10*k*t1*t1 + b10*p*t1  | + b0*k *t1 + b0*p | + b1*t1 | + b = 0
+  //
+  // (b10*k) * t1*t1 + (b10*p + b0*k + b1) * t1  + (b0*p + b)
+
+  const float _a = (b01 * k);
+  const float _b = (b01 * p + b0 * k + b1);
+  const float _c = (b0 * p + b);
+
+  const float eps = Eigen::NumTraits<float>::dummy_precision();
+
+  // Check for imaginary solutions, or small denominators.
+  if ((_b * _b - 4 * _a * _c) < 0 || std::abs(a0 - b0 * a01) < eps ||
+      std::abs(b01) < eps || std::abs(_a) < eps) {
+    PCL_DEBUG("[pcl::SampleConsensusModelTorus::computeModelCoefficients] Can't "
+              "compute model coefficients with this method!\n");
+    return (false);
+  }
+
+  const float s0 = (-_b + std::sqrt(_b * _b - 4 * _a * _c)) / (2 * _a);
+  const float s1 = (-_b - std::sqrt(_b * _b - 4 * _a * _c)) / (2 * _a);
+
+  float r_maj_stddev_cycle1 = std::numeric_limits<float>::max();
+
+  for (float s : {s0, s1}) {
+
+    const float t1 = s;
+    const float t0 = k * t1 + p;
+
+    // Direction vector
+    Eigen::Vector3f d = ((p1 + n1 * t1) - (p0 + n0 * t0));
+    d.normalize();
+    // Flip direction, so that the first element of the direction vector is
+    // positive, for consistency.
+    if (d[0] < 0) {
+      d *= -1;
+    }
+
+    // Flip normals if required. Note |d| = 1
+    // d
+    // if (n0.dot(d) / n0.norm() < M_PI / 2 ) n0 = -n0;
+    // if (n1.dot(d) / n1.norm() < M_PI / 2 ) n1 = -n1;
+    // if (n2.dot(d) / n2.norm() < M_PI / 2 ) n2 = -n2;
+    // if (n3.dot(d) / n3.norm() < M_PI / 2 ) n3 = -n3;
+
+    // We fit the points to the plane of the torus.
+    // Ax + By + Cz + D = 0
+    // We know that all for each point plus its normal
+    // times the minor radius will give us a point
+    // in that plane
+    // Pplane_i = P_i + n_i * r
+    // we substitute A,x,B,y,C,z
+    // dx *( P_i_x + n_i_x * r ) + dy *( P_i_y + n_i_y * r ) +dz *( P_i_z + n_i_z * r )
+    // + D = 0 and finally (dx*P_i_x + dy*P_i_y + dz*P_i_z) + (dx*n_i_x + dy*n_i_y +
+    // dz*n_i_z ) * r + D = 0 We can set up a linear least squares system of two
+    // variables r and D
+    //
+    Eigen::MatrixXf A(4, 2);
+    A << d.dot(n0), 1, d.dot(n1), 1, d.dot(n2), 1, d.dot(n3), 1;
+
+    Eigen::Matrix<float, -1, -1> B(4, 1);
+    B << -d.dot(p0), -d.dot(p1), -d.dot(p2), -d.dot(p3);
+
+    Eigen::Matrix<float, -1, -1> sol;
+    sol = A.bdcSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(B);
+
+    const float r_min = -sol(0);
+    const float D = sol(1);
+
+    // Axis line and plane intersect to find the centroid of the torus
+    // We take a random point on the line. We find P_rand + lambda * d belongs in the
+    // plane
+
+    const Eigen::Vector3f Pany = (p1 + n1 * t1);
+
+    const float lambda = (-d.dot(Pany) - D) / d.dot(d);
+
+    const Eigen::Vector3f centroid = Pany + d * lambda;
+
+    // Finally, the major radius. The least square solution will be
+    // the average in this case.
+    const float r_maj = std::sqrt(((p0 - r_min * n0 - centroid).squaredNorm() +
+                             (p1 - r_min * n1 - centroid).squaredNorm() +
+                             (p2 - r_min * n2 - centroid).squaredNorm() +
+                             (p3 - r_min * n3 - centroid).squaredNorm()) /
+                            4.f);
+
+    const float r_maj_stddev =
+        std::sqrt((std::pow(r_maj - (p0 - r_min * n0 - centroid).norm(), 2) +
+                   std::pow(r_maj - (p1 - r_min * n1 - centroid).norm(), 2) +
+                   std::pow(r_maj - (p2 - r_min * n2 - centroid).norm(), 2) +
+                   std::pow(r_maj - (p3 - r_min * n3 - centroid).norm(), 2)) /
+                  4.f);
+    // We select the minimum stddev cycle
+    if (r_maj_stddev < r_maj_stddev_cycle1) {
+      r_maj_stddev_cycle1 = r_maj_stddev;
+    }
+    else {
+      break;
+    }
+
+    model_coefficients.resize(model_size_);
+    model_coefficients[0] = r_maj;
+    model_coefficients[1] = r_min;
+
+    model_coefficients[2] = centroid[0];
+    model_coefficients[3] = centroid[1];
+    model_coefficients[4] = centroid[2];
+
+    model_coefficients[5] = d[0];
+    model_coefficients[6] = d[1];
+    model_coefficients[7] = d[2];
+  }
+  return true;
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+void
+pcl::SampleConsensusModelTorus<PointT, PointNT>::getDistancesToModel(
+    const Eigen::VectorXf& model_coefficients, std::vector<double>& distances) const
+{
+
+  if (!isModelValid(model_coefficients)) {
+    distances.clear();
+    return;
+  }
+
+  distances.resize(indices_->size());
+
+  // Iterate through the 3d points and calculate the distances to the closest torus
+  // point
+  for (std::size_t i = 0; i < indices_->size(); ++i) {
+    const Eigen::Vector3f pt = (*input_)[(*indices_)[i]].getVector3fMap();
+    const Eigen::Vector3f pt_n = (*normals_)[(*indices_)[i]].getNormalVector3fMap();
+
+    Eigen::Vector3f torus_closest;
+    projectPointToTorus(pt, pt_n, model_coefficients, torus_closest);
+
+    distances[i] = (torus_closest - pt).norm();
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+void
+pcl::SampleConsensusModelTorus<PointT, PointNT>::selectWithinDistance(
+    const Eigen::VectorXf& model_coefficients, const double threshold, Indices& inliers)
+{
+  // Check if the model is valid given the user constraints
+  if (!isModelValid(model_coefficients)) {
+    inliers.clear();
+    return;
+  }
+  inliers.clear();
+  error_sqr_dists_.clear();
+  inliers.reserve(indices_->size());
+  error_sqr_dists_.reserve(indices_->size());
+
+  for (std::size_t i = 0; i < indices_->size(); ++i) {
+    const Eigen::Vector3f pt = (*input_)[(*indices_)[i]].getVector3fMap();
+    const Eigen::Vector3f pt_n = (*normals_)[(*indices_)[i]].getNormalVector3fMap();
+
+    Eigen::Vector3f torus_closest;
+    projectPointToTorus(pt, pt_n, model_coefficients, torus_closest);
+
+    const float distance = (torus_closest - pt).norm();
+
+    if (distance < threshold) {
+      // Returns the indices of the points whose distances are smaller than the
+      // threshold
+      inliers.push_back((*indices_)[i]);
+      error_sqr_dists_.push_back(distance);
+    }
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+std::size_t
+pcl::SampleConsensusModelTorus<PointT, PointNT>::countWithinDistance(
+    const Eigen::VectorXf& model_coefficients, const double threshold) const
+{
+  if (!isModelValid(model_coefficients))
+    return (0);
+
+  std::size_t nr_p = 0;
+
+  for (std::size_t i = 0; i < indices_->size(); ++i) {
+    const Eigen::Vector3f pt = (*input_)[(*indices_)[i]].getVector3fMap();
+    const Eigen::Vector3f pt_n = (*normals_)[(*indices_)[i]].getNormalVector3fMap();
+
+    Eigen::Vector3f torus_closest;
+    projectPointToTorus(pt, pt_n, model_coefficients, torus_closest);
+
+    const float distance = (torus_closest - pt).norm();
+
+    if (distance < threshold) {
+      nr_p++;
+    }
+  }
+  return (nr_p);
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+void
+pcl::SampleConsensusModelTorus<PointT, PointNT>::optimizeModelCoefficients(
+    const Indices& inliers,
+    const Eigen::VectorXf& model_coefficients,
+    Eigen::VectorXf& optimized_coefficients) const
+{
+
+  optimized_coefficients = model_coefficients;
+
+  // Needs a set of valid model coefficients
+  if (!isModelValid(model_coefficients)) {
+    PCL_ERROR("[pcl::SampleConsensusModelTorus::optimizeModelCoefficients] Given model "
+              "is invalid!\n");
+    return;
+  }
+
+  // Need more than the minimum sample size to make a difference
+  if (inliers.size() <= sample_size_) {
+    PCL_ERROR("[pcl::SampleConsensusModelTorus::optimizeModelCoefficients] Not enough "
+              "inliers to refine/optimize the model's coefficients (%lu)! Returning "
+              "the same coefficients.\n",
+              inliers.size());
+    return;
+  }
+
+  OptimizationFunctor functor(this, inliers);
+  Eigen::NumericalDiff<OptimizationFunctor> num_diff(functor);
+  Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, double> lm(
+      num_diff);
+
+  Eigen::VectorXd coeff = model_coefficients.cast<double>();
+  int info = lm.minimize(coeff);
+
+  if (!info) {
+    PCL_ERROR(
+        "[pcl::SampleConsensusModelTorus::optimizeModelCoefficients] Optimizer returned"
+        "with error (%i)! Returning ",
+        info);
+    return;
+  }
+
+  // Normalize direction vector
+  coeff.tail<3>().normalize();
+  optimized_coefficients = coeff.cast<float>();
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+void
+pcl::SampleConsensusModelTorus<PointT, PointNT>::projectPointToTorus(
+    const Eigen::Vector3f& p_in,
+    const Eigen::Vector3f& p_n,
+    const Eigen::VectorXf& model_coefficients,
+    Eigen::Vector3f& pt_out) const
+{
+
+  // Fetch optimization parameters
+  const float& R = model_coefficients[0];
+  const float& r = model_coefficients[1];
+
+  const float& x0 = model_coefficients[2];
+  const float& y0 = model_coefficients[3];
+  const float& z0 = model_coefficients[4];
+
+  const float& nx = model_coefficients[5];
+  const float& ny = model_coefficients[6];
+  const float& nz = model_coefficients[7];
+
+  // Normal of the plane where the torus circle lies
+  Eigen::Vector3f n{nx, ny, nz};
+  n.normalize();
+
+  Eigen::Vector3f pt0{x0, y0, z0};
+
+  // Ax + By + Cz + D = 0
+  const float D = -n.dot(pt0);
+
+  // Project to the torus circle plane folling the point normal
+  // we want to find lambda such that p + pn_n*lambda lies on the
+  // torus plane.
+  // A*(pt_x + lambda*pn_x) + B *(pt_y + lambda*pn_y) + ... + D = 0
+  // given that: n = [A,B,C]
+  // n.dot(P) + lambda*n.dot(pn) + D = 0
+  //
+
+  Eigen::Vector3f pt_proj;
+  // If the point lies in the torus plane, we just use it as projected
+
+  // C++20 -> [[likely]]
+  if (std::abs(n.dot(p_n)) > Eigen::NumTraits<float>::dummy_precision()) {
+    float lambda = (-D - n.dot(p_in)) / n.dot(p_n);
+    pt_proj = p_in + lambda * p_n;
+  }
+  else {
+    pt_proj = p_in;
+  }
+
+  // Closest point from the inner circle to the current point
+  const Eigen::Vector3f circle_closest = (pt_proj - pt0).normalized() * R + pt0;
+
+  // From the that closest point we move towards the goal point until we
+  // meet the surface of the torus
+  pt_out = (p_in - circle_closest).normalized() * r + circle_closest;
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+void
+pcl::SampleConsensusModelTorus<PointT, PointNT>::projectPoints(
+    const Indices& inliers,
+    const Eigen::VectorXf& model_coefficients,
+    PointCloud& projected_points,
+    bool copy_data_fields) const
+{
+  // Needs a valid set of model coefficients
+  if (!isModelValid(model_coefficients)) {
+    PCL_ERROR(
+        "[pcl::SampleConsensusModelCylinder::projectPoints] Given model is invalid!\n");
+    return;
+  }
+
+  // Copy all the data fields from the input cloud to the projected one?
+  if (copy_data_fields) {
+    // Allocate enough space and copy the basics
+    projected_points.resize(input_->size());
+    projected_points.width = input_->width;
+    projected_points.height = input_->height;
+
+    using FieldList = typename pcl::traits::fieldList<PointT>::type;
+    // Iterate over each point
+    for (std::size_t i = 0; i < input_->size(); ++i)
+      // Iterate over each dimension
+      pcl::for_each_type<FieldList>(
+          NdConcatenateFunctor<PointT, PointT>((*input_)[i], projected_points[i]));
+
+    // Iterate through the 3d points and calculate the distances from them to the plane
+    for (const auto& inlier : inliers) {
+      Eigen::Vector3f q;
+      const Eigen::Vector3f pt_n = (*normals_)[inlier].getNormalVector3fMap();
+      projectPointToTorus(
+          (*input_)[inlier].getVector3fMap(), pt_n, model_coefficients, q);
+      projected_points[inlier].getVector3fMap() = q;
+    }
+  }
+  else {
+    // Allocate enough space and copy the basics
+    projected_points.resize(inliers.size());
+    projected_points.width = inliers.size();
+    projected_points.height = 1;
+
+    using FieldList = typename pcl::traits::fieldList<PointT>::type;
+    // Iterate over each point
+    for (std::size_t i = 0; i < inliers.size(); ++i) {
+      // Iterate over each dimension
+      pcl::for_each_type<FieldList>(NdConcatenateFunctor<PointT, PointT>(
+          (*input_)[inliers[i]], projected_points[i]));
+    }
+
+    for (const auto& inlier : inliers) {
+      Eigen::Vector3f q;
+      const Eigen::Vector3f pt_n = (*normals_)[inlier].getNormalVector3fMap();
+      projectPointToTorus(
+          (*input_)[inlier].getVector3fMap(), pt_n, model_coefficients, q);
+      projected_points[inlier].getVector3fMap() = q;
+    }
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+bool
+pcl::SampleConsensusModelTorus<PointT, PointNT>::doSamplesVerifyModel(
+    const std::set<index_t>& indices,
+    const Eigen::VectorXf& model_coefficients,
+    const double threshold) const
+{
+
+  for (const auto& index : indices) {
+    const Eigen::Vector3f pt_n = (*normals_)[index].getNormalVector3fMap();
+    Eigen::Vector3f torus_closest;
+    projectPointToTorus((*input_)[index].getVector3fMap(), pt_n, model_coefficients, torus_closest);
+
+    if (((*input_)[index].getVector3fMap() - torus_closest).squaredNorm() > threshold * threshold)
+      return (false);
+  }
+  return true;
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT, typename PointNT>
+bool
+pcl::SampleConsensusModelTorus<PointT, PointNT>::isModelValid(
+    const Eigen::VectorXf& model_coefficients) const
+{
+  if (!SampleConsensusModel<PointT>::isModelValid(model_coefficients))
+    return (false);
+
+  if (radius_min_ != std::numeric_limits<double>::lowest() &&
+      (model_coefficients[0] < radius_min_ || model_coefficients[1] < radius_min_)) {
+    PCL_DEBUG(
+        "[pcl::SampleConsensusModelTorus::isModelValid] Major radius OR minor radius "
+        "of torus is/are too small: should be larger than %g, but are {%g, %g}.\n",
+        radius_min_,
+        model_coefficients[0],
+        model_coefficients[1]);
+    return (false);
+  }
+  if (radius_max_ != std::numeric_limits<double>::max() &&
+      (model_coefficients[0] > radius_max_ || model_coefficients[1] > radius_max_)) {
+    PCL_DEBUG(
+        "[pcl::SampleConsensusModelTorus::isModelValid] Major radius OR minor radius "
+        "of torus is/are too big: should be smaller than %g, but are {%g, %g}.\n",
+        radius_max_,
+        model_coefficients[0],
+        model_coefficients[1]);
+    return (false);
+  }
+  return (true);
+}
+
+#define PCL_INSTANTIATE_SampleConsensusModelTorus(PointT, PointNT)                     \
+  template class PCL_EXPORTS pcl::SampleConsensusModelTorus<PointT, PointNT>;
+
+#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_TORUS_H_
index 4e690ef3e44b46b430cc85fd821cc4f799c1832a..2be6d581f4c30d5633dc22377dd93775e580e601 100644 (file)
@@ -75,7 +75,8 @@ namespace pcl
         */
       RandomizedMEstimatorSampleConsensus (const SampleConsensusModelPtr &model) 
         : SampleConsensus<PointT> (model)
-        , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents
+        , fraction_nr_pretest_ (-1.0)
+        , nr_samples_pretest_ (1)
       {
         // Maximum number of trials before we give up.
         max_iterations_ = 10000;
@@ -87,7 +88,8 @@ namespace pcl
         */
       RandomizedMEstimatorSampleConsensus (const SampleConsensusModelPtr &model, double threshold) 
         : SampleConsensus<PointT> (model, threshold)
-        , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents
+        , fraction_nr_pretest_ (-1.0)
+        , nr_samples_pretest_ (1)
       {
         // Maximum number of trials before we give up.
         max_iterations_ = 10000;
@@ -100,18 +102,41 @@ namespace pcl
       computeModel (int debug_verbosity_level = 0) override;
 
       /** \brief Set the percentage of points to pre-test.
+        * This is an alternative to setNrSamplesPretest.
         * \param[in] nr_pretest percentage of points to pre-test
         */
       inline void 
-      setFractionNrPretest (double nr_pretest) { fraction_nr_pretest_ = nr_pretest; }
+      setFractionNrPretest (double nr_pretest)
+      {
+        fraction_nr_pretest_ = nr_pretest;
+        nr_samples_pretest_ = 0;
+      }
 
       /** \brief Get the percentage of points to pre-test. */
       inline double 
       getFractionNrPretest () const { return (fraction_nr_pretest_); }
 
+      /** \brief Set the absolute number of points to pre-test.
+        * This is an alternative to setFractionNrPretest.
+        * \param[in] nr_pretest absolute number of points to pre-test
+        */
+      inline void
+      setNrSamplesPretest (std::size_t nr_pretest)
+      {
+        nr_samples_pretest_ = nr_pretest;
+        fraction_nr_pretest_ = -1.0;
+      }
+
+      /** \brief Get the absolute number of points to pre-test. */
+      inline std::size_t
+      getNrSamplesPretest () const { return (nr_samples_pretest_); }
+
     private:
-      /** \brief Number of samples to randomly pre-test, in percents. */
+      /** \brief Number of samples to randomly pre-test, in percents. This is an alternative and mutually exclusive to nr_samples_pretest_. */
       double fraction_nr_pretest_;
+
+      /** \brief Absolute number of samples to randomly pre-test. This is an alternative and mutually exclusive to fraction_nr_pretest_. */
+      std::size_t nr_samples_pretest_;
   };
 }
 
index 2f07f4f2ab4530b9b2b3281965a4290d381bae03..41b3e0d622df75687b2df582813e77820a6562f5 100644 (file)
@@ -79,7 +79,8 @@ namespace pcl
         */
       RandomizedRandomSampleConsensus (const SampleConsensusModelPtr &model) 
         : SampleConsensus<PointT> (model)
-        , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents
+        , fraction_nr_pretest_ (-1.0)
+        , nr_samples_pretest_ (1)
       {
         // Maximum number of trials before we give up.
         max_iterations_ = 10000;
@@ -91,7 +92,8 @@ namespace pcl
         */
       RandomizedRandomSampleConsensus (const SampleConsensusModelPtr &model, double threshold) 
         : SampleConsensus<PointT> (model, threshold)
-        , fraction_nr_pretest_ (10.0) // Number of samples to try randomly in percents
+        , fraction_nr_pretest_ (-1.0)
+        , nr_samples_pretest_ (1)
       {
         // Maximum number of trials before we give up.
         max_iterations_ = 10000;
@@ -104,18 +106,41 @@ namespace pcl
       computeModel (int debug_verbosity_level = 0) override;
 
       /** \brief Set the percentage of points to pre-test.
+        * This is an alternative to setNrSamplesPretest.
         * \param[in] nr_pretest percentage of points to pre-test
         */
       inline void 
-      setFractionNrPretest (double nr_pretest) { fraction_nr_pretest_ = nr_pretest; }
+      setFractionNrPretest (double nr_pretest)
+      {
+        fraction_nr_pretest_ = nr_pretest;
+        nr_samples_pretest_ = 0;
+      }
 
       /** \brief Get the percentage of points to pre-test. */
       inline double 
       getFractionNrPretest () const { return (fraction_nr_pretest_); }
 
+      /** \brief Set the absolute number of points to pre-test.
+        * This is an alternative to setFractionNrPretest.
+        * \param[in] nr_pretest absolute number of points to pre-test
+        */
+      inline void
+      setNrSamplesPretest (std::size_t nr_pretest)
+      {
+        nr_samples_pretest_ = nr_pretest;
+        fraction_nr_pretest_ = -1.0;
+      }
+
+      /** \brief Get the absolute number of points to pre-test. */
+      inline std::size_t
+      getNrSamplesPretest () const { return (nr_samples_pretest_); }
+
     private:
-      /** \brief Number of samples to randomly pre-test, in percents. */
+      /** \brief Number of samples to randomly pre-test, in percents. This is an alternative and mutually exclusive to nr_samples_pretest_. */
       double fraction_nr_pretest_;
+
+      /** \brief Absolute number of samples to randomly pre-test. This is an alternative and mutually exclusive to fraction_nr_pretest_. */
+      std::size_t nr_samples_pretest_;
   };
 }
 
index d4c6e53d9801d36517126ed594ebdcf1100a5a90..7531b5f96127064e2fddf1779ba77cd28585ebdb 100644 (file)
@@ -65,6 +65,7 @@ namespace pcl
       using SampleConsensusModel<PointT>::indices_;
       using SampleConsensusModel<PointT>::radius_min_;
       using SampleConsensusModel<PointT>::radius_max_;
+      using SampleConsensusModel<PointT>::error_sqr_dists_;
 
       using PointCloud = typename SampleConsensusModel<PointT>::PointCloud;
       using PointCloudPtr = typename SampleConsensusModel<PointT>::PointCloudPtr;
@@ -232,18 +233,19 @@ namespace pcl
          */
         int operator() (const Eigen::VectorXd &x, Eigen::VectorXd &fvec) const
         {
+          // Same for all points, so define outside of loop:
+          // C : Circle Center
+          const Eigen::Vector3d C (x[0], x[1], x[2]);
+          // N : Circle (Plane) Normal
+          const Eigen::Vector3d N (x[4], x[5], x[6]);
+          // r : Radius
+          const double r = x[3];
           for (int i = 0; i < values (); ++i)
           {
             // what i have:
             // P : Sample Point
             Eigen::Vector3d P =
                 (*model_->input_)[indices_[i]].getVector3fMap().template cast<double>();
-            // C : Circle Center
-            Eigen::Vector3d C (x[0], x[1], x[2]);
-            // N : Circle (Plane) Normal
-            Eigen::Vector3d N (x[4], x[5], x[6]);
-            // r : Radius
-            double r = x[3];
 
             Eigen::Vector3d helperVectorPC = P - C;
             // 1.1. get line parameter
index 6137c26126c99495d0f0a94afe0ec709340bb236..9bf228106507f0a93915b1361d00d07d74ef1d72 100644 (file)
 #include <pcl/sample_consensus/sac_model.h>
 #include <pcl/sample_consensus/model_types.h>
 #include <pcl/common/distances.h>
+#include <pcl/pcl_exports.h>
 
 namespace pcl
 {
   namespace internal {
-    int optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z);
+    PCL_EXPORTS int optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z);
   } // namespace internal
 
   /** \brief @b SampleConsensusModelCone defines a model for 3D cone segmentation.
index 95a6e80873befdebb2056346ba7382d3f086cd74..12a42ea5a41635f432ec721c049a1eb74e0a3451 100644 (file)
 #include <pcl/sample_consensus/sac_model.h>
 #include <pcl/sample_consensus/model_types.h>
 #include <pcl/common/distances.h>
+#include <pcl/pcl_exports.h>
 
 namespace pcl
 {
   namespace internal {
-    int optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z);
+    PCL_EXPORTS int optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z);
   } // namespace internal
 
   /** \brief @b SampleConsensusModelCylinder defines a model for 3D cylinder segmentation.
index fb6e8d49b1c4f444467a77c32b2768ef13467870..11b22de1585805d67f8b8d036b1fa4af86331193 100644 (file)
@@ -46,6 +46,7 @@ namespace pcl
       using SampleConsensusModel<PointT>::indices_;
       using SampleConsensusModel<PointT>::radius_min_;
       using SampleConsensusModel<PointT>::radius_max_;
+      using SampleConsensusModel<PointT>::error_sqr_dists_;
 
       using PointCloud = typename SampleConsensusModel<PointT>::PointCloud;
       using PointCloudPtr = typename SampleConsensusModel<PointT>::PointCloudPtr;
index 2bee660a23f52b6d50c3aa9d1274b460a8864b8d..2f81614c9c591c80a2276645234edbf2b4357295 100644 (file)
@@ -139,7 +139,7 @@ namespace pcl
     * \ingroup sample_consensus
     */
   template <typename PointT>
-  class SampleConsensusModelPlane : public SampleConsensusModel<PointT>
+  class PCL_EXPORTS SampleConsensusModelPlane : public SampleConsensusModel<PointT>
   {
     public:
       using SampleConsensusModel<PointT>::model_name_;
@@ -292,13 +292,35 @@ namespace pcl
                               std::size_t i = 0) const;
 #endif
 
+#define PCLAT(POS) ((*input_)[(*indices_)[(POS)]])
+
 #ifdef __AVX__
-      inline __m256 dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const;
-#endif
+// This function computes the distances of 8 points to the plane
+inline __m256 dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const
+{
+  // The andnot-function realizes an abs-operation: the sign bit is removed
+  return _mm256_andnot_ps (abs_help,
+        _mm256_add_ps (_mm256_add_ps (_mm256_mul_ps (a_vec, _mm256_set_ps (PCLAT(i  ).x, PCLAT(i+1).x, PCLAT(i+2).x, PCLAT(i+3).x, PCLAT(i+4).x, PCLAT(i+5).x, PCLAT(i+6).x, PCLAT(i+7).x)),
+                                      _mm256_mul_ps (b_vec, _mm256_set_ps (PCLAT(i  ).y, PCLAT(i+1).y, PCLAT(i+2).y, PCLAT(i+3).y, PCLAT(i+4).y, PCLAT(i+5).y, PCLAT(i+6).y, PCLAT(i+7).y))),
+                       _mm256_add_ps (_mm256_mul_ps (c_vec, _mm256_set_ps (PCLAT(i  ).z, PCLAT(i+1).z, PCLAT(i+2).z, PCLAT(i+3).z, PCLAT(i+4).z, PCLAT(i+5).z, PCLAT(i+6).z, PCLAT(i+7).z)),
+                                      d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
+}
+#endif // ifdef __AVX__
 
 #ifdef __SSE__
-      inline __m128 dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const;
-#endif
+// This function computes the distances of 4 points to the plane
+inline __m128 dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const
+{
+  // The andnot-function realizes an abs-operation: the sign bit is removed
+  return _mm_andnot_ps (abs_help,
+        _mm_add_ps (_mm_add_ps (_mm_mul_ps (a_vec, _mm_set_ps (PCLAT(i  ).x, PCLAT(i+1).x, PCLAT(i+2).x, PCLAT(i+3).x)),
+                                _mm_mul_ps (b_vec, _mm_set_ps (PCLAT(i  ).y, PCLAT(i+1).y, PCLAT(i+2).y, PCLAT(i+3).y))),
+                    _mm_add_ps (_mm_mul_ps (c_vec, _mm_set_ps (PCLAT(i  ).z, PCLAT(i+1).z, PCLAT(i+2).z, PCLAT(i+3).z)),
+                                d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal
+}
+#endif // ifdef __SSE__
+
+#undef PCLAT
 
     private:
       /** \brief Check if a sample of indices results in a good sample of points
index 537fcb3d0dd8c2c78ae7562c20152c091ff878a9..c3209e3f672d0010b9ebee84536d90c738509faf 100644 (file)
 
 #include <pcl/sample_consensus/sac_model.h>
 #include <pcl/sample_consensus/model_types.h>
+#include <pcl/pcl_exports.h>
 
 namespace pcl
 {
   namespace internal {
-    int optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z);
+    PCL_EXPORTS int optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z);
   } // namespace internal
 
   /** \brief SampleConsensusModelSphere defines a model for 3D sphere segmentation.
diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_torus.h b/sample_consensus/include/pcl/sample_consensus/sac_model_torus.h
new file mode 100644 (file)
index 0000000..d69a29f
--- /dev/null
@@ -0,0 +1,318 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2010-2011, Willow Garage, Inc.
+ *  Copyright (c) 2012-, Open Perception, Inc.
+ *
+ *  All rights reserved.
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * Redistributions in binary form must reproduce the above
+ *     copyright notice, this list of conditions and the following
+ *     disclaimer in the documentation and/or other materials provided
+ *     with the distribution.
+ *   * Neither the name of the copyright holder(s) nor the names of its
+ *     contributors may be used to endorse or promote products derived
+ *     from this software without specific prior written permission.
+ *
+ *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ *  POSSIBILITY OF SUCH DAMAGE.
+ *
+ * $Id$
+ *
+ */
+
+#pragma once
+
+#include <pcl/common/distances.h>
+#include <pcl/sample_consensus/model_types.h>
+#include <pcl/sample_consensus/sac_model.h>
+
+namespace pcl {
+
+/** \brief @b SampleConsensusModelTorus defines a model for 3D torus segmentation.
+ * The model coefficients are defined as:
+ *   - \b radii.inner          : the torus's inner radius
+ *   - \b radii.outer          : the torus's outer radius
+ *   - \b torus_center_point.x  : the X coordinate of the center of the torus
+ *   - \b torus_center_point.y  : the Y coordinate of the center of the torus
+ *   - \b torus_center_point.z  : the Z coordinate of the center of the torus
+ *   - \b torus_normal.x  : the X coordinate of the normal of the torus
+ *   - \b torus_normal.y  : the Y coordinate of the normal of the torus
+ *   - \b torus_normal.z  : the Z coordinate of the normal of the torus
+ *
+ * \author lasdasdas
+ * \ingroup sample_consensus
+ */
+template <typename PointT, typename PointNT>
+class SampleConsensusModelTorus
+: public SampleConsensusModel<PointT>,
+  public SampleConsensusModelFromNormals<PointT, PointNT> {
+  using SampleConsensusModel<PointT>::model_name_;
+  using SampleConsensusModel<PointT>::input_;
+  using SampleConsensusModel<PointT>::indices_;
+  using SampleConsensusModel<PointT>::radius_min_;
+  using SampleConsensusModel<PointT>::radius_max_;
+  using SampleConsensusModelFromNormals<PointT, PointNT>::normals_;
+  using SampleConsensusModelFromNormals<PointT, PointNT>::normal_distance_weight_;
+  using SampleConsensusModel<PointT>::error_sqr_dists_;
+
+  using PointCloud = typename SampleConsensusModel<PointT>::PointCloud;
+  using PointCloudPtr = typename SampleConsensusModel<PointT>::PointCloudPtr;
+  using PointCloudConstPtr = typename SampleConsensusModel<PointT>::PointCloudConstPtr;
+
+public:
+  using Ptr = shared_ptr<SampleConsensusModelTorus<PointT, PointNT>>;
+  using ConstPtr = shared_ptr<const SampleConsensusModelTorus<PointT, PointNT>>;
+
+  /** \brief Constructor for base SampleConsensusModelTorus.
+   * \param[in] cloud the input point cloud dataset
+   * \param[in] random if true set the random seed to the current time, else set to
+   * 12345 (default: false)
+   */
+  SampleConsensusModelTorus(const PointCloudConstPtr& cloud, bool random = false)
+  : SampleConsensusModel<PointT>(cloud, random)
+  , SampleConsensusModelFromNormals<PointT, PointNT>()
+  {
+    model_name_ = "SampleConsensusModelTorus";
+    sample_size_ = 4;
+    model_size_ = 8;
+  }
+
+  /** \brief Constructor for base SampleConsensusModelTorus.
+   * \param[in] cloud the input point cloud dataset
+   * \param[in] indices a vector of point indices to be used from \a cloud
+   * \param[in] random if true set the random seed to the current time, else set to
+   * 12345 (default: false)
+   */
+  SampleConsensusModelTorus(const PointCloudConstPtr& cloud,
+                            const Indices& indices,
+                            bool random = false)
+  : SampleConsensusModel<PointT>(cloud, indices, random)
+  , SampleConsensusModelFromNormals<PointT, PointNT>()
+  {
+    model_name_ = "SampleConsensusModelTorus";
+    sample_size_ = 4;
+    model_size_ = 8;
+  }
+
+  /** \brief Copy constructor.
+   * \param[in] source the model to copy into this
+   */
+  SampleConsensusModelTorus(const SampleConsensusModelTorus& source)
+  : SampleConsensusModel<PointT>(), SampleConsensusModelFromNormals<PointT, PointNT>()
+  {
+    *this = source;
+    model_name_ = "SampleConsensusModelTorus";
+  }
+
+  /** \brief Empty destructor */
+  ~SampleConsensusModelTorus() override = default;
+
+  /** \brief Copy constructor.
+   * \param[in] source the model to copy into this
+   */
+  inline SampleConsensusModelTorus&
+  operator=(const SampleConsensusModelTorus& source)
+  {
+    SampleConsensusModelFromNormals<PointT, PointNT>::operator=(source);
+    return (*this);
+  }
+  /** \brief Check whether the given index samples can form a valid torus model, compute
+   * the model coefficients from these samples and store them in model_coefficients. The
+   * torus coefficients are: radii, torus_center_point, torus_normal.
+   * \param[in] samples the point indices found as possible good candidates for creating a valid model
+   * \param[out] model_coefficients the resultant model coefficients
+   */
+  bool
+  computeModelCoefficients(const Indices& samples,
+                           Eigen::VectorXf& model_coefficients) const override;
+
+  /** \brief Compute all distances from the cloud data to a given torus model.
+   * \param[in] model_coefficients the coefficients of a torus model that we need to compute distances to
+   * \param[out] distances the resultant estimated distances
+   */
+  void
+  getDistancesToModel(const Eigen::VectorXf& model_coefficients,
+                      std::vector<double>& distances) const override;
+
+  /** \brief Select all the points which respect the given model coefficients as
+   * inliers.
+   * \param[in] model_coefficients the coefficients of a torus model that we need to compute distances to
+   * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers
+   * \param[out] inliers the
+   * resultant model inliers
+   */
+  void
+  selectWithinDistance(const Eigen::VectorXf& model_coefficients,
+                       const double threshold,
+                       Indices& inliers) override;
+
+  /** \brief Count all the points which respect the given model coefficients as inliers.
+   *
+   * \param[in] model_coefficients the coefficients of a model that we need to compute distances to
+   * \param[in] threshold maximum admissible distance threshold for
+   * determining the inliers from the outliers \return the resultant number of inliers
+   */
+  std::size_t
+  countWithinDistance(const Eigen::VectorXf& model_coefficients,
+                      const double threshold) const override;
+
+  /** \brief Recompute the torus coefficients using the given inlier set and return them
+   * to the user.
+   * \param[in] inliers the data inliers found as supporting the model
+   * \param[in] model_coefficients the initial guess for the optimization
+   * \param[out] optimized_coefficients the resultant recomputed coefficients after
+   * non-linear optimization
+   */
+  void
+  optimizeModelCoefficients(const Indices& inliers,
+                            const Eigen::VectorXf& model_coefficients,
+                            Eigen::VectorXf& optimized_coefficients) const override;
+
+  /** \brief Create a new point cloud with inliers projected onto the torus model.
+   * \param[in] inliers the data inliers that we want to project on the torus model
+   * \param[in] model_coefficients the coefficients of a torus model
+   * \param[out] projected_points the resultant projected points
+   * \param[in] copy_data_fields set to true if we need to copy the other data fields
+   */
+  void
+  projectPoints(const Indices& inliers,
+                const Eigen::VectorXf& model_coefficients,
+                PointCloud& projected_points,
+                bool copy_data_fields = true) const override;
+
+  /** \brief Verify whether a subset of indices verifies the given torus model
+   * coefficients.
+   * \param[in] indices the data indices that need to be tested against the torus model
+   * \param[in] model_coefficients the torus model coefficients
+   * \param[in] threshold a maximum admissible distance threshold for determining the
+   * inliers from the outliers
+   */
+  bool
+  doSamplesVerifyModel(const std::set<index_t>& indices,
+                       const Eigen::VectorXf& model_coefficients,
+                       const double threshold) const override;
+
+  /** \brief Return a unique id for this model (SACMODEL_TORUS). */
+  inline pcl::SacModel
+  getModelType() const override
+  {
+    return (SACMODEL_TORUS);
+  }
+
+protected:
+  using SampleConsensusModel<PointT>::sample_size_;
+  using SampleConsensusModel<PointT>::model_size_;
+
+  /** \brief Project a point onto a torus given by its model coefficients (radii,
+   * torus_center_point, torus_normal)
+   * \param[in] pt the input point to project
+   * \param[in] model_coefficients the coefficients of the torus (radii, torus_center_point, torus_normal)
+   * \param[out] pt_proj the resultant projected point
+   */
+  void
+  projectPointToTorus(const Eigen::Vector3f& pt,
+                      const Eigen::Vector3f& pt_n,
+                      const Eigen::VectorXf& model_coefficients,
+                      Eigen::Vector3f& pt_proj) const;
+
+  /** \brief Check whether a model is valid given the user constraints.
+   * \param[in] model_coefficients the set of model coefficients
+   */
+  bool
+  isModelValid(const Eigen::VectorXf& model_coefficients) const override;
+
+  /** \brief Check if a sample of indices results in a good sample of points
+   * indices. Pure virtual.
+   * \param[in] samples the resultant index samples
+   */
+  bool
+  isSampleGood(const Indices& samples) const override;
+
+private:
+  struct OptimizationFunctor : pcl::Functor<double> {
+    /** Functor constructor
+     * \param[in] indices the indices of data points to evaluate
+     * \param[in] estimator pointer to the estimator object
+     */
+    OptimizationFunctor(const pcl::SampleConsensusModelTorus<PointT, PointNT>* model,
+                        const Indices& indices)
+    : pcl::Functor<double>(indices.size()), model_(model), indices_(indices)
+    {}
+
+    /** Cost function to be minimized
+     * \param[in] x the variables array
+     * \param[out] fvec the resultant functions evaluations
+     * \return 0
+     */
+    int
+    operator()(const Eigen::VectorXd& xs, Eigen::VectorXd& fvec) const
+    {
+      // Getting constants from state vector
+      const double& R = xs[0];
+      const double& r = xs[1];
+
+      const double& x0 = xs[2];
+      const double& y0 = xs[3];
+      const double& z0 = xs[4];
+
+      const Eigen::Vector3d centroid{x0, y0, z0};
+
+      const double& nx = xs[5];
+      const double& ny = xs[6];
+      const double& nz = xs[7];
+
+      const Eigen::Vector3d n1{0.0, 0.0, 1.0};
+      const Eigen::Vector3d n2 = Eigen::Vector3d{nx, ny, nz}.normalized();
+
+      for (size_t j = 0; j < indices_.size(); j++) {
+
+        size_t i = indices_[j];
+        const Eigen::Vector3d pt =
+            (*model_->input_)[i].getVector3fMap().template cast<double>();
+
+        Eigen::Vector3d pte{pt - centroid};
+
+        // Transposition is inversion
+        // Using Quaternions instead of Rodrigues
+        pte = Eigen::Quaterniond()
+                  .setFromTwoVectors(n1, n2)
+                  .toRotationMatrix()
+                  .transpose() *
+              pte;
+
+        const double& x = pte[0];
+        const double& y = pte[1];
+        const double& z = pte[2];
+
+        fvec[j] = (std::pow(sqrt(x * x + y * y) - R, 2) + z * z - r * r);
+      }
+      return 0;
+    }
+
+    const pcl::SampleConsensusModelTorus<PointT, PointNT>* model_;
+    const Indices& indices_;
+  };
+};
+} // namespace pcl
+
+#ifdef PCL_NO_PRECOMPILE
+#include <pcl/sample_consensus/impl/sac_model_torus.hpp>
+#endif
index 914722bb28b167eee250a6d113d1eafa5cd05d59..5ad7932867c5168e6f65e41119522d39e35d3967 100644 (file)
@@ -23,7 +23,7 @@
     <li>\link pcl::SampleConsensusModelSphere SACMODEL_SPHERE \endlink - used to determine sphere models. The <b>four</b> coefficients of the sphere are given by its 3D center and radius as: [<b>center.x center.y center.z radius</b>]</li>
     <li>\link pcl::SampleConsensusModelCylinder SACMODEL_CYLINDER \endlink - used to determine cylinder models. The <b>seven</b> coefficients of the cylinder are given by a point on its axis, the axis direction, and a radius, as: [<b>point_on_axis.x point_on_axis.y point_on_axis.z axis_direction.x axis_direction.y axis_direction.z radius</b>]</li>
     <li>\link pcl::SampleConsensusModelCone SACMODEL_CONE \endlink - used to determine cone models. The <b>seven</b> coefficients of the cone are given by a point of its apex, the axis direction and the opening angle, as: [<b>apex.x, apex.y, apex.z, axis_direction.x, axis_direction.y, axis_direction.z, opening_angle</b>]</li>
-    <li>SACMODEL_TORUS - not implemented yet</li>
+    <li>\link pcl::SampleConsensusModelTorus SACMODEL_TORUS \endlink - used to determine torus models. The <b>eight</b> coefficients of the torus are given by the inner and outer radius, the center point, and the torus axis.</li>
     <li>\link pcl::SampleConsensusModelParallelLine SACMODEL_PARALLEL_LINE \endlink - a model for determining a line <b>parallel</b> with a given axis, within a maximum specified angular deviation. The line coefficients are similar to \link pcl::SampleConsensusModelLine SACMODEL_LINE \endlink.</li>
     <li>\link pcl::SampleConsensusModelPerpendicularPlane SACMODEL_PERPENDICULAR_PLANE \endlink - a model for determining a plane <b>perpendicular</b> to a user-specified axis, within a maximum specified angular deviation. The plane coefficients are similar to \link pcl::SampleConsensusModelPlane SACMODEL_PLANE \endlink.</li>
     <li>SACMODEL_PARALLEL_LINES - not implemented yet</li>
diff --git a/sample_consensus/src/sac_model_torus.cpp b/sample_consensus/src/sac_model_torus.cpp
new file mode 100644 (file)
index 0000000..f0d71b9
--- /dev/null
@@ -0,0 +1,44 @@
+/*
+ * Software License Agreement (BSD License)
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2009-2012, Willow Garage, Inc.
+ *  Copyright (c) 2012-, Open Perception, Inc.
+ *
+ *  All rights reserved.
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * Redistributions in binary form must reproduce the above
+ *     copyright notice, this list of conditions and the following
+ *     disclaimer in the documentation and/or other materials provided
+ *     with the distribution.
+ *   * Neither the name of the copyright holder(s) nor the names of its
+ *     contributors may be used to endorse or promote products derived
+ *     from this software without specific prior written permission.
+ *
+ *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ *  POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#include <pcl/sample_consensus/impl/sac_model_torus.hpp>
+
+#ifndef PCL_NO_PRECOMPILE
+#include <pcl/impl/instantiate.hpp>
+#include <pcl/point_types.h>
+PCL_INSTANTIATE_PRODUCT(SampleConsensusModelTorus, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGBA)(pcl::PointXYZRGB))((pcl::Normal)))
+#endif    // PCL_NO_PRECOMPILE
index 0b93e5255c2e4431f6d851f55024087c5a81ef2f..d8422ab9e541a2b459c944a457ee28046fd9bf99 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME search)
 set(SUBSYS_DESC "Point cloud generic search library")
 set(SUBSYS_DEPS common kdtree octree)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS flann)
 
@@ -39,7 +38,6 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_common FLANN::FLANN pcl_octree pcl_kdtree)
 list(APPEND EXT_DEPS flann)
index 12e6da32962d0c2322e51f792058820854a3b0b0..df089620fc31791e43f5e127190f220efeb849fb 100644 (file)
@@ -82,7 +82,7 @@ pcl::search::OrganizedNeighbor<PointT>::radiusSearch (const               PointT
   {
     for (; idx < xEnd; ++idx)
     {
-      if (!mask_[idx] || !isFinite ((*input_)[idx]))
+      if (!mask_[idx])
         continue;
 
       float dist_x = (*input_)[idx].x - query.x;
index fe07756ef4495453fb8af9ca651e01741ba2e97e..20f23841bbbfc4b140ad13ac72f49987958bc26e 100644 (file)
@@ -42,6 +42,7 @@
 #include <pcl/memory.h>
 #include <pcl/pcl_macros.h>
 #include <pcl/point_cloud.h>
+#include <pcl/common/point_tests.h> // for pcl::isFinite
 #include <pcl/search/search.h>
 #include <pcl/common/eigen.h>
 
@@ -80,7 +81,7 @@ namespace pcl
 
         /** \brief Constructor
           * \param[in] sorted_results whether the results should be return sorted in ascending order on the distances or not.
-          *        This applies only for radius search, since knn always returns sorted resutls    
+          *        This applies only for radius search, since knn always returns sorted results    
           * \param[in] eps the threshold for the mean-squared-error of the estimation of the projection matrix.
           *            if the MSE is above this value, the point cloud is considered as not from a projective device,
           *            thus organized neighbor search can not be applied on that cloud.
@@ -138,10 +139,16 @@ namespace pcl
           {
             mask_.assign (input_->size (), 0);
             for (const auto& idx : *indices_)
-              mask_[idx] = 1;
+              if (pcl::isFinite((*input_)[idx]))
+                mask_[idx] = 1;
           }
           else
-            mask_.assign (input_->size (), 1);
+          {
+            mask_.assign (input_->size (), 0);
+            for (std::size_t idx=0; idx<input_->size(); ++idx)
+              if (pcl::isFinite((*input_)[idx]))
+                mask_[idx] = 1;
+          }
 
           return estimateProjectionMatrix () && isValid ();
         }
@@ -216,7 +223,7 @@ namespace pcl
         testPoint (const PointT& query, unsigned k, std::vector<Entry>& queue, index_t index) const
         {
           const PointT& point = input_->points [index];
-          if (mask_ [index] && std::isfinite (point.x))
+          if (mask_ [index])
           {
             //float squared_distance = (point.getVector3fMap () - query.getVector3fMap ()).squaredNorm ();
             float dist_x = point.x - query.x;
@@ -278,7 +285,7 @@ namespace pcl
         /** \brief using only a subsample of points to calculate the projection matrix. pyramid_level_ = use down sampled cloud given by pyramid_level_*/
         const unsigned pyramid_level_;
         
-        /** \brief mask, indicating whether the point was in the indices list or not.*/
+        /** \brief mask, indicating whether the point was in the indices list or not, and whether it is finite.*/
         std::vector<unsigned char> mask_;
       public:
         PCL_MAKE_ALIGNED_OPERATOR_NEW
index f6cdf291a5ace5f5b49234f023b11a6414613273..901a63fcc387a971eddec928cc766dd05f40f535 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME segmentation)
 set(SUBSYS_DESC "Point cloud segmentation library")
 set(SUBSYS_DEPS common geometry search sample_consensus kdtree octree features filters ml)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
@@ -36,7 +35,6 @@ set(srcs
 )
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
   "include/pcl/${SUBSYS_NAME}/extract_clusters.h"
   "include/pcl/${SUBSYS_NAME}/extract_labeled_clusters.h"
   "include/pcl/${SUBSYS_NAME}/extract_polygonal_prism_data.h"
@@ -99,9 +97,8 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
-target_link_libraries("${LIB_NAME}" pcl_search pcl_sample_consensus pcl_filters pcl_ml pcl_features)
+target_link_libraries("${LIB_NAME}" pcl_geometry pcl_search pcl_sample_consensus pcl_filters pcl_ml pcl_features)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
 
 # Install include files
diff --git a/segmentation/include/pcl/segmentation/boost.h b/segmentation/include/pcl/segmentation/boost.h
deleted file mode 100644 (file)
index 6ef50c3..0000000
+++ /dev/null
@@ -1,55 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2010-2011, Willow Garage, Inc.
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: io.h 5850 2012-06-06 14:04:59Z stfox88 $
- *
- */
-
-#pragma once
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-#ifdef __GNUC__
-#pragma GCC system_header
-#endif
-
-#ifndef Q_MOC_RUN
-// Marking all Boost headers as system headers to remove warnings
-#include <boost/version.hpp>
-#include <boost/graph/adjacency_list.hpp>
-#include <boost/multi_array.hpp>
-#include <boost/ptr_container/ptr_list.hpp>
-
-#include <boost/graph/boykov_kolmogorov_max_flow.hpp>
-#endif
index cbda2cdf9523cca82d21a80336fa59e115a356ee..2bfb4196c7f48c190385b2226b73aba628a5bd74 100644 (file)
@@ -123,6 +123,8 @@ namespace pcl
                 static_cast<std::size_t>(normals.size()));
       return;
     }
+    // If tree gives sorted results, we can skip the first one because it is the query point itself
+    const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
     const double cos_eps_angle = std::cos (eps_angle); // compute this once instead of acos many times (faster)
 
     // Create a bool vector of processed point indices, and initialize it to false
@@ -151,7 +153,7 @@ namespace pcl
           continue;
         }
 
-        for (std::size_t j = 1; j < nn_indices.size (); ++j)             // nn_indices[0] should be sq_idx
+        for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
         {
           if (processed[nn_indices[j]])                         // Has this point been processed before ?
             continue;
@@ -243,6 +245,8 @@ namespace pcl
                 static_cast<std::size_t>(normals.size()));
       return;
     }
+    // If tree gives sorted results, we can skip the first one because it is the query point itself
+    const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
     const double cos_eps_angle = std::cos (eps_angle); // compute this once instead of acos many times (faster)
     // Create a bool vector of processed point indices, and initialize it to false
     std::vector<bool> processed (cloud.size (), false);
@@ -270,7 +274,7 @@ namespace pcl
           continue;
         }
 
-        for (std::size_t j = 1; j < nn_indices.size (); ++j)             // nn_indices[0] should be sq_idx
+        for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
         {
           if (processed[nn_indices[j]])                             // Has this point been processed before ?
             continue;
index 39aab83b0fd62b4750b7709d0289893b5b7604fe..acdd3e9a71d49f6797427a99ad67d1cc8afcce68 100644 (file)
@@ -187,7 +187,8 @@ protected:
 
   /** \brief The maximum number of labels we can find in this pointcloud (default =
    * MAXINT)*/
-  unsigned int max_label_{std::numeric_limits<int>::max()};
+  PCL_DEPRECATED(1, 18, "this member variable is unused")
+  unsigned int max_label_{std::numeric_limits<unsigned int>::max()};
 
   /** \brief Class getName method. */
   virtual std::string
index 0739726c53eaa820005b84fcf54f83c762efc770..08cc63f91d1a43a9bc3c042466dedd2cebba131d 100644 (file)
@@ -40,6 +40,7 @@
 #include <limits>
 
 #include <pcl/pcl_base.h>
+#include <pcl/Vertices.h> // for Vertices
 
 namespace pcl
 {
@@ -124,6 +125,16 @@ namespace pcl
       inline void 
       setInputPlanarHull (const PointCloudConstPtr &hull) { planar_hull_ = hull; }
 
+       /** \brief Provide a vector of the concave polygons indices, as recieved from ConcaveHull::polygons.
+       * \note This is only needed when using ConcaveHull that has more than one polygon.
+       * \param[in] polygons - see ConcaveHull::polygons
+       */
+      inline void
+      setPolygons(const std::vector<pcl::Vertices>& polygons)
+      {
+        polygons_ = polygons;
+      }
+
       /** \brief Get a pointer the input planar hull dataset. */
       inline PointCloudConstPtr 
       getInputPlanarHull () const { return (planar_hull_); }
@@ -185,6 +196,9 @@ namespace pcl
       /** \brief A pointer to the input planar hull dataset. */
       PointCloudConstPtr planar_hull_{nullptr};
 
+      /** \brief polygons indices vectors, as recieved from ConcaveHull */
+      std::vector<pcl::Vertices> polygons_;
+
       /** \brief The minimum number of points needed on the convex hull. */
       int min_pts_hull_{3};
 
index 8a054c54c1dcf6229d8001ae7f6e3616e66b2f00..564d3e9471a7e24a64098716edb8c9e621edde5f 100644 (file)
@@ -266,7 +266,7 @@ pcl::ApproximateProgressiveMorphologicalFilter<PointT>::extract (Indices& ground
 }
 
 
-#define PCL_INSTANTIATE_ApproximateProgressiveMorphologicalFilter(T) template class pcl::ApproximateProgressiveMorphologicalFilter<T>;
+#define PCL_INSTANTIATE_ApproximateProgressiveMorphologicalFilter(T) template class PCL_EXPORTS pcl::ApproximateProgressiveMorphologicalFilter<T>;
 
 #endif    // PCL_SEGMENTATION_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_
 
index 93230268017f7e2f503b47d79eb980ec442978d7..5eef5e599194ca2eab6a23339057487c198959bd 100644 (file)
@@ -60,11 +60,13 @@ pcl::ConditionalEuclideanClustering<PointT>::segment (pcl::IndicesClusters &clus
   if (!searcher_)
   {
     if (input_->isOrganized ())
-      searcher_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
+      searcher_.reset (new pcl::search::OrganizedNeighbor<PointT> (false)); // not requiring sorted results is much faster
     else
-      searcher_.reset (new pcl::search::KdTree<PointT> ());
+      searcher_.reset (new pcl::search::KdTree<PointT> (false)); // not requiring sorted results is much faster
   }
   searcher_->setInputCloud (input_, indices_);
+  // If searcher_ gives sorted results, we can skip the first one because it is the query point itself
+  const int nn_start_idx = searcher_->getSortedResults () ? 1 : 0;
 
   // Temp variables used by search class
   Indices nn_indices;
@@ -100,7 +102,7 @@ pcl::ConditionalEuclideanClustering<PointT>::segment (pcl::IndicesClusters &clus
       }
 
       // Process the neighbors
-      for (int nii = 1; nii < static_cast<int> (nn_indices.size ()); ++nii)  // nii = neighbor indices iterator
+      for (int nii = nn_start_idx; nii < static_cast<int> (nn_indices.size ()); ++nii)  // nii = neighbor indices iterator
       {
         // Has this point been processed before?
         if (nn_indices[nii] == UNAVAILABLE || processed[nn_indices[nii]])
index cf00fa56a846265d216b193f7e7e6b39da948291..01b9dba9a91caee78f73bbcd916b13d6c77fd67d 100644 (file)
@@ -71,6 +71,6 @@ pcl::CrfNormalSegmentation<PointT>::segmentPoints ()
 {
 }
 
-#define PCL_INSTANTIATE_CrfNormalSegmentation(T) template class pcl::CrfNormalSegmentation<T>;
+#define PCL_INSTANTIATE_CrfNormalSegmentation(T) template class PCL_EXPORTS pcl::CrfNormalSegmentation<T>;
 
 #endif    // PCL_CRF_NORMAL_SEGMENTATION_HPP_
index 2c2f9f5bac05d0564fc3ab3187b5017c36d81f8d..ff0615675199c07885c24e6514a333add3ce4d90 100644 (file)
@@ -595,6 +595,6 @@ pcl::CrfSegmentation<PointT>::segmentPoints (pcl::PointCloud<pcl::PointXYZRGBL>
 
 }
 
-#define PCL_INSTANTIATE_CrfSegmentation(T) template class pcl::CrfSegmentation<T>;
+#define PCL_INSTANTIATE_CrfSegmentation(T) template class PCL_EXPORTS pcl::CrfSegmentation<T>;
 
 #endif    // PCL_CRF_SEGMENTATION_HPP_
index 1f6ea1d88d1c941daf330374451c6ac356437756..37ed0d694352a78dbeb1a8969a7d24395b175181 100644 (file)
@@ -57,6 +57,8 @@ pcl::extractLabeledEuclideanClusters(
               cloud.size());
     return;
   }
+  // If tree gives sorted results, we can skip the first one because it is the query point itself
+  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
   // Create a bool vector of processed point indices, and initialize it to false
   std::vector<bool> processed(cloud.size(), false);
 
@@ -88,8 +90,7 @@ pcl::extractLabeledEuclideanClusters(
         continue;
       }
 
-      for (std::size_t j = 1; j < nn_indices.size();
-           ++j) // nn_indices[0] should be sq_idx
+      for (std::size_t j = nn_start_idx; j < nn_indices.size(); ++j)
       {
         if (processed[nn_indices[j]]) // Has this point been processed before ?
           continue;
index 26392cddcaafb392b3f319cba5eda168b68550c3..ac3a35fb2fb82aef2cdfb20ffb214a3382fa2095 100644 (file)
@@ -227,6 +227,20 @@ pcl::ExtractPolygonalPrismData<PointT>::segment (pcl::PointIndices &output)
   PointT pt_xy;
   pt_xy.z = 0;
 
+  std::vector<pcl::PointCloud<PointT>> polygons(polygons_.size());
+  if (polygons_.empty()) {
+    polygons.push_back(polygon);
+  }
+  else { // incase of concave hull, prepare separate polygons
+    for (size_t i = 0; i < polygons_.size(); i++) {
+      const auto& polygon_i = polygons_[i];
+      polygons[i].reserve(polygon_i.vertices.size());
+      for (const auto& pointIdx : polygon_i.vertices) {
+        polygons[i].points.push_back(polygon[pointIdx]);
+      }
+    }
+  }
+
   output.indices.resize (indices_->size ());
   int l = 0;
   for (std::size_t i = 0; i < projected_points.size (); ++i)
@@ -243,8 +257,14 @@ pcl::ExtractPolygonalPrismData<PointT>::segment (pcl::PointIndices &output)
     pt_xy.x = pt[k1];
     pt_xy.y = pt[k2];
 
-    if (!pcl::isXYPointIn2DXYPolygon (pt_xy, polygon))
+    bool in_poly = false;
+    for (const auto& poly : polygons) {
+      in_poly ^= pcl::isXYPointIn2DXYPolygon(pt_xy, poly);
+    }
+
+    if (!in_poly) {
       continue;
+    }
 
     output.indices[l++] = (*indices_)[i];
   }
index 2ef5fc27b160e0b5384e1d1be9dbc61337f9b9d3..5143080b6dea4e4d90e7948201df12feea66f57b 100644 (file)
@@ -48,8 +48,8 @@ namespace pcl
 {
 
 template <>
-float squaredEuclideanDistance (const pcl::segmentation::grabcut::Color &c1,
-                                const pcl::segmentation::grabcut::Color &c2)
+inline float squaredEuclideanDistance (const pcl::segmentation::grabcut::Color &c1,
+                                       const pcl::segmentation::grabcut::Color &c2)
 {
   return ((c1.r-c2.r)*(c1.r-c2.r)+(c1.g-c2.g)*(c1.g-c2.g)+(c1.b-c2.b)*(c1.b-c2.b));
 }
index 0ec614a8e53639ee5fe1899b92adc1b9a9ef2489..643649118866dd0afcf3938dfdeda530521ab83e 100644 (file)
@@ -579,6 +579,6 @@ pcl::MinCutSegmentation<PointT>::getColoredCloud ()
   return (colored_cloud);
 }
 
-#define PCL_INSTANTIATE_MinCutSegmentation(T) template class pcl::MinCutSegmentation<T>;
+#define PCL_INSTANTIATE_MinCutSegmentation(T) template class PCL_EXPORTS pcl::MinCutSegmentation<T>;
 
 #endif    // PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_
index 68a3d3cd240d8cbae74fea2cfd71d286612a9183..e65aa01bb5827092b1eca663a7c603bbe2de72c2 100644 (file)
@@ -134,7 +134,7 @@ pcl::ProgressiveMorphologicalFilter<PointT>::extract (Indices& ground)
   deinitCompute ();
 }
 
-#define PCL_INSTANTIATE_ProgressiveMorphologicalFilter(T) template class pcl::ProgressiveMorphologicalFilter<T>;
+#define PCL_INSTANTIATE_ProgressiveMorphologicalFilter(T) template class PCL_EXPORTS pcl::ProgressiveMorphologicalFilter<T>;
 
 #endif    // PCL_SEGMENTATION_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_
 
index 0677cfbe17e655ba74acb31e6f9c5ec87352727a..efbbe2fb22cab8064675c0a696bb3fa05a2f17ad 100644 (file)
@@ -705,5 +705,5 @@ pcl::RegionGrowing<PointT, NormalT>::getColoredCloudRGBA ()
   return (colored_cloud);
 }
 
-#define PCL_INSTANTIATE_RegionGrowing(T) template class pcl::RegionGrowing<T, pcl::Normal>;
+#define PCL_INSTANTIATE_RegionGrowing(T) template class PCL_EXPORTS pcl::RegionGrowing<T, pcl::Normal>;
 
index 2c240d37c46246a43c0cbcb1e3ace7b251c13dd6..dd35c5b1e749b76c4bffc75c5966d5202577ee53 100644 (file)
@@ -338,7 +338,7 @@ pcl::RegionGrowingRGB<PointT, NormalT>::findRegionsKNN (pcl::index_t index, pcl:
   {
     if (distances[i_seg] < max_dist)
     {
-      segment_neighbours.push (std::make_pair (distances[i_seg], i_seg) );
+      segment_neighbours.emplace (distances[i_seg], i_seg);
       if (segment_neighbours.size () > nghbr_number)
         segment_neighbours.pop ();
     }
index 3976c143e2dc4ca3529b11992281b49a1e1e2948..1c79547d966a9e5baacd2ec6977765614b81d3eb 100644 (file)
@@ -61,6 +61,8 @@ pcl::seededHueSegmentation (const PointCloud<PointXYZRGB>          &cloud,
               static_cast<std::size_t>(cloud.size()));
     return;
   }
+  // If tree gives sorted results, we can skip the first one because it is the query point itself
+  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
   // Create a bool vector of processed point indices, and initialize it to false
   std::vector<bool> processed (cloud.size (), false);
 
@@ -96,7 +98,7 @@ pcl::seededHueSegmentation (const PointCloud<PointXYZRGB>          &cloud,
         continue;
       }
 
-      for (std::size_t j = 1; j < nn_indices.size (); ++j)             // nn_indices[0] should be sq_idx
+      for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
       {
         if (processed[nn_indices[j]])                             // Has this point been processed before ?
           continue;
@@ -139,6 +141,8 @@ pcl::seededHueSegmentation (const PointCloud<PointXYZRGB>            &cloud,
               static_cast<std::size_t>(cloud.size()));
     return;
   }
+  // If tree gives sorted results, we can skip the first one because it is the query point itself
+  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
   // Create a bool vector of processed point indices, and initialize it to false
   std::vector<bool> processed (cloud.size (), false);
 
@@ -173,7 +177,7 @@ pcl::seededHueSegmentation (const PointCloud<PointXYZRGB>            &cloud,
         sq_idx++;
         continue;
       }
-      for (std::size_t j = 1; j < nn_indices.size (); ++j)             // nn_indices[0] should be sq_idx
+      for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
       {
         if (processed[nn_indices[j]])                             // Has this point been processed before ?
           continue;
index 9d627c600ff5e07c201ef998606f0d502e05a7ba..81e188551890c295b6cc02cfe1caffccddb35449 100644 (file)
@@ -686,57 +686,11 @@ pcl::SupervoxelClustering<PointT>::getMaxLabel () const
   return max_label;
 }
 
-namespace pcl
-{ 
-  namespace octree
-  {
-    //Explicit overloads for RGB types
-    template<>
-    void
-    pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGB,pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData>::addPoint (const pcl::PointXYZRGB &new_point);
-    
-    template<>
-    void
-    pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGBA,pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData>::addPoint (const pcl::PointXYZRGBA &new_point);
-    
-    //Explicit overloads for RGB types
-    template<> void
-    pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGB,pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData>::computeData ();
-    
-    template<> void
-    pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGBA,pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData>::computeData ();
-    
-    //Explicit overloads for XYZ types
-    template<>
-    void
-    pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZ,pcl::SupervoxelClustering<pcl::PointXYZ>::VoxelData>::addPoint (const pcl::PointXYZ &new_point);
-    
-    template<> void
-    pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZ,pcl::SupervoxelClustering<pcl::PointXYZ>::VoxelData>::computeData ();
-  }
-}
-
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 namespace pcl
-{
-  
-  template<> void
-  pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData::getPoint (pcl::PointXYZRGB &point_arg) const;
-  
-  template<> void
-  pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData::getPoint (pcl::PointXYZRGBA &point_arg ) const;
-  
-  template<typename PointT> void
-  pcl::SupervoxelClustering<PointT>::VoxelData::getPoint (PointT &point_arg ) const
-  {
-    //XYZ is required or this doesn't make much sense...
-    point_arg.x = xyz_[0];
-    point_arg.y = xyz_[1];
-    point_arg.z = xyz_[2];
-  }
-  
+{ 
   //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
   template <typename PointT> void
   pcl::SupervoxelClustering<PointT>::VoxelData::getNormal (Normal &normal_arg) const
index dc4ef677a38b3484139b942f80f11f997f21b516..5b7e6a1ca6027dce034627abe10fe316eb5b01b5 100644 (file)
@@ -420,6 +420,6 @@ pcl::UnaryClassifier<PointT>::segment (pcl::PointCloud<pcl::PointXYZRGBL>::Ptr &
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-#define PCL_INSTANTIATE_UnaryClassifier(T) template class pcl::UnaryClassifier<T>;
+#define PCL_INSTANTIATE_UnaryClassifier(T) template class PCL_EXPORTS pcl::UnaryClassifier<T>;
 
 #endif    // PCL_UNARY_CLASSIFIER_HPP_
index 79a872a25f311004ed657b43aa823f0f3dac84a3..d87e4a041d43d60082a305acd44ea299c2772d78 100644 (file)
@@ -206,7 +206,7 @@ namespace pcl
         * \param[out] model_coefficients a vector of model_coefficients for each plane found in the input cloud
         * \param[out] inlier_indices a vector of inliers for each detected plane
         * \param[out] centroids a vector of centroids for each plane
-        * \param[out] covariances a vector of covariance matricies for the inliers of each plane
+        * \param[out] covariances a vector of covariance matrices for the inliers of each plane
         * \param[out] labels a point cloud for the connected component labels of each pixel
         * \param[out] label_indices a vector of PointIndices for each labeled component
         */
index ea0699302a9e9141717c6eac29331272664dd350..d22a3ab6eac4e9d948d6142d282cf337db2d2b2f 100644 (file)
@@ -177,7 +177,7 @@ namespace pcl
         int current_label = (*labels_)[idx1].label;
         int next_label = (*labels_)[idx2].label;
 
-        if (!((*refine_labels_)[current_label] && !(*refine_labels_)[next_label]))
+        if (!(*refine_labels_)[current_label] || (*refine_labels_)[next_label])
           return (false);
 
         const pcl::ModelCoefficients& model_coeff = (*models_)[(*label_to_model_)[current_label]];
index e9e8018bf55f4d75459f1290edafd0e2678afa0c..4c6a4b76a6e4b45d932a510f0f42970dc2bba08e 100644 (file)
@@ -143,11 +143,33 @@ namespace pcl
             owner_ (nullptr)
             {}
 
+#ifdef DOXYGEN_ONLY
           /** \brief Gets the data of in the form of a point
            *  \param[out] point_arg Will contain the point value of the voxeldata
            */
           void
           getPoint (PointT &point_arg) const;
+#else
+          template<typename PointT2 = PointT, traits::HasColor<PointT2> = true> void
+          getPoint (PointT &point_arg) const
+          {
+            point_arg.rgba = static_cast<std::uint32_t>(rgb_[0]) << 16 |
+            static_cast<std::uint32_t>(rgb_[1]) << 8 |
+            static_cast<std::uint32_t>(rgb_[2]);
+            point_arg.x = xyz_[0];
+            point_arg.y = xyz_[1];
+            point_arg.z = xyz_[2];
+          }
+
+          template<typename PointT2 = PointT, traits::HasNoColor<PointT2> = true> void
+          getPoint (PointT &point_arg ) const
+          {
+            //XYZ is required or this doesn't make much sense...
+            point_arg.x = xyz_[0];
+            point_arg.y = xyz_[1];
+            point_arg.z = xyz_[2];
+          }
+#endif
 
           /** \brief Gets the data of in the form of a normal
            *  \param[out] normal_arg Will contain the normal value of the voxeldata
index cb06b73b75ff29b53e8901e5b806beec3f4c3201..fffdcccb5f68b1d52f5eb0828bbc6f59b139f4ea 100644 (file)
@@ -43,6 +43,6 @@
 #include <pcl/segmentation/impl/crf_segmentation.hpp>
 
 // Instantiations of specific point types
-template class pcl::CrfSegmentation<pcl::PointXYZRGB>;
-template class pcl::CrfSegmentation<pcl::PointXYZRGBA>;
-template class pcl::CrfSegmentation<pcl::PointXYZRGBNormal>;
+template class PCL_EXPORTS pcl::CrfSegmentation<pcl::PointXYZRGB>;
+template class PCL_EXPORTS pcl::CrfSegmentation<pcl::PointXYZRGBA>;
+template class PCL_EXPORTS pcl::CrfSegmentation<pcl::PointXYZRGBNormal>;
index ea2b75c7704aa5cfac47fefabed13cbb7627be35..f15aef829519ae43903598f5596a0e177169672b 100644 (file)
@@ -460,7 +460,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::adoptOrphans (std::deque<int>& orp
       if (cut_[jt->first] != tree_label) continue;
 
       // check edge capacity
-      const capacitated_edge::iterator kt = nodes_[jt->first].find (u);
+      const auto kt = nodes_[jt->first].find (u);
       if (((tree_label == TARGET) && (jt->second <= 0.0)) ||
           ((tree_label == SOURCE) && (kt->second <= 0.0)))
         continue;
@@ -483,7 +483,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::adoptOrphans (std::deque<int>& orp
     // free the orphan subtree and remove it from the active set
     if (b_free_orphan)
     {
-      for (capacitated_edge::const_iterator jt = nodes_[u].begin (); jt != nodes_[u].end (); ++jt)
+      for (auto jt = nodes_[u].cbegin (); jt != nodes_[u].cend (); ++jt)
       {
         if ((cut_[jt->first] == tree_label) && (parents_[jt->first].first == u))
         {
index 76b724e1cae0c154c0fb9e5839f3282c5f258345..f377ca0e983fef348852f33b141759780a571686 100644 (file)
@@ -43,7 +43,7 @@
 #include <pcl/segmentation/impl/region_growing_rgb.hpp>
 
 // Instantiations of specific point types
-template class pcl::RegionGrowingRGB<pcl::PointXYZRGBA>;
-template class pcl::RegionGrowingRGB<pcl::PointXYZRGB>;
-template class pcl::RegionGrowingRGB<pcl::PointXYZRGBL>;
-template class pcl::RegionGrowingRGB<pcl::PointXYZRGBNormal>;
+template class PCL_EXPORTS pcl::RegionGrowingRGB<pcl::PointXYZRGBA>;
+template class PCL_EXPORTS pcl::RegionGrowingRGB<pcl::PointXYZRGB>;
+template class PCL_EXPORTS pcl::RegionGrowingRGB<pcl::PointXYZRGBL>;
+template class PCL_EXPORTS pcl::RegionGrowingRGB<pcl::PointXYZRGBNormal>;
index 663b0eda7c162a86d830a7b4f8446e5d978b5bf5..821901ec540af42d389f42ace2456550f33c5b61 100644 (file)
 #include <pcl/segmentation/impl/supervoxel_clustering.hpp>
 #include <pcl/octree/impl/octree_pointcloud_adjacency.hpp>
 
+template class PCL_EXPORTS pcl::SupervoxelClustering<pcl::PointXYZ>;
+template class PCL_EXPORTS pcl::SupervoxelClustering<pcl::PointXYZRGB>;
+template class PCL_EXPORTS pcl::SupervoxelClustering<pcl::PointXYZRGBA>;
+
 namespace pcl
 { 
   namespace octree
@@ -135,31 +139,6 @@ namespace pcl
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-namespace pcl
-{
-  template<> void
-  pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData::getPoint (pcl::PointXYZRGB &point_arg) const
-  {
-    point_arg.rgba = static_cast<std::uint32_t>(rgb_[0]) << 16 | 
-    static_cast<std::uint32_t>(rgb_[1]) << 8 | 
-    static_cast<std::uint32_t>(rgb_[2]);  
-    point_arg.x = xyz_[0];
-    point_arg.y = xyz_[1];
-    point_arg.z = xyz_[2];
-  }
-  
-  template<> void
-  pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData::getPoint (pcl::PointXYZRGBA &point_arg ) const
-  {
-    point_arg.rgba = static_cast<std::uint32_t>(rgb_[0]) << 16 | 
-    static_cast<std::uint32_t>(rgb_[1]) << 8 | 
-    static_cast<std::uint32_t>(rgb_[2]);  
-    point_arg.x = xyz_[0];
-    point_arg.y = xyz_[1];
-    point_arg.z = xyz_[2];
-  }
-}
-
 using VoxelDataT = pcl::SupervoxelClustering<pcl::PointXYZ>::VoxelData;
 using VoxelDataRGBT = pcl::SupervoxelClustering<pcl::PointXYZRGB>::VoxelData;
 using VoxelDataRGBAT = pcl::SupervoxelClustering<pcl::PointXYZRGBA>::VoxelData;
@@ -168,10 +147,6 @@ using AdjacencyContainerT = pcl::octree::OctreePointCloudAdjacencyContainer<pcl:
 using AdjacencyContainerRGBT = pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGB, VoxelDataRGBT>;
 using AdjacencyContainerRGBAT = pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGBA, VoxelDataRGBAT>;
 
-template class pcl::SupervoxelClustering<pcl::PointXYZ>;
-template class pcl::SupervoxelClustering<pcl::PointXYZRGB>;
-template class pcl::SupervoxelClustering<pcl::PointXYZRGBA>;
-
 template class pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZ, VoxelDataT>;
 template class pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGB, VoxelDataRGBT>;
 template class pcl::octree::OctreePointCloudAdjacencyContainer<pcl::PointXYZRGBA, VoxelDataRGBAT>;
index 22bb8207b710984f024ad935ea3530c76c62be90..0591f09f70cc9bd5252e74670b421e5efe25825d 100644 (file)
@@ -2,11 +2,6 @@ set(SUBSYS_NAME simulation)
 set(SUBSYS_DESC "Point Cloud Library Simulation")
 set(SUBSYS_DEPS common io surface kdtree features search octree visualization filters geometry)
 
-set(build FALSE)
-find_package(OpenGL)
-
-find_package(GLEW)
-
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS opengl glew)
 
@@ -35,8 +30,6 @@ set(incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs})
 
 target_link_libraries("${LIB_NAME}" pcl_common pcl_io
index 99ec4d45fc3b5f24e2bfbe865c3baafddddead2e..656600fe018836338b3b18df95dada3ead3a85ae 100644 (file)
@@ -24,10 +24,10 @@ pcl::simulation::TriangleMeshModel::TriangleMeshModel(pcl::PolygonMesh::Ptr plg)
     for (const auto& polygon : plg->polygons) {
       for (const auto& point : polygon.vertices) {
         tmp = newcloud[point].getVector4fMap();
-        vertices.push_back(Vertex(Eigen::Vector3f(tmp(0), tmp(1), tmp(2)),
-                                  Eigen::Vector3f(newcloud[point].r / 255.0f,
-                                                  newcloud[point].g / 255.0f,
-                                                  newcloud[point].b / 255.0f)));
+        vertices.emplace_back(Eigen::Vector3f(tmp(0), tmp(1), tmp(2)),
+                              Eigen::Vector3f(newcloud[point].r / 255.0f,
+                                              newcloud[point].g / 255.0f,
+                                              newcloud[point].b / 255.0f));
         indices.push_back(indices.size());
       }
     }
@@ -39,8 +39,8 @@ pcl::simulation::TriangleMeshModel::TriangleMeshModel(pcl::PolygonMesh::Ptr plg)
     for (const auto& polygon : plg->polygons) {
       for (const auto& point : polygon.vertices) {
         tmp = newcloud[point].getVector4fMap();
-        vertices.push_back(Vertex(Eigen::Vector3f(tmp(0), tmp(1), tmp(2)),
-                                  Eigen::Vector3f(1.0, 1.0, 1.0)));
+        vertices.emplace_back(Eigen::Vector3f(tmp(0), tmp(1), tmp(2)),
+                              Eigen::Vector3f(1.0, 1.0, 1.0));
         indices.push_back(indices.size());
       }
     }
index 39ece06c895ee439f034bc557f392529042e3e1e..f6ce17a588b4b66f58be6d0dc34c6ee8b1c8c879 100644 (file)
@@ -13,8 +13,6 @@ else()
   set(_glut_target GLUT::GLUT)
 endif()
 
-include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
-
 PCL_ADD_EXECUTABLE(pcl_sim_viewer COMPONENT ${SUBSYS_NAME} SOURCES sim_viewer.cpp)
 target_link_libraries (pcl_sim_viewer
   ${VTK_IO_TARGET_LINK_LIBRARIES}    pcl_kdtree
index 02bf5745b13caedd07dc2586785c6417a2316a21..7978fc7a39a5ccf923f5b4e325b56cd4384b8eea 100644 (file)
@@ -268,13 +268,13 @@ capture(Eigen::Isometry3d pose_in)
   // 27840 triangle faces
   // 13670 vertices
 
-  // 45.00Hz: simuation only
-  //  1.28Hz: simuation, addNoise?    , getPointCloud, writeASCII
-  // 33.33Hz: simuation, getPointCloud
-  // 23.81Hz: simuation, getPointCloud, writeBinary
-  // 14.28Hz: simuation, addNoise, getPointCloud, writeBinary
+  // 45.00Hz: simulation only
+  //  1.28Hz: simulation, addNoise?    , getPointCloud, writeASCII
+  // 33.33Hz: simulation, getPointCloud
+  // 23.81Hz: simulation, getPointCloud, writeBinary
+  // 14.28Hz: simulation, addNoise, getPointCloud, writeBinary
   // MODULE        TIME      FRACTION
-  // simuation     0.02222   31%
+  // simulation     0.02222   31%
   // addNoise      0.03             41%
   // getPointCloud 0.008     11%
   // writeBinary   0.012     16%
index c8973635d9547a0f2a2f5e31821eacb8266f2e89..2188c88d838f2fbd695bc9c1c2726dc8c86aa214 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME stereo)
 set(SUBSYS_DESC "Point cloud stereo library")
 set(SUBSYS_DEPS common io)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
@@ -33,9 +32,8 @@ set(srcs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
-target_link_libraries("${LIB_NAME}" pcl_common)
+target_link_libraries("${LIB_NAME}" pcl_common pcl_io)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
 # Install include files
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs})
index b86614fe471edfe670d20409cb4176627afb6172..a9976b70c456e1b08d8a31ad657b51b2318fb204 100644 (file)
@@ -3,7 +3,6 @@ set(SUBSYS_DESC "Point cloud surface library")
 set(SUBSYS_DEPS common search kdtree octree)
 set(SUBSYS_EXT_DEPS "")
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS qhull vtk OpenMP)
 
@@ -137,8 +136,6 @@ set(srcs
 )
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/boost.h"
-  "include/pcl/${SUBSYS_NAME}/eigen.h"
   "include/pcl/${SUBSYS_NAME}/ear_clipping.h"
   "include/pcl/${SUBSYS_NAME}/gp3.h"
   "include/pcl/${SUBSYS_NAME}/grid_projection.h"
@@ -175,11 +172,6 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-
-include_directories(
-  "${CMAKE_CURRENT_SOURCE_DIR}/include"
-  "${CMAKE_CURRENT_SOURCE_DIR}"
-)
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${VTK_SMOOTHING_INCLUDES} ${POISSON_INCLUDES} ${OPENNURBS_INCLUDES} ${ON_NURBS_INCLUDES})
 
 target_link_libraries("${LIB_NAME}" pcl_common pcl_search pcl_kdtree pcl_octree ${ON_NURBS_LIBRARIES})
@@ -192,7 +184,6 @@ if(VTK_FOUND)
                           VTK::FiltersModeling
                           VTK::FiltersCore)
   else()
-    include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
     link_directories(${VTK_LIBRARY_DIRS})
     target_link_libraries("${LIB_NAME}"
                           vtkCommonCore
index 87c73fcdde88a48e042b337a534827babb1f2b14..18af58c8407691e9e7db307aaf529d19d4c03e21 100644 (file)
@@ -195,8 +195,9 @@ public:
           const ON_UUID& object_id
           );
 
+  using ON_CurveProxy::Trim; // Explicitly introduce the base class Trim function
   const ON_BrepEdge* Edge() const;
-  const ON_BrepTrim* Trim() const;
+  const ON_BrepTrim* Trim() const; // overload, not override
   const ON_Brep*     Brep() const;
   const ON_BrepFace* Face() const;
   const ON_Surface*  Surface() const;
index 7ed8aaf9d828ebb167ebff2194e69690c06068a6..e7f45b650e99d89eaf412292569ca0f65c3d8487 100644 (file)
@@ -746,7 +746,10 @@ namespace pcl
       Real temp,dist2;
       if(!children){return this;}
       for(int i=0;i<Cube::CORNERS;i++){
-        temp=SquareDistance(children[i].center,p);
+        Point3D<Real> child_center;
+        Real child_width;
+        children[i].centerAndWidth(child_center, child_width);
+        temp=SquareDistance(child_center,p);
         if(!i || temp<dist2){
           dist2=temp;
           nearest=i;
@@ -807,7 +810,7 @@ namespace pcl
       children=NULL;
 
       d=node.depth ();
-      for(i=0;i<DIMENSION;i++){this->offset[i] = node.offset[i];}
+      for(i=0;i<DIMENSION;i++){this->off[i] = node.off[i];}
       if(node.children){
         initChildren();
         for(i=0;i<Cube::CORNERS;i++){children[i] = node.children[i];}
@@ -817,7 +820,7 @@ namespace pcl
 
     template <class NodeData,class Real>
     int OctNode<NodeData,Real>::CompareForwardDepths(const void* v1,const void* v2){
-      return ((const OctNode<NodeData,Real>*)v1)->depth-((const OctNode<NodeData,Real>*)v2)->depth;
+      return ((const OctNode<NodeData,Real>*)v1)->depth()-((const OctNode<NodeData,Real>*)v2)->depth();
     }
 
     template< class NodeData , class Real >
@@ -874,7 +877,7 @@ namespace pcl
 
     template <class NodeData,class Real>
     int OctNode<NodeData,Real>::CompareBackwardDepths(const void* v1,const void* v2){
-      return ((const OctNode<NodeData,Real>*)v2)->depth-((const OctNode<NodeData,Real>*)v1)->depth;
+      return ((const OctNode<NodeData,Real>*)v2)->depth()-((const OctNode<NodeData,Real>*)v1)->depth();
     }
 
     template <class NodeData,class Real>
index 6a861a64ea68f970d1355cb2b6a4c63fcf44b2ff..6c012b0856cd2cc8d59c9019c9d6b69f8a5f9cab 100644 (file)
   * Adapted from PCL_THROW_EXCEPTION. We intentionally do not reuse PCL_THROW_EXCEPTION here
   * to avoid introducing any dependencies on PCL in this 3rd party module.       
   */
+// NOLINTBEGIN(bugprone-macro-parentheses)
 #define POISSON_THROW_EXCEPTION(ExceptionName, message)                     \
 {                                                                           \
   std::ostringstream s;                                                     \
   s << message;                                                             \
   throw ExceptionName(s.str(), __FILE__, BOOST_CURRENT_FUNCTION, __LINE__); \
 }
+// NOLINTEND(bugprone-macro-parentheses)
 
 namespace pcl
 {
index 24f0a5402c5210a4751a8892f85892905825546c..5e54ac7862df4f1de8f99df0749b25349b08671e 100644 (file)
@@ -228,14 +228,18 @@ namespace pcl
     template<class T>
     void SparseMatrix<T>::SetZero()
     {
-      Resize(this->m_N, this->m_M);
+      // copied from operator *=
+      for (int i=0; i<rows; i++)
+      {
+        for(int ii=0;ii<rowSizes[i];ii++){m_ppElements[i][ii].Value=T(0);}
+      }
     }
 
     template<class T>
     void SparseMatrix<T>::SetIdentity()
     {
       SetZero();
-      for(int ij=0; ij < Min( this->Rows(), this->Columns() ); ij++)
+      for(int ij=0; ij < std::min<int>( rows, _maxEntriesPerRow ); ij++)
         (*this)(ij,ij) = T(1);
     }
 
@@ -388,7 +392,7 @@ namespace pcl
       T alpha,beta,rDotR;
       int i;
 
-      solution.Resize(M.Columns());
+      solution.Resize(bb.Dimensions());
       solution.SetZero();
 
       d=r=bb;
index 1be6fc857771fcd72d36d6ce1a1115bf3dcfcdba..97e2c091920c2dcb74981fe866296a077adb54e1 100644 (file)
@@ -153,3 +153,6 @@ namespace pcl
       PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
 }
+#ifdef PCL_NO_PRECOMPILE
+#include <pcl/surface/impl/bilateral_upsampling.hpp>
+#endif
diff --git a/surface/include/pcl/surface/boost.h b/surface/include/pcl/surface/boost.h
deleted file mode 100644 (file)
index 86aca4e..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.")
-
-#include <boost/dynamic_bitset/dynamic_bitset.hpp>
diff --git a/surface/include/pcl/surface/eigen.h b/surface/include/pcl/surface/eigen.h
deleted file mode 100644 (file)
index e3f46b0..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-
-#include <Eigen/SVD>
index 77142c50006020c68500d50a9f1fafb61a504116..f49f8b82ccac6a81e57b79a9b13483c583fba84a 100644 (file)
@@ -234,7 +234,7 @@ namespace pcl
 
       /** \brief When the input data points don't fill into the 1*1*1 box, 
         * scale them so that they can be filled in the unit box. Otherwise, 
-        * it will be some drawing problem when doing visulization
+        * it will be some drawing problem when doing visualization
         * \param scale_factor scale all the input data point by scale_factor
         */
       void 
index 47d7e80d82c187a15d4c511fc7b7b5c74020270c..d17f47b9d11c6b9b050136394060e14ba0ca9245 100644 (file)
@@ -85,13 +85,12 @@ pcl::ConvexHull<PointInT>::performReconstruction2D (PointCloud &hull, std::vecto
   PointInT p0 = (*input_)[(*indices_)[0]];
   PointInT p1 = (*input_)[(*indices_)[indices_->size () - 1]];
   PointInT p2 = (*input_)[(*indices_)[indices_->size () / 2]];
-  Eigen::Array4f dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ());
-  while (!( (dy1dy2[0] != dy1dy2[1]) || (dy1dy2[2] != dy1dy2[1]) ) )
+  while (!pcl::isXYZFinite(p0) || !pcl::isXYZFinite(p1) || !pcl::isXYZFinite(p2) || 
+  (p1.getVector3fMap() - p0.getVector3fMap()).cross(p2.getVector3fMap() - p0.getVector3fMap()).stableNorm() < Eigen::NumTraits<float>::dummy_precision ())
   {
     p0 = (*input_)[(*indices_)[rand () % indices_->size ()]];
     p1 = (*input_)[(*indices_)[rand () % indices_->size ()]];
     p2 = (*input_)[(*indices_)[rand () % indices_->size ()]];
-    dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ());
   }
     
   pcl::PointCloud<PointInT> normal_calc_cloud;
index 5f6c4bd449e4a2ca83594a0175ade6a2711a8735..e93b92b3eb32195cd6b5ec30af8d9f79b670e2b8 100644 (file)
@@ -667,7 +667,7 @@ pcl::GreedyProjectionTriangulation<PointInT>::reconstructPolygons (std::vector<p
                 }
                 if (inside_CB && !outside_CB)
                   need_invert = true;
-                else if (!(!inside_CB && outside_CB))
+                else if (inside_CB || !outside_CB)
                 {
                   if ((angles_[end].angle - angles_[start].angle) < M_PI)
                     need_invert = true;
index c5e232fa606a757a1189d667b03b4fab6568c541..6147e51fea26f6755b3e09a1cce7e9b5567bb2a4 100644 (file)
@@ -630,9 +630,7 @@ pcl::GridProjection<PointNT>::reconstructPolygons (std::vector<pcl::Vertices> &p
   for (pcl::index_t cp = 0; cp < static_cast<pcl::index_t> (data_->size ()); ++cp)
   {
     // Check if the point is invalid
-    if (!std::isfinite ((*data_)[cp].x) ||
-        !std::isfinite ((*data_)[cp].y) ||
-        !std::isfinite ((*data_)[cp].z))
+    if (!pcl::isXYZFinite((*data_)[cp]))
       continue;
 
     Eigen::Vector3i index_3d;
index a70f16c5c20028a112c6b08b33f0b828b392011f..12d28a5c27831d9fcc54aaf3f9806da41e4b8b5a 100644 (file)
@@ -218,7 +218,7 @@ template <typename PointNT> void
 pcl::MarchingCubes<PointNT>::performReconstruction (pcl::PointCloud<PointNT> &points,
                                                     std::vector<pcl::Vertices> &polygons)
 {
-  if (!(iso_level_ >= 0 && iso_level_ < 1))
+  if (iso_level_ < 0 || iso_level_ >= 1)
   {
     PCL_ERROR ("[pcl::%s::performReconstruction] Invalid iso level %f! Please use a number between 0 and 1.\n", 
         getClassName ().c_str (), iso_level_);
index 3c8529c978ce8af6951c09e92e982096d68e94ad..3e72a13aac46f5536632bcf05faf3b94ab087b5d 100644 (file)
@@ -94,9 +94,9 @@ pcl::MarchingCubesRBF<PointNT>::voxelizeData ()
         const Eigen::Vector3d point = point_f.cast<double> ();
 
         double f = 0.0;
-        std::vector<double>::const_iterator w_it (weights.begin());
-        for (std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> >::const_iterator c_it = centers.begin ();
-             c_it != centers.end (); ++c_it, ++w_it)
+        auto w_it (weights.cbegin());
+        for (auto c_it = centers.cbegin ();
+             c_it != centers.cend (); ++c_it, ++w_it)
           f += *w_it * kernel (*c_it, point);
 
         grid_[x * res_y_*res_z_ + y * res_z_ + z] = static_cast<float>(f);
index 8c3a45e1dff81a9ecf887f0a6ea807b1b4dabdbd..7c33feddfffbbf60c5982cca7626b934a90e0230 100644 (file)
@@ -144,16 +144,6 @@ namespace pcl
     Eigen::Vector2f
     calculatePrincipalCurvatures (const double u, const double v) const;
 
-    /** \brief Calculate the principal curvatures using the polynomial surface.
-      * \param[in] u The u-coordinate of the point in local MLS frame.
-      * \param[in] v The v-coordinate of the point in local MLS frame.
-      * \return The principal curvature [k1, k2] at the provided uv coordinates.
-      * \note If an error occurs then 1e-5 is returned.
-      */
-    PCL_DEPRECATED(1, 15, "use calculatePrincipalCurvatures() instead")
-    inline Eigen::Vector2f
-    calculatePrincipleCurvatures (const double u, const double v) const { return calculatePrincipalCurvatures(u, v); };
-
     /** \brief Project a point orthogonal to the polynomial surface.
       * \param[in] u The u-coordinate of the point in local MLS frame.
       * \param[in] v The v-coordinate of the point in local MLS frame.
index 3d2dfa57961ff6fd57b85cbfd5dbd056107c5a14..76385d167e5977889be6e2c34ee056c7de04edb7 100644 (file)
@@ -88,6 +88,8 @@ namespace pcl
         updateCurve (double damp) override;
 
       protected:
+        using FittingCurve2dAPDM::addPointConstraint;
+        using FittingCurve2dAPDM::assembleClosestPoints;
 
         /** \brief Add minimization constraint: point-to-surface distance (squared-distance-minimization). */
         virtual void
index 8bd189e67d40bc9084a82f6eac027e52cdf5c3f9..22e7869b6b39b91c7b30f914d839ded944311f61 100644 (file)
@@ -82,6 +82,9 @@ namespace pcl
       updateCurve (double damp) override;
 
     protected:
+      using FittingCurve2dAPDM::addPointConstraint;
+      using FittingCurve2dAPDM::assembleClosestPoints;
+
       /** \brief Add minimization constraint: point-to-surface distance (tangent-distance-minimization). */
       virtual void
       addPointConstraint (const double &param, const Eigen::Vector2d &point, const Eigen::Vector2d &normal,
index 592fcae9939868a581ceddd9a6f9530a3c9360a9..e6db46188b9cbba990ee5161b30693d773286ccb 100644 (file)
@@ -87,6 +87,7 @@ namespace pcl
         updateCurve (double damp) override;
 
       protected:
+        using FittingCurve2dPDM::addPointConstraint;
 
         /** \brief Add minimization constraint: point-to-surface distance (squared-distance-minimization). */
         virtual void
index 521a16895bfbab4e5abad500c45e22d53bd620e2..bcfc5963351acbf72ef0d620ffa6e4aa4ab31f64 100644 (file)
@@ -89,6 +89,8 @@ namespace pcl
         updateCurve (double damp) override;
 
       protected:
+        using FittingCurve2dPDM::addPointConstraint;
+
         /** \brief Add minimization constraint: point-to-surface distance (tangent-distance-minimization). */
         virtual void
         addPointConstraint (const double &param, const Eigen::Vector2d &point, const Eigen::Vector2d &normal,
index 4b236ba1a07389a884d75e03e16291af6b9a5955..4960da85905e9155818c6c2c6b18de53698f5804 100644 (file)
@@ -50,6 +50,7 @@ namespace pcl
     class FittingSurfaceTDM : public FittingSurface
     {
     public:
+      using FittingSurface::assemble;
 
       /** \brief Parameters with TDM extensions for fitting */
       struct ParameterTDM : public FittingSurface::Parameter
@@ -94,6 +95,9 @@ namespace pcl
       updateSurf (double damp) override;
 
     protected:
+      using FittingSurface::assembleInterior;
+      using FittingSurface::assembleBoundary;
+      using FittingSurface::addPointConstraint;
 
       /** \brief Assemble point-to-surface constraints for interior points. */
       virtual void
index e1b8bdfcc46acf1a0badd826db5401816e3afa7b..f5f2f001389eeefa176828bc4b2767c30222feec 100644 (file)
@@ -3049,8 +3049,7 @@ static bool ON_3dmSettings_Read_v1_TCODE_VIEWPORT(ON_BinaryArchive& file, ON_3dm
   double clipdist = 0.0;
   double snapsize = 0.0;
 
-  int chunk_count = 0;// debugging counter
-  for ( chunk_count = 0; rc; chunk_count++ )
+  while ( rc )
   {
     rc = file.BeginRead3dmBigChunk( &tcode, &big_value );
     if (!rc )
@@ -3159,8 +3158,7 @@ bool ON_3dmSettings::Read_v1( ON_BinaryArchive& file )
   ON__INT64 big_value;
   rc = file.SeekFromStart(32)?true:false; // skip 32 byte header
   
-  int chunk_count = 0; // debugging counter
-  for ( chunk_count = 0; rc; chunk_count++ )
+  while ( rc )
   {
     rc = file.BeginRead3dmBigChunk( &tcode, &big_value );
     if ( !rc ) 
index f4da1709a32d4fea1b1b2e03a131dbafb892ee18..eb74cfd4262d8526dc94f48b9c8ff5d6369a6cbb 100644 (file)
@@ -15318,15 +15318,21 @@ const wchar_t* ON_FileIterator::NextFile()
   for(;;)
   {
     current_file_attributes = 0;
+    /*
+      from readdir man page:
+      If the end of the directory stream is reached,
+      NULL is returned and errno is not changed. If an error occurs,
+      NULL is returned and errno is set appropriately.
+    */
     struct dirent* dp = 0;
-    int readdir_errno = readdir_r(m_dir, &m_dirent, &dp);
-    if ( 0 !=  readdir_errno )
-      break;
+    dp = readdir(m_dir);
     if ( 0 == dp )
       break;
-    if ( 0 == m_dirent.d_name[0] )
+    if ( 0 == dp->d_name[0] )
       break;
 
+    m_dirent = *dp;
+
     if ( IsDotOrDotDotDir(m_dirent.d_name) )
       continue;
 
index cd936dce7a8e1f00c648ba6a8d1c13318a9358fc..e006d3a56679b45e805c850baa5c0dde92f301aa 100644 (file)
@@ -666,9 +666,13 @@ std::size_t ON_SerialNumberMap::ActiveIdCount() const
   return m_active_id_count;
 }
 
-#if (_MSC_VER >= 1930 && _MSC_VER <= 1939)
+#if (_MSC_VER >= 1930 && _MSC_VER <= 1949)
 // Solves internal compiler error on MSVC 2022
 // (see https://github.com/microsoft/vcpkg/issues/19561)
+#define ON_VS2022_COMPILER_CRASH
+#endif
+
+#if defined(ON_VS2022_COMPILER_CRASH)
 #pragma optimize("", off)
 #endif
 struct ON_SerialNumberMap::SN_ELEMENT* ON_SerialNumberMap::FirstElement() const
@@ -722,7 +726,7 @@ struct ON_SerialNumberMap::SN_ELEMENT* ON_SerialNumberMap::FirstElement() const
   }
   return e;
 }
-#if (_MSC_VER >= 1930 && _MSC_VER <= 1939)
+#if defined(ON_VS2022_COMPILER_CRASH)
 #pragma optimize("", on)
 #endif
 
index c77a365d147ad598356513235ca81f4d6f3cbe73..979a2b211a0435d7404991b054243058f9a32115 100644 (file)
@@ -1505,7 +1505,7 @@ void ON_TextureMapping::Dump( ON_TextLog& text_log ) const
   case single:
     text_log.Print("single texture space\n");
     break;
-  case clspt_projection:
+  case divided:
     text_log.Print("divided texture space\n");
     break;
   default:
@@ -2359,7 +2359,7 @@ ON__UINT32 ON_TextureMapping::MappingCRC() const
       case ON_TextureMapping::cylinder_mapping:
       case ON_TextureMapping::sphere_mapping:
       case ON_TextureMapping::box_mapping:
-      case ON_TextureMapping::force_32bit_mapping_projection:
+      case ON_TextureMapping::force_32bit_mapping_type:
       default:
         break;
       }
index 923ae63ad96f5262b5675183a25a59378d1687d4..933059afdc951c0d7b2913f4577612cddad10860 100644 (file)
@@ -1280,8 +1280,6 @@ ON_TransformPointList(
 
   if ( !ON_IsValidPointList( dim, is_rat, count, stride, point ) )
     return false;
-  if ( xform.m_xform == NULL )
-    return false;
   if (count == 0)
     return true;
 
@@ -1381,8 +1379,6 @@ ON_TransformPointList(
 
   if ( !ON_IsValidPointList( dim, is_rat, count, stride, point ) )
     return false;
-  if ( xform.m_xform == NULL )
-    return false;
   if (count == 0)
     return true;
 
@@ -1507,8 +1503,6 @@ ON_TransformVectorList(
 
   if ( !ON_IsValidPointList( dim, 0, count, stride, vector ) )
     return false;
-  if ( xform.m_xform == NULL )
-    return false;
   if (count == 0)
     return true;
 
@@ -1556,8 +1550,6 @@ ON_TransformVectorList(
 
   if ( !ON_IsValidPointList( dim, 0, count, stride, vector ) )
     return false;
-  if ( xform.m_xform == NULL )
-    return false;
   if (count == 0)
     return true;
 
index aab8e5cdf6cd248156bedbcdb6920d70a481b68e..a60ebc0b19811773a5146799e080c25cba415bb3 100644 (file)
@@ -3689,7 +3689,6 @@ bool ON_Mesh::CombineIdenticalVertices(
     ON_SimpleArray<int> remap_array(vertex_count);
 
     int remap_vertex_count = 0;
-    int merge_count = 0;
     int i0, i1, k;
 
     struct tagMESHPOINTS mp;
@@ -3738,8 +3737,6 @@ bool ON_Mesh::CombineIdenticalVertices(
       {
         if ( CompareMeshPoint( mp.p0+index[i0], mp.p0+index[i1], &mp ) )
           break;
-        else
-          merge_count++;
       }
       for ( /*empty*/; i0 < i1; i0++ )
       {
index b93256cbf6a4b914a0e46b46032e5cdeff4bdc59..5c8618e67fc1b12111582e08d203aa9afaeab5c0 100644 (file)
@@ -143,7 +143,7 @@ ON_BOOL32 ON_NurbsSurface::SetDomain(
             )
 {
   bool rc = false;
-  if ( m_order[dir] >= 2 && m_cv_count[dir] >= m_order[dir] && m_knot && t0 < t1 ) {
+  if ( m_order[dir] >= 2 && m_cv_count[dir] >= m_order[dir] && nullptr != m_knot[dir] && t0 < t1 ) {
     const double k0 = m_knot[dir][m_order[dir]-2];
     const double k1 = m_knot[dir][m_cv_count[dir]-1];
     if ( k0 == t0 && k1 == t1 )
index ae09677ce12edf02c6d15e3ff96bdc318bcfa1a7..6933ceb3c275789aa73c5ddfc67e50b43be876ef 100644 (file)
@@ -533,7 +533,7 @@ ON__UINT32 ON_NurbsCage::DataCRC(ON__UINT32 current_remainder) const
       for ( j = 0; j < m_cv_count[1]; j++ )
       {
         cv = CV(i,j,0);
-        for (k = 0; i < m_cv_count[2]; k++ )
+        for (k = 0; k < m_cv_count[2]; k++ )
         {
           current_remainder = ON_CRC32(current_remainder,sizeof_cv,cv);
           cv += m_cv_stride[2];
index db615eba4407cda22f32b1bf668d2678c4d4cb6f..1027aed9b453639f4d705c960dc0b3e19939ccd4 100644 (file)
@@ -840,7 +840,8 @@ void ON_ClassId::ConstructorHelper( const char* sClassName,
   {
     for ( ON_ClassId* p = m_p0; p; p = p->m_pNext )
     {
-      if ( !p->m_pBaseClassId && p->m_sBaseClassName ) {
+      if ( 0 == p->m_pBaseClassId && 0 != p->m_sBaseClassName[0] &&
+           0 == p->m_sBaseClassName[sizeof(p->m_sBaseClassName) / sizeof(p->m_sBaseClassName[0]) - 1] ) {
         if ( !strcmp( m_sClassName, p->m_sBaseClassName ) )
           p->m_pBaseClassId = this;
       }
index f8ea329b0f8afcb71c9a2e32e0fabb9e69fc305e..d6a8529a052bbb5cc8aa07864c933946c1c99438 100644 (file)
@@ -668,60 +668,52 @@ ON_3dVector::PerpendicularTo(
 void ON_2dPoint::Transform( const ON_Xform& xform )
 {
   double xx,yy,ww;
-  if ( xform.m_xform ) {
-    ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][3];
-    if ( ww != 0.0 )
-      ww = 1.0/ww;
-    xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][3]);
-    yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][3]);
-    x = xx;
-    y = yy;
-  }
+  ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][3];
+  if ( ww != 0.0 )
+    ww = 1.0/ww;
+  xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][3]);
+  yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][3]);
+  x = xx;
+  y = yy;
 }
 
 void ON_3dPoint::Transform( const ON_Xform& xform )
 {
   double xx,yy,zz,ww;
-  if ( xform.m_xform ) {
-    ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3];
-    if ( ww != 0.0 )
-      ww = 1.0/ww;
-    xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]);
-    yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]);
-    zz = ww*(xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]);
-    x = xx;
-    y = yy;
-    z = zz;
-  }
+  ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3];
+  if ( ww != 0.0 )
+    ww = 1.0/ww;
+  xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]);
+  yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]);
+  zz = ww*(xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]);
+  x = xx;
+  y = yy;
+  z = zz;
 }
 
 void ON_4dPoint::Transform( const ON_Xform& xform )
 {
   double xx,yy,zz,ww;
-  if ( xform.m_xform ) {
-    xx = xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]*w;
-    yy = xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]*w;
-    zz = xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]*w;
-    ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3]*w;
-    x = xx;
-    y = yy;
-    z = zz;
-    w = ww;
-  }
+  xx = xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]*w;
+  yy = xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]*w;
+  zz = xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]*w;
+  ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3]*w;
+  x = xx;
+  y = yy;
+  z = zz;
+  w = ww;
 }
 
 void ON_2fPoint::Transform( const ON_Xform& xform )
 {
   double xx,yy,ww;
-  if ( xform.m_xform ) {
-    ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][3];
-    if ( ww != 0.0 )
-      ww = 1.0/ww;
-    xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][3]);
-    yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][3]);
-    x = (float)xx;
-    y = (float)yy;
-  }
+  ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][3];
+  if ( ww != 0.0 )
+    ww = 1.0/ww;
+  xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][3]);
+  yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][3]);
+  x = (float)xx;
+  y = (float)yy;
 }
 
 void ON_2fPoint::Rotate( 
@@ -767,32 +759,28 @@ void ON_3fPoint::Rotate(
 void ON_3fPoint::Transform( const ON_Xform& xform )
 {
   double xx,yy,zz,ww;
-  if ( xform.m_xform ) {
-    ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3];
-    if ( ww != 0.0 )
-      ww = 1.0/ww;
-    xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]);
-    yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]);
-    zz = ww*(xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]);
-    x = (float)xx;
-    y = (float)yy;
-    z = (float)zz;
-  }
+  ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3];
+  if ( ww != 0.0 )
+    ww = 1.0/ww;
+  xx = ww*(xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]);
+  yy = ww*(xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]);
+  zz = ww*(xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]);
+  x = (float)xx;
+  y = (float)yy;
+  z = (float)zz;
 }
 
 void ON_4fPoint::Transform( const ON_Xform& xform )
 {
   double xx,yy,zz,ww;
-  if ( xform.m_xform ) {
-    xx = xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]*w;
-    yy = xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]*w;
-    zz = xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]*w;
-    ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3]*w;
-    x = (float)xx;
-    y = (float)yy;
-    z = (float)zz;
-    w = (float)ww;
-  }
+  xx = xform.m_xform[0][0]*x + xform.m_xform[0][1]*y + xform.m_xform[0][2]*z + xform.m_xform[0][3]*w;
+  yy = xform.m_xform[1][0]*x + xform.m_xform[1][1]*y + xform.m_xform[1][2]*z + xform.m_xform[1][3]*w;
+  zz = xform.m_xform[2][0]*x + xform.m_xform[2][1]*y + xform.m_xform[2][2]*z + xform.m_xform[2][3]*w;
+  ww = xform.m_xform[3][0]*x + xform.m_xform[3][1]*y + xform.m_xform[3][2]*z + xform.m_xform[3][3]*w;
+  x = (float)xx;
+  y = (float)yy;
+  z = (float)zz;
+  w = (float)ww;
 }
 
 double ON_3fPoint::Fuzz( 
index 071631cd2e8adc2fd81e009e5ca69b4dcc900f5b..d7687eacf97698607b6bc375632f062fa98d1ffa 100644 (file)
@@ -1472,22 +1472,6 @@ std::size_t ON_RTree::SizeOf() const
 }
 
 
-static void NodeCountHelper( const ON_RTreeNode* node, std::size_t& node_count, std::size_t& wasted_branch_count, std::size_t& leaf_count )
-{
-  if ( 0 == node )
-    return;
-  node_count++;
-  wasted_branch_count += (ON_RTree_MAX_NODE_COUNT - node->m_count);
-  if ( node->m_level > 0 )
-  {
-    for ( int i = 0; i < node->m_count; i++ )
-    {
-      NodeCountHelper(node->m_branch[i].m_child,node_count,wasted_branch_count,leaf_count);
-    }
-  }
-  else
-    leaf_count += node->m_count;
-}
 
 void ON_RTree::RemoveAll()
 {
index 362d0ba8445488ff0fe7138867d3d071ff5c7c41..e099ff3f6049e28d5720f4adf3935b49c21f617f 100644 (file)
@@ -41,5 +41,5 @@
 #include <pcl/point_types.h>
 
 // Instantiations of specific point types
-PCL_INSTANTIATE(GreedyProjectionTriangulation, (pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal))
+PCL_INSTANTIATE(GreedyProjectionTriangulation, (pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal)(pcl::PointXYZLNormal))
 
index 20d4269d284fa837c0bd99b1fc7602c4de04694a..985e6ef72a1456470f29ffd45cbd04709029be54 100644 (file)
@@ -49,8 +49,10 @@ set(ON_NURBS_SOURCES
 
 set(USE_UMFPACK 0 CACHE BOOL "Use UmfPack for solving sparse systems of equations (e.g. in surface/on_nurbs)")
 if(USE_UMFPACK)
+  find_package(CHOLMOD REQUIRED)
+  find_package(UMFPACK REQUIRED)
   set(ON_NURBS_SOURCES ${ON_NURBS_SOURCES} src/on_nurbs/nurbs_solve_umfpack.cpp)
-  set(ON_NURBS_LIBRARIES ${ON_NURBS_LIBRARIES} cholmod umfpack)
+  set(ON_NURBS_LIBRARIES ${ON_NURBS_LIBRARIES} SuiteSparse::CHOLMOD SuiteSparse::UMFPACK)
 else()
   set(ON_NURBS_SOURCES ${ON_NURBS_SOURCES} src/on_nurbs/nurbs_solve_eigen.cpp)
 endif()
index 4e74c0f511d1f45ae4b1d9ef4c4cbd7a537dc494..82220e0a1507e63ebcf1b49d397cddc3b9e2c2c0 100644 (file)
@@ -2,19 +2,15 @@ set(SUBSYS_NAME tests_2d)
 set(SUBSYS_DESC "Point cloud library 2d module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS 2d)
 
-set(OPT_DEPS)
-
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
-PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
 
 if(NOT build)
   return()
 endif()
 
 PCL_ADD_TEST(test_2d test_2d FILES test_2d.cpp
-             LINK_WITH pcl_io pcl_gtest
+             LINK_WITH pcl_2d pcl_io pcl_gtest
              ARGUMENTS "${PCL_SOURCE_DIR}/test/2d/lena.pcd"
                        "${PCL_SOURCE_DIR}/test/2d/gauss_smooth.pcd"
                        "${PCL_SOURCE_DIR}/test/2d/erosion.pcd"
@@ -27,7 +23,7 @@ PCL_ADD_TEST(test_2d test_2d FILES test_2d.cpp
                        "${PCL_SOURCE_DIR}/test/2d/closing_binary.pcd"
                        "${PCL_SOURCE_DIR}/test/2d/canny.pcd")
 
-PCL_ADD_TEST(test_2d_keypoint_instantiation_with_precompile test_2d_keypoint_instantiation_with_precompile FILES keypoint_instantiation.cpp LINK_WITH pcl_gtest pcl_common)
+PCL_ADD_TEST(test_2d_keypoint_instantiation_with_precompile test_2d_keypoint_instantiation_with_precompile FILES keypoint_instantiation.cpp LINK_WITH pcl_2d pcl_gtest pcl_common)
 
-PCL_ADD_TEST(test_2d_keypoint_instantiation_without_precompile test_2d_keypoint_instantiation_without_precompile FILES keypoint_instantiation.cpp LINK_WITH pcl_gtest pcl_common)
+PCL_ADD_TEST(test_2d_keypoint_instantiation_without_precompile test_2d_keypoint_instantiation_without_precompile FILES keypoint_instantiation.cpp LINK_WITH pcl_2d pcl_gtest pcl_common)
 target_compile_definitions(test_2d_keypoint_instantiation_without_precompile PUBLIC PCL_NO_PRECOMPILE)
index 555b4c7969d5f1cfecd90480619df15ea2fb7da5..c47ba3b837dcd8eefd6cb8807fbf68396effe688 100644 (file)
@@ -1,10 +1,7 @@
 set(SUBSYS_NAME global_tests)
 set(SUBSYS_DESC "Point cloud library global unit tests")
 
-set(DEFAULT OFF)
-set(build TRUE)
-set(REASON "Disabled by default")
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
@@ -15,6 +12,7 @@ find_package(GTestSource REQUIRED)
 include_directories(SYSTEM ${GTEST_INCLUDE_DIRS} ${GTEST_SRC_DIR})
 
 add_library(pcl_gtest STATIC ${GTEST_SRC_DIR}/src/gtest-all.cc)
+target_include_directories(pcl_gtest PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include)
 
 enable_testing()
 
@@ -44,8 +42,6 @@ add_custom_target(tests "${CMAKE_CTEST_COMMAND}" ${PCL_CTEST_ARGUMENTS} -V -T Te
 
 set_target_properties(tests PROPERTIES FOLDER "Tests")
 
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-
 add_subdirectory(2d)
 add_subdirectory(common)
 add_subdirectory(features)
index a4ef890c3d504c6646ff116141f82cee51452363..5851543b3c3074be57968c1377a5fdb62a09c23e 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library common module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS common)
 set(OPT_DEPS io search kdtree octree)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index e5d742ad74931643192990850b87cacb3a369d51..489fb7871ce0ad54cf8b1185008dce2e9400c7da 100644 (file)
@@ -250,6 +250,128 @@ TEST (PCL, CopyPointCloudWithSameTypes)
   ASSERT_EQ (0, cloud_out.size ());
 }
 
+TEST (toPCLPointCloud2NoPadding, PointXYZI)
+{
+  pcl::PointCloud<pcl::PointXYZI> cloud;
+  cloud.resize(static_cast<pcl::uindex_t>(2), static_cast<pcl::uindex_t>(2));
+  cloud[0].x = 1.0; cloud[0].y = 2.0; cloud[0].z = 3.0; cloud[0].intensity = 123.0;
+  cloud[1].x = -1.0; cloud[1].y = -2.0; cloud[1].z = -3.0; cloud[1].intensity = -123.0;
+  cloud[2].x = 0.1; cloud[2].y = 0.2; cloud[2].z = 0.3; cloud[2].intensity = 12.3;
+  cloud[3].x = 0.0; cloud[3].y = -1.7; cloud[3].z = 100.0; cloud[3].intensity = 3.14;
+  pcl::PCLPointCloud2 msg;
+  pcl::toPCLPointCloud2(cloud, msg, false);
+  EXPECT_EQ (msg.height, cloud.height);
+  EXPECT_EQ (msg.width, cloud.width);
+  EXPECT_EQ (msg.fields.size(), 4);
+  EXPECT_EQ (msg.fields[0].name, "x");
+  EXPECT_EQ (msg.fields[0].offset, 0);
+  EXPECT_EQ (msg.fields[0].datatype, pcl::PCLPointField::FLOAT32);
+  EXPECT_EQ (msg.fields[0].count, 1);
+  EXPECT_EQ (msg.fields[1].name, "y");
+  EXPECT_EQ (msg.fields[1].offset, 4);
+  EXPECT_EQ (msg.fields[1].datatype, pcl::PCLPointField::FLOAT32);
+  EXPECT_EQ (msg.fields[1].count, 1);
+  EXPECT_EQ (msg.fields[2].name, "z");
+  EXPECT_EQ (msg.fields[2].offset, 8);
+  EXPECT_EQ (msg.fields[2].datatype, pcl::PCLPointField::FLOAT32);
+  EXPECT_EQ (msg.fields[2].count, 1);
+  EXPECT_EQ (msg.fields[3].name, "intensity");
+  EXPECT_EQ (msg.fields[3].offset, 12);
+  EXPECT_EQ (msg.fields[3].datatype, pcl::PCLPointField::FLOAT32);
+  EXPECT_EQ (msg.fields[3].count, 1);
+  EXPECT_EQ (msg.point_step, 16);
+  EXPECT_EQ (msg.row_step, 16*cloud.width);
+  EXPECT_EQ (msg.data.size(), 16*cloud.width*cloud.height);
+  EXPECT_EQ (msg.at<float>(0, 0), 1.0f);
+  EXPECT_EQ (msg.at<float>(3, 4), -1.7f);
+  EXPECT_EQ (msg.at<float>(1, 8), -3.0f);
+  EXPECT_EQ (msg.at<float>(2, 12), 12.3f);
+  pcl::PointCloud<pcl::PointXYZI> cloud2;
+  pcl::fromPCLPointCloud2(msg, cloud2);
+  for(std::size_t i=0; i<cloud2.size(); ++i) {
+    EXPECT_EQ (cloud[i].x, cloud2[i].x);
+    EXPECT_EQ (cloud[i].y, cloud2[i].y);
+    EXPECT_EQ (cloud[i].z, cloud2[i].z);
+    EXPECT_EQ (cloud[i].intensity, cloud2[i].intensity);
+  }
+}
+
+TEST(PCL, fromPCLPointCloud2CastingXYZI)
+{
+  // test fromPCLPointCloud2, but in PCLPointCloud2 the fields have different types than in PointXYZI
+  pcl::PCLPointCloud2 msg;
+  msg.height = 2;
+  msg.width = 2;
+  msg.fields.resize(4);
+  msg.fields[0].name = "x";
+  msg.fields[0].offset = 0;
+  msg.fields[0].datatype = pcl::PCLPointField::FLOAT64;
+  msg.fields[0].count = 1;
+  msg.fields[1].name = "y";
+  msg.fields[1].offset = 8;
+  msg.fields[1].datatype = pcl::PCLPointField::FLOAT64;
+  msg.fields[1].count = 1;
+  msg.fields[2].name = "z";
+  msg.fields[2].offset = 16;
+  msg.fields[2].datatype = pcl::PCLPointField::FLOAT64;
+  msg.fields[2].count = 1;
+  msg.fields[3].name = "intensity";
+  msg.fields[3].offset = 24;
+  msg.fields[3].datatype = pcl::PCLPointField::UINT16;
+  msg.fields[3].count = 1;
+  msg.point_step = 32;
+  msg.row_step = 32*msg.width;
+  msg.data.resize(32*msg.width*msg.height);
+  for(std::size_t i=0; i<msg.width*msg.height; ++i) {
+    msg.at<double>(i, 0) = 1.0*i;
+    msg.at<double>(i, 8) = -1.6*i;
+    msg.at<double>(i, 16) = -3.141*i;
+    msg.at<std::uint16_t>(i, 24) = 123*i;
+  }
+  pcl::PointCloud<pcl::PointXYZI> cloud;
+  pcl::fromPCLPointCloud2(msg, cloud);
+  for(std::size_t i=0; i<msg.width*msg.height; ++i) {
+    EXPECT_EQ(cloud[i].x, 1.0f*i);
+    EXPECT_EQ(cloud[i].y, -1.6f*i);
+    EXPECT_EQ(cloud[i].z, -3.141f*i);
+    EXPECT_EQ(cloud[i].intensity, 123.0f*i);
+  }
+}
+
+TEST(PCL, fromPCLPointCloud2CastingSHOT352)
+{
+  // test whether casting also works if point type contains arrays
+  pcl::PCLPointCloud2 msg;
+  msg.height = 2;
+  msg.width = 2;
+  msg.fields.resize(2);
+  msg.fields[0].name = "shot";
+  msg.fields[0].offset = 0;
+  msg.fields[0].datatype = pcl::PCLPointField::INT64;
+  msg.fields[0].count = 352;
+  msg.fields[1].name = "rf";
+  msg.fields[1].offset = 352*8;
+  msg.fields[1].datatype = pcl::PCLPointField::FLOAT64;
+  msg.fields[1].count = 9;
+  msg.point_step = (352*8+9*8);
+  msg.row_step = msg.point_step*msg.width;
+  msg.data.resize(msg.point_step*msg.width*msg.height);
+  for(std::size_t i=0; i<msg.width*msg.height; ++i) {
+    for(std::size_t j=0; j<352; ++j)
+      msg.at<std::int64_t>(i, 8*j) = 1000*i+j;
+    for(std::size_t j=0; j<9; ++j)
+      msg.at<double>(i, 352*8+8*j) = (10*i+j)/10.0;
+  }
+  pcl::PointCloud<pcl::SHOT352> cloud;
+  pcl::fromPCLPointCloud2(msg, cloud);
+  for(std::size_t i=0; i<msg.width*msg.height; ++i) {
+    for(std::size_t j=0; j<352; ++j)
+      EXPECT_EQ(cloud[i].descriptor[j], 1000*i+j);
+    for(std::size_t j=0; j<9; ++j)
+      EXPECT_EQ(cloud[i].rf[j], (10*i+j)/10.0f);
+  }
+}
+
 /* ---[ */
 int
 main (int argc, char** argv)
index 676f92cdd256b082dc11b85525b5244e3d03303e..4fd195bb5eaba00a6ff0329a9592ececf03b5779 100644 (file)
@@ -108,8 +108,8 @@ TEST (PointCloud, iterators)
                      cloud.begin ()->getVector3fMap ());
   EXPECT_EQ_VECTORS ((--cloud.end ())->getVector3fMap (),
                      (--cloud.end ())->getVector3fMap ());
-  PointCloud<PointXYZ>::const_iterator pit = cloud.begin ();
-  PointCloud<PointXYZ>::VectorType::const_iterator pit2 = cloud.begin ();
+  auto pit = cloud.begin ();
+  auto pit2 = cloud.begin ();
   for (; pit < cloud.end (); ++pit2, ++pit)
     EXPECT_EQ_VECTORS (pit->getVector3fMap (), pit2->getVector3fMap ());
 }
@@ -125,8 +125,8 @@ TEST (PointCloud, insert_range)
   EXPECT_EQ (cloud.width, cloud.size ());
   EXPECT_EQ (cloud.height, 1);
   EXPECT_EQ (cloud.width, old_size + cloud2.size ());
-  PointCloud<PointXYZ>::const_iterator pit = cloud.begin ();
-  PointCloud<PointXYZ>::const_iterator pit2 = cloud2.begin ();
+  auto pit = cloud.begin ();
+  auto pit2 = cloud2.begin ();
   for (; pit2 < cloud2.end (); ++pit2, ++pit)
     EXPECT_EQ_VECTORS (pit->getVector3fMap (), pit2->getVector3fMap ());
 }
index 4dbab6e8bc28b8acdf228698ede1279736ceb716..c686f506f10428cdaeb1ac98c3414f3db1f52569 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library features module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS features)
 set(OPT_DEPS io keypoints) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index 11e858f3ff85afa08d26fe9524dc3ac95f2715db..07d3e249e9832e1443003e9521b35408ec07d32d 100644 (file)
@@ -116,7 +116,7 @@ TEST (PCL, PrincipalCurvaturesEstimation)
   pc.compute (*pcs);
   EXPECT_EQ (pcs->size (), indices.size ());
 
-  // Adjust for small numerical inconsitencies (due to nn_indices not being sorted)
+  // Adjust for small numerical inconsistencies (due to nn_indices not being sorted)
   EXPECT_NEAR (std::abs ((*pcs)[0].principal_curvature[0]), 0.98509, 1e-4);
   EXPECT_NEAR (std::abs ((*pcs)[0].principal_curvature[1]), 0.10713, 1e-4);
   EXPECT_NEAR (std::abs ((*pcs)[0].principal_curvature[2]), 0.13462, 1e-4);
index 64c87097a10a9fc850ff3082d3c050f91726c4b5..80fb22c75d7b0d865ef1658b3d5962caf89b5ee2 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library filters module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS filters)
 set(OPT_DEPS io features segmentation)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index 2cc5b88361ebacbd64f1ecd487351b44139891b1..85e9a05b406fa4bc7d270fa58f6cc43a603d169e 100644 (file)
@@ -48,6 +48,7 @@
 #include <pcl/filters/frustum_culling.h>
 #include <pcl/filters/sampling_surface_normal.h>
 #include <pcl/filters/voxel_grid.h>
+#include <pcl/filters/voxel_grid_occlusion_estimation.h>
 #include <pcl/filters/voxel_grid_covariance.h>
 #include <pcl/filters/extract_indices.h>
 #include <pcl/filters/project_inliers.h>
@@ -637,6 +638,19 @@ TEST (VoxelGrid, Filters)
   EXPECT_LE (std::abs (output[neighbors.at (0)].y - output[centroidIdx].y), 0.02);
   EXPECT_LE ( output[neighbors.at (0)].z - output[centroidIdx].z, 0.02 * 2);
 
+  // indices must be handled correctly
+  auto indices = grid.getIndices(); // original cloud indices
+  auto cloud_copied = std::make_shared<PointCloud<PointXYZ>>();
+  *cloud_copied = *cloud;
+  for (int i = 0; i < 100; i++) {
+    cloud_copied->emplace_back(100 + i, 100 + i, 100 + i);
+  }
+  grid.setInputCloud(cloud_copied);
+  grid.setIndices(indices);
+  grid.filter(output);
+
+  EXPECT_EQ(output.size(), 100); // additional points should be ignored
+
   // Test the pcl::PCLPointCloud2 method
   VoxelGrid<PCLPointCloud2> grid2;
 
@@ -718,6 +732,18 @@ TEST (VoxelGrid, Filters)
   EXPECT_LE (std::abs (output[neighbors2.at (0)].x - output[centroidIdx2].x), 0.02);
   EXPECT_LE (std::abs (output[neighbors2.at (0)].y - output[centroidIdx2].y), 0.02);
   EXPECT_LE (output[neighbors2.at (0)].z - output[centroidIdx2].z, 0.02 * 2);
+
+  // indices must be handled correctly
+  auto indices2 = grid2.getIndices(); // original cloud indices
+  auto cloud_blob2 = std::make_shared<PCLPointCloud2>();
+  toPCLPointCloud2(*cloud_copied, *cloud_blob2);
+
+  grid2.setInputCloud(cloud_blob2);
+  grid2.setIndices(indices2);
+  grid2.filter(output_blob);
+
+  fromPCLPointCloud2(output_blob, output);
+  EXPECT_EQ(output.size(), 100); // additional points should be ignored
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -1352,7 +1378,7 @@ TEST (VoxelGridMinPoints, Filters)
 
   // Verify 2 clusters (0.11 and 0.31) passed threshold and verify their location and color
   EXPECT_EQ (outputMin4.size (), 2);
-  // Offset noise applied by offsets vec are 1e-3 magnitude, so check within 1e-2 
+  // Offset noise applied by offsets vec are 1e-3 magnitude, so check within 1e-2
   EXPECT_NEAR (outputMin4[0].x, input->at(1).x, 1e-2);
   EXPECT_NEAR (outputMin4[0].y, input->at(1).y, 1e-2);
   EXPECT_NEAR (outputMin4[0].z, input->at(1).z, 1e-2);
@@ -1468,19 +1494,43 @@ TEST (RadiusOutlierRemoval, Filters)
 {
   // Test the PointCloud<PointT> method
   PointCloud<PointXYZ> cloud_out;
+  PointCloud<PointXYZ> cloud_out_neg;
   // Remove outliers using a spherical density criterion
   RadiusOutlierRemoval<PointXYZ> outrem;
   outrem.setInputCloud (cloud);
   outrem.setRadiusSearch (0.02);
   outrem.setMinNeighborsInRadius (14);
+  outrem.setNumberOfThreads(4);
   outrem.filter (cloud_out);
 
   EXPECT_EQ (cloud_out.size (), 307);
   EXPECT_EQ (cloud_out.width, 307);
   EXPECT_TRUE (cloud_out.is_dense);
-  EXPECT_NEAR (cloud_out[cloud_out.size () - 1].x, -0.077893, 1e-4);
-  EXPECT_NEAR (cloud_out[cloud_out.size () - 1].y, 0.16039, 1e-4);
-  EXPECT_NEAR (cloud_out[cloud_out.size () - 1].z, -0.021299, 1e-4);
+
+  outrem.setNegative(true);
+  outrem.filter(cloud_out_neg);
+
+  EXPECT_EQ(cloud_out_neg.size(), 90);
+  EXPECT_TRUE(cloud_out_neg.is_dense);
+
+  PointCloud<PointXYZRGB> cloud_out_rgb;
+  PointCloud<PointXYZRGB> cloud_out_rgb_neg;
+  // Remove outliers using a spherical density criterion on non-dense pointcloud
+  RadiusOutlierRemoval<PointXYZRGB> outremNonDense;
+  outremNonDense.setInputCloud(cloud_organized);
+  outremNonDense.setRadiusSearch(0.02);
+  outremNonDense.setMinNeighborsInRadius(14);
+  outremNonDense.setNumberOfThreads(4);
+  outremNonDense.filter(cloud_out_rgb);
+
+  EXPECT_EQ(cloud_out_rgb.size(), 240801);
+  EXPECT_EQ(cloud_out_rgb.width, 240801);
+  //EXPECT_TRUE(cloud_out_rgb.is_dense);
+
+  outremNonDense.setNegative(true);
+  outremNonDense.filter(cloud_out_rgb_neg);
+  EXPECT_EQ(cloud_out_rgb_neg.size(), 606);
+  //EXPECT_TRUE(cloud_out_rgb_neg.is_dense);
 
   // Test the pcl::PCLPointCloud2 method
   PCLPointCloud2 cloud_out2;
@@ -1997,11 +2047,11 @@ TEST (FrustumCulling, Filters)
     Eigen::AngleAxisf (0 * M_PI / 180, Eigen::Vector3f::UnitY ()) *
     Eigen::AngleAxisf (0 * M_PI / 180, Eigen::Vector3f::UnitZ ());
 
-  camera_pose.block (0, 0, 3, 3) = R;
+  camera_pose.topLeftCorner<3, 3> () = R;
 
   Eigen::Vector3f T;
   T (0) = -5; T (1) = 0; T (2) = 0;
-  camera_pose.block (0, 3, 3, 1) = T;
+  camera_pose.block<3, 1> (0, 3) = T;
   camera_pose (3, 3) = 1;
 
   fc.setCameraPose (camera_pose);
@@ -2051,7 +2101,7 @@ TEST (FrustumCulling, Filters)
 
   Eigen::Matrix4f cam2robot;
   cam2robot << 0, 0, 1, 0, 0, -1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1;
-  // Cut out object based on ROI 
+  // Cut out object based on ROI
   fc.setInputCloud (model);
   fc.setNegative (false);
   fc.setVerticalFOV (43);
@@ -2062,7 +2112,7 @@ TEST (FrustumCulling, Filters)
   fc.setCameraPose (cam2robot);
   fc.filter (*output);
   // Should extract milk cartoon with 13541 points
-  EXPECT_EQ (output->size (), 13541); 
+  EXPECT_EQ (output->size (), 13541);
   removed = fc.getRemovedIndices ();
   EXPECT_EQ (removed->size (), model->size () - output->size ());
 
@@ -2460,6 +2510,27 @@ TEST (NormalRefinement, Filters)
   EXPECT_LT(err_refined_var, err_est_var);
 }
 
+TEST (VoxelGridOcclusionEstimation, Filters)
+{
+  auto input_cloud = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>();
+  input_cloud->emplace_back(0.0, 0.0, 0.0);
+  input_cloud->emplace_back(9.9, 9.9, 9.9); // we want a nice bounding box from (0, 0, 0) to (10, 10, 10)
+  input_cloud->sensor_origin_ << -0.1f, 0.5f, 0.5f, 0.0f; // just outside the bounding box. Most rays will enter at voxel (0, 0, 0)
+  pcl::VoxelGridOcclusionEstimation<pcl::PointXYZ> vg;
+  vg.setInputCloud (input_cloud);
+  vg.setLeafSize (1.0, 1.0, 1.0);
+  vg.initializeVoxelGrid ();
+  std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> > occluded_voxels;
+  vg.occlusionEstimationAll (occluded_voxels);
+  for(std::size_t y=0; y<10; ++y) {
+    for (std::size_t z=0; z<10; ++z) {
+      if(y==9 && z==9) continue; // voxel (9, 9, 9) is occupied by point (9.9, 9.9, 9.9), so it will not be counted as occluded
+      Eigen::Vector3i cell(9, y, z);
+      EXPECT_NE(std::find(occluded_voxels.begin(), occluded_voxels.end(), cell), occluded_voxels.end()); // not equal means it was found
+    }
+  }
+}
+
 /* ---[ */
 int
 main (int argc, char** argv)
index 50a3446c0368c9415bba6ae5015e426c7bbbfead..7403a1d49cd832fa058da9c4803422f307cd11f0 100644 (file)
@@ -61,17 +61,75 @@ TEST(UniformSampling, extractRemovedIndices)
   // sure that each cell has at least one point. As a result, we expect 1000 points in
   // the output cloud and the rest in removed indices.
 
-  pcl::UniformSampling<pcl::PointXYZ> us(true); // extract removed indices
-  us.setInputCloud(xyz);
-  us.setRadiusSearch(0.1);
+  pcl::UniformSampling<pcl::PointXYZ>::Ptr us_ptr(new pcl::UniformSampling<pcl::PointXYZ>(true));// extract removed indices
+  us_ptr->setRadiusSearch(0.1);
   pcl::PointCloud<pcl::PointXYZ> output;
-  us.filter(output);
+  pcl::Indices indices;
+  
+  // Empty input cloud
+  us_ptr->filter(output);
+  us_ptr->filter(indices);
 
-  auto removed_indices = us.getRemovedIndices();
+  us_ptr->setInputCloud(xyz);
+  // Cloud
+  us_ptr->filter(output);
+  // Indices
+  us_ptr->filter(indices);
+
+  for (const auto& outputIndex : indices)
+  {
+    // Check if the point exists in the output cloud
+    bool found = false;
+    for (const auto& j : output)
+    {
+      if (j.x == (*xyz)[outputIndex].x &&
+          j.y == (*xyz)[outputIndex].y &&
+          j.z == (*xyz)[outputIndex].z)
+      {
+        found = true;
+        break;
+      }
+    }
+
+    // Assert that the point was found in the output cloud
+    ASSERT_TRUE(found);
+  }
+
+  auto removed_indices = us_ptr->getRemovedIndices();
   ASSERT_EQ(output.size(), 1000);
-  EXPECT_EQ(removed_indices->size(), xyz->size() - 1000);
+  EXPECT_EQ(int(removed_indices->size()), int(xyz->size() - 1000));
   std::set<int> removed_indices_set(removed_indices->begin(), removed_indices->end());
   ASSERT_EQ(removed_indices_set.size(), removed_indices->size());
+
+  // Negative
+  us_ptr->setNegative (true);
+  us_ptr->filter(output);
+  removed_indices = us_ptr->getRemovedIndices ();
+  EXPECT_EQ (int (removed_indices->size ()), 1000);
+  EXPECT_EQ (int (output.size ()), int (xyz->size() - 1000));
+
+  // Organized
+  us_ptr->setKeepOrganized (true);
+  us_ptr->setNegative (false);
+  us_ptr->filter(output);
+  removed_indices = us_ptr->getRemovedIndices ();
+  EXPECT_EQ (int (removed_indices->size ()), int(xyz->size() - 1000));
+  for (std::size_t i = 0; i < removed_indices->size (); ++i)
+  {
+    EXPECT_TRUE (std::isnan (output.at ((*removed_indices)[i]).x));
+    EXPECT_TRUE (std::isnan (output.at ((*removed_indices)[i]).y));
+    EXPECT_TRUE (std::isnan (output.at ((*removed_indices)[i]).z));
+  }
+
+  EXPECT_EQ (output.width, xyz->width);
+  EXPECT_EQ (output.height, xyz->height);
+
+  // Check input cloud with nan values
+  us_ptr->setInputCloud (output.makeShared ());
+  us_ptr->setRadiusSearch(2);
+  us_ptr->filter (output);
+  removed_indices = us_ptr->getRemovedIndices ();
+  EXPECT_EQ (int (removed_indices->size ()), output.size()-1);
 }
 
 int
index 747809f7e7e05dcde00f3aa0ce990b3cf6b79a91..ccf53d863220315e99f67b982c4ad6cce5fd145f 100644 (file)
@@ -54,7 +54,7 @@ $CXX $CXXFLAGS -DPCLAPI_EXPORTS \
         -I/src/pcl/build/include -I/src/pcl/common/include \
         -I/src/pcl/dssdk/include \
         -I/src/pcl/io/include -isystem /usr/include/eigen3 \
-        -O2 -g -DNDEBUG -fPIC -std=c++14 \
+        -O2 -g -DNDEBUG -fPIC -std=c++17 \
         -o ply_reader_fuzzer.o -c ply_reader_fuzzer.cpp
 
 $CXX $CXXFLAGS $LIB_FUZZING_ENGINE ply_reader_fuzzer.o \
index 4b9f788c8da2525651b14f3cec224bf5c6f99224..7074ede0c6f676d9e481271ca2e1d4f1b61bb70e 100644 (file)
@@ -2,9 +2,7 @@ set(SUBSYS_NAME tests_geometry)
 set(SUBSYS_DESC "Point cloud library geometry module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS geometry)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index 0b6df7d97ccc3c0eb0f9ff3dd49a3c2481732015..aa54bb4aee0a809303bf0f436b5d7361534d06d5 100644 (file)
@@ -89,9 +89,9 @@ TEST (TestAddDeleteFace, NonManifold1)
   using VI = VertexIndex;
   VertexIndices vi;
   std::vector <VertexIndices> faces;
-  vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear (); // 0
-  vi.push_back (VI (2)); vi.push_back (VI (1)); vi.push_back (VI (4)); faces.push_back (vi); vi.clear (); // 1
-  vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (5)); faces.push_back (vi); vi.clear (); // 2
+  vi.emplace_back(0); vi.emplace_back(3); vi.emplace_back(1); faces.push_back (vi); vi.clear (); // 0
+  vi.emplace_back(2); vi.emplace_back(1); vi.emplace_back(4); faces.push_back (vi); vi.clear (); // 1
+  vi.emplace_back(0); vi.emplace_back(2); vi.emplace_back(5); faces.push_back (vi); vi.clear (); // 2
   for (const auto &face : faces)
   {
     ASSERT_TRUE (mesh.addFace (face).isValid ());
@@ -100,18 +100,18 @@ TEST (TestAddDeleteFace, NonManifold1)
 
   // Check if the whole boundary is reached.
   VertexIndices boundary_expected;
-  boundary_expected.push_back (VI (0));
-  boundary_expected.push_back (VI (5));
-  boundary_expected.push_back (VI (2));
-  boundary_expected.push_back (VI (4));
-  boundary_expected.push_back (VI (1));
-  boundary_expected.push_back (VI (3));
+  boundary_expected.emplace_back(0);
+  boundary_expected.emplace_back(5);
+  boundary_expected.emplace_back(2);
+  boundary_expected.emplace_back(4);
+  boundary_expected.emplace_back(1);
+  boundary_expected.emplace_back(3);
 
   VertexIndices boundary_vertices = getBoundaryVertices (mesh, VI (3));
   EXPECT_EQ (boundary_expected, boundary_vertices);
 
   // Close the gaps.
-  vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces.push_back (vi); vi.clear (); // 3
+  vi.emplace_back(0); vi.emplace_back(1); vi.emplace_back(2); faces.push_back (vi); vi.clear (); // 3
   ASSERT_TRUE (mesh.addFace (faces [3]).isValid ());
   EXPECT_TRUE (hasFaces (mesh, faces));
 
@@ -152,8 +152,8 @@ TEST (TestAddDeleteFace, NonManifold2)
   //   0   //
   //  / \  //
   // 3 - 4 //
-  vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (4)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(1); vi.emplace_back(2); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(3); vi.emplace_back(4); faces.push_back (vi); vi.clear ();
   for (const auto &face : faces)
   {
     ASSERT_TRUE (mesh.addFace (face).isValid ());
@@ -161,23 +161,23 @@ TEST (TestAddDeleteFace, NonManifold2)
   EXPECT_TRUE (hasFaces (mesh, faces));
 
   // (*) Adding the next two faces would destroy the connectivity around vertex 0. E.g. a VertexAroundVertexCirculator would not be able to access all the vertices (1, 2, 3, 4) anymore.
-  vi.push_back (VI (3)); vi.push_back (VI (0)); vi.push_back (VI (4));
+  vi.emplace_back(3); vi.emplace_back(0); vi.emplace_back(4);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
-  vi.push_back (VI (1)); vi.push_back (VI (0)); vi.push_back (VI (2));
+  vi.emplace_back(1); vi.emplace_back(0); vi.emplace_back(2);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
   {
     // Check if the whole boundary is reached.
     VertexIndices boundary_expected;
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (1));
-    boundary_expected.push_back (VI (2));
-    boundary_expected.push_back (VI (3));
-    boundary_expected.push_back (VI (4));
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(1);
+    boundary_expected.emplace_back(2);
+    boundary_expected.emplace_back(3);
+    boundary_expected.emplace_back(4);
 
     VertexIndices boundary_vertices = getBoundaryVertices (mesh, VI (2));
     std::sort (boundary_vertices.begin (), boundary_vertices.end ());
@@ -190,35 +190,35 @@ TEST (TestAddDeleteFace, NonManifold2)
   // 3 - 0 - 6  //
   //  \ / \ /   //
   //   4   5    //
-  vi.push_back (VI (0)); vi.push_back (VI (5)); vi.push_back (VI (6)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(5); vi.emplace_back(6); faces.push_back (vi); vi.clear ();
   EXPECT_TRUE (mesh.addFace (faces [2]).isValid ());
   EXPECT_TRUE (hasFaces (mesh, faces));
 
   // Same as (*)
-  vi.push_back (VI (1)); vi.push_back (VI (0)); vi.push_back (VI (2));
+  vi.emplace_back(1); vi.emplace_back(0); vi.emplace_back(2);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
-  vi.push_back (VI (3)); vi.push_back (VI (0)); vi.push_back (VI (4));
+  vi.emplace_back(3); vi.emplace_back(0); vi.emplace_back(4);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
-  vi.push_back (VI (5)); vi.push_back (VI (0)); vi.push_back (VI (6));
+  vi.emplace_back(5); vi.emplace_back(0); vi.emplace_back(6);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
   {
     // Check if the whole boundary is reached.
     VertexIndices boundary_expected;
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (1));
-    boundary_expected.push_back (VI (2));
-    boundary_expected.push_back (VI (3));
-    boundary_expected.push_back (VI (4));
-    boundary_expected.push_back (VI (5));
-    boundary_expected.push_back (VI (6));
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(1);
+    boundary_expected.emplace_back(2);
+    boundary_expected.emplace_back(3);
+    boundary_expected.emplace_back(4);
+    boundary_expected.emplace_back(5);
+    boundary_expected.emplace_back(6);
 
     VertexIndices boundary_vertices = getBoundaryVertices (mesh, VI (2));
     std::sort (boundary_vertices.begin (), boundary_vertices.end ());
@@ -235,42 +235,42 @@ TEST (TestAddDeleteFace, NonManifold2)
   // | / | \    //
   // |/  |  \   //
   // 4   5---6  //
-  vi.push_back (VI (0)); vi.push_back (VI (7)); vi.push_back (VI (8)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(7); vi.emplace_back(8); faces.push_back (vi); vi.clear ();
   EXPECT_TRUE (mesh.addFace (faces [3]).isValid ());
   EXPECT_TRUE (hasFaces (mesh, faces));
 
   // Same as (*)
-  vi.push_back (VI (1)); vi.push_back (VI (0)); vi.push_back (VI (2));
+  vi.emplace_back(1); vi.emplace_back(0); vi.emplace_back(2);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
-  vi.push_back (VI (3)); vi.push_back (VI (0)); vi.push_back (VI (4));
+  vi.emplace_back(3); vi.emplace_back(0); vi.emplace_back(4);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
-  vi.push_back (VI (5)); vi.push_back (VI (0)); vi.push_back (VI (6));
+  vi.emplace_back(5); vi.emplace_back(0); vi.emplace_back(6);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
-  vi.push_back (VI (7)); vi.push_back (VI (0)); vi.push_back (VI (8));
+  vi.emplace_back(7); vi.emplace_back(0); vi.emplace_back(8);
   EXPECT_FALSE (mesh.addFace (vi).isValid ());
   vi.clear ();
 
   // Check if the whole boundary is reached.
   {
     VertexIndices boundary_expected;
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (0));
-    boundary_expected.push_back (VI (1));
-    boundary_expected.push_back (VI (2));
-    boundary_expected.push_back (VI (3));
-    boundary_expected.push_back (VI (4));
-    boundary_expected.push_back (VI (5));
-    boundary_expected.push_back (VI (6));
-    boundary_expected.push_back (VI (7));
-    boundary_expected.push_back (VI (8));
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(0);
+    boundary_expected.emplace_back(1);
+    boundary_expected.emplace_back(2);
+    boundary_expected.emplace_back(3);
+    boundary_expected.emplace_back(4);
+    boundary_expected.emplace_back(5);
+    boundary_expected.emplace_back(6);
+    boundary_expected.emplace_back(7);
+    boundary_expected.emplace_back(8);
 
     VertexIndices boundary_vertices = getBoundaryVertices (mesh, VI (2));
     std::sort (boundary_vertices.begin (), boundary_vertices.end ());
@@ -287,10 +287,10 @@ TEST (TestAddDeleteFace, NonManifold2)
   // | /4|2\ |      //
   // |/  |  \|      //
   // 4---5---6      //
-  vi.push_back (VI (0)); vi.push_back (VI (4)); vi.push_back (VI (5)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (8)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (3)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (6)); vi.push_back (VI (7)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(4); vi.emplace_back(5); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(8); vi.emplace_back(1); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(2); vi.emplace_back(3); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(6); vi.emplace_back(7); faces.push_back (vi); vi.clear ();
   for (std::size_t i = 4; i < faces.size (); ++i)
   {
     EXPECT_TRUE (mesh.addFace (faces [i]).isValid ());
@@ -300,7 +300,7 @@ TEST (TestAddDeleteFace, NonManifold2)
   VertexIndices boundary_expected;
   for (unsigned int i=8; i>0; --i)
   {
-    boundary_expected.push_back (VI (i));
+    boundary_expected.emplace_back(i);
   }
   VertexIndices boundary_vertices = getBoundaryVertices (mesh, VI (1));
   EXPECT_EQ (boundary_expected, boundary_vertices);
@@ -334,7 +334,7 @@ TEST (TestAddDeleteFace, NonManifold2)
 TEST (TestAddDeleteFace, Manifold1)
 {
   using Mesh = ManifoldTriangleMesh;
-  using VI = VertexIndex;
+  
   Mesh mesh;
   for (unsigned int i=0; i<7; ++i) mesh.addVertex (i);
 
@@ -346,12 +346,12 @@ TEST (TestAddDeleteFace, Manifold1)
   std::vector <VertexIndices> faces;
   std::vector <std::vector <int> > expected;
   VertexIndices vi;
-  vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (3)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (4)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (4)); vi.push_back (VI (5)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (5)); vi.push_back (VI (6)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (6)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(1); vi.emplace_back(2); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(2); vi.emplace_back(3); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(3); vi.emplace_back(4); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(4); vi.emplace_back(5); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(5); vi.emplace_back(6); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(6); vi.emplace_back(1); faces.push_back (vi); vi.clear ();
 
   for (std::size_t i = 0; i < faces.size (); ++i)
   {
@@ -386,11 +386,11 @@ TEST (TestAddDeleteFace, Manifold1)
   mesh.clear ();
   expected.clear ();
   for (unsigned int i=0; i<11; ++i) mesh.addVertex (i);
-  vi.push_back (VI ( 3)); vi.push_back (VI (7)); vi.push_back (VI (4)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 3)); vi.push_back (VI (2)); vi.push_back (VI (8)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 8)); vi.push_back (VI (2)); vi.push_back (VI (9)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (10)); vi.push_back (VI (9)); vi.push_back (VI (2)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (10)); vi.push_back (VI (2)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 3); vi.emplace_back(7); vi.emplace_back(4); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 3); vi.emplace_back(2); vi.emplace_back(8); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 8); vi.emplace_back(2); vi.emplace_back(9); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(10); vi.emplace_back(9); vi.emplace_back(2); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(10); vi.emplace_back(2); vi.emplace_back(1); faces.push_back (vi); vi.clear ();
   for (std::size_t i = 0; i < faces.size (); ++i)
   {
     ASSERT_TRUE (mesh.addFace (faces [i]).isValid ()) << "Face " << i;
@@ -442,9 +442,9 @@ TEST (TestAddDeleteFace, Manifold2)
   //      2      //
   std::vector <VertexIndices> faces;
   VertexIndices vi;
-  vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (3)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(1); vi.emplace_back(2); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(2); vi.emplace_back(3); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(3); vi.emplace_back(1); faces.push_back (vi); vi.clear ();
 
   // Try all possible combinations of adding the faces and deleting a vertex.
   // NOTE: Some cases are redundant.
@@ -511,12 +511,12 @@ TEST (TestDelete, VertexAndEdge)
   std::vector <VertexIndices> faces;
   std::vector <std::vector <int> > expected;
   VertexIndices vi;
-  vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (3)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (4)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (4)); vi.push_back (VI (5)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (5)); vi.push_back (VI (6)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (0)); vi.push_back (VI (6)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(1); vi.emplace_back(2); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(2); vi.emplace_back(3); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(3); vi.emplace_back(4); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(4); vi.emplace_back(5); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(5); vi.emplace_back(6); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(0); vi.emplace_back(6); vi.emplace_back(1); faces.push_back (vi); vi.clear ();
 
   for (std::size_t i = 0; i < faces.size (); ++i)
   {
@@ -581,9 +581,9 @@ TEST (TestMesh, IsBoundaryIsManifold)
   using VI = VertexIndex;
   VertexIndices vi;
   std::vector <VertexIndices> faces;
-  vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (1)); faces.push_back (vi); vi.clear (); // 0
-  vi.push_back (VI (2)); vi.push_back (VI (1)); vi.push_back (VI (4)); faces.push_back (vi); vi.clear (); // 1
-  vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (5)); faces.push_back (vi); vi.clear (); // 2
+  vi.emplace_back(0); vi.emplace_back(3); vi.emplace_back(1); faces.push_back (vi); vi.clear (); // 0
+  vi.emplace_back(2); vi.emplace_back(1); vi.emplace_back(4); faces.push_back (vi); vi.clear (); // 1
+  vi.emplace_back(0); vi.emplace_back(2); vi.emplace_back(5); faces.push_back (vi); vi.clear (); // 2
   for (const auto &face : faces)
   {
     ASSERT_TRUE (mesh.addFace (face).isValid ());
@@ -592,12 +592,12 @@ TEST (TestMesh, IsBoundaryIsManifold)
 
   // Check if the whole boundary is reached.
   VertexIndices boundary_expected;
-  boundary_expected.push_back (VI (0));
-  boundary_expected.push_back (VI (5));
-  boundary_expected.push_back (VI (2));
-  boundary_expected.push_back (VI (4));
-  boundary_expected.push_back (VI (1));
-  boundary_expected.push_back (VI (3));
+  boundary_expected.emplace_back(0);
+  boundary_expected.emplace_back(5);
+  boundary_expected.emplace_back(2);
+  boundary_expected.emplace_back(4);
+  boundary_expected.emplace_back(1);
+  boundary_expected.emplace_back(3);
 
   VertexIndices boundary_vertices = getBoundaryVertices (mesh, VI (3));
   EXPECT_EQ (boundary_expected, boundary_vertices);
@@ -615,7 +615,7 @@ TEST (TestMesh, IsBoundaryIsManifold)
   }
 
   // Make manifold
-  vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces.push_back (vi); vi.clear (); // 3
+  vi.emplace_back(0); vi.emplace_back(1); vi.emplace_back(2); faces.push_back (vi); vi.clear (); // 3
   ASSERT_TRUE  (mesh.addFace (faces [3]).isValid ());
   EXPECT_TRUE  (hasFaces (mesh, faces));
 
index b198c6dcb082d6400dddf9f1d0752aea4db9ab9b..35b44035e68a440a2ca03c1c45dc4d7dff268e7c 100644 (file)
@@ -90,21 +90,21 @@ class TestMeshCirculators : public ::testing::Test
       for (int i=0; i<7; ++i) mesh_.addVertex ();
 
       VertexIndices vi;
-      using VI = VertexIndex;
-      vi.push_back (VI (0)); vi.push_back (VI (1)); vi.push_back (VI (2)); faces_.push_back (vi); vi.clear ();
-      vi.push_back (VI (0)); vi.push_back (VI (2)); vi.push_back (VI (3)); faces_.push_back (vi); vi.clear ();
-      vi.push_back (VI (0)); vi.push_back (VI (3)); vi.push_back (VI (4)); faces_.push_back (vi); vi.clear ();
-      vi.push_back (VI (0)); vi.push_back (VI (4)); vi.push_back (VI (5)); faces_.push_back (vi); vi.clear ();
-      vi.push_back (VI (0)); vi.push_back (VI (5)); vi.push_back (VI (6)); faces_.push_back (vi); vi.clear ();
-      vi.push_back (VI (0)); vi.push_back (VI (6)); vi.push_back (VI (1)); faces_.push_back (vi); vi.clear ();
+      
+      vi.emplace_back(0); vi.emplace_back(1); vi.emplace_back(2); faces_.push_back (vi); vi.clear ();
+      vi.emplace_back(0); vi.emplace_back(2); vi.emplace_back(3); faces_.push_back (vi); vi.clear ();
+      vi.emplace_back(0); vi.emplace_back(3); vi.emplace_back(4); faces_.push_back (vi); vi.clear ();
+      vi.emplace_back(0); vi.emplace_back(4); vi.emplace_back(5); faces_.push_back (vi); vi.clear ();
+      vi.emplace_back(0); vi.emplace_back(5); vi.emplace_back(6); faces_.push_back (vi); vi.clear ();
+      vi.emplace_back(0); vi.emplace_back(6); vi.emplace_back(1); faces_.push_back (vi); vi.clear ();
       for (std::size_t i=0; i<faces_.size (); ++i)
       {
         ASSERT_TRUE (mesh_.addFace (faces_ [i]).isValid ()) << "Face number " << i;
       }
       for (int i=1; i<=6; ++i)
       {
-        expected_123456_.push_back (VertexIndex (i));
-        expected_654321_.push_back (VertexIndex (7-i));
+        expected_123456_.emplace_back(i);
+        expected_654321_.emplace_back(7-i);
       }
     }
 
@@ -497,9 +497,9 @@ TEST_F (TestMeshCirculators, FaceAroundFaceIncrement)
   for (int i = 0; i < static_cast<int> (mesh_.sizeFaces ()); ++i)
   {
     expected.clear ();
-    expected.push_back (FaceIndex (i==(n-1) ?  0    : (i+1)));
-    expected.push_back (FaceIndex (i== 0    ? (n-1) : (i-1)));
-    expected.push_back (FaceIndex ());
+    expected.emplace_back(i==(n-1) ?  0    : (i+1));
+    expected.emplace_back(i== 0    ? (n-1) : (i-1));
+    expected.emplace_back();
 
     FAFC       circ     = mesh_.getFaceAroundFaceCirculator (FaceIndex (i));
     const FAFC circ_end = circ;
@@ -525,9 +525,9 @@ TEST_F (TestMeshCirculators, FaceAroundFaceDecrement)
   for (int i = 0; i < static_cast<int> (mesh_.sizeFaces ()); ++i)
   {
     expected.clear ();
-    expected.push_back (FaceIndex (i== 0    ? (n-1) : (i-1)));
-    expected.push_back (FaceIndex (i==(n-1) ?  0    : (i+1)));
-    expected.push_back (FaceIndex ());
+    expected.emplace_back(i== 0    ? (n-1) : (i-1));
+    expected.emplace_back(i==(n-1) ?  0    : (i+1));
+    expected.emplace_back();
 
     FAFC       circ     = mesh_.getFaceAroundFaceCirculator (FaceIndex (i));
     const FAFC circ_end = circ;
index 5f3d42f5f2b189ebbf2d043b1c8c9fde9e0852ad..0579b99e63d688e32aa6360ceae1d951ce5faa84 100644 (file)
@@ -40,6 +40,7 @@
 
 #pragma once
 
+#include <iomanip> // for setw
 #include <iostream>
 #include <vector>
 
index 6bd229ee792f8194db0eddd42d6772b3adf5ee3c..be11f9b9ed9867140eeb086ab3e7593e34c189df 100644 (file)
@@ -123,9 +123,9 @@ TEST (TestMesh, MeshData)
   //  \ / \ /  //
   //   0 - 1   //
   VertexIndices vi_0, vi_1, vi_2;
-  vi_0.push_back (VertexIndex (0)); vi_0.push_back (VertexIndex (1)); vi_0.push_back (VertexIndex (2));
-  vi_1.push_back (VertexIndex (0)); vi_1.push_back (VertexIndex (2)); vi_1.push_back (VertexIndex (3));
-  vi_2.push_back (VertexIndex (4)); vi_2.push_back (VertexIndex (2)); vi_2.push_back (VertexIndex (1));
+  vi_0.emplace_back(0); vi_0.emplace_back(1); vi_0.emplace_back(2);
+  vi_1.emplace_back(0); vi_1.emplace_back(2); vi_1.emplace_back(3);
+  vi_2.emplace_back(4); vi_2.emplace_back(2); vi_2.emplace_back(1);
 
   // Mesh data.
   int vd_0  (10), vd_1  (11), vd_2  (12), vd_3 (13), vd_4 (14);
index 41f9e73a3b6386218cf7e0c260bf77c96aec2d7f..07871763b8243a6f7a81d29a281da3ac42a283c6 100644 (file)
@@ -132,7 +132,7 @@ TYPED_TEST (TestPolygonMesh, CorrectNumberOfVertices)
     VertexIndices vi;
     for (unsigned int i=0; i<n; ++i)
     {
-      vi.push_back (VertexIndex (i));
+      vi.emplace_back(i);
       mesh.addVertex (i);
     }
 
@@ -158,24 +158,24 @@ TYPED_TEST (TestPolygonMesh, ThreePolygons)
 
   std::vector <VertexIndices> faces;
   VertexIndices vi;
-  vi.push_back (VertexIndex (0));
-  vi.push_back (VertexIndex (1));
-  vi.push_back (VertexIndex (2));
+  vi.emplace_back(0);
+  vi.emplace_back(1);
+  vi.emplace_back(2);
   faces.push_back (vi);
   vi.clear ();
 
-  vi.push_back (VertexIndex (0));
-  vi.push_back (VertexIndex (2));
-  vi.push_back (VertexIndex (3));
-  vi.push_back (VertexIndex (4));
+  vi.emplace_back(0);
+  vi.emplace_back(2);
+  vi.emplace_back(3);
+  vi.emplace_back(4);
   faces.push_back (vi);
   vi.clear ();
 
-  vi.push_back (VertexIndex (0));
-  vi.push_back (VertexIndex (4));
-  vi.push_back (VertexIndex (5));
-  vi.push_back (VertexIndex (6));
-  vi.push_back (VertexIndex (1));
+  vi.emplace_back(0);
+  vi.emplace_back(4);
+  vi.emplace_back(5);
+  vi.emplace_back(6);
+  vi.emplace_back(1);
   faces.push_back (vi);
   vi.clear ();
 
index 3bafedb1827620297a92dba8cda78d5dad9fd544..f138aa93bc2bb5d94b4adb95aa5616d1b1161128 100644 (file)
@@ -104,7 +104,7 @@ TYPED_TEST (TestQuadMesh, CorrectNumberOfVertices)
     VertexIndices vi;
     for (unsigned int i=0; i<n; ++i)
     {
-      vi.push_back (VertexIndex (i));
+      vi.emplace_back(i);
       mesh.addVertex (i);
     }
 
@@ -328,18 +328,17 @@ TYPED_TEST (TestQuadMesh, NineQuads)
   // 08 - 09 - 10 - 11 //
   //  |    |    |    | //
   // 12 - 13 - 14 - 15 //
-  using VI = VertexIndex;
   std::vector <VertexIndices> faces;
   VertexIndices vi;
-  vi.push_back (VI ( 0)); vi.push_back (VI ( 4)); vi.push_back (VI ( 5)); vi.push_back (VI ( 1)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 1)); vi.push_back (VI ( 5)); vi.push_back (VI ( 6)); vi.push_back (VI ( 2)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 2)); vi.push_back (VI ( 6)); vi.push_back (VI ( 7)); vi.push_back (VI ( 3)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 4)); vi.push_back (VI ( 8)); vi.push_back (VI ( 9)); vi.push_back (VI ( 5)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 5)); vi.push_back (VI ( 9)); vi.push_back (VI (10)); vi.push_back (VI ( 6)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 6)); vi.push_back (VI (10)); vi.push_back (VI (11)); vi.push_back (VI ( 7)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 8)); vi.push_back (VI (12)); vi.push_back (VI (13)); vi.push_back (VI ( 9)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI ( 9)); vi.push_back (VI (13)); vi.push_back (VI (14)); vi.push_back (VI (10)); faces.push_back (vi); vi.clear ();
-  vi.push_back (VI (10)); vi.push_back (VI (14)); vi.push_back (VI (15)); vi.push_back (VI (11)); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 0); vi.emplace_back( 4); vi.emplace_back( 5); vi.emplace_back( 1); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 1); vi.emplace_back( 5); vi.emplace_back( 6); vi.emplace_back( 2); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 2); vi.emplace_back( 6); vi.emplace_back( 7); vi.emplace_back( 3); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 4); vi.emplace_back( 8); vi.emplace_back( 9); vi.emplace_back( 5); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 5); vi.emplace_back( 9); vi.emplace_back(10); vi.emplace_back( 6); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 6); vi.emplace_back(10); vi.emplace_back(11); vi.emplace_back( 7); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 8); vi.emplace_back(12); vi.emplace_back(13); vi.emplace_back( 9); faces.push_back (vi); vi.clear ();
+  vi.emplace_back( 9); vi.emplace_back(13); vi.emplace_back(14); vi.emplace_back(10); faces.push_back (vi); vi.clear ();
+  vi.emplace_back(10); vi.emplace_back(14); vi.emplace_back(15); vi.emplace_back(11); faces.push_back (vi); vi.clear ();
 
   ASSERT_EQ (order_vec.size (), non_manifold.size ());
   ASSERT_EQ (9, faces.size ());
index 3c1d8d371a7a97c6a7a9bc8b8a4d649b267b5fd1..857df978f5c91cd815febe13a245d1ad113e61fc 100644 (file)
@@ -104,7 +104,7 @@ TYPED_TEST (TestTriangleMesh, CorrectNumberOfVertices)
     VertexIndices vi;
     for (unsigned int i=0; i<n; ++i)
     {
-      vi.push_back (VertexIndex (i));
+      vi.emplace_back(i);
       mesh.addVertex (i);
     }
 
index d351641a035dcfd0d37db8c33a7587c0c0624d0f..a2a8f2c354c80e000bb548eae11fdbbe3e514b29 100644 (file)
@@ -2,10 +2,7 @@ set(SUBSYS_NAME tests_gpu_octree)
 set(SUBSYS_DESC "Point cloud library gpu octree tests")
 set(SUBSYS_DEPS common octree gpu_containers gpu_octree gpu_utils)
 
-set(DEFAULT ON)
-set(build TRUE)
-set(REASON "")
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index 6a57a6826625aa8d69691877aa4788ac5e4badf0..9cbef8203289ab49b5f857bcb7f42524ea7aa2d7 100644 (file)
@@ -1,11 +1,9 @@
 set(SUBSYS_NAME tests_io)
 set(SUBSYS_DESC "Point cloud library io module unit tests")
-PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS io)
+PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS common io octree)
 set(OPT_DEPS visualization)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
@@ -43,7 +41,6 @@ PCL_ADD_TEST(io_ply_io test_ply_io
 
 # Uses VTK readers to verify
 if(VTK_FOUND AND NOT ANDROID)
-  include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
   PCL_ADD_TEST (io_ply_mesh_io test_ply_mesh_io
                 FILES test_ply_mesh_io.cpp
                 LINK_WITH pcl_gtest pcl_io
@@ -56,7 +53,7 @@ PCL_ADD_TEST(point_cloud_image_extractors test_point_cloud_image_extractors
 
 PCL_ADD_TEST(buffers test_buffers
              FILES test_buffers.cpp
-             LINK_WITH pcl_gtest pcl_common)
+             LINK_WITH pcl_gtest pcl_common pcl_io)
 
 PCL_ADD_TEST(io_octree_compression test_octree_compression
         FILES test_octree_compression.cpp
index 09185f9f8d23d4401b9f26aaa647079724ff4827..732c0faf20347c5b7eb71d6165f3b6a088a541de 100644 (file)
@@ -1,4 +1,5 @@
 #include <pcl/test/gtest.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/point_types.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/io/pcd_grabber.h>
@@ -7,7 +8,7 @@
 #include <string>
 #include <thread>
 #include <vector>
-#include <boost/filesystem.hpp> // for directory_iterator, extension
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace std::chrono_literals;
@@ -519,8 +520,8 @@ int
   pclzf_dir_ = grabber_sequences + "/pclzf";
   pcd_dir_ = grabber_sequences + "/pcd";
   // Get pcd files
-  boost::filesystem::directory_iterator end_itr;
-  for (boost::filesystem::directory_iterator itr (pcd_dir_); itr != end_itr; ++itr)
+  pcl_fs::directory_iterator end_itr;
+  for (pcl_fs::directory_iterator itr (pcd_dir_); itr != end_itr; ++itr)
   {
     if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
     {
index 53438b2e92f7d54f1eba7eddaddfa5c16f320e9a..caa95123cb8166c52d07c3e5bba5bfffda9e8194 100644 (file)
@@ -49,6 +49,7 @@
 #include <pcl/io/ascii_io.h>
 #include <pcl/io/obj_io.h>
 #include <fstream>
+#include <iomanip> // for setprecision
 #include <locale>
 #include <stdexcept>
 
@@ -1081,7 +1082,7 @@ TEST(PCL, OBJRead)
   fs.close ();
 
   pcl::PCLPointCloud2 blob;
-  pcl::OBJReader objreader = pcl::OBJReader();
+  pcl::OBJReader objreader;
   int res = objreader.read ("test_obj.obj", blob);
   EXPECT_NE (res, -1);
   EXPECT_EQ (blob.width, 8);
@@ -1120,10 +1121,55 @@ TEST(PCL, OBJRead)
   EXPECT_EQ (blob.fields[5].count, 1);
   EXPECT_EQ (blob.fields[5].datatype, pcl::PCLPointField::FLOAT32);
 
+  auto fblob = reinterpret_cast<const float*>(blob.data.data());
+
+  size_t offset_p = 0;
+  size_t offset_vn = blob.fields[3].offset / 4;
+  for (size_t i = 0; i < blob.width; ++i, offset_p += 6, offset_vn += 6)
+  {
+    Eigen::Vector3f expected_normal =
+        Eigen::Vector3f(fblob[offset_p], fblob[offset_p + 1], fblob[offset_p + 2])
+            .normalized();
+
+    Eigen::Vector3f actual_normal =
+        Eigen::Vector3f(fblob[offset_vn], fblob[offset_vn + 1], fblob[offset_vn + 2])
+            .normalized();
+
+    EXPECT_NEAR(expected_normal.x(), actual_normal.x(), 1e-4);
+    EXPECT_NEAR(expected_normal.y(), actual_normal.y(), 1e-4);
+    EXPECT_NEAR(expected_normal.z(), actual_normal.z(), 1e-4);
+  }
+
   remove ("test_obj.obj");
   remove ("test_obj.mtl");
 }
 
+TEST(PCL, loadOBJWithoutFaces)
+{
+  std::ofstream fs;
+  fs.open ("test_obj.obj");
+  fs << "v -1.000000 -1.000000 1.000000\n"
+        "v -1.000000 1.000000 1.000000\n"
+        "v 1.000000 -1.000000 1.000000\n"
+        "v 1.000000 1.000000 1.000000\n"
+        "vn -1.0000 0.0000 0.0000\n"
+        "vn 0.0000 0.0000 -1.0000\n"
+        "vn 1.0000 0.0000 0.0000\n"
+        "vn 0.0000 1.0000 0.0000\n";
+
+  fs.close ();
+  pcl::PointCloud<pcl::PointNormal> point_cloud;
+  pcl::io::loadOBJFile("test_obj.obj", point_cloud);
+  EXPECT_EQ(point_cloud.size(), 4);
+  EXPECT_NEAR(point_cloud[0].normal_x, -1.0, 1e-5);
+  EXPECT_NEAR(point_cloud[1].normal_z, -1.0, 1e-5);
+  EXPECT_NEAR(point_cloud[2].normal_x, 1.0, 1e-5);
+  EXPECT_NEAR(point_cloud[3].normal_y, 1.0, 1e-5);
+  EXPECT_NEAR(point_cloud[1].normal_y, 0.0, 1e-5);
+  EXPECT_NEAR(point_cloud[3].normal_z, 0.0, 1e-5);
+  remove ("test_obj.obj");
+}
+
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 
 struct PointXYZFPFH33
index a9f318217f7244bd16845bd0cd778c53447688b1..a4858681baf23c0399ec0f339985684656120981 100644 (file)
@@ -18,7 +18,7 @@ TEST(PCL, TestTimestampGeneratorZeroFraction)
 
   const auto timestamp = pcl::getTimestamp(time);
 
-  EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000");
+  EXPECT_EQ(timestamp.size(), 15);
 }
 
 TEST(PCL, TestTimestampGeneratorWithFraction)
@@ -28,7 +28,8 @@ TEST(PCL, TestTimestampGeneratorWithFraction)
 
   const auto timestamp = pcl::getTimestamp(dt);
 
-  EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.123456");
+  ASSERT_EQ(timestamp.size(), 22);
+  EXPECT_EQ(timestamp.substr(15), ".123456");
 }
 
 TEST(PCL, TestTimestampGeneratorWithSmallFraction)
@@ -38,7 +39,8 @@ TEST(PCL, TestTimestampGeneratorWithSmallFraction)
 
   const auto timestamp = pcl::getTimestamp(dt);
 
-  EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.000123");
+  ASSERT_EQ(timestamp.size(), 22);
+  EXPECT_EQ(timestamp.substr(15), ".000123");
 }
 
 TEST(PCL, TestParseTimestamp)
index e88a4a346b58c114d7312d075f96f91815142486..a597d1938e872a2ac6592b09ecedc7bbff28b042 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library kdtree module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS kdtree)
 set(OPT_DEPS io) # io is not a mandatory dependency in kdtree
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT (build AND BUILD_io))
index a8a3498da48ba74d776e22a12476abf34ed9c1a7..173bf4473d488e6fdddfb17f7297f38627cf61e2 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library keypoints module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS keypoints)
 set(OPT_DEPS io) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT (build AND BUILD_io))
index c345583489e85a65fac2243109a9d0688ef5dbb1..ada0833f5ef3d4a4011566614094cfc562d2629d 100644 (file)
@@ -2,9 +2,7 @@ set(SUBSYS_NAME tests_ml)
 set(SUBSYS_DESC "Point cloud library ml module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS ml)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index 7c71c702ba0214fae4bdd438161b9dcc84e6eb15..43fcb734cedae6930b82aca9e50c339184665380 100644 (file)
@@ -2,9 +2,7 @@ set(SUBSYS_NAME tests_octree)
 set(SUBSYS_DESC "Point cloud library octree module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS octree)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
@@ -13,7 +11,7 @@ endif()
 
 PCL_ADD_TEST(a_octree_test test_octree
               FILES test_octree.cpp
-              LINK_WITH pcl_gtest pcl_common)
+              LINK_WITH pcl_gtest pcl_common pcl_octree)
 PCL_ADD_TEST(a_octree_iterator_test test_octree_iterator
               FILES test_octree_iterator.cpp
               LINK_WITH pcl_gtest pcl_common pcl_octree)
index 7fbd7bb0925947f53d2544d09ab9ae42121b139b..4ca4def3815fb79076d26e3044a18a46356ab45a 100644 (file)
@@ -265,7 +265,7 @@ TEST (PCL, Octree_Dynamic_Depth_Test)
 
     for (int point = 0; point < 15; point++)
     {
-      // gereate a random point
+      // generate a random point
       PointXYZ newPoint (1.0, 2.0, 3.0);
 
       // OctreePointCloudPointVector can store all points..
@@ -290,7 +290,7 @@ TEST (PCL, Octree_Dynamic_Depth_Test)
 
     for (int point = 0; point < pointcount; point++)
     {
-      // gereate a random point
+      // generate a random point
       PointXYZ newPoint (static_cast<float> (1024.0 * rand () / RAND_MAX),
           static_cast<float> (1024.0 * rand () / RAND_MAX),
           static_cast<float> (1024.0 * rand () / RAND_MAX));
@@ -713,7 +713,7 @@ TEST (PCL, Octree_Pointcloud_Test)
 
     for (int point = 0; point < pointcount; point++)
     {
-      // gereate a random point
+      // generate a random point
       PointXYZ newPoint (static_cast<float> (1024.0 * rand () / RAND_MAX),
                          static_cast<float> (1024.0 * rand () / RAND_MAX),
                          static_cast<float> (1024.0 * rand () / RAND_MAX));
index e4b4b449177fe2e81b878bee3f72e0ac845c36c1..7ce9303bcd2ab8a4382012c576d89ffcd5736b8a 100644 (file)
@@ -3,16 +3,13 @@ set(SUBSYS_DESC "Point cloud library outofcore module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS outofcore)
 set(OPT_DEPS) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
   return()
 endif()
 
-include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
 PCL_ADD_TEST (outofcore_test test_outofcore
               FILES test_outofcore.cpp
               LINK_WITH pcl_gtest pcl_common pcl_io pcl_filters pcl_outofcore pcl_visualization)
index cb5cfff4aca489bf029e8713f175635bad8d1071..1d75415322a9215a7bde4972ad171b82997e721a 100644 (file)
@@ -44,6 +44,7 @@
 
 #include <pcl/test/gtest.h>
 
+#include <list>
 #include <vector>
 #include <iostream>
 #include <random>
@@ -98,7 +99,7 @@ AlignedPointTVector points;
 bool 
 compPt (const PointT &p1, const PointT &p2)
 {
-  return !(p1.x != p2.x || p1.y != p2.y || p1.z != p2.z);
+  return (p1.x == p2.x && p1.y == p2.y && p1.z == p2.z);
 }
 
 TEST (PCL, Outofcore_Octree_Build)
@@ -444,7 +445,7 @@ TEST_F (OutofcoreTest, Outofcore_Constructors)
   AlignedPointTVector some_points;
 
   for (unsigned int i=0; i< numPts; i++)
-    some_points.push_back (PointT (static_cast<float>(rand () % 1024), static_cast<float>(rand () % 1024), static_cast<float>(rand () % 1024)));
+    some_points.emplace_back(static_cast<float>(rand () % 1024), static_cast<float>(rand () % 1024), static_cast<float>(rand () % 1024));
   
 
   //(Case 1)
index 4dc04fe0e8731873ed7def8ad26a1bad67e70a58..d920a36bf474315e1a384b981fb35213b651aeff 100644 (file)
@@ -3,16 +3,13 @@ set(SUBSYS_DESC "Point cloud library people module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS people)
 set(OPT_DEPS) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
   return()
 endif()
 
-include_directories(SYSTEM ${VTK_INCLUDE_DIRS})
 PCL_ADD_TEST(a_people_detection_test test_people_detection
              FILES test_people_groundBasedPeopleDetectionApp.cpp
              LINK_WITH pcl_gtest pcl_common pcl_io pcl_kdtree pcl_search pcl_features pcl_sample_consensus pcl_filters pcl_segmentation pcl_people
index 06dc86c9503471469d8db8f865550ccef6590035..0377cfda7f24a79a48b76d9c9b05a81006e381ff 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library recognition module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS recognition)
 set(OPT_DEPS keypoints) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
@@ -14,7 +12,7 @@ endif()
 
 PCL_ADD_TEST(a_recognition_ism_test test_recognition_ism
              FILES test_recognition_ism.cpp
-             LINK_WITH pcl_gtest pcl_io pcl_features
+             LINK_WITH pcl_gtest pcl_io pcl_features pcl_recognition
              ARGUMENTS "${PCL_SOURCE_DIR}/test/ism_train.pcd" "${PCL_SOURCE_DIR}/test/ism_test.pcd")
 
 if(BUILD_keypoints)
index db199f02cbcd804525a243bbe28e940cb5618d37..f58ee30be175de68bcb22417656be94993c21b90 100644 (file)
@@ -1,11 +1,9 @@
 set(SUBSYS_NAME tests_registration)
 set(SUBSYS_DESC "Point cloud library registration module unit tests")
-PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS registration)
+PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS io registration)
 set(OPT_DEPS io) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index b251dd974c49d74d02a0e0ec438f26a15dc5e4a8..3e026707841383145d56ce7838ae9f38d7cbbc01 100644 (file)
@@ -36,7 +36,6 @@
  */
 
 #include <pcl/test/gtest.h>
-#include <pcl/io/pcd_io.h>
 #include <pcl/registration/correspondence_estimation_normal_shooting.h>
 #include <pcl/features/normal_3d.h>
 #include <pcl/kdtree/kdtree.h>
@@ -101,7 +100,7 @@ TYPED_TEST(CorrespondenceEstimationTestSuite, CorrespondenceEstimationNormalShoo
   auto cloud1 (pcl::make_shared<pcl::PointCloud<PointSource>> ());
   auto cloud2 (pcl::make_shared<pcl::PointCloud<PointTarget>> ());
 
-  // Defining two parallel planes differing only by the y co-ordinate
+  // Defining two parallel planes differing only by the y coordinate
   for (std::size_t i = 0; i < 50; ++i)
   {
     for (std::size_t j = 0; j < 25; ++j)
index 75a780a17a1919f7846273d257d31afab3550f5a..18f1d1cb02f8b8e890a7db9318cb5e2b61d74f32 100644 (file)
@@ -73,17 +73,18 @@ TEST (PCL, FPCSInitialAlignment)
   fpcs_ia.setNumberOfThreads (nr_threads);
   fpcs_ia.setApproxOverlap (approx_overlap);
   fpcs_ia.setDelta (delta, true);
+  fpcs_ia.setScoreThreshold (0.025); // if score is below this threshold, fpcs can stop because the solution is very good
   fpcs_ia.setNumberOfSamples (nr_samples);
 
   // align
   fpcs_ia.align (source_aligned);
   EXPECT_EQ (source_aligned.size (), cloud_source.size ());
 
-  // check for correct coarse transformation marix
-  //Eigen::Matrix4f transform_res_from_fpcs = fpcs_ia.getFinalTransformation ();
-  //for (int i = 0; i < 4; ++i)
-  //  for (int j = 0; j < 4; ++j)
-  //    EXPECT_NEAR (transform_res_from_fpcs (i,j), transform_from_fpcs[i][j], 0.5);
+  // check for correct coarse transformation matrix
+  Eigen::Matrix4f transform_res_from_fpcs = fpcs_ia.getFinalTransformation ();
+  for (int i = 0; i < 4; ++i)
+    for (int j = 0; j < 4; ++j)
+      EXPECT_NEAR (transform_res_from_fpcs (i,j), transform_from_fpcs[i][j], 0.25);
 }
 
 
index ec3c8229e495e21989de1d9159b4405a35cf9e77..84236a2dab0f9573da748b64d99b5e9fc2b30b04 100644 (file)
@@ -6,7 +6,7 @@ constexpr float delta = 1.f;
 constexpr int nr_samples = 100;
 
 const float transform_from_fpcs [4][4] = {
-  { -0.0019f, 0.8266f, -0.5628f, -0.0378f },
+  { -0.0019f, 0.8266f, -0.5628f, 0.0378f },
   { -0.9999f, -0.0094f, -0.0104f, 0.9997f },
   { -0.0139f, 0.5627f, 0.8265f, 0.0521f },
   { 0.f, 0.f, 0.f, 1.f }
index ed709afc7b09c950b13c920410f7f66b74078a0c..4caba0b41a4d0941a4477d6ab9faae18c0a9fbfa 100644 (file)
@@ -49,7 +49,7 @@ using namespace pcl;
 using namespace pcl::io;
 using namespace pcl::registration;
 
-PointCloud<PointXYZI> cloud_source, cloud_target;
+PointCloud<PointXYZ> cloud_source, cloud_target;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST (PCL, KFPCSInitialAlignment)
@@ -57,13 +57,13 @@ TEST (PCL, KFPCSInitialAlignment)
   const auto previous_verbosity_level = pcl::console::getVerbosityLevel();
   pcl::console::setVerbosityLevel(pcl::console::L_VERBOSE);
   // create shared pointers
-  PointCloud<PointXYZI>::Ptr cloud_source_ptr, cloud_target_ptr;
+  PointCloud<PointXYZ>::Ptr cloud_source_ptr, cloud_target_ptr;
   cloud_source_ptr = cloud_source.makeShared ();
   cloud_target_ptr = cloud_target.makeShared ();
 
   // initialize k-fpcs
-  PointCloud <PointXYZI> cloud_source_aligned;
-  KFPCSInitialAlignment <PointXYZI, PointXYZI> kfpcs_ia;
+  PointCloud <PointXYZ> cloud_source_aligned;
+  KFPCSInitialAlignment <PointXYZ, PointXYZ> kfpcs_ia;
   kfpcs_ia.setInputSource (cloud_source_ptr);
   kfpcs_ia.setInputTarget (cloud_target_ptr);
 
@@ -71,6 +71,7 @@ TEST (PCL, KFPCSInitialAlignment)
   kfpcs_ia.setApproxOverlap (approx_overlap);
   kfpcs_ia.setDelta (voxel_size, false);
   kfpcs_ia.setScoreThreshold (abort_score);
+  kfpcs_ia.setMaximumIterations (100);
 
   // repeat alignment 2 times to increase probability to ~99.99%
   constexpr float max_angle3d = 0.1745f, max_translation3d = 1.f;
@@ -107,19 +108,19 @@ main (int argc, char** argv)
 {
   if (argc < 3)
   {
-    std::cerr << "No test files given. Please download `bun0.pcd` and `bun4.pcd` pass their path to the test." << std::endl;
+    std::cerr << "No test files given. Please download `office1_keypoints.pcd` and `office2_keypoints.pcd` pass their path to the test." << std::endl;
     return (-1);
   }
 
   // Input
   if (loadPCDFile (argv[1], cloud_source) < 0)
   {
-    std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
+    std::cerr << "Failed to read test file. Please download `office1_keypoints.pcd` and pass its path to the test." << std::endl;
     return (-1);
   }
   if (loadPCDFile (argv[2], cloud_target) < 0)
   {
-    std::cerr << "Failed to read test file. Please download `bun4.pcd` and pass its path to the test." << std::endl;
+    std::cerr << "Failed to read test file. Please download `office2_keypoints.pcd` and pass its path to the test." << std::endl;
     return (-1);
   }
 
index 4b7e8905630b6e222365b586b5537a9a1c7442ba..349c7721c925b49846a56c3538de1a7c5a62cd98 100644 (file)
@@ -3,7 +3,7 @@
 constexpr int nr_threads = 1;
 constexpr float voxel_size = 0.1f;
 constexpr float approx_overlap = 0.9f;
-constexpr float abort_score = 0.0f;
+constexpr float abort_score = 0.4f;
 
 const float transformation_office1_office2 [4][4] = {
   { -0.6946f, -0.7194f, -0.0051f, -3.6352f },
index 0b2d33712aa72cb5f99410b3af2aaae817f72bc4..0eda177b8a245da1de033a746a5dca0feb0478f7 100644 (file)
@@ -155,30 +155,26 @@ TEST (PCL, findFeatureCorrespondences)
 
 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 // This test if the ICP algorithm can successfully find the transformation of a cloud that has been
-// moved 0.7 in x direction.
+// moved 0.2 in z direction.
 // It indirectly test the KDTree doesn't get an empty input cloud, see #3624
 // It is more or less a copy of https://github.com/PointCloudLibrary/pcl/blob/cc7fe363c6463a0abc617b1e17e94ab4bd4169ef/doc/tutorials/content/sources/iterative_closest_point/iterative_closest_point.cpp
 TEST(PCL, ICP_translated)
 {
-  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in(new pcl::PointCloud<pcl::PointXYZ>(5,1));
+  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in(new pcl::PointCloud<pcl::PointXYZ>);
   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_out(new pcl::PointCloud<pcl::PointXYZ>);
 
   // Fill in the CloudIn data
-  for (auto& point : *cloud_in)
-  {
-    point.x = 1024 * rand() / (RAND_MAX + 1.0f);
-    point.y = 1024 * rand() / (RAND_MAX + 1.0f);
-    point.z = 1024 * rand() / (RAND_MAX + 1.0f);
-  }
+  *cloud_in = cloud_source;
 
   *cloud_out = *cloud_in;
 
   for (auto& point : *cloud_out)
-    point.x += 0.7f;
+    point.z += 0.2f;
 
   pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> icp;
   icp.setInputSource(cloud_in);
   icp.setInputTarget(cloud_out);
+  icp.setMaximumIterations (50);
 
   pcl::PointCloud<pcl::PointXYZ> Final;
   icp.align(Final);
@@ -190,9 +186,12 @@ TEST(PCL, ICP_translated)
   EXPECT_LT(icp.getFitnessScore(), 1e-6);
 
   // Ensure that the translation found is within acceptable threshold.
-  EXPECT_NEAR(icp.getFinalTransformation()(0, 3), 0.7, 2e-3);
+  EXPECT_NEAR(icp.getFinalTransformation()(0, 0), 1.0, 2e-3);
+  EXPECT_NEAR(icp.getFinalTransformation()(1, 1), 1.0, 2e-3);
+  EXPECT_NEAR(icp.getFinalTransformation()(2, 2), 1.0, 2e-3);
+  EXPECT_NEAR(icp.getFinalTransformation()(0, 3), 0.0, 2e-3);
   EXPECT_NEAR(icp.getFinalTransformation()(1, 3), 0.0, 2e-3);
-  EXPECT_NEAR(icp.getFinalTransformation()(2, 3), 0.0, 2e-3);
+  EXPECT_NEAR(icp.getFinalTransformation()(2, 3), 0.2, 2e-3);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -900,7 +899,7 @@ main (int argc, char** argv)
   testing::InitGoogleTest (&argc, argv);
   return (RUN_ALL_TESTS ());
 
-  // Tranpose the cloud_model
+  // Transpose the cloud_model
   /*for (std::size_t i = 0; i < cloud_model.size (); ++i)
   {
   //  cloud_model[i].z += 1;
index 1aeebb78918bdd361e942bad2f1b8a9fe4414ab4..ab3fec261939620cbdb530eff8a63bd8997332c2 100644 (file)
@@ -401,7 +401,7 @@ TEST (PCL, TransformationEstimationSVD)
   // Check if the estimation with correspondences gives the same results
   Eigen::Matrix4f T_SVD_2;
   pcl::Correspondences corr; corr.reserve (source->size ());
-  for (std::size_t i=0; i<source->size (); ++i) corr.push_back (pcl::Correspondence (i, i, 0.f));
+  for (std::size_t i=0; i<source->size (); ++i) corr.emplace_back(i, i, 0.f);
   trans_est_svd.estimateRigidTransformation(*source, *target, corr, T_SVD_2);
 
   const Eigen::Quaternionf   R_SVD_2 (T_SVD_2.topLeftCorner  <3, 3> ());
@@ -444,7 +444,7 @@ TEST (PCL, TransformationEstimationDualQuaternion)
   // Check if the estimation with correspondences gives the same results
   Eigen::Matrix4f T_DQ_2;
   pcl::Correspondences corr; corr.reserve (source->size ());
-  for (std::size_t i=0; i<source->size (); ++i) corr.push_back (pcl::Correspondence (i, i, 0.f));
+  for (std::size_t i=0; i<source->size (); ++i) corr.emplace_back(i, i, 0.f);
   trans_est_dual_quaternion.estimateRigidTransformation(*source, *target, corr, T_DQ_2);
 
   const Eigen::Quaternionf   R_DQ_2 (T_DQ_2.topLeftCorner  <3, 3> ());
@@ -540,7 +540,7 @@ TEST (PCL, TransformationEstimationLM)
   pcl::Correspondences corr;
   corr.reserve (source->size ());
   for (std::size_t i = 0; i < source->size (); ++i)
-    corr.push_back (pcl::Correspondence (i, i, 0.f));
+    corr.emplace_back(i, i, 0.f);
   trans_est_lm_float.estimateRigidTransformation (*source, *target, corr, T_LM_2_float);
 
   const Eigen::Quaternionf   R_LM_2_float (T_LM_2_float.topLeftCorner  <3, 3> ());
@@ -578,7 +578,7 @@ TEST (PCL, TransformationEstimationLM)
   corr.clear ();
   corr.reserve (source->size ());
   for (std::size_t i = 0; i < source->size (); ++i)
-    corr.push_back (pcl::Correspondence (i, i, 0.f));
+    corr.emplace_back(i, i, 0.f);
   trans_est_lm_double.estimateRigidTransformation (*source, *target, corr, T_LM_2_double);
 
   const Eigen::Quaterniond   R_LM_2_double (T_LM_2_double.topLeftCorner  <3, 3> ());
@@ -733,7 +733,7 @@ main (int argc, char** argv)
   testing::InitGoogleTest (&argc, argv);
   return (RUN_ALL_TESTS ());
 
-  // Tranpose the cloud_model
+  // Transpose the cloud_model
   /*for (std::size_t i = 0; i < cloud_model.size (); ++i)
   {
   //  cloud_model[i].z += 1;
index 7656f9bf4aa1335225266b32da3204d65e83c436..fbf004e4a79f1d44e0caa92be3059f18e24d3176 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library sample_consensus module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS sample_consensus)
 set(OPT_DEPS io)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index dbdf375aa46d6262f5e15105da988eab7634e0fd..75606bdcf17ffc85745c93eee6430777aeb2eee6 100644 (file)
  *
  */
 
-#include <pcl/test/gtest.h>
-#include <pcl/pcl_tests.h> // for EXPECT_XYZ_NEAR
-
 #include <pcl/sample_consensus/ransac.h>
-#include <pcl/sample_consensus/sac_model_sphere.h>
-#include <pcl/sample_consensus/sac_model_cone.h>
-#include <pcl/sample_consensus/sac_model_cylinder.h>
 #include <pcl/sample_consensus/sac_model_circle.h>
 #include <pcl/sample_consensus/sac_model_circle3d.h>
-#include <pcl/sample_consensus/sac_model_normal_sphere.h>
+#include <pcl/sample_consensus/sac_model_cone.h>
+#include <pcl/sample_consensus/sac_model_cylinder.h>
 #include <pcl/sample_consensus/sac_model_ellipse3d.h>
+#include <pcl/sample_consensus/sac_model_normal_sphere.h>
+#include <pcl/sample_consensus/sac_model_sphere.h>
+#include <pcl/sample_consensus/sac_model_torus.h>
+#include <pcl/test/gtest.h>
+#include <pcl/pcl_tests.h> // for EXPECT_XYZ_NEAR
 
 using namespace pcl;
 
@@ -54,526 +54,550 @@ using SampleConsensusModelSpherePtr = SampleConsensusModelSphere<PointXYZ>::Ptr;
 using SampleConsensusModelConePtr = SampleConsensusModelCone<PointXYZ, Normal>::Ptr;
 using SampleConsensusModelCircle2DPtr = SampleConsensusModelCircle2D<PointXYZ>::Ptr;
 using SampleConsensusModelCircle3DPtr = SampleConsensusModelCircle3D<PointXYZ>::Ptr;
-using SampleConsensusModelCylinderPtr = SampleConsensusModelCylinder<PointXYZ, Normal>::Ptr;
-using SampleConsensusModelNormalSpherePtr = SampleConsensusModelNormalSphere<PointXYZ, Normal>::Ptr;
+using SampleConsensusModelCylinderPtr =
+    SampleConsensusModelCylinder<PointXYZ, Normal>::Ptr;
+using SampleConsensusModelNormalSpherePtr =
+    SampleConsensusModelNormalSphere<PointXYZ, Normal>::Ptr;
 using SampleConsensusModelEllipse3DPtr = SampleConsensusModelEllipse3D<PointXYZ>::Ptr;
+using SampleConsensusModelTorusPtr = SampleConsensusModelTorus<PointXYZ,Normal>::Ptr;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-TEST (SampleConsensusModelSphere, RANSAC)
+TEST(SampleConsensusModelSphere, RANSAC)
 {
-  srand (0);
+  srand(0);
 
   // Use a custom point cloud for these tests until we need something better
   PointCloud<PointXYZ> cloud;
-  cloud.resize (10);
-  cloud[0].getVector3fMap () << 1.7068f, 1.0684f, 2.2147f;
-  cloud[1].getVector3fMap () << 2.4708f, 2.3081f, 1.1736f;
-  cloud[2].getVector3fMap () << 2.7609f, 1.9095f, 1.3574f;
-  cloud[3].getVector3fMap () << 2.8016f, 1.6704f, 1.5009f;
-  cloud[4].getVector3fMap () << 1.8517f, 2.0276f, 1.0112f;
-  cloud[5].getVector3fMap () << 1.8726f, 1.3539f, 2.7523f;
-  cloud[6].getVector3fMap () << 2.5179f, 2.3218f, 1.2074f;
-  cloud[7].getVector3fMap () << 2.4026f, 2.5114f, 2.7588f;
-  cloud[8].getVector3fMap () << 2.6999f, 2.5606f, 1.5571f;
-  cloud[9].getVector3fMap () << 0.0000f, 0.0000f, 0.0000f;
+  cloud.resize(10);
+  cloud[0].getVector3fMap() << 1.7068f, 1.0684f, 2.2147f;
+  cloud[1].getVector3fMap() << 2.4708f, 2.3081f, 1.1736f;
+  cloud[2].getVector3fMap() << 2.7609f, 1.9095f, 1.3574f;
+  cloud[3].getVector3fMap() << 2.8016f, 1.6704f, 1.5009f;
+  cloud[4].getVector3fMap() << 1.8517f, 2.0276f, 1.0112f;
+  cloud[5].getVector3fMap() << 1.8726f, 1.3539f, 2.7523f;
+  cloud[6].getVector3fMap() << 2.5179f, 2.3218f, 1.2074f;
+  cloud[7].getVector3fMap() << 2.4026f, 2.5114f, 2.7588f;
+  cloud[8].getVector3fMap() << 2.6999f, 2.5606f, 1.5571f;
+  cloud[9].getVector3fMap() << 0.0000f, 0.0000f, 0.0000f;
 
   // Create a shared sphere model pointer directly
-  SampleConsensusModelSpherePtr model (new SampleConsensusModelSphere<PointXYZ> (cloud.makeShared ()));
+  SampleConsensusModelSpherePtr model(
+      new SampleConsensusModelSphere<PointXYZ>(cloud.makeShared()));
 
   // Create the RANSAC object
-  RandomSampleConsensus<PointXYZ> sac (model, 0.03);
+  RandomSampleConsensus<PointXYZ> sac(model, 0.03);
 
   // Algorithm tests
-  bool result = sac.computeModel ();
-  ASSERT_TRUE (result);
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
 
   pcl::Indices sample;
-  sac.getModel (sample);
-  EXPECT_EQ (4, sample.size ());
+  sac.getModel(sample);
+  EXPECT_EQ(4, sample.size());
 
   pcl::Indices inliers;
-  sac.getInliers (inliers);
-  EXPECT_EQ (9, inliers.size ());
+  sac.getInliers(inliers);
+  EXPECT_EQ(9, inliers.size());
 
   Eigen::VectorXf coeff;
-  sac.getModelCoefficients (coeff);
-  EXPECT_EQ (4, coeff.size ());
-  EXPECT_NEAR (2, coeff[0] / coeff[3], 1e-2);
-  EXPECT_NEAR (2, coeff[1] / coeff[3], 1e-2);
-  EXPECT_NEAR (2, coeff[2] / coeff[3], 1e-2);
+  sac.getModelCoefficients(coeff);
+  EXPECT_EQ(4, coeff.size());
+  EXPECT_NEAR(2, coeff[0] / coeff[3], 1e-2);
+  EXPECT_NEAR(2, coeff[1] / coeff[3], 1e-2);
+  EXPECT_NEAR(2, coeff[2] / coeff[3], 1e-2);
 
   Eigen::VectorXf coeff_refined;
-  model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
-  EXPECT_EQ (4, coeff_refined.size ());
-  EXPECT_NEAR (2, coeff_refined[0] / coeff_refined[3], 1e-2);
-  EXPECT_NEAR (2, coeff_refined[1] / coeff_refined[3], 1e-2);
-  EXPECT_NEAR (2, coeff_refined[2] / coeff_refined[3], 1e-2);
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(4, coeff_refined.size());
+  EXPECT_NEAR(2, coeff_refined[0] / coeff_refined[3], 1e-2);
+  EXPECT_NEAR(2, coeff_refined[1] / coeff_refined[3], 1e-2);
+  EXPECT_NEAR(2, coeff_refined[2] / coeff_refined[3], 1e-2);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-class SampleConsensusModelSphereTest : private SampleConsensusModelSphere<PointT>
-{
-  public:
-    using SampleConsensusModelSphere<PointT>::SampleConsensusModelSphere;
-    using SampleConsensusModelSphere<PointT>::countWithinDistanceStandard;
-#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__)
-    using SampleConsensusModelSphere<PointT>::countWithinDistanceSSE;
+class SampleConsensusModelSphereTest : private SampleConsensusModelSphere<PointT> {
+public:
+  using SampleConsensusModelSphere<PointT>::SampleConsensusModelSphere;
+  using SampleConsensusModelSphere<PointT>::countWithinDistanceStandard;
+#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__)
+  using SampleConsensusModelSphere<PointT>::countWithinDistanceSSE;
 #endif
-#if defined (__AVX__) && defined (__AVX2__)
-    using SampleConsensusModelSphere<PointT>::countWithinDistanceAVX;
+#if defined(__AVX__) && defined(__AVX2__)
+  using SampleConsensusModelSphere<PointT>::countWithinDistanceAVX;
 #endif
 };
 
-TEST (SampleConsensusModelSphere, SIMD_countWithinDistance) // Test if all countWithinDistance implementations return the same value
+TEST(SampleConsensusModelSphere,
+     SIMD_countWithinDistance) // Test if all countWithinDistance implementations return
+                               // the same value
 {
-  const auto seed = static_cast<unsigned> (std::time (nullptr));
-  srand (seed);
-  for (size_t i=0; i<100; i++) // Run as often as you like
+  const auto seed = static_cast<unsigned>(std::time(nullptr));
+  srand(seed);
+  for (size_t i = 0; i < 100; i++) // Run as often as you like
   {
     // Generate a cloud with 1000 random points
     PointCloud<PointXYZ> cloud;
     pcl::Indices indices;
-    cloud.resize (1000);
-    for (std::size_t idx = 0; idx < cloud.size (); ++idx)
-    {
-      cloud[idx].x = 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0;
-      cloud[idx].y = 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0;
-      cloud[idx].z = 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0;
-      if (rand () % 3 != 0)
-      {
-        indices.push_back (static_cast<int> (idx));
+    cloud.resize(1000);
+    for (std::size_t idx = 0; idx < cloud.size(); ++idx) {
+      cloud[idx].x = 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0;
+      cloud[idx].y = 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0;
+      cloud[idx].z = 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0;
+      if (rand() % 3 != 0) {
+        indices.push_back(static_cast<int>(idx));
       }
     }
-    SampleConsensusModelSphereTest<PointXYZ> model (cloud.makeShared (), indices, true);
+    SampleConsensusModelSphereTest<PointXYZ> model(cloud.makeShared(), indices, true);
 
     // Generate random sphere model parameters
     Eigen::VectorXf model_coefficients(4);
-    model_coefficients << 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0,
-                          2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0,
-                          2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0,
-                          0.15 * static_cast<float> (rand ()) / RAND_MAX; // center and radius
+    model_coefficients << 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0,
+        2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0,
+        2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0,
+        0.15 * static_cast<float>(rand()) / RAND_MAX; // center and radius
 
-    const double threshold = 0.15 * static_cast<double> (rand ()) / RAND_MAX; // threshold in [0; 0.1]
+    const double threshold =
+        0.15 * static_cast<double>(rand()) / RAND_MAX; // threshold in [0; 0.1]
 
     // The number of inliers is usually somewhere between 0 and 10
-    const auto res_standard = model.countWithinDistanceStandard (model_coefficients, threshold); // Standard
-    PCL_DEBUG ("seed=%lu, i=%lu, model=(%f, %f, %f, %f), threshold=%f, res_standard=%lu\n", seed, i,
-               model_coefficients(0), model_coefficients(1), model_coefficients(2), model_coefficients(3), threshold, res_standard);
-#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__)
-    const auto res_sse      = model.countWithinDistanceSSE (model_coefficients, threshold); // SSE
-    ASSERT_EQ (res_standard, res_sse);
+    const auto res_standard =
+        model.countWithinDistanceStandard(model_coefficients, threshold); // Standard
+    PCL_DEBUG(
+        "seed=%lu, i=%lu, model=(%f, %f, %f, %f), threshold=%f, res_standard=%lu\n",
+        seed,
+        i,
+        model_coefficients(0),
+        model_coefficients(1),
+        model_coefficients(2),
+        model_coefficients(3),
+        threshold,
+        res_standard);
+#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__)
+    const auto res_sse =
+        model.countWithinDistanceSSE(model_coefficients, threshold); // SSE
+    ASSERT_EQ(res_standard, res_sse);
 #endif
-#if defined (__AVX__) && defined (__AVX2__)
-    const auto res_avx      = model.countWithinDistanceAVX (model_coefficients, threshold); // AVX
-    ASSERT_EQ (res_standard, res_avx);
+#if defined(__AVX__) && defined(__AVX2__)
+    const auto res_avx =
+        model.countWithinDistanceAVX(model_coefficients, threshold); // AVX
+    ASSERT_EQ(res_standard, res_avx);
 #endif
   }
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-TEST (SampleConsensusModelNormalSphere, RANSAC)
+TEST(SampleConsensusModelNormalSphere, RANSAC)
 {
-  srand (0);
+  srand(0);
 
   // Use a custom point cloud for these tests until we need something better
   PointCloud<PointXYZ> cloud;
   PointCloud<Normal> normals;
-  cloud.resize (27); normals.resize (27);
-  cloud[ 0].getVector3fMap () << -0.014695f,  0.009549f, 0.954775f;
-  cloud[ 1].getVector3fMap () <<  0.014695f,  0.009549f, 0.954775f;
-  cloud[ 2].getVector3fMap () << -0.014695f,  0.040451f, 0.954775f;
-  cloud[ 3].getVector3fMap () <<  0.014695f,  0.040451f, 0.954775f;
-  cloud[ 4].getVector3fMap () << -0.009082f, -0.015451f, 0.972049f;
-  cloud[ 5].getVector3fMap () <<  0.009082f, -0.015451f, 0.972049f;
-  cloud[ 6].getVector3fMap () << -0.038471f,  0.009549f, 0.972049f;
-  cloud[ 7].getVector3fMap () <<  0.038471f,  0.009549f, 0.972049f;
-  cloud[ 8].getVector3fMap () << -0.038471f,  0.040451f, 0.972049f;
-  cloud[ 9].getVector3fMap () <<  0.038471f,  0.040451f, 0.972049f;
-  cloud[10].getVector3fMap () << -0.009082f,  0.065451f, 0.972049f;
-  cloud[11].getVector3fMap () <<  0.009082f,  0.065451f, 0.972049f;
-  cloud[12].getVector3fMap () << -0.023776f, -0.015451f, 0.982725f;
-  cloud[13].getVector3fMap () <<  0.023776f, -0.015451f, 0.982725f;
-  cloud[14].getVector3fMap () << -0.023776f,  0.065451f, 0.982725f;
-  cloud[15].getVector3fMap () <<  0.023776f,  0.065451f, 0.982725f;
-  cloud[16].getVector3fMap () << -0.000000f, -0.025000f, 1.000000f;
-  cloud[17].getVector3fMap () <<  0.000000f, -0.025000f, 1.000000f;
-  cloud[18].getVector3fMap () << -0.029389f, -0.015451f, 1.000000f;
-  cloud[19].getVector3fMap () <<  0.029389f, -0.015451f, 1.000000f;
-  cloud[20].getVector3fMap () << -0.047553f,  0.009549f, 1.000000f;
-  cloud[21].getVector3fMap () <<  0.047553f,  0.009549f, 1.000000f;
-  cloud[22].getVector3fMap () << -0.047553f,  0.040451f, 1.000000f;
-  cloud[23].getVector3fMap () <<  0.047553f,  0.040451f, 1.000000f;
-  cloud[24].getVector3fMap () << -0.029389f,  0.065451f, 1.000000f;
-  cloud[25].getVector3fMap () <<  0.029389f,  0.065451f, 1.000000f;
-  cloud[26].getVector3fMap () <<  0.000000f,  0.075000f, 1.000000f;
-
-  normals[ 0].getNormalVector3fMap () << -0.293893f, -0.309017f, -0.904509f;
-  normals[ 1].getNormalVector3fMap () <<  0.293893f, -0.309017f, -0.904508f;
-  normals[ 2].getNormalVector3fMap () << -0.293893f,  0.309017f, -0.904509f;
-  normals[ 3].getNormalVector3fMap () <<  0.293893f,  0.309017f, -0.904508f;
-  normals[ 4].getNormalVector3fMap () << -0.181636f, -0.809017f, -0.559017f;
-  normals[ 5].getNormalVector3fMap () <<  0.181636f, -0.809017f, -0.559017f;
-  normals[ 6].getNormalVector3fMap () << -0.769421f, -0.309017f, -0.559017f;
-  normals[ 7].getNormalVector3fMap () <<  0.769421f, -0.309017f, -0.559017f;
-  normals[ 8].getNormalVector3fMap () << -0.769421f,  0.309017f, -0.559017f;
-  normals[ 9].getNormalVector3fMap () <<  0.769421f,  0.309017f, -0.559017f;
-  normals[10].getNormalVector3fMap () << -0.181636f,  0.809017f, -0.559017f;
-  normals[11].getNormalVector3fMap () <<  0.181636f,  0.809017f, -0.559017f;
-  normals[12].getNormalVector3fMap () << -0.475528f, -0.809017f, -0.345491f;
-  normals[13].getNormalVector3fMap () <<  0.475528f, -0.809017f, -0.345491f;
-  normals[14].getNormalVector3fMap () << -0.475528f,  0.809017f, -0.345491f;
-  normals[15].getNormalVector3fMap () <<  0.475528f,  0.809017f, -0.345491f;
-  normals[16].getNormalVector3fMap () << -0.000000f, -1.000000f,  0.000000f;
-  normals[17].getNormalVector3fMap () <<  0.000000f, -1.000000f,  0.000000f;
-  normals[18].getNormalVector3fMap () << -0.587785f, -0.809017f,  0.000000f;
-  normals[19].getNormalVector3fMap () <<  0.587785f, -0.809017f,  0.000000f;
-  normals[20].getNormalVector3fMap () << -0.951057f, -0.309017f,  0.000000f;
-  normals[21].getNormalVector3fMap () <<  0.951057f, -0.309017f,  0.000000f;
-  normals[22].getNormalVector3fMap () << -0.951057f,  0.309017f,  0.000000f;
-  normals[23].getNormalVector3fMap () <<  0.951057f,  0.309017f,  0.000000f;
-  normals[24].getNormalVector3fMap () << -0.587785f,  0.809017f,  0.000000f;
-  normals[25].getNormalVector3fMap () <<  0.587785f,  0.809017f,  0.000000f;
-  normals[26].getNormalVector3fMap () <<  0.000000f,  1.000000f,  0.000000f;
+  cloud.resize(27);
+  normals.resize(27);
+  cloud[0].getVector3fMap() << -0.014695f, 0.009549f, 0.954775f;
+  cloud[1].getVector3fMap() << 0.014695f, 0.009549f, 0.954775f;
+  cloud[2].getVector3fMap() << -0.014695f, 0.040451f, 0.954775f;
+  cloud[3].getVector3fMap() << 0.014695f, 0.040451f, 0.954775f;
+  cloud[4].getVector3fMap() << -0.009082f, -0.015451f, 0.972049f;
+  cloud[5].getVector3fMap() << 0.009082f, -0.015451f, 0.972049f;
+  cloud[6].getVector3fMap() << -0.038471f, 0.009549f, 0.972049f;
+  cloud[7].getVector3fMap() << 0.038471f, 0.009549f, 0.972049f;
+  cloud[8].getVector3fMap() << -0.038471f, 0.040451f, 0.972049f;
+  cloud[9].getVector3fMap() << 0.038471f, 0.040451f, 0.972049f;
+  cloud[10].getVector3fMap() << -0.009082f, 0.065451f, 0.972049f;
+  cloud[11].getVector3fMap() << 0.009082f, 0.065451f, 0.972049f;
+  cloud[12].getVector3fMap() << -0.023776f, -0.015451f, 0.982725f;
+  cloud[13].getVector3fMap() << 0.023776f, -0.015451f, 0.982725f;
+  cloud[14].getVector3fMap() << -0.023776f, 0.065451f, 0.982725f;
+  cloud[15].getVector3fMap() << 0.023776f, 0.065451f, 0.982725f;
+  cloud[16].getVector3fMap() << -0.000000f, -0.025000f, 1.000000f;
+  cloud[17].getVector3fMap() << 0.000000f, -0.025000f, 1.000000f;
+  cloud[18].getVector3fMap() << -0.029389f, -0.015451f, 1.000000f;
+  cloud[19].getVector3fMap() << 0.029389f, -0.015451f, 1.000000f;
+  cloud[20].getVector3fMap() << -0.047553f, 0.009549f, 1.000000f;
+  cloud[21].getVector3fMap() << 0.047553f, 0.009549f, 1.000000f;
+  cloud[22].getVector3fMap() << -0.047553f, 0.040451f, 1.000000f;
+  cloud[23].getVector3fMap() << 0.047553f, 0.040451f, 1.000000f;
+  cloud[24].getVector3fMap() << -0.029389f, 0.065451f, 1.000000f;
+  cloud[25].getVector3fMap() << 0.029389f, 0.065451f, 1.000000f;
+  cloud[26].getVector3fMap() << 0.000000f, 0.075000f, 1.000000f;
+
+  normals[0].getNormalVector3fMap() << -0.293893f, -0.309017f, -0.904509f;
+  normals[1].getNormalVector3fMap() << 0.293893f, -0.309017f, -0.904508f;
+  normals[2].getNormalVector3fMap() << -0.293893f, 0.309017f, -0.904509f;
+  normals[3].getNormalVector3fMap() << 0.293893f, 0.309017f, -0.904508f;
+  normals[4].getNormalVector3fMap() << -0.181636f, -0.809017f, -0.559017f;
+  normals[5].getNormalVector3fMap() << 0.181636f, -0.809017f, -0.559017f;
+  normals[6].getNormalVector3fMap() << -0.769421f, -0.309017f, -0.559017f;
+  normals[7].getNormalVector3fMap() << 0.769421f, -0.309017f, -0.559017f;
+  normals[8].getNormalVector3fMap() << -0.769421f, 0.309017f, -0.559017f;
+  normals[9].getNormalVector3fMap() << 0.769421f, 0.309017f, -0.559017f;
+  normals[10].getNormalVector3fMap() << -0.181636f, 0.809017f, -0.559017f;
+  normals[11].getNormalVector3fMap() << 0.181636f, 0.809017f, -0.559017f;
+  normals[12].getNormalVector3fMap() << -0.475528f, -0.809017f, -0.345491f;
+  normals[13].getNormalVector3fMap() << 0.475528f, -0.809017f, -0.345491f;
+  normals[14].getNormalVector3fMap() << -0.475528f, 0.809017f, -0.345491f;
+  normals[15].getNormalVector3fMap() << 0.475528f, 0.809017f, -0.345491f;
+  normals[16].getNormalVector3fMap() << -0.000000f, -1.000000f, 0.000000f;
+  normals[17].getNormalVector3fMap() << 0.000000f, -1.000000f, 0.000000f;
+  normals[18].getNormalVector3fMap() << -0.587785f, -0.809017f, 0.000000f;
+  normals[19].getNormalVector3fMap() << 0.587785f, -0.809017f, 0.000000f;
+  normals[20].getNormalVector3fMap() << -0.951057f, -0.309017f, 0.000000f;
+  normals[21].getNormalVector3fMap() << 0.951057f, -0.309017f, 0.000000f;
+  normals[22].getNormalVector3fMap() << -0.951057f, 0.309017f, 0.000000f;
+  normals[23].getNormalVector3fMap() << 0.951057f, 0.309017f, 0.000000f;
+  normals[24].getNormalVector3fMap() << -0.587785f, 0.809017f, 0.000000f;
+  normals[25].getNormalVector3fMap() << 0.587785f, 0.809017f, 0.000000f;
+  normals[26].getNormalVector3fMap() << 0.000000f, 1.000000f, 0.000000f;
 
   // Create a shared sphere model pointer directly
-  SampleConsensusModelNormalSpherePtr model (new SampleConsensusModelNormalSphere<PointXYZ, Normal> (cloud.makeShared ()));
-  model->setInputNormals (normals.makeShared ());
+  SampleConsensusModelNormalSpherePtr model(
+      new SampleConsensusModelNormalSphere<PointXYZ, Normal>(cloud.makeShared()));
+  model->setInputNormals(normals.makeShared());
 
   // Create the RANSAC object
-  RandomSampleConsensus<PointXYZ> sac (model, 0.03);
+  RandomSampleConsensus<PointXYZ> sac(model, 0.03);
 
   // Algorithm tests
-  bool result = sac.computeModel ();
-  ASSERT_TRUE (result);
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
 
   pcl::Indices sample;
-  sac.getModel (sample);
-  EXPECT_EQ (4, sample.size ());
+  sac.getModel(sample);
+  EXPECT_EQ(4, sample.size());
 
   pcl::Indices inliers;
-  sac.getInliers (inliers);
-  EXPECT_EQ (27, inliers.size ());
+  sac.getInliers(inliers);
+  EXPECT_EQ(27, inliers.size());
 
   Eigen::VectorXf coeff;
-  sac.getModelCoefficients (coeff);
-  EXPECT_EQ (4, coeff.size ());
-  EXPECT_NEAR (0.000, coeff[0], 1e-2);
-  EXPECT_NEAR (0.025, coeff[1], 1e-2);
-  EXPECT_NEAR (1.000, coeff[2], 1e-2);
-  EXPECT_NEAR (0.050, coeff[3], 1e-2);
+  sac.getModelCoefficients(coeff);
+  EXPECT_EQ(4, coeff.size());
+  EXPECT_NEAR(0.000, coeff[0], 1e-2);
+  EXPECT_NEAR(0.025, coeff[1], 1e-2);
+  EXPECT_NEAR(1.000, coeff[2], 1e-2);
+  EXPECT_NEAR(0.050, coeff[3], 1e-2);
 
   Eigen::VectorXf coeff_refined;
-  model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
-  EXPECT_EQ (4, coeff_refined.size ());
-  EXPECT_NEAR (0.000, coeff_refined[0], 1e-2);
-  EXPECT_NEAR (0.025, coeff_refined[1], 1e-2);
-  EXPECT_NEAR (1.000, coeff_refined[2], 1e-2);
-  EXPECT_NEAR (0.050, coeff_refined[3], 1e-2);
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(4, coeff_refined.size());
+  EXPECT_NEAR(0.000, coeff_refined[0], 1e-2);
+  EXPECT_NEAR(0.025, coeff_refined[1], 1e-2);
+  EXPECT_NEAR(1.000, coeff_refined[2], 1e-2);
+  EXPECT_NEAR(0.050, coeff_refined[3], 1e-2);
 }
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-TEST (SampleConsensusModelCone, RANSAC)
+TEST(SampleConsensusModelCone, RANSAC)
 {
-  srand (0);
+  srand(0);
 
   // Use a custom point cloud for these tests until we need something better
   PointCloud<PointXYZ> cloud;
   PointCloud<Normal> normals;
-  cloud.resize (31); normals.resize (31);
-
-  cloud[ 0].getVector3fMap () << -0.011247f, 0.200000f, 0.965384f;
-  cloud[ 1].getVector3fMap () <<  0.000000f, 0.200000f, 0.963603f;
-  cloud[ 2].getVector3fMap () <<  0.011247f, 0.200000f, 0.965384f;
-  cloud[ 3].getVector3fMap () << -0.016045f, 0.175000f, 0.977916f;
-  cloud[ 4].getVector3fMap () << -0.008435f, 0.175000f, 0.974038f;
-  cloud[ 5].getVector3fMap () <<  0.004218f, 0.175000f, 0.973370f;
-  cloud[ 6].getVector3fMap () <<  0.016045f, 0.175000f, 0.977916f;
-  cloud[ 7].getVector3fMap () << -0.025420f, 0.200000f, 0.974580f;
-  cloud[ 8].getVector3fMap () <<  0.025420f, 0.200000f, 0.974580f;
-  cloud[ 9].getVector3fMap () << -0.012710f, 0.150000f, 0.987290f;
-  cloud[10].getVector3fMap () << -0.005624f, 0.150000f, 0.982692f;
-  cloud[11].getVector3fMap () <<  0.002812f, 0.150000f, 0.982247f;
-  cloud[12].getVector3fMap () <<  0.012710f, 0.150000f, 0.987290f;
-  cloud[13].getVector3fMap () << -0.022084f, 0.175000f, 0.983955f;
-  cloud[14].getVector3fMap () <<  0.022084f, 0.175000f, 0.983955f;
-  cloud[15].getVector3fMap () << -0.034616f, 0.200000f, 0.988753f;
-  cloud[16].getVector3fMap () <<  0.034616f, 0.200000f, 0.988753f;
-  cloud[17].getVector3fMap () << -0.006044f, 0.125000f, 0.993956f;
-  cloud[18].getVector3fMap () <<  0.004835f, 0.125000f, 0.993345f;
-  cloud[19].getVector3fMap () << -0.017308f, 0.150000f, 0.994376f;
-  cloud[20].getVector3fMap () <<  0.017308f, 0.150000f, 0.994376f;
-  cloud[21].getVector3fMap () << -0.025962f, 0.175000f, 0.991565f;
-  cloud[22].getVector3fMap () <<  0.025962f, 0.175000f, 0.991565f;
-  cloud[23].getVector3fMap () << -0.009099f, 0.125000f, 1.000000f;
-  cloud[24].getVector3fMap () <<  0.009099f, 0.125000f, 1.000000f;
-  cloud[25].getVector3fMap () << -0.018199f, 0.150000f, 1.000000f;
-  cloud[26].getVector3fMap () <<  0.018199f, 0.150000f, 1.000000f;
-  cloud[27].getVector3fMap () << -0.027298f, 0.175000f, 1.000000f;
-  cloud[28].getVector3fMap () <<  0.027298f, 0.175000f, 1.000000f;
-  cloud[29].getVector3fMap () << -0.036397f, 0.200000f, 1.000000f;
-  cloud[30].getVector3fMap () <<  0.036397f, 0.200000f, 1.000000f;
-
-  normals[ 0].getNormalVector3fMap () << -0.290381f, -0.342020f, -0.893701f;
-  normals[ 1].getNormalVector3fMap () <<  0.000000f, -0.342020f, -0.939693f;
-  normals[ 2].getNormalVector3fMap () <<  0.290381f, -0.342020f, -0.893701f;
-  normals[ 3].getNormalVector3fMap () << -0.552338f, -0.342020f, -0.760227f;
-  normals[ 4].getNormalVector3fMap () << -0.290381f, -0.342020f, -0.893701f;
-  normals[ 5].getNormalVector3fMap () <<  0.145191f, -0.342020f, -0.916697f;
-  normals[ 6].getNormalVector3fMap () <<  0.552337f, -0.342020f, -0.760227f;
-  normals[ 7].getNormalVector3fMap () << -0.656282f, -0.342020f, -0.656283f;
-  normals[ 8].getNormalVector3fMap () <<  0.656282f, -0.342020f, -0.656283f;
-  normals[ 9].getNormalVector3fMap () << -0.656283f, -0.342020f, -0.656282f;
-  normals[10].getNormalVector3fMap () << -0.290381f, -0.342020f, -0.893701f;
-  normals[11].getNormalVector3fMap () <<  0.145191f, -0.342020f, -0.916697f;
-  normals[12].getNormalVector3fMap () <<  0.656282f, -0.342020f, -0.656282f;
-  normals[13].getNormalVector3fMap () << -0.760228f, -0.342020f, -0.552337f;
-  normals[14].getNormalVector3fMap () <<  0.760228f, -0.342020f, -0.552337f;
-  normals[15].getNormalVector3fMap () << -0.893701f, -0.342020f, -0.290380f;
-  normals[16].getNormalVector3fMap () <<  0.893701f, -0.342020f, -0.290380f;
-  normals[17].getNormalVector3fMap () << -0.624162f, -0.342020f, -0.624162f;
-  normals[18].getNormalVector3fMap () <<  0.499329f, -0.342020f, -0.687268f;
-  normals[19].getNormalVector3fMap () << -0.893701f, -0.342020f, -0.290380f;
-  normals[20].getNormalVector3fMap () <<  0.893701f, -0.342020f, -0.290380f;
-  normals[21].getNormalVector3fMap () << -0.893701f, -0.342020f, -0.290381f;
-  normals[22].getNormalVector3fMap () <<  0.893701f, -0.342020f, -0.290381f;
-  normals[23].getNormalVector3fMap () << -0.939693f, -0.342020f,  0.000000f;
-  normals[24].getNormalVector3fMap () <<  0.939693f, -0.342020f,  0.000000f;
-  normals[25].getNormalVector3fMap () << -0.939693f, -0.342020f,  0.000000f;
-  normals[26].getNormalVector3fMap () <<  0.939693f, -0.342020f,  0.000000f;
-  normals[27].getNormalVector3fMap () << -0.939693f, -0.342020f,  0.000000f;
-  normals[28].getNormalVector3fMap () <<  0.939693f, -0.342020f,  0.000000f;
-  normals[29].getNormalVector3fMap () << -0.939693f, -0.342020f,  0.000000f;
-  normals[30].getNormalVector3fMap () <<  0.939693f, -0.342020f,  0.000000f;
+  cloud.resize(31);
+  normals.resize(31);
+
+  cloud[0].getVector3fMap() << -0.011247f, 0.200000f, 0.965384f;
+  cloud[1].getVector3fMap() << 0.000000f, 0.200000f, 0.963603f;
+  cloud[2].getVector3fMap() << 0.011247f, 0.200000f, 0.965384f;
+  cloud[3].getVector3fMap() << -0.016045f, 0.175000f, 0.977916f;
+  cloud[4].getVector3fMap() << -0.008435f, 0.175000f, 0.974038f;
+  cloud[5].getVector3fMap() << 0.004218f, 0.175000f, 0.973370f;
+  cloud[6].getVector3fMap() << 0.016045f, 0.175000f, 0.977916f;
+  cloud[7].getVector3fMap() << -0.025420f, 0.200000f, 0.974580f;
+  cloud[8].getVector3fMap() << 0.025420f, 0.200000f, 0.974580f;
+  cloud[9].getVector3fMap() << -0.012710f, 0.150000f, 0.987290f;
+  cloud[10].getVector3fMap() << -0.005624f, 0.150000f, 0.982692f;
+  cloud[11].getVector3fMap() << 0.002812f, 0.150000f, 0.982247f;
+  cloud[12].getVector3fMap() << 0.012710f, 0.150000f, 0.987290f;
+  cloud[13].getVector3fMap() << -0.022084f, 0.175000f, 0.983955f;
+  cloud[14].getVector3fMap() << 0.022084f, 0.175000f, 0.983955f;
+  cloud[15].getVector3fMap() << -0.034616f, 0.200000f, 0.988753f;
+  cloud[16].getVector3fMap() << 0.034616f, 0.200000f, 0.988753f;
+  cloud[17].getVector3fMap() << -0.006044f, 0.125000f, 0.993956f;
+  cloud[18].getVector3fMap() << 0.004835f, 0.125000f, 0.993345f;
+  cloud[19].getVector3fMap() << -0.017308f, 0.150000f, 0.994376f;
+  cloud[20].getVector3fMap() << 0.017308f, 0.150000f, 0.994376f;
+  cloud[21].getVector3fMap() << -0.025962f, 0.175000f, 0.991565f;
+  cloud[22].getVector3fMap() << 0.025962f, 0.175000f, 0.991565f;
+  cloud[23].getVector3fMap() << -0.009099f, 0.125000f, 1.000000f;
+  cloud[24].getVector3fMap() << 0.009099f, 0.125000f, 1.000000f;
+  cloud[25].getVector3fMap() << -0.018199f, 0.150000f, 1.000000f;
+  cloud[26].getVector3fMap() << 0.018199f, 0.150000f, 1.000000f;
+  cloud[27].getVector3fMap() << -0.027298f, 0.175000f, 1.000000f;
+  cloud[28].getVector3fMap() << 0.027298f, 0.175000f, 1.000000f;
+  cloud[29].getVector3fMap() << -0.036397f, 0.200000f, 1.000000f;
+  cloud[30].getVector3fMap() << 0.036397f, 0.200000f, 1.000000f;
+
+  normals[0].getNormalVector3fMap() << -0.290381f, -0.342020f, -0.893701f;
+  normals[1].getNormalVector3fMap() << 0.000000f, -0.342020f, -0.939693f;
+  normals[2].getNormalVector3fMap() << 0.290381f, -0.342020f, -0.893701f;
+  normals[3].getNormalVector3fMap() << -0.552338f, -0.342020f, -0.760227f;
+  normals[4].getNormalVector3fMap() << -0.290381f, -0.342020f, -0.893701f;
+  normals[5].getNormalVector3fMap() << 0.145191f, -0.342020f, -0.916697f;
+  normals[6].getNormalVector3fMap() << 0.552337f, -0.342020f, -0.760227f;
+  normals[7].getNormalVector3fMap() << -0.656282f, -0.342020f, -0.656283f;
+  normals[8].getNormalVector3fMap() << 0.656282f, -0.342020f, -0.656283f;
+  normals[9].getNormalVector3fMap() << -0.656283f, -0.342020f, -0.656282f;
+  normals[10].getNormalVector3fMap() << -0.290381f, -0.342020f, -0.893701f;
+  normals[11].getNormalVector3fMap() << 0.145191f, -0.342020f, -0.916697f;
+  normals[12].getNormalVector3fMap() << 0.656282f, -0.342020f, -0.656282f;
+  normals[13].getNormalVector3fMap() << -0.760228f, -0.342020f, -0.552337f;
+  normals[14].getNormalVector3fMap() << 0.760228f, -0.342020f, -0.552337f;
+  normals[15].getNormalVector3fMap() << -0.893701f, -0.342020f, -0.290380f;
+  normals[16].getNormalVector3fMap() << 0.893701f, -0.342020f, -0.290380f;
+  normals[17].getNormalVector3fMap() << -0.624162f, -0.342020f, -0.624162f;
+  normals[18].getNormalVector3fMap() << 0.499329f, -0.342020f, -0.687268f;
+  normals[19].getNormalVector3fMap() << -0.893701f, -0.342020f, -0.290380f;
+  normals[20].getNormalVector3fMap() << 0.893701f, -0.342020f, -0.290380f;
+  normals[21].getNormalVector3fMap() << -0.893701f, -0.342020f, -0.290381f;
+  normals[22].getNormalVector3fMap() << 0.893701f, -0.342020f, -0.290381f;
+  normals[23].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f;
+  normals[24].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f;
+  normals[25].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f;
+  normals[26].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f;
+  normals[27].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f;
+  normals[28].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f;
+  normals[29].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f;
+  normals[30].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f;
 
   // Create a shared cylinder model pointer directly
-  SampleConsensusModelConePtr model (new SampleConsensusModelCone<PointXYZ, Normal> (cloud.makeShared ()));
-  model->setInputNormals (normals.makeShared ());
+  SampleConsensusModelConePtr model(
+      new SampleConsensusModelCone<PointXYZ, Normal>(cloud.makeShared()));
+  model->setInputNormals(normals.makeShared());
 
   // Create the RANSAC object
-  RandomSampleConsensus<PointXYZ> sac (model, 0.03);
+  RandomSampleConsensus<PointXYZ> sac(model, 0.03);
 
   // Algorithm tests
-  bool result = sac.computeModel ();
-  ASSERT_TRUE (result);
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
 
   pcl::Indices sample;
-  sac.getModel (sample);
-  EXPECT_EQ (3, sample.size ());
+  sac.getModel(sample);
+  EXPECT_EQ(3, sample.size());
 
   pcl::Indices inliers;
-  sac.getInliers (inliers);
-  EXPECT_EQ (31, inliers.size ());
+  sac.getInliers(inliers);
+  EXPECT_EQ(31, inliers.size());
 
   Eigen::VectorXf coeff;
-  sac.getModelCoefficients (coeff);
-  EXPECT_EQ (7, coeff.size ());
-  EXPECT_NEAR (0.000000, coeff[0], 1e-2);
-  EXPECT_NEAR (0.100000, coeff[1], 1e-2);
-  EXPECT_NEAR (0.349066, coeff[6], 1e-2);
+  sac.getModelCoefficients(coeff);
+  EXPECT_EQ(7, coeff.size());
+  EXPECT_NEAR(0.000000, coeff[0], 1e-2);
+  EXPECT_NEAR(0.100000, coeff[1], 1e-2);
+  EXPECT_NEAR(0.349066, coeff[6], 1e-2);
 
   Eigen::VectorXf coeff_refined;
-  model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
-  EXPECT_EQ (7, coeff_refined.size ());
-  EXPECT_NEAR (0.349066, coeff_refined[6], 1e-2);
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(7, coeff_refined.size());
+  EXPECT_NEAR(0.349066, coeff_refined[6], 1e-2);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-TEST (SampleConsensusModelCylinder, RANSAC)
+TEST(SampleConsensusModelCylinder, RANSAC)
 {
-  srand (0);
+  srand(0);
 
   // Use a custom point cloud for these tests until we need something better
   PointCloud<PointXYZ> cloud;
   PointCloud<Normal> normals;
-  cloud.resize (20); normals.resize (20);
-
-  cloud[ 0].getVector3fMap () << -0.499902f, 2.199701f, 0.000008f;
-  cloud[ 1].getVector3fMap () << -0.875397f, 2.030177f, 0.050104f;
-  cloud[ 2].getVector3fMap () << -0.995875f, 1.635973f, 0.099846f;
-  cloud[ 3].getVector3fMap () << -0.779523f, 1.285527f, 0.149961f;
-  cloud[ 4].getVector3fMap () << -0.373285f, 1.216488f, 0.199959f;
-  cloud[ 5].getVector3fMap () << -0.052893f, 1.475973f, 0.250101f;
-  cloud[ 6].getVector3fMap () << -0.036558f, 1.887591f, 0.299839f;
-  cloud[ 7].getVector3fMap () << -0.335048f, 2.171994f, 0.350001f;
-  cloud[ 8].getVector3fMap () << -0.745456f, 2.135528f, 0.400072f;
-  cloud[ 9].getVector3fMap () << -0.989282f, 1.803311f, 0.449983f;
-  cloud[10].getVector3fMap () << -0.900651f, 1.400701f, 0.500126f;
-  cloud[11].getVector3fMap () << -0.539658f, 1.201468f, 0.550079f;
-  cloud[12].getVector3fMap () << -0.151875f, 1.340951f, 0.599983f;
-  cloud[13].getVector3fMap () << -0.000724f, 1.724373f, 0.649882f;
-  cloud[14].getVector3fMap () << -0.188573f, 2.090983f, 0.699854f;
-  cloud[15].getVector3fMap () << -0.587925f, 2.192257f, 0.749956f;
-  cloud[16].getVector3fMap () << -0.927724f, 1.958846f, 0.800008f;
-  cloud[17].getVector3fMap () << -0.976888f, 1.549655f, 0.849970f;
-  cloud[18].getVector3fMap () << -0.702003f, 1.242707f, 0.899954f;
-  cloud[19].getVector3fMap () << -0.289916f, 1.246296f, 0.950075f;
-
-  normals[ 0].getNormalVector3fMap () <<  0.000098f,  1.000098f,  0.000008f;
-  normals[ 1].getNormalVector3fMap () << -0.750891f,  0.660413f,  0.000104f;
-  normals[ 2].getNormalVector3fMap () << -0.991765f, -0.127949f, -0.000154f;
-  normals[ 3].getNormalVector3fMap () << -0.558918f, -0.829439f, -0.000039f;
-  normals[ 4].getNormalVector3fMap () <<  0.253627f, -0.967447f, -0.000041f;
-  normals[ 5].getNormalVector3fMap () <<  0.894105f, -0.447965f,  0.000101f;
-  normals[ 6].getNormalVector3fMap () <<  0.926852f,  0.375543f, -0.000161f;
-  normals[ 7].getNormalVector3fMap () <<  0.329948f,  0.943941f,  0.000001f;
-  normals[ 8].getNormalVector3fMap () << -0.490966f,  0.871203f,  0.000072f;
-  normals[ 9].getNormalVector3fMap () << -0.978507f,  0.206425f, -0.000017f;
-  normals[10].getNormalVector3fMap () << -0.801227f, -0.598534f,  0.000126f;
-  normals[11].getNormalVector3fMap () << -0.079447f, -0.996697f,  0.000079f;
-  normals[12].getNormalVector3fMap () <<  0.696154f, -0.717889f, -0.000017f;
-  normals[13].getNormalVector3fMap () <<  0.998685f,  0.048502f, -0.000118f;
-  normals[14].getNormalVector3fMap () <<  0.622933f,  0.782133f, -0.000146f;
-  normals[15].getNormalVector3fMap () << -0.175948f,  0.984480f, -0.000044f;
-  normals[16].getNormalVector3fMap () << -0.855476f,  0.517824f,  0.000008f;
-  normals[17].getNormalVector3fMap () << -0.953769f, -0.300571f, -0.000030f;
-  normals[18].getNormalVector3fMap () << -0.404035f, -0.914700f, -0.000046f;
-  normals[19].getNormalVector3fMap () <<  0.420154f, -0.907445f,  0.000075f;
+  cloud.resize(20);
+  normals.resize(20);
+
+  cloud[0].getVector3fMap() << -0.499902f, 2.199701f, 0.000008f;
+  cloud[1].getVector3fMap() << -0.875397f, 2.030177f, 0.050104f;
+  cloud[2].getVector3fMap() << -0.995875f, 1.635973f, 0.099846f;
+  cloud[3].getVector3fMap() << -0.779523f, 1.285527f, 0.149961f;
+  cloud[4].getVector3fMap() << -0.373285f, 1.216488f, 0.199959f;
+  cloud[5].getVector3fMap() << -0.052893f, 1.475973f, 0.250101f;
+  cloud[6].getVector3fMap() << -0.036558f, 1.887591f, 0.299839f;
+  cloud[7].getVector3fMap() << -0.335048f, 2.171994f, 0.350001f;
+  cloud[8].getVector3fMap() << -0.745456f, 2.135528f, 0.400072f;
+  cloud[9].getVector3fMap() << -0.989282f, 1.803311f, 0.449983f;
+  cloud[10].getVector3fMap() << -0.900651f, 1.400701f, 0.500126f;
+  cloud[11].getVector3fMap() << -0.539658f, 1.201468f, 0.550079f;
+  cloud[12].getVector3fMap() << -0.151875f, 1.340951f, 0.599983f;
+  cloud[13].getVector3fMap() << -0.000724f, 1.724373f, 0.649882f;
+  cloud[14].getVector3fMap() << -0.188573f, 2.090983f, 0.699854f;
+  cloud[15].getVector3fMap() << -0.587925f, 2.192257f, 0.749956f;
+  cloud[16].getVector3fMap() << -0.927724f, 1.958846f, 0.800008f;
+  cloud[17].getVector3fMap() << -0.976888f, 1.549655f, 0.849970f;
+  cloud[18].getVector3fMap() << -0.702003f, 1.242707f, 0.899954f;
+  cloud[19].getVector3fMap() << -0.289916f, 1.246296f, 0.950075f;
+
+  normals[0].getNormalVector3fMap() << 0.000098f, 1.000098f, 0.000008f;
+  normals[1].getNormalVector3fMap() << -0.750891f, 0.660413f, 0.000104f;
+  normals[2].getNormalVector3fMap() << -0.991765f, -0.127949f, -0.000154f;
+  normals[3].getNormalVector3fMap() << -0.558918f, -0.829439f, -0.000039f;
+  normals[4].getNormalVector3fMap() << 0.253627f, -0.967447f, -0.000041f;
+  normals[5].getNormalVector3fMap() << 0.894105f, -0.447965f, 0.000101f;
+  normals[6].getNormalVector3fMap() << 0.926852f, 0.375543f, -0.000161f;
+  normals[7].getNormalVector3fMap() << 0.329948f, 0.943941f, 0.000001f;
+  normals[8].getNormalVector3fMap() << -0.490966f, 0.871203f, 0.000072f;
+  normals[9].getNormalVector3fMap() << -0.978507f, 0.206425f, -0.000017f;
+  normals[10].getNormalVector3fMap() << -0.801227f, -0.598534f, 0.000126f;
+  normals[11].getNormalVector3fMap() << -0.079447f, -0.996697f, 0.000079f;
+  normals[12].getNormalVector3fMap() << 0.696154f, -0.717889f, -0.000017f;
+  normals[13].getNormalVector3fMap() << 0.998685f, 0.048502f, -0.000118f;
+  normals[14].getNormalVector3fMap() << 0.622933f, 0.782133f, -0.000146f;
+  normals[15].getNormalVector3fMap() << -0.175948f, 0.984480f, -0.000044f;
+  normals[16].getNormalVector3fMap() << -0.855476f, 0.517824f, 0.000008f;
+  normals[17].getNormalVector3fMap() << -0.953769f, -0.300571f, -0.000030f;
+  normals[18].getNormalVector3fMap() << -0.404035f, -0.914700f, -0.000046f;
+  normals[19].getNormalVector3fMap() << 0.420154f, -0.907445f, 0.000075f;
 
   // Create a shared cylinder model pointer directly
-  SampleConsensusModelCylinderPtr model (new SampleConsensusModelCylinder<PointXYZ, Normal> (cloud.makeShared ()));
-  model->setInputNormals (normals.makeShared ());
+  SampleConsensusModelCylinderPtr model(
+      new SampleConsensusModelCylinder<PointXYZ, Normal>(cloud.makeShared()));
+  model->setInputNormals(normals.makeShared());
 
   // Create the RANSAC object
-  RandomSampleConsensus<PointXYZ> sac (model, 0.03);
+  RandomSampleConsensus<PointXYZ> sac(model, 0.03);
 
   // Algorithm tests
-  bool result = sac.computeModel ();
-  ASSERT_TRUE (result);
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
 
   pcl::Indices sample;
-  sac.getModel (sample);
-  EXPECT_EQ (2, sample.size ());
+  sac.getModel(sample);
+  EXPECT_EQ(2, sample.size());
 
   pcl::Indices inliers;
-  sac.getInliers (inliers);
-  EXPECT_EQ (20, inliers.size ());
+  sac.getInliers(inliers);
+  EXPECT_EQ(20, inliers.size());
 
   Eigen::VectorXf coeff;
-  sac.getModelCoefficients (coeff);
-  EXPECT_EQ (7, coeff.size ());
-  EXPECT_NEAR (-0.5, coeff[0], 1e-3);
-  EXPECT_NEAR ( 1.7, coeff[1], 1e-3);
-  EXPECT_NEAR ( 0.5, coeff[6], 1e-3);
+  sac.getModelCoefficients(coeff);
+  EXPECT_EQ(7, coeff.size());
+  EXPECT_NEAR(-0.5, coeff[0], 1e-3);
+  EXPECT_NEAR(1.7, coeff[1], 1e-3);
+  EXPECT_NEAR(0.5, coeff[6], 1e-3);
 
   Eigen::VectorXf coeff_refined;
-  model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
-  EXPECT_EQ (7, coeff_refined.size ());
-  EXPECT_NEAR (0.5, coeff_refined[6], 1e-3);
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(7, coeff_refined.size());
+  EXPECT_NEAR(0.5, coeff_refined[6], 1e-3);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-TEST (SampleConsensusModelCircle2D, RANSAC)
+TEST(SampleConsensusModelCircle2D, RANSAC)
 {
-  srand (0);
+  srand(0);
 
   // Use a custom point cloud for these tests until we need something better
   PointCloud<PointXYZ> cloud;
-  cloud.resize (18);
-
-  cloud[ 0].getVector3fMap () << 3.587751f, -4.190982f, 0.0f;
-  cloud[ 1].getVector3fMap () << 3.808883f, -4.412265f, 0.0f;
-  cloud[ 2].getVector3fMap () << 3.587525f, -5.809143f, 0.0f;
-  cloud[ 3].getVector3fMap () << 2.999913f, -5.999980f, 0.0f;
-  cloud[ 4].getVector3fMap () << 2.412224f, -5.809090f, 0.0f;
-  cloud[ 5].getVector3fMap () << 2.191080f, -5.587682f, 0.0f;
-  cloud[ 6].getVector3fMap () << 2.048941f, -5.309003f, 0.0f;
-  cloud[ 7].getVector3fMap () << 2.000397f, -4.999944f, 0.0f;
-  cloud[ 8].getVector3fMap () << 2.999953f, -6.000056f, 0.0f;
-  cloud[ 9].getVector3fMap () << 2.691127f, -5.951136f, 0.0f;
-  cloud[10].getVector3fMap () << 2.190892f, -5.587838f, 0.0f;
-  cloud[11].getVector3fMap () << 2.048874f, -5.309052f, 0.0f;
-  cloud[12].getVector3fMap () << 1.999990f, -5.000147f, 0.0f;
-  cloud[13].getVector3fMap () << 2.049026f, -4.690918f, 0.0f;
-  cloud[14].getVector3fMap () << 2.190956f, -4.412162f, 0.0f;
-  cloud[15].getVector3fMap () << 2.412231f, -4.190918f, 0.0f;
-  cloud[16].getVector3fMap () << 2.691027f, -4.049060f, 0.0f;
-  cloud[17].getVector3fMap () << 2.000000f, -3.000000f, 0.0f;
+  cloud.resize(18);
+
+  cloud[0].getVector3fMap() << 3.587751f, -4.190982f, 0.0f;
+  cloud[1].getVector3fMap() << 3.808883f, -4.412265f, 0.0f;
+  cloud[2].getVector3fMap() << 3.587525f, -5.809143f, 0.0f;
+  cloud[3].getVector3fMap() << 2.999913f, -5.999980f, 0.0f;
+  cloud[4].getVector3fMap() << 2.412224f, -5.809090f, 0.0f;
+  cloud[5].getVector3fMap() << 2.191080f, -5.587682f, 0.0f;
+  cloud[6].getVector3fMap() << 2.048941f, -5.309003f, 0.0f;
+  cloud[7].getVector3fMap() << 2.000397f, -4.999944f, 0.0f;
+  cloud[8].getVector3fMap() << 2.999953f, -6.000056f, 0.0f;
+  cloud[9].getVector3fMap() << 2.691127f, -5.951136f, 0.0f;
+  cloud[10].getVector3fMap() << 2.190892f, -5.587838f, 0.0f;
+  cloud[11].getVector3fMap() << 2.048874f, -5.309052f, 0.0f;
+  cloud[12].getVector3fMap() << 1.999990f, -5.000147f, 0.0f;
+  cloud[13].getVector3fMap() << 2.049026f, -4.690918f, 0.0f;
+  cloud[14].getVector3fMap() << 2.190956f, -4.412162f, 0.0f;
+  cloud[15].getVector3fMap() << 2.412231f, -4.190918f, 0.0f;
+  cloud[16].getVector3fMap() << 2.691027f, -4.049060f, 0.0f;
+  cloud[17].getVector3fMap() << 2.000000f, -3.000000f, 0.0f;
 
   // Create a shared 2d circle model pointer directly
-  SampleConsensusModelCircle2DPtr model (new SampleConsensusModelCircle2D<PointXYZ> (cloud.makeShared ()));
+  SampleConsensusModelCircle2DPtr model(
+      new SampleConsensusModelCircle2D<PointXYZ>(cloud.makeShared()));
 
   // Create the RANSAC object
-  RandomSampleConsensus<PointXYZ> sac (model, 0.03);
+  RandomSampleConsensus<PointXYZ> sac(model, 0.03);
 
   // Algorithm tests
-  bool result = sac.computeModel ();
-  ASSERT_TRUE (result);
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
 
   pcl::Indices sample;
-  sac.getModel (sample);
-  EXPECT_EQ (3, sample.size ());
+  sac.getModel(sample);
+  EXPECT_EQ(3, sample.size());
 
   pcl::Indices inliers;
-  sac.getInliers (inliers);
-  EXPECT_EQ (17, inliers.size ());
+  sac.getInliers(inliers);
+  EXPECT_EQ(17, inliers.size());
 
   Eigen::VectorXf coeff;
-  sac.getModelCoefficients (coeff);
-  EXPECT_EQ (3, coeff.size ());
-  EXPECT_NEAR ( 3, coeff[0], 1e-3);
-  EXPECT_NEAR (-5, coeff[1], 1e-3);
-  EXPECT_NEAR ( 1, coeff[2], 1e-3);
+  sac.getModelCoefficients(coeff);
+  EXPECT_EQ(3, coeff.size());
+  EXPECT_NEAR(3, coeff[0], 1e-3);
+  EXPECT_NEAR(-5, coeff[1], 1e-3);
+  EXPECT_NEAR(1, coeff[2], 1e-3);
 
   Eigen::VectorXf coeff_refined;
-  model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
-  EXPECT_EQ (3, coeff_refined.size ());
-  EXPECT_NEAR ( 3, coeff_refined[0], 1e-3);
-  EXPECT_NEAR (-5, coeff_refined[1], 1e-3);
-  EXPECT_NEAR ( 1, coeff_refined[2], 1e-3);
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(3, coeff_refined.size());
+  EXPECT_NEAR(3, coeff_refined[0], 1e-3);
+  EXPECT_NEAR(-5, coeff_refined[1], 1e-3);
+  EXPECT_NEAR(1, coeff_refined[2], 1e-3);
 }
 
 ///////////////////////////////////////////////////////////////////////////////
 
-TEST (SampleConsensusModelCircle2D, SampleValidationPointsValid)
+TEST(SampleConsensusModelCircle2D, SampleValidationPointsValid)
 {
   PointCloud<PointXYZ> cloud;
-  cloud.resize (3);
+  cloud.resize(3);
 
-  cloud[0].getVector3fMap () <<  1.0f,  2.0f,  0.0f;
-  cloud[1].getVector3fMap () <<  0.0f,  1.0f,  0.0f;
-  cloud[2].getVector3fMap () <<  1.5f,  0.0f,  0.0f;
+  cloud[0].getVector3fMap() << 1.0f, 2.0f, 0.0f;
+  cloud[1].getVector3fMap() << 0.0f, 1.0f, 0.0f;
+  cloud[2].getVector3fMap() << 1.5f, 0.0f, 0.0f;
 
   // Create a shared line model pointer directly
-  SampleConsensusModelCircle2DPtr model (
-    new SampleConsensusModelCircle2D<PointXYZ> (cloud.makeShared ()));
+  SampleConsensusModelCircle2DPtr model(
+      new SampleConsensusModelCircle2D<PointXYZ>(cloud.makeShared()));
 
   // Algorithm tests
   pcl::Indices samples;
   int iterations = 0;
   model->getSamples(iterations, samples);
-  EXPECT_EQ (samples.size(), 3);
+  EXPECT_EQ(samples.size(), 3);
 
   Eigen::VectorXf modelCoefficients;
-  EXPECT_TRUE (model->computeModelCoefficients (samples, modelCoefficients));
+  EXPECT_TRUE(model->computeModelCoefficients(samples, modelCoefficients));
 
-  EXPECT_NEAR (modelCoefficients[0], 1.05f, 1e-3);   // center x
-  EXPECT_NEAR (modelCoefficients[1], 0.95f, 1e-3);   // center y
-  EXPECT_NEAR (modelCoefficients[2], std::sqrt (1.105f), 1e-3);  // radius
+  EXPECT_NEAR(modelCoefficients[0], 1.05f, 1e-3);             // center x
+  EXPECT_NEAR(modelCoefficients[1], 0.95f, 1e-3);             // center y
+  EXPECT_NEAR(modelCoefficients[2], std::sqrt(1.105f), 1e-3); // radius
 }
 
 using PointVector = std::vector<PointXYZ>;
 class SampleConsensusModelCircle2DCollinearTest
-  : public testing::TestWithParam<PointVector> {
-  protected:
-    void SetUp() override {
-      pointCloud_ = make_shared<PointCloud<PointXYZ>>();
-      for(const auto& point : GetParam()) {
-        pointCloud_->emplace_back(point);
-      }
+: public testing::TestWithParam<PointVector> {
+protected:
+  void
+  SetUp() override
+  {
+    pointCloud_ = make_shared<PointCloud<PointXYZ>>();
+    for (const auto& point : GetParam()) {
+      pointCloud_->emplace_back(point);
     }
+  }
 
-    PointCloud<PointXYZ>::Ptr pointCloud_ = nullptr;
+  PointCloud<PointXYZ>::Ptr pointCloud_ = nullptr;
 };
 
 // Parametric tests clearly show the input for which they failed and provide
 // clearer feedback if something is changed in the future.
-TEST_P (SampleConsensusModelCircle2DCollinearTest, SampleValidationPointsInvalid)
+TEST_P(SampleConsensusModelCircle2DCollinearTest, SampleValidationPointsInvalid)
 {
-  ASSERT_NE (pointCloud_, nullptr);
+  ASSERT_NE(pointCloud_, nullptr);
 
-  SampleConsensusModelCircle2DPtr model (
-      new SampleConsensusModelCircle2D<PointXYZ> (pointCloud_));
-  ASSERT_GE (model->getInputCloud ()->size (), model->getSampleSize ());
+  SampleConsensusModelCircle2DPtr model(
+      new SampleConsensusModelCircle2D<PointXYZ>(pointCloud_));
+  ASSERT_GE(model->getInputCloud()->size(), model->getSampleSize());
 
   // Algorithm tests
   // (Maybe) TODO: try to implement the "cheat point" trick from
@@ -586,171 +610,194 @@ TEST_P (SampleConsensusModelCircle2DCollinearTest, SampleValidationPointsInvalid
   // Explicitly enforce sample order so they can act as designed
   pcl::Indices forcedSamples = {0, 1, 2};
   Eigen::VectorXf modelCoefficients;
-  EXPECT_FALSE (model->computeModelCoefficients (forcedSamples, modelCoefficients));
+  EXPECT_FALSE(model->computeModelCoefficients(forcedSamples, modelCoefficients));
 }
 
-INSTANTIATE_TEST_SUITE_P (CollinearInputs, SampleConsensusModelCircle2DCollinearTest,
-  testing::Values( // Throw in some negative coordinates and "asymmetric" points to cover more cases
-    PointVector {{ 0.0f,  0.0f, 0.0f}, { 1.0f,  0.0f, 0.0f}, { 2.0f,  0.0f, 0.0f}}, // collinear along x-axis
-    PointVector {{-1.0f,  0.0f, 0.0f}, { 1.0f,  0.0f, 0.0f}, { 2.0f,  0.0f, 0.0f}},
-    PointVector {{ 0.0f, -1.0f, 0.0f}, { 0.0f,  1.0f, 0.0f}, { 0.0f,  2.0f, 0.0f}}, // collinear along y-axis
-    PointVector {{ 0.0f, -1.0f, 0.0f}, { 0.0f,  1.0f, 0.0f}, { 0.0f,  2.0f, 0.0f}},
-    PointVector {{ 0.0f,  0.0f, 0.0f}, { 1.0f,  1.0f, 0.0f}, { 2.0f,  2.0f, 0.0f}}, // collinear along diagonal
-    PointVector {{ 0.0f,  0.0f, 0.0f}, {-1.0f, -1.0f, 0.0f}, {-2.0f, -2.0f, 0.0f}},
-    PointVector {{-3.0f, -6.5f, 0.0f}, {-2.0f, -0.5f, 0.0f}, {-1.5f,  2.5f, 0.0f}}, // other collinear input
-    PointVector {{ 2.0f,  2.0f, 0.0f}, { 0.0f,  0.0f, 0.0f}, { 0.0f,  0.0f, 0.0f}}, // two points equal
-    PointVector {{ 0.0f,  0.0f, 0.0f}, { 2.0f,  2.0f, 0.0f}, { 0.0f,  0.0f, 0.0f}},
-    PointVector {{ 0.0f,  0.0f, 0.0f}, { 0.0f,  0.0f, 0.0f}, { 2.0f,  2.0f, 0.0f}},
-    PointVector {{ 1.0f,  1.0f, 0.0f}, { 1.0f,  1.0f, 0.0f}, { 1.0f,  1.0f, 0.0f}}  // all points equal
-  )
-);
+INSTANTIATE_TEST_SUITE_P(
+    CollinearInputs,
+    SampleConsensusModelCircle2DCollinearTest,
+    testing::Values( // Throw in some negative coordinates and "asymmetric" points to
+                     // cover more cases
+        PointVector{{0.0f, 0.0f, 0.0f},
+                    {1.0f, 0.0f, 0.0f},
+                    {2.0f, 0.0f, 0.0f}}, // collinear along x-axis
+        PointVector{{-1.0f, 0.0f, 0.0f}, {1.0f, 0.0f, 0.0f}, {2.0f, 0.0f, 0.0f}},
+        PointVector{{0.0f, -1.0f, 0.0f},
+                    {0.0f, 1.0f, 0.0f},
+                    {0.0f, 2.0f, 0.0f}}, // collinear along y-axis
+        PointVector{{0.0f, -1.0f, 0.0f}, {0.0f, 1.0f, 0.0f}, {0.0f, 2.0f, 0.0f}},
+        PointVector{{0.0f, 0.0f, 0.0f},
+                    {1.0f, 1.0f, 0.0f},
+                    {2.0f, 2.0f, 0.0f}}, // collinear along diagonal
+        PointVector{{0.0f, 0.0f, 0.0f}, {-1.0f, -1.0f, 0.0f}, {-2.0f, -2.0f, 0.0f}},
+        PointVector{{-3.0f, -6.5f, 0.0f},
+                    {-2.0f, -0.5f, 0.0f},
+                    {-1.5f, 2.5f, 0.0f}}, // other collinear input
+        PointVector{{2.0f, 2.0f, 0.0f},
+                    {0.0f, 0.0f, 0.0f},
+                    {0.0f, 0.0f, 0.0f}}, // two points equal
+        PointVector{{0.0f, 0.0f, 0.0f}, {2.0f, 2.0f, 0.0f}, {0.0f, 0.0f, 0.0f}},
+        PointVector{{0.0f, 0.0f, 0.0f}, {0.0f, 0.0f, 0.0f}, {2.0f, 2.0f, 0.0f}},
+        PointVector{{1.0f, 1.0f, 0.0f}, {1.0f, 1.0f, 0.0f}, {1.0f, 1.0f, 0.0f}}
+        // all points equal
+        ));
 
 //////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-class SampleConsensusModelCircle2DTest : private SampleConsensusModelCircle2D<PointT>
-{
-  public:
-    using SampleConsensusModelCircle2D<PointT>::SampleConsensusModelCircle2D;
-    using SampleConsensusModelCircle2D<PointT>::countWithinDistanceStandard;
-#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__)
-    using SampleConsensusModelCircle2D<PointT>::countWithinDistanceSSE;
+class SampleConsensusModelCircle2DTest : private SampleConsensusModelCircle2D<PointT> {
+public:
+  using SampleConsensusModelCircle2D<PointT>::SampleConsensusModelCircle2D;
+  using SampleConsensusModelCircle2D<PointT>::countWithinDistanceStandard;
+#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__)
+  using SampleConsensusModelCircle2D<PointT>::countWithinDistanceSSE;
 #endif
-#if defined (__AVX__) && defined (__AVX2__)
-    using SampleConsensusModelCircle2D<PointT>::countWithinDistanceAVX;
+#if defined(__AVX__) && defined(__AVX2__)
+  using SampleConsensusModelCircle2D<PointT>::countWithinDistanceAVX;
 #endif
 };
 
-TEST (SampleConsensusModelCircle2D, SIMD_countWithinDistance) // Test if all countWithinDistance implementations return the same value
+TEST(SampleConsensusModelCircle2D,
+     SIMD_countWithinDistance) // Test if all countWithinDistance implementations return
+                               // the same value
 {
-  const auto seed = static_cast<unsigned> (std::time (nullptr));
-  srand (seed);
-  for (size_t i=0; i<100; i++) // Run as often as you like
+  const auto seed = static_cast<unsigned>(std::time(nullptr));
+  srand(seed);
+  for (size_t i = 0; i < 100; i++) // Run as often as you like
   {
     // Generate a cloud with 1000 random points
     PointCloud<PointXYZ> cloud;
     pcl::Indices indices;
-    cloud.resize (1000);
-    for (std::size_t idx = 0; idx < cloud.size (); ++idx)
-    {
-      cloud[idx].x = 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0;
-      cloud[idx].y = 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0;
-      cloud[idx].z = 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0;
-      if (rand () % 2 == 0)
-      {
-        indices.push_back (static_cast<int> (idx));
+    cloud.resize(1000);
+    for (std::size_t idx = 0; idx < cloud.size(); ++idx) {
+      cloud[idx].x = 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0;
+      cloud[idx].y = 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0;
+      cloud[idx].z = 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0;
+      if (rand() % 2 == 0) {
+        indices.push_back(static_cast<int>(idx));
       }
     }
-    SampleConsensusModelCircle2DTest<PointXYZ> model (cloud.makeShared (), indices, true);
+    SampleConsensusModelCircle2DTest<PointXYZ> model(cloud.makeShared(), indices, true);
 
     // Generate random circle model parameters
     Eigen::VectorXf model_coefficients(3);
-    model_coefficients << 2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0,
-                          2.0 * static_cast<float> (rand ()) / RAND_MAX - 1.0,
-                          0.1 * static_cast<float> (rand ()) / RAND_MAX; // center and radius
+    model_coefficients << 2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0,
+        2.0 * static_cast<float>(rand()) / RAND_MAX - 1.0,
+        0.1 * static_cast<float>(rand()) / RAND_MAX; // center and radius
 
-    const double threshold = 0.1 * static_cast<double> (rand ()) / RAND_MAX; // threshold in [0; 0.1]
+    const double threshold =
+        0.1 * static_cast<double>(rand()) / RAND_MAX; // threshold in [0; 0.1]
 
     // The number of inliers is usually somewhere between 0 and 20
-    const auto res_standard = model.countWithinDistanceStandard (model_coefficients, threshold); // Standard
-    PCL_DEBUG ("seed=%lu, i=%lu, model=(%f, %f, %f), threshold=%f, res_standard=%lu\n", seed, i,
-               model_coefficients(0), model_coefficients(1), model_coefficients(2), threshold, res_standard);
-#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__)
-    const auto res_sse      = model.countWithinDistanceSSE (model_coefficients, threshold); // SSE
-    ASSERT_EQ (res_standard, res_sse);
+    const auto res_standard =
+        model.countWithinDistanceStandard(model_coefficients, threshold); // Standard
+    PCL_DEBUG("seed=%lu, i=%lu, model=(%f, %f, %f), threshold=%f, res_standard=%lu\n",
+              seed,
+              i,
+              model_coefficients(0),
+              model_coefficients(1),
+              model_coefficients(2),
+              threshold,
+              res_standard);
+#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__)
+    const auto res_sse =
+        model.countWithinDistanceSSE(model_coefficients, threshold); // SSE
+    ASSERT_EQ(res_standard, res_sse);
 #endif
-#if defined (__AVX__) && defined (__AVX2__)
-    const auto res_avx      = model.countWithinDistanceAVX (model_coefficients, threshold); // AVX
-    ASSERT_EQ (res_standard, res_avx);
+#if defined(__AVX__) && defined(__AVX2__)
+    const auto res_avx =
+        model.countWithinDistanceAVX(model_coefficients, threshold); // AVX
+    ASSERT_EQ(res_standard, res_avx);
 #endif
   }
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-TEST (SampleConsensusModelCircle3D, RANSAC)
+TEST(SampleConsensusModelCircle3D, RANSAC)
 {
-  srand (0);
+  srand(0);
 
   // Use a custom point cloud for these tests until we need something better
   PointCloud<PointXYZ> cloud;
-  cloud.resize (20);
-
-  cloud[ 0].getVector3fMap () << 1.00000000f, 5.0000000f, -2.9000001f;
-  cloud[ 1].getVector3fMap () << 1.03420200f, 5.0000000f, -2.9060307f;
-  cloud[ 2].getVector3fMap () << 1.06427870f, 5.0000000f, -2.9233956f;
-  cloud[ 3].getVector3fMap () << 1.08660260f, 5.0000000f, -2.9500000f;
-  cloud[ 4].getVector3fMap () << 1.09848080f, 5.0000000f, -2.9826353f;
-  cloud[ 5].getVector3fMap () << 1.09848080f, 5.0000000f, -3.0173647f;
-  cloud[ 6].getVector3fMap () << 1.08660260f, 5.0000000f, -3.0500000f;
-  cloud[ 7].getVector3fMap () << 1.06427870f, 5.0000000f, -3.0766044f;
-  cloud[ 8].getVector3fMap () << 1.03420200f, 5.0000000f, -3.0939693f;
-  cloud[ 9].getVector3fMap () << 1.00000000f, 5.0000000f, -3.0999999f;
-  cloud[10].getVector3fMap () << 0.96579796f, 5.0000000f, -3.0939693f;
-  cloud[11].getVector3fMap () << 0.93572122f, 5.0000000f, -3.0766044f;
-  cloud[12].getVector3fMap () << 0.91339743f, 5.0000000f, -3.0500000f;
-  cloud[13].getVector3fMap () << 0.90151924f, 5.0000000f, -3.0173647f;
-  cloud[14].getVector3fMap () << 0.90151924f, 5.0000000f, -2.9826353f;
-  cloud[15].getVector3fMap () << 0.91339743f, 5.0000000f, -2.9500000f;
-  cloud[16].getVector3fMap () << 0.93572122f, 5.0000000f, -2.9233956f;
-  cloud[17].getVector3fMap () << 0.96579796f, 5.0000000f, -2.9060307f;
-  cloud[18].getVector3fMap () << 0.85000002f, 4.8499999f, -3.1500001f;
-  cloud[19].getVector3fMap () << 1.15000000f, 5.1500001f, -2.8499999f;
+  cloud.resize(20);
+
+  cloud[0].getVector3fMap() << 1.00000000f, 5.0000000f, -2.9000001f;
+  cloud[1].getVector3fMap() << 1.03420200f, 5.0000000f, -2.9060307f;
+  cloud[2].getVector3fMap() << 1.06427870f, 5.0000000f, -2.9233956f;
+  cloud[3].getVector3fMap() << 1.08660260f, 5.0000000f, -2.9500000f;
+  cloud[4].getVector3fMap() << 1.09848080f, 5.0000000f, -2.9826353f;
+  cloud[5].getVector3fMap() << 1.09848080f, 5.0000000f, -3.0173647f;
+  cloud[6].getVector3fMap() << 1.08660260f, 5.0000000f, -3.0500000f;
+  cloud[7].getVector3fMap() << 1.06427870f, 5.0000000f, -3.0766044f;
+  cloud[8].getVector3fMap() << 1.03420200f, 5.0000000f, -3.0939693f;
+  cloud[9].getVector3fMap() << 1.00000000f, 5.0000000f, -3.0999999f;
+  cloud[10].getVector3fMap() << 0.96579796f, 5.0000000f, -3.0939693f;
+  cloud[11].getVector3fMap() << 0.93572122f, 5.0000000f, -3.0766044f;
+  cloud[12].getVector3fMap() << 0.91339743f, 5.0000000f, -3.0500000f;
+  cloud[13].getVector3fMap() << 0.90151924f, 5.0000000f, -3.0173647f;
+  cloud[14].getVector3fMap() << 0.90151924f, 5.0000000f, -2.9826353f;
+  cloud[15].getVector3fMap() << 0.91339743f, 5.0000000f, -2.9500000f;
+  cloud[16].getVector3fMap() << 0.93572122f, 5.0000000f, -2.9233956f;
+  cloud[17].getVector3fMap() << 0.96579796f, 5.0000000f, -2.9060307f;
+  cloud[18].getVector3fMap() << 0.85000002f, 4.8499999f, -3.1500001f;
+  cloud[19].getVector3fMap() << 1.15000000f, 5.1500001f, -2.8499999f;
 
   // Create a shared 3d circle model pointer directly
-  SampleConsensusModelCircle3DPtr model (new SampleConsensusModelCircle3D<PointXYZ> (cloud.makeShared ()));
+  SampleConsensusModelCircle3DPtr model(
+      new SampleConsensusModelCircle3D<PointXYZ>(cloud.makeShared()));
 
   // Create the RANSAC object
-  RandomSampleConsensus<PointXYZ> sac (model, 0.03);
+  RandomSampleConsensus<PointXYZ> sac(model, 0.03);
 
   // Algorithm tests
-  bool result = sac.computeModel ();
-  ASSERT_TRUE (result);
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
 
   pcl::Indices sample;
-  sac.getModel (sample);
-  EXPECT_EQ (3, sample.size ());
+  sac.getModel(sample);
+  EXPECT_EQ(3, sample.size());
 
   pcl::Indices inliers;
-  sac.getInliers (inliers);
-  EXPECT_EQ (18, inliers.size ());
+  sac.getInliers(inliers);
+  EXPECT_EQ(18, inliers.size());
 
   Eigen::VectorXf coeff;
-  sac.getModelCoefficients (coeff);
-  EXPECT_EQ (7, coeff.size ());
-  EXPECT_NEAR ( 1.0, coeff[0], 1e-3);
-  EXPECT_NEAR ( 5.0, coeff[1], 1e-3);
-  EXPECT_NEAR (-3.0, coeff[2], 1e-3);
-  EXPECT_NEAR ( 0.1, coeff[3], 1e-3);
-  EXPECT_NEAR ( 0.0, coeff[4], 1e-3);
+  sac.getModelCoefficients(coeff);
+  EXPECT_EQ(7, coeff.size());
+  EXPECT_NEAR(1.0, coeff[0], 1e-3);
+  EXPECT_NEAR(5.0, coeff[1], 1e-3);
+  EXPECT_NEAR(-3.0, coeff[2], 1e-3);
+  EXPECT_NEAR(0.1, coeff[3], 1e-3);
+  EXPECT_NEAR(0.0, coeff[4], 1e-3);
   // Use abs in y component because both variants are valid normal vectors
-  EXPECT_NEAR ( 1.0, std::abs (coeff[5]), 1e-3);
-  EXPECT_NEAR ( 0.0, coeff[6], 1e-3);
+  EXPECT_NEAR(1.0, std::abs(coeff[5]), 1e-3);
+  EXPECT_NEAR(0.0, coeff[6], 1e-3);
 
   Eigen::VectorXf coeff_refined;
-  model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
-  EXPECT_EQ (7, coeff_refined.size ());
-  EXPECT_NEAR ( 1.0, coeff_refined[0], 1e-3);
-  EXPECT_NEAR ( 5.0, coeff_refined[1], 1e-3);
-  EXPECT_NEAR (-3.0, coeff_refined[2], 1e-3);
-  EXPECT_NEAR ( 0.1, coeff_refined[3], 1e-3);
-  EXPECT_NEAR ( 0.0, coeff_refined[4], 1e-3);
-  EXPECT_NEAR ( 1.0, std::abs (coeff_refined[5]), 1e-3);
-  EXPECT_NEAR ( 0.0, coeff_refined[6], 1e-3);
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(7, coeff_refined.size());
+  EXPECT_NEAR(1.0, coeff_refined[0], 1e-3);
+  EXPECT_NEAR(5.0, coeff_refined[1], 1e-3);
+  EXPECT_NEAR(-3.0, coeff_refined[2], 1e-3);
+  EXPECT_NEAR(0.1, coeff_refined[3], 1e-3);
+  EXPECT_NEAR(0.0, coeff_refined[4], 1e-3);
+  EXPECT_NEAR(1.0, std::abs(coeff_refined[5]), 1e-3);
+  EXPECT_NEAR(0.0, coeff_refined[6], 1e-3);
 }
 
-TEST (SampleConsensusModelSphere, projectPoints)
+TEST(SampleConsensusModelSphere, projectPoints)
 {
   Eigen::VectorXf model_coefficients(4);
   model_coefficients << -0.32, -0.89, 0.37, 0.12; // center and radius
 
   pcl::PointCloud<pcl::PointXYZ>::Ptr input(new pcl::PointCloud<pcl::PointXYZ>);
-  input->emplace_back(-0.259754, -0.950873,  0.318377); // inlier, dist from center=0.10
-  input->emplace_back( 0.595892,  0.455094,  0.025545); // outlier, not projected
-  input->emplace_back(-0.221871, -0.973718,  0.353817); // inlier, dist from center=0.13
-  input->emplace_back(-0.332269, -0.848851,  0.437499); // inlier, dist from center=0.08
+  input->emplace_back(-0.259754, -0.950873, 0.318377);  // inlier, dist from center=0.10
+  input->emplace_back(0.595892, 0.455094, 0.025545);    // outlier, not projected
+  input->emplace_back(-0.221871, -0.973718, 0.353817);  // inlier, dist from center=0.13
+  input->emplace_back(-0.332269, -0.848851, 0.437499);  // inlier, dist from center=0.08
   input->emplace_back(-0.242308, -0.561036, -0.365535); // outlier, not projected
-  input->emplace_back(-0.327668, -0.800009,  0.290988); // inlier, dist from center=0.12
-  input->emplace_back(-0.173948, -0.883831,  0.403625); // inlier, dist from center=0.15
-  input->emplace_back(-0.033891,  0.624537, -0.606994); // outlier, not projected
+  input->emplace_back(-0.327668, -0.800009, 0.290988);  // inlier, dist from center=0.12
+  input->emplace_back(-0.173948, -0.883831, 0.403625);  // inlier, dist from center=0.15
+  input->emplace_back(-0.033891, 0.624537, -0.606994);  // outlier, not projected
 
   pcl::SampleConsensusModelSphere<pcl::PointXYZ> model(input);
   pcl::Indices inliers = {0, 2, 3, 5, 6};
@@ -765,20 +812,20 @@ TEST (SampleConsensusModelSphere, projectPoints)
   pcl::PointCloud<pcl::PointXYZ> projected_points;
   model.projectPoints(inliers, model_coefficients, projected_points, false);
   EXPECT_EQ(projected_points.size(), 5);
-  for(int i=0; i<5; ++i)
+  for (int i = 0; i < 5; ++i)
     EXPECT_XYZ_NEAR(projected_points[i], projected_truth[i], 1e-5);
 
   pcl::PointCloud<pcl::PointXYZ> projected_points_all;
   model.projectPoints(inliers, model_coefficients, projected_points_all, true);
   EXPECT_EQ(projected_points_all.size(), 8);
   EXPECT_XYZ_NEAR(projected_points_all[0], projected_truth[0], 1e-5);
-  EXPECT_XYZ_NEAR(projected_points_all[1],        (*input)[1], 1e-5);
+  EXPECT_XYZ_NEAR(projected_points_all[1], (*input)[1], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[2], projected_truth[1], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[3], projected_truth[2], 1e-5);
-  EXPECT_XYZ_NEAR(projected_points_all[4],        (*input)[4], 1e-5);
+  EXPECT_XYZ_NEAR(projected_points_all[4], (*input)[4], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[5], projected_truth[3], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[6], projected_truth[4], 1e-5);
-  EXPECT_XYZ_NEAR(projected_points_all[7],        (*input)[7], 1e-5);
+  EXPECT_XYZ_NEAR(projected_points_all[7], (*input)[7], 1e-5);
 }
 
 TEST(SampleConsensusModelCylinder, projectPoints)
@@ -817,13 +864,13 @@ TEST(SampleConsensusModelCylinder, projectPoints)
   model.projectPoints(inliers, model_coefficients, projected_points_all, true);
   EXPECT_EQ(projected_points_all.size(), 8);
   EXPECT_XYZ_NEAR(projected_points_all[0], projected_truth[0], 1e-5);
-  EXPECT_XYZ_NEAR(projected_points_all[1],        (*input)[1], 1e-5);
+  EXPECT_XYZ_NEAR(projected_points_all[1], (*input)[1], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[2], projected_truth[1], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[3], projected_truth[2], 1e-5);
-  EXPECT_XYZ_NEAR(projected_points_all[4],        (*input)[4], 1e-5);
+  EXPECT_XYZ_NEAR(projected_points_all[4], (*input)[4], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[5], projected_truth[3], 1e-5);
   EXPECT_XYZ_NEAR(projected_points_all[6], projected_truth[4], 1e-5);
-  EXPECT_XYZ_NEAR(projected_points_all[7],        (*input)[7], 1e-5);
+  EXPECT_XYZ_NEAR(projected_points_all[7], (*input)[7], 1e-5);
 }
 
 TEST(SampleConsensusModelEllipse3D, RANSAC)
@@ -834,16 +881,16 @@ TEST(SampleConsensusModelEllipse3D, RANSAC)
   PointCloud<PointXYZ> cloud;
   cloud.resize(22);
 
-  cloud[ 0].getVector3fMap() << 1.000000, 5.000000, 3.000000;
-  cloud[ 1].getVector3fMap() << 0.690983, 5.000000, 2.902110;
-  cloud[ 2].getVector3fMap() << 0.412215, 5.000000, 2.618030;
-  cloud[ 3].getVector3fMap() << 0.190983, 5.000000, 2.175570;
-  cloud[ 4].getVector3fMap() << 0.048944, 5.000000, 1.618030;
-  cloud[ 5].getVector3fMap() << 0.000000, 5.000000, 1.000000;
-  cloud[ 6].getVector3fMap() << 0.048944, 5.000000, 0.381966;
-  cloud[ 7].getVector3fMap() << 0.190983, 5.000000, -0.175571;
-  cloud[ 8].getVector3fMap() << 0.412215, 5.000000, -0.618034;
-  cloud[ 9].getVector3fMap() << 0.690983, 5.000000, -0.902113;
+  cloud[0].getVector3fMap() << 1.000000, 5.000000, 3.000000;
+  cloud[1].getVector3fMap() << 0.690983, 5.000000, 2.902110;
+  cloud[2].getVector3fMap() << 0.412215, 5.000000, 2.618030;
+  cloud[3].getVector3fMap() << 0.190983, 5.000000, 2.175570;
+  cloud[4].getVector3fMap() << 0.048944, 5.000000, 1.618030;
+  cloud[5].getVector3fMap() << 0.000000, 5.000000, 1.000000;
+  cloud[6].getVector3fMap() << 0.048944, 5.000000, 0.381966;
+  cloud[7].getVector3fMap() << 0.190983, 5.000000, -0.175571;
+  cloud[8].getVector3fMap() << 0.412215, 5.000000, -0.618034;
+  cloud[9].getVector3fMap() << 0.690983, 5.000000, -0.902113;
   cloud[10].getVector3fMap() << 1.000000, 5.000000, -1.000000;
   cloud[11].getVector3fMap() << 1.309020, 5.000000, -0.902113;
   cloud[12].getVector3fMap() << 1.587790, 5.000000, -0.618034;
@@ -859,7 +906,8 @@ TEST(SampleConsensusModelEllipse3D, RANSAC)
   cloud[21].getVector3fMap() << 1.15000000f, 5.1500001f, -2.8499999f;
 
   // Create a shared 3d ellipse model pointer directly
-  SampleConsensusModelEllipse3DPtr model( new SampleConsensusModelEllipse3D<PointXYZ>(cloud.makeShared()));
+  SampleConsensusModelEllipse3DPtr model(
+      new SampleConsensusModelEllipse3D<PointXYZ>(cloud.makeShared()));
 
   // Create the RANSAC object
   RandomSampleConsensus<PointXYZ> sac(model, 0.0011);
@@ -917,10 +965,685 @@ TEST(SampleConsensusModelEllipse3D, RANSAC)
   EXPECT_NEAR(1.0, std::abs(coeff_refined[10]), 1e-3);
 }
 
-int
-main (int argc, char** argv)
+// Heavy oclusion, all points on a 30 degree segment on the major radius
+//  and 90 degrees on the minor
+TEST(SampleConsensusModelTorusOclusion, RANSAC)
+{
+
+  srand(0);
+
+  PointCloud<PointXYZ> cloud;
+  PointCloud<Normal> normals;
+
+  cloud.resize(50);
+  normals.resize(50);
+
+  cloud[0].getVector3fMap() << 1.4386461277601734, -1.0569588316537601,
+      3.6109405500068648;
+  cloud[1].getVector3fMap() << 1.5892272151771987, -1.0107131751656608,
+      3.7524801792294786;
+  cloud[2].getVector3fMap() << 0.779450850990528, -1.1095381992814901,
+      2.1362474566704086;
+  cloud[3].getVector3fMap() << 2.2332764042301116, -1.0712898227325813,
+      4.104289150491388;
+  cloud[4].getVector3fMap() << 1.4625240977021328, -1.0262438455563425,
+      3.6408698702774327;
+  cloud[5].getVector3fMap() << 1.107288574597542, -1.038213986002474,
+      3.2111695308737334;
+  cloud[6].getVector3fMap() << 1.634136176426644, -1.0586849054858922,
+      3.7791937450863844;
+  cloud[7].getVector3fMap() << 2.8081039281494284, -1.124052124218725,
+      4.208730485774282;
+  cloud[8].getVector3fMap() << 2.7325382847100004, -1.0968720291167913,
+      4.214374570675481;
+  cloud[9].getVector3fMap() << 1.1897810394404515, -1.0861469920822655,
+      3.3103205876091675;
+  cloud[10].getVector3fMap() << 0.8242772124713484, -1.0935505936537508,
+      2.4973185149793924;
+  cloud[11].getVector3fMap() << 2.9589166075430366, -1.0656763334810868,
+      4.240842449620676;
+  cloud[12].getVector3fMap() << 1.7930324882302902, -1.0629548347911097,
+      3.8893227292858175;
+  cloud[13].getVector3fMap() << 0.7810401372209808, -1.0705732580035723,
+      2.305065186549668;
+  cloud[14].getVector3fMap() << 0.9062603270739178, -1.0815748767074063,
+      2.785726514647834;
+  cloud[15].getVector3fMap() << 1.3832157146170436, -1.0790593653653633,
+      3.546265907749163;
+  cloud[16].getVector3fMap() << 2.040614544849421, -1.0918678466867353,
+      4.015855816881193;
+  cloud[17].getVector3fMap() << 2.274098663746168, -1.0273778393320356,
+      4.128098505334945;
+  cloud[18].getVector3fMap() << 1.2518457008499417, -1.0912889870169762,
+      3.38890936771287;
+  cloud[19].getVector3fMap() << 0.8773148573186607, -1.026298817514791,
+      2.7419351335271855;
+  cloud[20].getVector3fMap() << 2.460972277763233, -1.0874470683716413,
+      4.168209147029958;
+  cloud[21].getVector3fMap() << 2.326091552875379, -1.0983984335719184,
+      4.125546904328003;
+  cloud[22].getVector3fMap() << 2.0996991277329786, -1.0707210059905774,
+      4.050880542671691;
+  cloud[23].getVector3fMap() << 0.95831333743683, -1.061687690479444,
+      2.9269785200505813;
+  cloud[24].getVector3fMap() << 2.0588703194976024, -1.0025516869353353,
+      4.043701622831673;
+  normals[0].getNormalVector3fMap() << -0.6776646502188018, -0.2278353266150415,
+      0.6991864456566977;
+  normals[1].getNormalVector3fMap() << -0.6264981002776666, -0.04285270066264479,
+      0.7782440339600377;
+  normals[2].getNormalVector3fMap() << -0.8972132050327152, -0.4381527971259608,
+      0.05505080458648829;
+  normals[3].getNormalVector3fMap() << -0.32813125795357256, -0.2851592909303272,
+      0.9005631884270638;
+  normals[4].getNormalVector3fMap() << -0.6799645795137096, -0.10497538222537117,
+      0.7256916285402369;
+  normals[5].getNormalVector3fMap() << -0.8324065340358171, -0.15285594400989705,
+      0.5326672718267207;
+  normals[6].getNormalVector3fMap() << -0.5919262688649901, -0.2347396219435707,
+      0.7710516209161101;
+  normals[7].getNormalVector3fMap() << -0.07514704519204393, -0.4962084968749015,
+      0.8649451134193752;
+  normals[8].getNormalVector3fMap() << -0.11054456443635059, -0.387488116467167,
+      0.9152228465626854;
+  normals[9].getNormalVector3fMap() << -0.7604417087668234, -0.34458796832906313,
+      0.5504430394242827;
+  normals[10].getNormalVector3fMap() << -0.9040312337559508, -0.3742023746150035,
+      0.20664005232816324;
+  normals[11].getNormalVector3fMap() << -0.0176869745485768, -0.2627053339243488,
+      0.964713987904713;
+  normals[12].getNormalVector3fMap() << -0.5210086952913671, -0.25181933916444066,
+      0.8155592926658195;
+  normals[13].getNormalVector3fMap() << -0.950388588906301, -0.2822930320142894,
+      0.13066053020277188;
+  normals[14].getNormalVector3fMap() << -0.8850007317473024, -0.32629950682962533,
+      0.3321179559275326;
+  normals[15].getNormalVector3fMap() << -0.6856032449538655, -0.31623746146145426,
+      0.65569967094482;
+  normals[16].getNormalVector3fMap() << -0.3996678191380136, -0.36747138674694285,
+      0.8397799796778576;
+  normals[17].getNormalVector3fMap() << -0.3208968621888316, -0.10951135732814456,
+      0.9407616416784378;
+  normals[18].getNormalVector3fMap() << -0.728898292732006, -0.36515594806790613,
+      0.5791100175640165;
+  normals[19].getNormalVector3fMap() << -0.9387598943114375, -0.1051952700591645,
+      0.3281216481574453;
+  normals[20].getNormalVector3fMap() << -0.22602052518599647, -0.34978827348656716,
+      0.9091550395427244;
+  normals[21].getNormalVector3fMap() << -0.27783106746442193, -0.3935937342876755,
+      0.8762955382067529;
+  normals[22].getNormalVector3fMap() << -0.38553965278262686, -0.2828840239623112,
+      0.878257254521215;
+  normals[23].getNormalVector3fMap() << -0.8823896524250601, -0.24675076191777665,
+      0.4006277109564169;
+  normals[24].getNormalVector3fMap() << -0.4182604905252856, -0.010206747741342384,
+      0.908269775103241;
+
+  // 50% noise uniform [-2,2]
+  //
+  cloud[25].getVector3fMap() << 0.25023241635877147, 0.27654549396527894,
+      1.07955881369387;
+  cloud[26].getVector3fMap() << 1.5449856383148206, -0.46768009897289264,
+      -2.062172100500517;
+  cloud[27].getVector3fMap() << 2.068709384697231, -0.8995244010670893,
+      0.4472750119304405;
+  cloud[28].getVector3fMap() << -1.9703101501142217, 1.1677926799358453,
+      -1.0951161775500093;
+  cloud[29].getVector3fMap() << 1.5128012164196942, -0.3784790741317119,
+      1.9953141538660382;
+  cloud[30].getVector3fMap() << -1.7035274240520712, -0.040343373432154106,
+      -0.13506114362465782;
+  cloud[31].getVector3fMap() << 1.390301434734198, -1.0836155740357354,
+      1.3817400889837255;
+  cloud[32].getVector3fMap() << 0.6973526735174085, 1.4609265623041212,
+      0.3991283042562106;
+  cloud[33].getVector3fMap() << 0.4585644490692351, 1.8056826118986748,
+      1.1908087822224616;
+  cloud[34].getVector3fMap() << -1.899161354377058, -1.2250806902713103,
+      1.5135509588271026;
+  cloud[35].getVector3fMap() << 0.05728241071603746, -1.3140082682155136,
+      -1.6804780212669348;
+  cloud[36].getVector3fMap() << -0.5371089158049953, -0.02542717526439331,
+      -0.6188539490393421;
+  cloud[37].getVector3fMap() << -0.21842672967261145, 0.6528285340670843,
+      1.937369474575887;
+  cloud[38].getVector3fMap() << 1.6906916394191258, 1.6029527944840072,
+      1.3312465637845015;
+  cloud[39].getVector3fMap() << 0.3871457304584722, -0.7014470556575774,
+      -1.3686189094260588;
+  cloud[40].getVector3fMap() << 1.1287360826333366, -1.8859435547052814,
+      -0.1392786225318703;
+  cloud[41].getVector3fMap() << -0.8284092960915028, 1.0112260700590863,
+      -1.1937340633604672;
+  cloud[42].getVector3fMap() << 1.8440270354564277, -0.3703200026464992,
+      -1.5917391524525757;
+  cloud[43].getVector3fMap() << 0.02671922592530418, 1.7827062803768543,
+      0.22852714632858673;
+  cloud[44].getVector3fMap() << -1.5132468082647963, -1.3357890987499987,
+      -1.158617245205414;
+  cloud[45].getVector3fMap() << -1.1450583549521511, 1.45432498632732,
+      -2.095300144813141;
+  cloud[46].getVector3fMap() << 0.18809078359436793, -1.6008222007566066,
+      -1.9699784955663424;
+  cloud[47].getVector3fMap() << -1.1753993948548627, 1.5857927603987902,
+      0.14497327864750886;
+  cloud[48].getVector3fMap() << 1.121788740853686, -0.27095183911320286,
+      -0.12199102154089814;
+  cloud[49].getVector3fMap() << 0.768999145889063, -2.0309651709863434,
+      0.7930530394403963;
+  normals[25].getNormalVector3fMap() << -0.5835940349115277, 0.1757014210775822,
+      0.7928095692201251;
+  normals[26].getNormalVector3fMap() << -0.6960838602866861, -0.42094642891496487,
+      -0.5816110069729798;
+  normals[27].getNormalVector3fMap() << 0.255914777841287, 0.6279839361250196,
+      -0.7349447614966528;
+  normals[28].getNormalVector3fMap() << -0.6075736135140413, 0.1336509980609126,
+      -0.7829378742140479;
+  normals[29].getNormalVector3fMap() << -0.4983181083004855, 0.6669454154651717,
+      -0.5539520518328415;
+  normals[30].getNormalVector3fMap() << -0.7745671302471588, 0.5084406300820161,
+      -0.37620989676307437;
+  normals[31].getNormalVector3fMap() << -0.424778132583581, -0.3243720781494619,
+      0.8451900928168792;
+  normals[32].getNormalVector3fMap() << -0.5821055941507861, 0.35171580987235973,
+      0.73310917764286;
+  normals[33].getNormalVector3fMap() << 0.8396655225180351, -0.48303927894460474,
+      0.2482637011147448;
+  normals[34].getNormalVector3fMap() << 0.256742174797301, 0.7352345686595317,
+      0.6273066114177216;
+  normals[35].getNormalVector3fMap() << -0.0652239383938407, -0.5360244339035914,
+      0.8416790624214975;
+  normals[36].getNormalVector3fMap() << 0.6702382164209467, -0.3031905309377628,
+      0.6773892789220579;
+  normals[37].getNormalVector3fMap() << -0.6040272704362459, -0.10302003040831528,
+      -0.7902771222197995;
+  normals[38].getNormalVector3fMap() << 0.9983521281387145, 0.041967677271189614,
+      -0.03913747954788317;
+  normals[39].getNormalVector3fMap() << -0.573664090993926, 0.46793032429526715,
+      0.6722728034875713;
+  normals[40].getNormalVector3fMap() << -0.5945467180061245, -0.48897233716525434,
+      -0.6382948014791401;
+  normals[41].getNormalVector3fMap() << 0.11334045761805764, -0.6164053590067436,
+      0.7792293462483921;
+  normals[42].getNormalVector3fMap() << -0.766256491311007, 0.13240541094009678,
+      -0.6287446196012567;
+  normals[43].getNormalVector3fMap() << 0.43564165550696804, 0.7816025130800787,
+      0.4464458080596722;
+  normals[44].getNormalVector3fMap() << 0.7597220695940338, -0.5120511261307517,
+      -0.4007817625591101;
+  normals[45].getNormalVector3fMap() << -0.6597147170804349, -0.27171235425320656,
+      -0.7006774497681952;
+  normals[46].getNormalVector3fMap() << -0.14344953607996272, 0.06349058786868034,
+      -0.9876189426345229;
+  normals[47].getNormalVector3fMap() << 0.2696193746529791, 0.8928064202811087,
+      -0.36083526534496174;
+  normals[48].getNormalVector3fMap() << 0.5473019047514905, 0.29388155846326774,
+      -0.7836416621457739;
+  normals[49].getNormalVector3fMap() << 0.053697689135186716, 0.05924709269452209,
+      -0.9967980438327452;
+
+  SampleConsensusModelTorus<PointXYZ, Normal>::Ptr model(
+      new SampleConsensusModelTorus<PointXYZ, Normal>(cloud.makeShared()));
+
+  model->setInputNormals(normals.makeShared());
+
+  // Create the RANSAC object
+  // Small threshold to filter out the numerous outliers
+  RandomSampleConsensus<PointXYZ> sac(model, 0.001);
+
+  // Algorithm tests
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
+
+  pcl::Indices sample;
+  sac.getModel(sample);
+  EXPECT_EQ(4, sample.size());
+  pcl::Indices inliers;
+  sac.getInliers(inliers);
+  EXPECT_EQ(25, inliers.size());
+
+  Eigen::VectorXf coeff;
+  sac.getModelCoefficients(coeff);
+
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 2, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[2], 3, 1e-2);
+  EXPECT_NEAR(coeff[3], -1, 1e-2);
+  EXPECT_NEAR(coeff[4], 2, 1e-2);
+  EXPECT_NEAR(coeff[5], 0.0, 1e-2);
+  EXPECT_NEAR(std::abs(coeff[6]), 1.0, 1e-2);
+  EXPECT_NEAR(coeff[7], 0.0, 1e-2);
+  Eigen::VectorXf coeff_refined;
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 2, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[2], 3, 1e-2);
+  EXPECT_NEAR(coeff[3], -1, 1e-2);
+  EXPECT_NEAR(coeff[4], 2, 1e-2);
+  EXPECT_NEAR(coeff[5], 0.0, 1e-2);
+  EXPECT_NEAR(std::abs(coeff[6]), 1.0, 1e-2);
+  EXPECT_NEAR(coeff[7], 2.220446049250313e-16, 1e-2);
+}
+
+// A horn shaped torus
+TEST(SampleConsensusModelTorusHorn, RANSAC)
+{
+
+  srand(0);
+
+  PointCloud<PointXYZ> cloud;
+  PointCloud<Normal> normals;
+
+  cloud.resize(7);
+  normals.resize(7);
+
+  cloud[0].getVector3fMap() << 3.000501648262739, -1.0005866141772064,
+      2.0196299263944386;
+  cloud[1].getVector3fMap() << 2.9306387358067587, -0.9355559306559758,
+      1.804104008927194;
+  cloud[2].getVector3fMap() << 3.1148967392352143, -1.3928055353556932,
+      2.1927039488583757;
+  cloud[3].getVector3fMap() << 3.0736420787608285, -0.8370133320562925,
+      1.7603380061176133;
+  cloud[4].getVector3fMap() << 2.88008899080742, -1.245300517665885, 1.7510639730129496;
+  cloud[5].getVector3fMap() << 3.0000040500927305, -1.0005041529688534,
+      2.0158691660694794;
+  cloud[6].getVector3fMap() << 2.983210284063484, -0.5044792022516073,
+      2.0456050860401795;
+  normals[0].getNormalVector3fMap() << -0.6479150922982518, 0.7576547294171206,
+      0.07851970557775474;
+  normals[1].getNormalVector3fMap() << 0.45515258767393824, -0.4228856734855979,
+      -0.783583964291224;
+  normals[2].getNormalVector3fMap() << 0.17884740355312917, -0.6114381536611204,
+      0.7708157954335032;
+  normals[3].getNormalVector3fMap() << -0.11718185523562125, -0.2593500950773666,
+      -0.958647975529547;
+  normals[4].getNormalVector3fMap() << -0.04047436729113163, -0.08279792919404502,
+      -0.995744107948202;
+  normals[5].getNormalVector3fMap() << -0.008017000458096018, 0.9979511214462377,
+      0.06347666427791779;
+  normals[6].getNormalVector3fMap() << -0.03329532756428898, 0.9826567250055698,
+      0.18242034416071792;
+
+  SampleConsensusModelTorus<PointXYZ, Normal>::Ptr model(
+      new SampleConsensusModelTorus<PointXYZ, Normal>(cloud.makeShared()));
+
+  model->setInputNormals(normals.makeShared());
+
+  // Create the RANSAC object
+  RandomSampleConsensus<PointXYZ> sac(model, 0.2);
+
+  // Algorithm tests
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
+
+  pcl::Indices sample;
+  sac.getModel(sample);
+  EXPECT_EQ(4, sample.size());
+  pcl::Indices inliers;
+  sac.getInliers(inliers);
+  EXPECT_EQ(7, inliers.size());
+
+  Eigen::VectorXf coeff;
+  sac.getModelCoefficients(coeff);
+
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[2], 3, 1e-2);
+  EXPECT_NEAR(coeff[3], -1, 1e-2);
+  EXPECT_NEAR(coeff[4], 2, 1e-2);
+  EXPECT_NEAR(coeff[5], 0.0, 1e-2);
+  EXPECT_NEAR(coeff[6], 0.0, 1e-2);
+  EXPECT_NEAR(std::abs(coeff[7]), 1.0, 1e-2);
+  return;
+
+  Eigen::VectorXf coeff_refined;
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[2], 3, 1e-2);
+  EXPECT_NEAR(coeff[3], -1, 1e-2);
+  EXPECT_NEAR(coeff[4], 2, 1e-2);
+  EXPECT_NEAR(coeff[5], 0.0, 1e-2);
+  EXPECT_NEAR(coeff[6], 0.0, 1e-2);
+  EXPECT_NEAR(coeff[7], 1.0, 1e-2);
+}
+
+TEST(SampleConsensusModelTorusRefine, RANSAC)
+{
+
+  srand(0);
+
+  PointCloud<PointXYZ> cloud;
+  PointCloud<Normal> normals;
+
+  cloud.resize(12);
+  normals.resize(12);
+
+  cloud[0].getVector3fMap() << 2.052800042174215, -1.499473956010903, 2.5922393000558;
+  cloud[1].getVector3fMap() << 3.388588815443773, -0.2804951689253241,
+      2.016023579560368;
+  cloud[2].getVector3fMap() << 2.1062433380708585, -1.9174254209231951,
+      2.2138169934854175;
+  cloud[3].getVector3fMap() << 2.9741032000482, -1.0699765160210948, 1.2784833859363935;
+  cloud[4].getVector3fMap() << 3.9945837837405858, -0.24398838472758466,
+      1.994969222832288;
+  cloud[5].getVector3fMap() << 3.29052359025732, -0.7052701711244429,
+      1.4026501046485196;
+  cloud[6].getVector3fMap() << 3.253762467235399, -1.2666426752546665,
+      1.2533731806961965;
+  cloud[7].getVector3fMap() << 2.793231427168476, -1.406941876180895, 2.914835409806976;
+  cloud[8].getVector3fMap() << 3.427656537026421, -0.3921726018138755,
+      1.1167321991754167;
+  cloud[9].getVector3fMap() << 3.45310885872988, -1.187857062974888, 0.9128847947344318;
+
+  normals[0].getNormalVector3fMap() << -0.9655752892034741, 0.13480487505578329,
+      0.22246798992399325;
+  normals[1].getNormalVector3fMap() << -0.9835035116470829, -0.02321732676535275,
+      -0.17939286026965295;
+  normals[2].getNormalVector3fMap() << -0.6228348353863176, -0.7614744633300792,
+      0.17953665231775656;
+  normals[3].getNormalVector3fMap() << -0.3027649706212169, 0.4167626949130777,
+      0.8571127281131243;
+  normals[4].getNormalVector3fMap() << 0.9865410652838972, 0.13739803967452247,
+      0.08864821037173687;
+  normals[5].getNormalVector3fMap() << -0.723213640950708, -0.05078427284613152,
+      0.688754663994597;
+  normals[6].getNormalVector3fMap() << 0.4519195477489684, -0.4187464441250127,
+      0.7876675300499734;
+  normals[7].getNormalVector3fMap() << 0.7370319397802214, -0.6656659398898118,
+      0.11693064702813241;
+  normals[8].getNormalVector3fMap() << -0.4226770542031876, 0.7762818780175667,
+      -0.4676863839279862;
+  normals[9].getNormalVector3fMap() << 0.720025487985072, -0.5768131803911037,
+      -0.38581064212766236;
+
+  // Uniform noise between -0.1 and 0.1
+  cloud[0].getVector3fMap() += Eigen::Vector3f(-0.02519484, 0.03325529, 0.09188957);
+  cloud[1].getVector3fMap() += Eigen::Vector3f(0.06969781, -0.06921317, -0.07229406);
+  cloud[2].getVector3fMap() += Eigen::Vector3f(-0.00064637, -0.00231905, -0.0080026);
+  cloud[3].getVector3fMap() += Eigen::Vector3f(0.05039557, -0.0229141, 0.0594657);
+  cloud[4].getVector3fMap() += Eigen::Vector3f(-0.05717322, -0.09670288, 0.00176189);
+  cloud[5].getVector3fMap() += Eigen::Vector3f(0.02668492, -0.06824032, 0.05790168);
+  cloud[6].getVector3fMap() += Eigen::Vector3f(0.07829713, 0.06426746, 0.04172692);
+  cloud[7].getVector3fMap() += Eigen::Vector3f(0.0006326, -0.02518951, -0.00927858);
+  cloud[8].getVector3fMap() += Eigen::Vector3f(-0.04975343, 0.09912357, -0.04233801);
+  cloud[9].getVector3fMap() += Eigen::Vector3f(-0.04810247, 0.03382804, 0.07958129);
+
+  // Outliers
+  cloud[10].getVector3fMap() << 5, 1, 1;
+  cloud[11].getVector3fMap() << 5, 2, 1;
+
+  normals[10].getNormalVector3fMap() << 1, 0, 0;
+  normals[11].getNormalVector3fMap() << 1, 0, 0;
+
+  SampleConsensusModelTorus<PointXYZ, Normal>::Ptr model(
+      new SampleConsensusModelTorus<PointXYZ, Normal>(cloud.makeShared()));
+
+  model->setInputNormals(normals.makeShared());
+
+  // Create the RANSAC object
+  RandomSampleConsensus<PointXYZ> sac(model, 0.2);
+
+  // Algorithm tests
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
+
+  pcl::Indices sample;
+  sac.getModel(sample);
+  EXPECT_EQ(4, sample.size());
+  pcl::Indices inliers;
+  sac.getInliers(inliers);
+  EXPECT_EQ(10, inliers.size());
+
+  Eigen::VectorXf coeff;
+  sac.getModelCoefficients(coeff);
+
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 1, 2e-1);
+  EXPECT_NEAR(coeff[1], 0.3, 2e-1);
+  EXPECT_NEAR(coeff[2], 3, 2e-1);
+  EXPECT_NEAR(coeff[3], -1, 2e-1);
+  EXPECT_NEAR(coeff[4], 2, 2e-1);
+
+  if (coeff[5] < 0){
+    coeff[5] *= -1.0;
+    coeff[6] *= -1.0;
+    coeff[7] *= -1.0;
+  }
+
+  EXPECT_NEAR(coeff[5], 0.7071067811865476, 2e-1);
+  EXPECT_NEAR(coeff[6], -0.6830127018922194, 2e-1);
+  EXPECT_NEAR(coeff[7], 0.1830127018922194, 2e-1);
+
+  Eigen::VectorXf coeff_refined(8);
+  return;
+
+  // Optimize goes from 2e-1 to 1e-1
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 1, 1e-1);
+  EXPECT_NEAR(coeff[1], 0.3, 1e-1);
+  EXPECT_NEAR(coeff[2], 3, 1e-1);
+  EXPECT_NEAR(coeff[3], -1, 1e-1);
+  EXPECT_NEAR(coeff[4], 2, 1e-1);
+  EXPECT_NEAR(coeff[5], 0.7071067811865476, 1e-1);
+  EXPECT_NEAR(coeff[6], -0.6830127018922194, 1e-1);
+  EXPECT_NEAR(coeff[7], 0.1830127018922194, 1e-1);
+}
+
+TEST(SampleConsensusModelTorus, RANSAC)
+{
+  srand(0);
+
+  PointCloud<PointXYZ> cloud;
+  PointCloud<Normal> normals;
+
+  cloud.resize(4);
+  normals.resize(4);
+
+  cloud[0].getVector3fMap() << 8.359341574088198, 7.22552693060636, 5.4049978066219575;
+  cloud[1].getVector3fMap() << 7.777710489873524, 6.9794499622227635, 5.96264148630509;
+  cloud[2].getVector3fMap() << 7.578062528900397, 8.466627338184125, 6.764936180563802;
+  cloud[3].getVector3fMap() << 6.8073801963063225, 6.950495936581675,
+      6.5682651621988140636;
+
+  normals[0].getNormalVector3fMap() << 0.78726775, -0.60899961, -0.09658657;
+  normals[1].getNormalVector3fMap() << 0.66500173, 0.11532684, 0.73788374;
+  normals[2].getNormalVector3fMap() << -0.58453172, 0.0233942, -0.81103353;
+  normals[3].getNormalVector3fMap() << -0.92017329, -0.39125533, 0.01415573;
+
+  // Create a shared 3d torus model pointer directly
+  SampleConsensusModelTorus<PointXYZ, Normal>::Ptr model(
+      new SampleConsensusModelTorus<PointXYZ, Normal>(cloud.makeShared()));
+  model->setInputNormals(normals.makeShared());
+
+  // Create the RANSAC object
+  RandomSampleConsensus<PointXYZ> sac(model, 0.11);
+
+  // Algorithm tests
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
+
+  pcl::Indices sample;
+  sac.getModel(sample);
+  EXPECT_EQ(4, sample.size());
+  pcl::Indices inliers;
+  sac.getInliers(inliers);
+  EXPECT_EQ(4, inliers.size());
+
+  Eigen::VectorXf coeff;
+  sac.getModelCoefficients(coeff);
+
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 1, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.3, 1e-2);
+
+  EXPECT_NEAR(coeff[2], 7.758357590948854, 1e-2);
+  EXPECT_NEAR(coeff[3], 7.756009480304242, 1e-2);
+  EXPECT_NEAR(coeff[4], 6.297666724054506, 1e-2);
+
+  EXPECT_NEAR(coeff[5], 0.7071067811865475, 1e-2);
+  EXPECT_NEAR(coeff[6], -0.5, 1e-2);
+  EXPECT_NEAR(coeff[7], 0.5, 1e-2);
+
+  Eigen::VectorXf coeff_refined;
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(8, coeff.size());
+
+  EXPECT_NEAR(coeff[0], 1, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.3, 1e-2);
+
+  EXPECT_NEAR(coeff[2], 7.758357590948854, 1e-2);
+  EXPECT_NEAR(coeff[3], 7.756009480304242, 1e-2);
+  EXPECT_NEAR(coeff[4], 6.297666724054506, 1e-2);
+
+  if (coeff[5] < 0){
+    coeff[5] *= -1.0;
+    coeff[6] *= -1.0;
+    coeff[7] *= -1.0;
+  }
+
+  EXPECT_NEAR(coeff[5], 0.7071067811865475, 1e-2);
+  EXPECT_NEAR(coeff[6], -0.5, 1e-2);
+  EXPECT_NEAR(coeff[7], 0.5, 1e-2);
+}
+
+TEST(SampleConsensusModelTorusSelfIntersectSpindle, RANSAC)
 {
-  testing::InitGoogleTest (&argc, argv);
-  return (RUN_ALL_TESTS ());
+  srand(0);
+
+  PointCloud<PointXYZ> cloud;
+  PointCloud<Normal> normals;
+
+  cloud.resize(15);
+  normals.resize(15);
+
+  cloud[0].getVector3fMap() << 4.197443296388562, -2.244178951074561,
+      2.6544058976891054;
+  cloud[1].getVector3fMap() << 3.9469472011448596, -2.2109428683077716,
+      1.8207364262436627;
+  cloud[2].getVector3fMap() << 4.036997360721013, -1.9837065514073593, 2.88062697126334;
+  cloud[3].getVector3fMap() << 4.554241490476904, -1.8200324440442106,
+      2.242830580711606;
+  cloud[4].getVector3fMap() << 3.9088172351876764, -1.7982235216273337,
+      2.268412990083617;
+  cloud[5].getVector3fMap() << 3.842480541291084, -1.8025598756948282,
+      2.2527669926394016;
+  cloud[6].getVector3fMap() << 4.3496726790753755, -2.2441275500858833,
+      2.239055754148472;
+  cloud[7].getVector3fMap() << 4.52235090070925, -1.7373785296059916, 2.466177376096933;
+  cloud[8].getVector3fMap() << 3.7710839801895077, -1.7082589118588576,
+      2.393963290485919;
+  cloud[9].getVector3fMap() << 4.068180803015269, -1.3503789464621836,
+      2.3423326381708147;
+  cloud[10].getVector3fMap() << 3.873973067071098, -1.7135016016729774,
+      2.2124191518411247;
+  cloud[11].getVector3fMap() << 4.390758174759903, -2.171435874256942,
+      2.214023036691005;
+  cloud[12].getVector3fMap() << 4.324106983802413, -1.3650663408422128,
+      2.453692863759843;
+  cloud[13].getVector3fMap() << 4.345401269961894, -2.0286148560415813,
+      2.456689045210522;
+  cloud[14].getVector3fMap() << 4.31528844186095, -2.0083582606580292,
+      2.367720270538135;
+  normals[0].getNormalVector3fMap() << 0.6131882081326164, -0.6055955130301103,
+      0.5072024211347066;
+  normals[1].getNormalVector3fMap() << -0.37431625455633444, -0.44239562607541916,
+      -0.8149683746037361;
+  normals[2].getNormalVector3fMap() << 0.03426300530560111, -0.20348141751799728,
+      0.9784791051383237;
+  normals[3].getNormalVector3fMap() << 0.940856493913579, -0.2960809146555105,
+      0.1646971458083096;
+  normals[4].getNormalVector3fMap() << -0.6286552509632886, 0.5146645236295431,
+      0.5830205858745127;
+  normals[5].getNormalVector3fMap() << -0.3871040511550286, 0.724048220462587,
+      -0.5708805724705703;
+  normals[6].getNormalVector3fMap() << 0.8666661368649906, -0.43068753570421703,
+      0.25178970153789454;
+  normals[7].getNormalVector3fMap() << 0.9362467937507173, -0.17430389316386408,
+      0.30505752575444156;
+  normals[8].getNormalVector3fMap() << -0.8229596731853971, 0.3855286394843701,
+      -0.4172589656890726;
+  normals[9].getNormalVector3fMap() << -0.36653063101311856, 0.9297937437536523,
+      -0.033747453321582466;
+  normals[10].getNormalVector3fMap() << -0.9907072431684454, -0.07717115427192464,
+      -0.11199897893247729;
+  normals[11].getNormalVector3fMap() << 0.8661927924780622, -0.3669697390799624,
+      0.3391802719184018;
+  normals[12].getNormalVector3fMap() << 0.3744106777049837, 0.8911051835726027,
+      0.25641411082569643;
+  normals[13].getNormalVector3fMap() << 0.8809879144326921, -0.4062669413039098,
+      -0.2425025093212462;
+  normals[14].getNormalVector3fMap() << 0.8117975834319093, -0.31266565300418725,
+      -0.49317833789165666;
+
+  // Create a shared 3d torus model pointer directly
+  SampleConsensusModelTorus<PointXYZ, Normal>::Ptr model(
+      new SampleConsensusModelTorus<PointXYZ, Normal>(cloud.makeShared()));
+  model->setInputNormals(normals.makeShared());
+
+  // Create the RANSAC object
+  RandomSampleConsensus<PointXYZ> sac(model, 0.11);
+
+  // Algorithm tests
+  bool result = sac.computeModel();
+  ASSERT_TRUE(result);
+
+  pcl::Indices sample;
+  sac.getModel(sample);
+  EXPECT_EQ(4, sample.size());
+  pcl::Indices inliers;
+  sac.getInliers(inliers);
+  EXPECT_EQ(15, inliers.size());
+
+  Eigen::VectorXf coeff;
+  sac.getModelCoefficients(coeff);
+
+  EXPECT_EQ(8, coeff.size());
+  EXPECT_NEAR(coeff[0], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.35, 1e-2);
+  EXPECT_NEAR(coeff[2], 4.1, 1e-2);
+  EXPECT_NEAR(coeff[3], -1.9, 1e-2);
+  EXPECT_NEAR(coeff[4], 2.3, 1e-2);
+  EXPECT_NEAR(coeff[5], 0.8660254037844385, 1e-2);
+  EXPECT_NEAR(coeff[6], -0.4330127018922194, 1e-2);
+  EXPECT_NEAR(coeff[7], 0.25000000000000017, 1e-2);
+
+  Eigen::VectorXf coeff_refined;
+  model->optimizeModelCoefficients(inliers, coeff, coeff_refined);
+  EXPECT_EQ(8, coeff.size());
+  EXPECT_NEAR(coeff[0], 0.25, 1e-2);
+  EXPECT_NEAR(coeff[1], 0.35, 1e-2);
+  EXPECT_NEAR(coeff[2], 4.1, 1e-2);
+  EXPECT_NEAR(coeff[3], -1.9, 1e-2);
+  EXPECT_NEAR(coeff[4], 2.3, 1e-2);
+
+  if (coeff[5] < 0){
+    coeff[5] *= -1.0;
+    coeff[6] *= -1.0;
+    coeff[7] *= -1.0;
+  }
+
+  EXPECT_NEAR(coeff[5], 0.8660254037844385, 1e-2);
+  EXPECT_NEAR(coeff[6], -0.4330127018922194, 1e-2);
+  EXPECT_NEAR(coeff[7], 0.25000000000000017, 1e-2);
 }
 
+int
+main(int argc, char** argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  return (RUN_ALL_TESTS());
+}
index be1e13814c4de49073b125c9311ebbd9a07a01a8..22f950078380a6e7774768869661600bfd687a68 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library search module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS search)
 set(OPT_DEPS io)
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index 32dca5863138478e69877fbaaee61d92429ccc75..3445468e187ea9a0c54fc14ca7c3e53795191048 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library segmentation module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS segmentation)
 set(OPT_DEPS) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
@@ -22,6 +20,10 @@ PCL_ADD_TEST(a_segmentation_test test_segmentation
              LINK_WITH pcl_gtest pcl_io pcl_segmentation pcl_features pcl_kdtree pcl_search pcl_common
              ARGUMENTS "${PCL_SOURCE_DIR}/test/bun0.pcd" "${PCL_SOURCE_DIR}/test/car6.pcd" "${PCL_SOURCE_DIR}/test/colored_cloud.pcd")
 
+PCL_ADD_TEST(a_prism_test test_concave_prism
+             FILES test_concave_prism.cpp
+             LINK_WITH pcl_gtest pcl_segmentation pcl_common)
+
 PCL_ADD_TEST(test_non_linear test_non_linear
              FILES test_non_linear.cpp
              LINK_WITH pcl_gtest pcl_common pcl_io pcl_sample_consensus pcl_segmentation pcl_kdtree pcl_search
diff --git a/test/segmentation/test_concave_prism.cpp b/test/segmentation/test_concave_prism.cpp
new file mode 100644 (file)
index 0000000..10ab894
--- /dev/null
@@ -0,0 +1,92 @@
+#include <pcl/test/gtest.h>
+#include <pcl/point_types.h>
+#include <pcl/point_cloud.h>
+
+#include <pcl/segmentation/extract_polygonal_prism_data.h>
+
+#include <random>
+
+using namespace pcl;
+using std::vector;
+
+TEST(ExtractPolygonalPrism, two_rings)
+{
+  float rMin = 0.1, rMax = 0.25f;
+  float dx = 0.5f; // shift the rings from [0,0,0] to [+/-dx, 0, 0]
+
+  // prepare 2 rings
+  PointCloud<PointXYZ>::Ptr ring(new PointCloud<PointXYZ>);
+  { // use random
+    std::random_device rd;
+    std::mt19937 gen(rd());
+    std::uniform_real_distribution<float> radiusDist(rMin, rMax);
+    std::uniform_real_distribution<float> radianDist(-M_PI, M_PI);
+    std::uniform_real_distribution<float> zDist(-0.01f, 0.01f);
+    for (size_t i = 0; i < 1000; i++) {
+      float radius = radiusDist(gen);
+      float angle = radianDist(gen);
+      float z = zDist(gen);
+      PointXYZ point(cosf(angle) * radius, sinf(angle) * radius, z);
+      ring->push_back(point);
+    }
+  }
+
+  PointCloud<PointXYZ>::Ptr cloud(new PointCloud<PointXYZ>);
+  cloud->reserve(ring->size() * 2);
+  for (auto& point : ring->points) {
+    auto left = point;
+    auto right = point;
+    left.x -= dx;
+    right.x += dx;
+    cloud->push_back(left);
+    cloud->push_back(right);
+  }
+
+  // create hull
+  PointCloud<PointXYZ>::Ptr hullCloud(new PointCloud<PointXYZ>);
+  vector<Vertices> rings(4);
+  float radiuses[] = {rMin - 0.01f, rMax + 0.01f, rMin - 0.01f, rMax + 0.01f};
+  float centers[] = {-dx, -dx, +dx, +dx};
+  for (size_t i = 0; i < rings.size(); i++) {
+    auto r = radiuses[i];
+    auto xCenter = centers[i];
+    for (float a = -M_PI; a < M_PI; a += 0.05f) {
+      rings[i].vertices.push_back(hullCloud->size());
+      PointXYZ point(xCenter + r * cosf(a), r * sinf(a), 0);
+      hullCloud->push_back(point);
+    }
+  }
+
+  // add more points before using prism
+  size_t ringsPointCount = cloud->size();
+  cloud->push_back(PointXYZ(0, 0, 0));
+  for (float a = -M_PI; a < M_PI; a += 0.05f) {
+    float r = 4 * rMax;
+    PointXYZ point(r * cosf(a), r * sinf(a), 0);
+    cloud->push_back(point);
+  }
+
+  // do prism
+  PointIndices::Ptr inliers(new PointIndices);
+  ExtractPolygonalPrismData<PointXYZ> ex;
+  {
+    ex.setInputCloud(cloud);
+    ex.setInputPlanarHull(hullCloud);
+    ex.setHeightLimits(-1, 1);
+    ex.setPolygons(rings);
+    ex.segment(*inliers);
+  }
+
+  // check that all of the rings are in the prism.
+  EXPECT_EQ(inliers->indices.size(), ringsPointCount);
+  for(std::size_t i=0; i<inliers->indices.size(); ++i) {
+    EXPECT_EQ(inliers->indices[i], i);
+  }
+}
+
+int
+main(int argc, char** argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  return (RUN_ALL_TESTS());
+}
index f565dd27af7cc7c8bc4b70485729bb19e875d163..d02a5103808d226e026d5f94d6c1d40a8953a5aa 100644 (file)
@@ -417,7 +417,7 @@ main (int argc, char** argv)
     return (-1);
   }
 
-  // Tranpose the cloud
+  // Transpose the cloud
   cloud_t_.reset(new PointCloud<PointXYZ>);
   *cloud_t_ = *cloud_;
   for (auto& point: *cloud_t_)
index 3abd8c60fbcb07782487c8b5e38f355a2185f6d9..7c01b28a663855040c1cd5465a919e0b068ecfe6 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library surface module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS surface)
 set(OPT_DEPS io features sample_consensus filters) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT (build AND BUILD_io AND BUILD_features))
index c02630ecdb20a18d376fc17c84ba2acdad4e4afb..ae3a0e401597c98527c5f31e9052b684dcfa80cb 100644 (file)
@@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library visualization module unit tests")
 PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS visualization)
 set(OPT_DEPS features) # module does not depend on these
 
-set(DEFAULT ON)
-set(build TRUE)
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS})
 
 if(NOT build)
index a4151e9c2d4378edcdb3807b8f55c081a7d055e2..dd1f34f9912d3146f29ac27e2b33793da9552fed 100644 (file)
@@ -2,10 +2,8 @@ set(SUBSYS_NAME tools)
 set(SUBSYS_DESC "Useful PCL-based command line tools")
 set(SUBSYS_DEPS io)
 set(SUBSYS_OPT_DEPS filters sample_consensus segmentation search kdtree features surface octree registration recognition geometry keypoints ml visualization vtk)
-set(DEFAULT ON)
-set(REASON "")
 
-PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ${DEFAULT} ${REASON})
+PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${SUBSYS_OPT_DEPS})
 
 if(NOT build)
@@ -186,6 +184,8 @@ if(TARGET pcl_filters)
     PCL_ADD_EXECUTABLE(pcl_mls_smoothing COMPONENT ${SUBSYS_NAME} SOURCES mls_smoothing.cpp)
     target_link_libraries (pcl_mls_smoothing pcl_common pcl_io pcl_surface pcl_filters)
 
+    PCL_ADD_EXECUTABLE(pcl_bilateral_upsampling COMPONENT ${SUBSYS_NAME} SOURCES bilateral_upsampling.cpp)
+    target_link_libraries(pcl_bilateral_upsampling pcl_common pcl_io pcl_surface)
   endif()
 
   if(TARGET pcl_keypoints)
index f4d61d8b2cf3827f1c7f964502b6c9674a24e3da..600af41e2f1921b29071aae86973e0da67638127 100644 (file)
@@ -67,7 +67,7 @@ printHelp (int, char **argv)
   print_value ("%d", default_min); print_info (")\n");
   print_info ("                     -max X      = use a maximum of X points peer cluster (default: ");
   print_value ("%d", default_max); print_info (")\n");
-  print_info ("                     -tolerance X = the spacial distance between clusters (default: ");
+  print_info ("                     -tolerance X = the spatial distance between clusters (default: ");
   print_value ("%lf", default_tolerance); print_info (")\n");
 }
 
index dd155ec41c9ba9e6d59abd08c9a3a427eb717d96..89ef59c7677cbf6453c7c62c6a773597a1d2533d 100644 (file)
 
 #include <vector>
 
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/io/auto_io.h>
 #include <pcl/io/obj_io.h>
 #include <pcl/io/vtk_lib_io.h>
 #include <pcl/memory.h>  // for pcl::make_shared
 
-#include <boost/filesystem.hpp>  // for boost::filesystem::path
 #include <boost/algorithm/string.hpp>  // for boost::algorithm::ends_with
 
 #define ASCII 0
@@ -103,7 +103,7 @@ savePointCloud (const pcl::PCLPointCloud2::Ptr& input,
                 std::string output_file,
                 int output_type)
 {
-  if (boost::filesystem::path (output_file).extension () == ".pcd")
+  if (pcl_fs::path (output_file).extension () == ".pcd")
   {
     //TODO Support precision, origin, orientation
     pcl::PCDWriter w;
@@ -126,7 +126,7 @@ savePointCloud (const pcl::PCLPointCloud2::Ptr& input,
         return (false);
     }
   }
-  else if (boost::filesystem::path (output_file).extension () == ".stl")
+  else if (pcl_fs::path (output_file).extension () == ".stl")
   {
     PCL_ERROR ("STL file format does not support point clouds! Aborting.\n");
     return (false);
@@ -156,7 +156,7 @@ saveMesh (pcl::PolygonMesh& input,
           std::string output_file,
           int output_type)
 {
-  if (boost::filesystem::path (output_file).extension () == ".obj")
+  if (pcl_fs::path (output_file).extension () == ".obj")
   {
     if (output_type == BINARY || output_type == BINARY_COMPRESSED)
       PCL_WARN ("OBJ file format only supports ASCII.\n");
@@ -167,7 +167,7 @@ saveMesh (pcl::PolygonMesh& input,
     if (pcl::io::saveOBJFile (output_file, input) != 0)
       return (false);
   }
-  else if (boost::filesystem::path (output_file).extension () == ".pcd")
+  else if (pcl_fs::path (output_file).extension () == ".pcd")
   {
     if (!input.polygons.empty ())
       PCL_WARN ("PCD file format does not support meshes! Only points be saved.\n");
@@ -180,7 +180,7 @@ saveMesh (pcl::PolygonMesh& input,
     if (output_type == BINARY_COMPRESSED)
       PCL_WARN ("PLY, STL and VTK file formats only supports ASCII and binary output file types.\n");
 
-    if (input.polygons.empty() && boost::filesystem::path (output_file).extension () == ".stl")
+    if (input.polygons.empty() && pcl_fs::path (output_file).extension () == ".stl")
     {
       PCL_ERROR ("STL file format does not support point clouds! Aborting.\n");
       return (false);
@@ -263,7 +263,7 @@ main (int argc,
 
   // Try to load as mesh
   pcl::PolygonMesh mesh;
-  if (boost::filesystem::path (argv[file_args[0]]).extension () != ".pcd" &&
+  if (pcl_fs::path (argv[file_args[0]]).extension () != ".pcd" &&
       pcl::io::loadPolygonFile (argv[file_args[0]], mesh) != 0)
   {
     PCL_INFO ("Loaded a mesh with %d points (total size is %d) and the following channels:\n%s\n",
@@ -275,7 +275,7 @@ main (int argc,
     if (!saveMesh (mesh, argv[file_args[1]], output_type))
       return (-1);
   }
-  else if (boost::filesystem::path (argv[file_args[0]]).extension () == ".stl")
+  else if (pcl_fs::path (argv[file_args[0]]).extension () == ".stl")
   {
     PCL_ERROR ("Unable to load %s.\n", argv[file_args[0]]);
     return (-1);
@@ -283,7 +283,7 @@ main (int argc,
   else
   {
     // PCD, OBJ, PLY or VTK
-    if (boost::filesystem::path (argv[file_args[0]]).extension () != ".pcd")
+    if (pcl_fs::path (argv[file_args[0]]).extension () != ".pcd")
       PCL_WARN ("Could not load %s as a mesh, trying as a point cloud instead.\n", argv[file_args[0]]);
 
     //Eigen::Vector4f origin; // TODO: Support origin/orientation
index e8e721955eef9cf6cf3f42a4cb46a64bd85d03f9..071f8ccbcfaac8c5c817b7ee9cc1de97a494ebb7 100644 (file)
@@ -126,7 +126,7 @@ main (int argc, char **argv)
   {
     CloudPtr pc (new Cloud);
     pcl::io::loadPCDFile (argv[pcd_indices[i]], *pc);
-    clouds.push_back (CloudPair (argv[pcd_indices[i]], pc));
+    clouds.emplace_back(argv[pcd_indices[i]], pc);
     std::cout << "loading file: " << argv[pcd_indices[i]] << " size: " << pc->size () << std::endl;
     elch.addPointCloud (clouds[i].second);
   }
index ff9d49544a30bdb38c5c6d6906f8d5568d95def5..09a653fad7fd273b3a83a248d8310373950a6186 100644 (file)
 #include <pcl/PCLPointCloud2.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/filters/fast_bilateral.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -131,7 +132,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, sigma_s, sigma_r);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_files[i]).filename().string();
+    std::string filename = pcl_fs::path(pcd_files[i]).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -203,11 +204,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index 1a5c2fa913aeaa4fc084664d7670211d7e5d68f0..5563864fdf2e4b5329a392b45499d7984ad36178 100644 (file)
 
 #include <pcl/point_types.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
 #include <pcl/filters/grid_minimum.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -129,7 +130,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, resolution);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_file).filename().string();
+    std::string filename = pcl_fs::path(pcd_file).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -195,11 +196,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index 1dab5d9230d81f346d9bab4e66961f6554b42048..8f89a8765dc56838d1f82b72e5f1f05bc8998cf1 100644 (file)
  *
  */
 #include <pcl/io/image_grabber.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/print.h>
 #include <pcl/io/pcd_io.h>
-#include <boost/filesystem.hpp> // for exists
 
 using pcl::console::print_error;
 using pcl::console::print_info;
@@ -108,7 +108,7 @@ main (int argc, char** argv)
 
   pcl::console::parse_argument (argc, argv, "-out_dir", out_folder);
 
-  if (out_folder.empty() || !boost::filesystem::exists (out_folder))
+  if (out_folder.empty() || !pcl_fs::exists (out_folder))
   {
     PCL_INFO("No correct directory was given with the -out_dir flag. Setting to current dir\n");
     out_folder = "./";
@@ -116,7 +116,7 @@ main (int argc, char** argv)
   else
     PCL_INFO("Using %s as output dir", out_folder.c_str());
 
-  if (!rgb_path.empty() && !depth_path.empty() && boost::filesystem::exists (rgb_path) && boost::filesystem::exists (depth_path))
+  if (!rgb_path.empty() && !depth_path.empty() && pcl_fs::exists (rgb_path) && pcl_fs::exists (depth_path))
   {
     grabber.reset (new pcl::ImageGrabber<pcl::PointXYZRGBA> (depth_path, rgb_path, frames_per_second, false));
   }
index 4cf45843fe14e984c3a9f18370d48757479185f8..3622cb4620dc4c8dc3b0d0ad9c2bba713776742b 100644 (file)
@@ -38,6 +38,7 @@
  */
 
 #include <pcl/io/image_grabber.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/print.h>
 #include <pcl/visualization/cloud_viewer.h>
@@ -45,7 +46,6 @@
 
 #include <mutex>
 #include <thread>
-#include <boost/filesystem.hpp> // for exists
 
 using namespace std::chrono_literals;
 using pcl::console::print_error;
@@ -197,7 +197,7 @@ main (int argc, char** argv)
   std::string path;
   pcl::console::parse_argument (argc, argv, "-dir", path);
   std::cout << "path: " << path << std::endl;
-  if (!path.empty() && boost::filesystem::exists (path))
+  if (!path.empty() && pcl_fs::exists (path))
   {
     grabber.reset (new pcl::ImageGrabber<pcl::PointXYZRGBA> (path, frames_per_second, repeat, use_pclzf));
   }
index 9a51397d1817a6bec12f433aa980b346c5827928..02c047b101b28d9cbf430f9c3c40cbb820cf923a 100644 (file)
@@ -58,7 +58,7 @@ main (int, char ** argv)
   depth_image_viewer_.showFloatImage (img, 
                                       xyz.width, xyz.height,
                                       std::numeric_limits<float>::min (), 
-                                      // Scale so that the colors look brigher on screen
+                                      // Scale so that the colors look brighter on screen
                                       std::numeric_limits<float>::max () / 10, 
                                       true);
   depth_image_viewer_.spin ();
index 665aee3759c008b28432bd1f9a3f03017c550245..d7035d01d0f62f33c98c0a6e806fbd8e0121fce6 100644 (file)
 
 #include <pcl/point_types.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
 #include <pcl/filters/local_maximum.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -130,7 +131,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, radius);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_file).filename().string();
+    std::string filename = pcl_fs::path(pcd_file).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -196,11 +197,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index e4f80f22811bd7233bab150fbf9fd7cc3d1bdbd3..3930e189bd87058c5d8e17fb59f667756e5c90f4 100644 (file)
@@ -85,7 +85,7 @@ main (int argc, char **argv)
   {
     CloudPtr pc (new Cloud);
     pcl::io::loadPCDFile (argv[pcd_indices[i]], *pc);
-    clouds.push_back (CloudPair (argv[pcd_indices[i]], pc));
+    clouds.emplace_back(argv[pcd_indices[i]], pc);
     std::cout << "loading file: " << argv[pcd_indices[i]] << " size: " << pc->size () << std::endl;
     lum.addPointCloud (clouds[i].second);
   }
index 7c33cdbd2faffe7873429ec169ff47a94c5fa604..0cd696d76da17c2797d8b213bc94917d142d2ee8 100644 (file)
 
 #include <pcl/point_types.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
 #include <pcl/filters/morphological_filter.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -151,7 +152,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, resolution, method);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_file).filename().string();
+    std::string filename = pcl_fs::path(pcd_file).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -219,11 +220,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index 149427c3d6818a9ec47a3b3848143f105e86c623..51baec2e8d222fcbb9c65917d638c1f198c74b5f 100644 (file)
 #include <pcl/io/pcd_io.h>
 #include <pcl/features/normal_3d.h>
 #include <pcl/features/integral_image_normal.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -150,7 +151,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, k, radius);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_files[i]).filename().string();
+    std::string filename = pcl_fs::path(pcd_files[i]).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -222,11 +223,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index fcf331d6f23f12daec5be13d457da8dbdb751785..c46f168687e67109144ace7d7e45f6f4c20c003b 100644 (file)
@@ -58,7 +58,7 @@ do \
     if (pcl::getTime() - last >= 1.0) \
     { \
       double now = pcl::getTime (); \
-      std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
+      std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
       count = 0; \
       last = now; \
     } \
index 9df14649ec2f5adc89eba5a823afae5b3a200e4e..1dcc879e5fdffad7de10f82d03fde2b206005dd5 100644 (file)
@@ -58,7 +58,7 @@
   ++count; \
   if (now - last >= 1.0) \
 { \
-  std::cout << "Average framerate ("<< _WHAT_ << "): " << double (count)/double (now - last) << " Hz" <<  std::endl; \
+  std::cout << "Average framerate ("<< (_WHAT_) << "): " << double (count)/double (now - last) << " Hz" <<  std::endl; \
   count = 0; \
   last = now; \
 } \
index 5560ef682e22c1a4199971db39c24fe297c605c5..c70c75e1f3b5a25835afda67c562ec1e386594de 100644 (file)
@@ -97,7 +97,7 @@ do \
     ++count; \
     if (now - last >= 1.0) \
     { \
-      std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << ", number of frames written so far: " << nr_frames_total << "\n"; \
+      std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff).getSize () << ", number of frames written so far: " << nr_frames_total << "\n"; \
       count = 0; \
       last = now; \
     } \
@@ -112,7 +112,7 @@ do \
     ++count; \
     if (now - last >= 1.0) \
     { \
-      std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << "\n"; \
+      std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff).getSize () << "\n"; \
       count = 0; \
       last = now; \
     } \
@@ -128,9 +128,9 @@ do \
     if (now - last >= 1.0) \
     { \
       if (visualize && global_visualize) \
-        std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff1.getSize () << " (w) / " << buff2.getSize () << " (v)\n"; \
+        std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff1).getSize () << " (w) / " << (buff2).getSize () << " (v)\n"; \
       else \
-        std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff1.getSize () << " (w)\n"; \
+        std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff1).getSize () << " (w)\n"; \
       count = 0; \
       last = now; \
     } \
@@ -524,7 +524,7 @@ class Viewer
                 reinterpret_cast<const unsigned short*> (&frame->depth_image->getDepthMetaData ().Data ()[0]),
                   frame->depth_image->getWidth (), frame->depth_image->getHeight (),
                   std::numeric_limits<unsigned short>::min (), 
-                  // Scale so that the colors look brigher on screen
+                  // Scale so that the colors look brighter on screen
                   std::numeric_limits<unsigned short>::max () / 10, 
                   true);
 
index 0f3bfed73de02ee7a4b247bf33d533fb73bd84f7..91d06fb16a876710e21ad6629f62add526c03527 100644 (file)
@@ -200,7 +200,7 @@ do \
     ++count; \
     if (now - last >= 1.0) \
     { \
-      std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << "\n"; \
+      std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff).getSize () << "\n"; \
       count = 0; \
       last = now; \
     } \
index 1787c977d3c6dbb70a1c535d6e0858f70e7f29d6..0c3dfb10772098143158aa53bb6dc301e3c8df2f 100644 (file)
@@ -64,7 +64,7 @@ do \
     ++count; \
     if (now - last >= 1.0) \
     { \
-      std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
+      std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
       count = 0; \
       last = now; \
     } \
index 3b131c8a820de5161fd6830ebf7fe1b97cc7391c..509fa886dee92516c8d92a783be0501149406f8a 100644 (file)
@@ -56,7 +56,7 @@ do \
     ++count; \
     if (now - last >= 1.0) \
     { \
-      std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
+      std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
       count = 0; \
       last = now; \
     } \
index 90190279d297e234aed318e3e69397718493fc86..927d8bd6354465e22a1f789ebb6c831792a4e454 100644 (file)
@@ -66,7 +66,7 @@ do \
     ++count; \
     if (now - last >= 1.0) \
     { \
-      std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
+      std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
       count = 0; \
       last = now; \
     } \
index f79a87f0d63bb6c21f7ad29043b175809c666478..fe31ed1df63e5d99f49d20ae75249a14bd6840b0 100644 (file)
 
 #include <pcl/PCLPointCloud2.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
 #include <pcl/filters/passthrough.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -138,7 +139,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, field_name, min, max, inside, keep_organized);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_file).filename().string();
+    std::string filename = pcl_fs::path(pcd_file).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -211,11 +212,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index b8216c3a82afde3821861ae1619746a3e4c3489e..966f055b041bc592838cbd3a8ef381c9fd8c8ae7 100644 (file)
  *
  */
 #include <pcl/io/pcd_grabber.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/print.h>
 #include <pcl/visualization/cloud_viewer.h>
 #include <pcl/visualization/image_viewer.h>
-#include <boost/filesystem.hpp> // for exists, extension, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 #include <mutex>
 #include <thread>
@@ -179,7 +180,7 @@ main (int argc, char** argv)
   std::string path;
   pcl::console::parse_argument (argc, argv, "-file", path);
   std::cout << "path: " << path << std::endl;
-  if (!path.empty() && boost::filesystem::exists (path))
+  if (!path.empty() && pcl_fs::exists (path))
   {
     grabber.reset (new pcl::PCDGrabber<pcl::PointXYZRGBA> (path, frames_per_second, repeat));
   }
@@ -188,10 +189,10 @@ main (int argc, char** argv)
     std::vector<std::string> pcd_files;
     pcl::console::parse_argument (argc, argv, "-dir", path);
     std::cout << "path: " << path << std::endl;
-    if (!path.empty() && boost::filesystem::exists (path))
+    if (!path.empty() && pcl_fs::exists (path))
     {
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (path); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (path); itr != end_itr; ++itr)
       {
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
index 7d045fc9cb71cac3e82aff6980a3c2a35c7f542f..6084d82a7ede96ff4e1235358c523e7594f500bd 100644 (file)
@@ -513,9 +513,6 @@ main (int argc, char** argv)
       if (useEDLRendering)
         p->enableEDLRendering();
 
-      // Set whether or not we should be using the vtkVertexBufferObjectMapper
-      p->setUseVbos (use_vbos);
-
       if (!p->cameraParamsSet () && !p->cameraFileLoaded ())
       {
         Eigen::Matrix3f rotation;
index 943d5657c9da5b3a40c83c13be3b9a34b2de7a45..fd6cebca9f2b18e512ffa1731e1295a639c7900b 100644 (file)
 
 #include <pcl/point_types.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
 #include <pcl/filters/extract_indices.h>
 #include <pcl/segmentation/approximate_progressive_morphological_filter.h>
 #include <pcl/segmentation/progressive_morphological_filter.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -188,7 +189,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, max_window_size, slope, max_distance, initial_distance, cell_size, base, exponential, approximate);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_file).filename().string();
+    std::string filename = pcl_fs::path(pcd_file).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -297,11 +298,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index be5c50dbd8bf6e41fde49d81ec7509e0eefdf5e3..163789e425a698e4391499b9bfc699ff1a08b28c 100644 (file)
 
 #include <pcl/point_types.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
 #include <pcl/filters/conditional_removal.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
-#include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
+#include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using PointType = pcl::PointXYZ;
 using Cloud = pcl::PointCloud<PointType>;
@@ -131,7 +131,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, radius, inside, keep_organized);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_file).filename().string();
+    std::string filename = pcl_fs::path(pcd_file).filename().string();
 
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -201,11 +201,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index 455546840554ee512ef53bb8ecaa9a60869b887c..6508352da9129d324b6ee668d32c20f1f7e302a6 100644 (file)
 #include <pcl/sample_consensus/ransac.h>
 #include <pcl/sample_consensus/sac_model_plane.h>
 #include <pcl/segmentation/extract_clusters.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
+
 #include <boost/algorithm/string/case_conv.hpp> // for to_upper_copy
 
 using namespace pcl;
@@ -191,7 +192,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
     compute (cloud, output, max_it, thresh, negative);
 
     // Prepare output file name
-    std::string filename = boost::filesystem::path(pcd_file).filename().string();
+    std::string filename = pcl_fs::path(pcd_file).filename().string();
     
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
@@ -276,11 +277,11 @@ main (int argc, char** argv)
   }
   else
   {
-    if (!input_dir.empty() && boost::filesystem::exists (input_dir))
+    if (!input_dir.empty() && pcl_fs::exists (input_dir))
     {
       std::vector<std::string> pcd_files;
-      boost::filesystem::directory_iterator end_itr;
-      for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
+      pcl_fs::directory_iterator end_itr;
+      for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
index d92eddab4693dbf289af6fc4149cdd73e2c5acbe..011d26b08e5e9ed4021f9c1a4e38fb98e5d23c11 100644 (file)
  **/
 
 #include <iostream>
-#include <boost/filesystem.hpp>
 
 #include <pcl/point_types.h>
 #include <pcl/point_cloud.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/print.h>
 #include <pcl/io/pcd_io.h>
@@ -235,12 +235,12 @@ int main(int argc, char ** argv)
     PCL_INFO ("Creating RGB Tiff List\n");
 
   std::vector<std::string> tiff_rgb_files;
-  std::vector<boost::filesystem::path> tiff_rgb_paths;
-  boost::filesystem::directory_iterator end_itr;
+  std::vector<pcl_fs::path> tiff_rgb_paths;
+  pcl_fs::directory_iterator end_itr;
 
-  if(boost::filesystem::is_directory(rgb_path_))
+  if(pcl_fs::is_directory(rgb_path_))
   {
-    for (boost::filesystem::directory_iterator itr(rgb_path_); itr != end_itr; ++itr)
+    for (pcl_fs::directory_iterator itr(rgb_path_); itr != end_itr; ++itr)
     {
       std::string ext = itr->path().extension().string();
       if(ext == ".tiff")
@@ -278,11 +278,11 @@ int main(int argc, char ** argv)
     PCL_INFO ("Creating Depth Tiff List\n");
 
   std::vector<std::string> tiff_depth_files;
-  std::vector<boost::filesystem::path> tiff_depth_paths;
+  std::vector<pcl_fs::path> tiff_depth_paths;
 
-  if(boost::filesystem::is_directory(depth_path_))
+  if(pcl_fs::is_directory(depth_path_))
   {
-    for (boost::filesystem::directory_iterator itr(depth_path_); itr != end_itr; ++itr)
+    for (pcl_fs::directory_iterator itr(depth_path_); itr != end_itr; ++itr)
     {
       std::string ext = itr->path().extension().string();
       if(ext == ".tiff")
index e7dcfd6b7aec759118c008d27ae79a85746d80c1..ddd23c45276c60f1acf90dc7f0ebbf17ab81e74b 100644 (file)
@@ -225,7 +225,7 @@ scaleInPlace (pcl::PCLPointCloud2 &cloud, double* multiplier)
 #define MULTIPLY(CASE_LABEL)                                                           \
   case CASE_LABEL: {                                                                   \
     for (int i = 0; i < 3; ++i)                                                        \
-      multiply<pcl::traits::asType_t<CASE_LABEL>>(                                     \
+      multiply<pcl::traits::asType_t<(CASE_LABEL)>>(                                   \
           cloud, xyz_offset[i], multiplier[i]);                                        \
     break;                                                                             \
   }
@@ -295,7 +295,7 @@ main (int argc, char** argv)
       const float& y = values[1];
       const float& z = values[2];
       const float& w = values[3];
-      tform.topLeftCorner (3, 3) = Eigen::Matrix3f (Eigen::Quaternionf (w, x, y, z));
+      tform.topLeftCorner<3, 3> () = Eigen::Matrix3f (Eigen::Quaternionf (w, x, y, z));
     }
     else
     {
@@ -312,7 +312,7 @@ main (int argc, char** argv)
       const float& ay = values[1];
       const float& az = values[2];
       const float& theta = values[3];
-      tform.topLeftCorner (3, 3) = Eigen::Matrix3f (Eigen::AngleAxisf (theta, Eigen::Vector3f (ax, ay, az)));
+      tform.topLeftCorner<3, 3> () = Eigen::Matrix3f (Eigen::AngleAxisf (theta, Eigen::Vector3f (ax, ay, az)));
     }
     else
     {
index cdec686d155b04ae2ffb639045381c2e3dfb8a44..926d8c7880f926685b11abe3a07789a6502d5d1f 100644 (file)
 
 
 #include <pcl/io/pcd_io.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
 #include <pcl/filters/filter.h> // for removeNaNFromPointCloud
 
 #include <pcl/segmentation/unary_classifier.h>
-#include <boost/filesystem.hpp> // for path, exists, ...
 
 using namespace pcl;
 using namespace pcl::io;
@@ -76,14 +76,14 @@ printHelp (int, char **argv)
 
 bool
 loadTrainedFeatures (std::vector<FeatureT::Ptr> &out,
-                     const boost::filesystem::path &base_dir)
+                     const pcl_fs::path &base_dir)
 {
-  if (!boost::filesystem::exists (base_dir) && !boost::filesystem::is_directory (base_dir))
+  if (!pcl_fs::exists (base_dir) && !pcl_fs::is_directory (base_dir))
     return false;
 
-  for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it)
+  for (pcl_fs::directory_iterator it (base_dir); it != pcl_fs::directory_iterator (); ++it)
   {    
-    if (!boost::filesystem::is_directory (it->status ()) &&
+    if (!pcl_fs::is_directory (it->status ()) &&
         it->path ().extension ().string () == ".pcd")
     {   
       const std::string path = it->path ().string ();
index 269552b16aa70e9271fe985d1705188cc64778fe..fef5cfd51056b2481c8bbc56de7532b42106f897 100644 (file)
 #include <pcl/PCLPointCloud2.h>
 #include <pcl/io/auto_io.h>
 #include <pcl/filters/uniform_sampling.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
-#include <boost/filesystem.hpp>
+
 #include <algorithm>
 #include <string>
 
@@ -129,7 +130,7 @@ saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
 
   PCDWriter w_pcd;
   PLYWriter w_ply;
-  std::string output_ext = boost::filesystem::path (filename).extension ().string ();
+  std::string output_ext = pcl_fs::path (filename).extension ().string ();
   std::transform (output_ext.begin (), output_ext.end (), output_ext.begin (), ::tolower);
 
   if (output_ext == ".pcd")
index d339a88413d1a2c4a5812fa4f0073454747edacf..8d714241c2fabd5d241632a8f4c84ef2b2b67005 100644 (file)
@@ -53,6 +53,7 @@
 #include <pcl/filters/voxel_grid.h>
 #include <pcl/memory.h>  // for pcl::make_shared
 #include <pcl/point_types.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/console/parse.h>
 
 #include <vtkGeneralTransform.h>
@@ -64,7 +65,6 @@
 #include <vtkMath.h>
 
 #include <boost/algorithm/string.hpp>  // for boost::is_any_of, boost::split, boost::token_compress_on, boost::trim
-#include <boost/filesystem.hpp>  // for boost::filesystem::create_directories, boost::filesystem::exists, boost::filesystem::path, boost::filesystem::path::extension
 
 using namespace pcl;
 
@@ -87,7 +87,7 @@ struct ScanParameters
 vtkPolyData*
 loadDataSet (const char* file_name)
 {
-  std::string extension = boost::filesystem::path (file_name).extension ().string ();
+  std::string extension = pcl_fs::path (file_name).extension ().string ();
   if (extension == ".ply")
   {
     vtkPLYReader* reader = vtkPLYReader::New ();
@@ -413,10 +413,10 @@ main (int argc, char** argv)
 
     const std::string output_dir = st.at (st.size () - 1) + "_output";
 
-    boost::filesystem::path outpath (output_dir);
-    if (!boost::filesystem::exists (outpath))
+    pcl_fs::path outpath (output_dir);
+    if (!pcl_fs::exists (outpath))
     {
-      if (!boost::filesystem::create_directories (outpath))
+      if (!pcl_fs::create_directories (outpath))
       {
         PCL_ERROR ("Error creating directory %s.\n", output_dir.c_str ());
         return (-1);
index 985e4ce64dc0e323dee03799386cdf6a0bc21fab..cd1fb8777a8c6b423243f7e8f74af5f71e684b52 100644 (file)
@@ -2,7 +2,6 @@ set(SUBSYS_NAME tracking)
 set(SUBSYS_DESC "Point cloud tracking library")
 set(SUBSYS_DEPS common search kdtree filters octree)
 
-set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
@@ -52,7 +51,6 @@ set(impl_incs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs})
 target_link_libraries("${LIB_NAME}" pcl_common pcl_kdtree pcl_search pcl_filters pcl_octree)
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
index f7d6eda2a2b5784236c70ba2e550f6355db7f415..e096baaab6087bd88f945ac6da1cac5865b55a25 100644 (file)
@@ -11,7 +11,8 @@ namespace tracking {
  * \ingroup tracking
  */
 template <typename PointInT>
-class NearestPairPointCloudCoherence : public PointCloudCoherence<PointInT> {
+class PCL_EXPORTS NearestPairPointCloudCoherence
+: public PointCloudCoherence<PointInT> {
 public:
   using PointCloudCoherence<PointInT>::getClassName;
   using PointCloudCoherence<PointInT>::coherence_name_;
index 122d4b5417cfbf61e7ed814313ad1521f33c3da9..216c27841d99c01f28112477d6acea91bcf4e180 100644 (file)
@@ -472,7 +472,7 @@ protected:
 
   /** \brief Resampling phase of particle filter method. Sampling the particles
    * according to the weights calculated in weight method. In particular,
-   * "sample with replacement" is archieved by walker's alias method.
+   * "sample with replacement" is achieved by walker's alias method.
    */
   virtual void
   resample();
index fa4101142733252364d8d36a922c8a04a82e6a25..d5b4490835591197ff931dfbfb80f69dcf1bb01f 100644 (file)
@@ -49,7 +49,7 @@ namespace tracking {
 /** Pyramidal Kanade Lucas Tomasi tracker.
  * This is an implementation of the Pyramidal Kanade Lucas Tomasi tracker that
  * operates on organized 3D keypoints with color/intensity information (this is
- * the default behaviour but you can alterate it by providing another operator
+ * the default behaviour but you can alternate it by providing another operator
  * as second template argument). It is an affine tracker that iteratively
  * computes the optical flow to find the best guess for a point p at t given its
  * location at t-1. User is advised to respect the Tomasi condition: the
@@ -254,22 +254,6 @@ public:
     return (keypoints_);
   };
 
-  /** \return the status of points to track.
-   * Status == 0  --> points successfully tracked;
-   * Status < 0   --> point is lost;
-   * Status == -1 --> point is out of bond;
-   * Status == -2 --> optical flow can not be computed for this point.
-   */
-  PCL_DEPRECATED(1, 15, "use getStatusOfPointsToTrack instead")
-  inline pcl::PointIndicesConstPtr
-  getPointsToTrackStatus() const
-  {
-    pcl::PointIndicesPtr res(new pcl::PointIndices);
-    res->indices.insert(
-        res->indices.end(), keypoints_status_->begin(), keypoints_status_->end());
-    return (res);
-  }
-
   /** \return the status of points to track.
    * Status == 0  --> points successfully tracked;
    * Status < 0   --> point is lost;
index 325e03aee8377236a9ce7128127c8d978fa19fa2..f5bcb8061ed3431b9e909aa1162c3f5197ae264d 100644 (file)
 #include <pcl/point_types.h>
 
 // clang-format off
-PCL_INSTANTIATE(ApproxNearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES)
 PCL_INSTANTIATE(DistanceCoherence, PCL_XYZ_POINT_TYPES)
 PCL_INSTANTIATE(HSVColorCoherence,
                 (pcl::PointXYZRGB)
                 (pcl::PointXYZRGBNormal)
                 (pcl::PointXYZRGBA))
 PCL_INSTANTIATE(NearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES)
+// NearestPairPointCloudCoherence is the parent class of ApproxNearestPairPointCloudCoherence.
+// They must be instantiated in this order, otherwise visibility attributes of the former are not applied correctly.
+PCL_INSTANTIATE(ApproxNearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES)
 PCL_INSTANTIATE(NormalCoherence, PCL_NORMAL_POINT_TYPES)
 // clang-format on
 #endif // PCL_NO_PRECOMPILE
index 9c4e000ecf393762e06ca21d91ec1f69d1a4374f..6e6ce0c7dda2b20662f12faac9b19a3b4966449f 100644 (file)
@@ -2,27 +2,15 @@ set(SUBSYS_NAME visualization)
 set(SUBSYS_DESC "Point cloud visualization library")
 set(SUBSYS_DEPS common io kdtree geometry search octree)
 
-if(NOT VTK_FOUND)
-  set(DEFAULT FALSE)
-  set(REASON "VTK was not found.")
-else()
-  set(DEFAULT TRUE)
-  set(REASON)
-  include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
-endif()
-
-PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}")
+PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS vtk OPT_DEPS openni openni2 ensenso davidSDK dssdk rssdk)
 
 if(ANDROID)
-  set(build FALSE)
   message("VTK was found, but cannot be compiled for Android. Please use VES instead.")
+  return()
 endif()
 
 if(OPENGL_FOUND)
-  if(OPENGL_INCLUDE_DIR)
-    include_directories(SYSTEM "${OPENGL_INCLUDE_DIR}")
-  endif()
   if(OPENGL_DEFINITIONS)
     add_definitions("${OPENGL_DEFINITIONS}")
   endif()
@@ -69,7 +57,6 @@ if(NOT (${VTK_VERSION} VERSION_LESS 9.0))
 endif()
 
 set(incs
-  "include/pcl/${SUBSYS_NAME}/eigen.h"
   "include/pcl/${SUBSYS_NAME}/boost.h"
   "include/pcl/${SUBSYS_NAME}/cloud_viewer.h"
   "include/pcl/${SUBSYS_NAME}/histogram_visualizer.h"
@@ -87,7 +74,6 @@ set(incs
   "include/pcl/${SUBSYS_NAME}/mouse_event.h"
   "include/pcl/${SUBSYS_NAME}/window.h"
   "include/pcl/${SUBSYS_NAME}/range_image_visualizer.h"
-  "include/pcl/${SUBSYS_NAME}/vtk.h"
   "include/pcl/${SUBSYS_NAME}/simple_buffer_visualizer.h"
   "include/pcl/${SUBSYS_NAME}/pcl_plotter.h"
   "include/pcl/${SUBSYS_NAME}/qvtk_compatibility.h"
@@ -152,7 +138,7 @@ if(APPLE)
   target_link_libraries("${LIB_NAME}" "-framework Cocoa")
 endif()
 
-target_link_libraries("${LIB_NAME}" pcl_common pcl_io pcl_kdtree ${OPENGL_LIBRARIES})
+target_link_libraries("${LIB_NAME}" pcl_common pcl_io pcl_kdtree pcl_geometry pcl_search ${OPENGL_LIBRARIES})
 
 if(${VTK_VERSION} VERSION_GREATER_EQUAL 9.0)
   #Some libs are referenced through depending on IO
index 26cb217612f019ad2ee2dddbea5063be992f3259..eba9764da2a648132c5946d0f2ad91c4b0d788ec 100644 (file)
@@ -81,6 +81,8 @@ namespace pcl
         getCloudNames () const
         {
           std::vector<std::string> names;
+          names.reserve(cloud_indices_.size());
+          
           for (const auto& i : cloud_indices_)
             names.push_back (i.first);
           return names;
index 1841f13a28f5cfa07e3d6e047264d8128d7554e1..31810c5fd83283b4e70d9653a9b0c68a590328d0 100644 (file)
@@ -38,6 +38,8 @@
 
 #pragma once
 
+#include <pcl/pcl_exports.h>
+
 #include <map>
 #include <string>
 
@@ -53,7 +55,7 @@ namespace pcl
 {
   namespace visualization
   {
-    class RenWinInteract
+    class PCL_EXPORTS RenWinInteract
     {
       public:
 
diff --git a/visualization/include/pcl/visualization/eigen.h b/visualization/include/pcl/visualization/eigen.h
deleted file mode 100644 (file)
index 09d57c5..0000000
+++ /dev/null
@@ -1,48 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012-, Open Perception, Inc.
- *
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of the copyright holder(s) nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *
- * $Id: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $
- *
- */
-
-#pragma once
-
-#if defined __GNUC__
-#  pragma GCC system_header 
-#endif
-PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.")
-
-#include <Eigen/Geometry>
-#include <Eigen/Dense>
index 0f746cabb8397a8f6aece506401c226fff876d2e..f8060868d75842075a202e25154efafb888f694a 100644 (file)
@@ -259,9 +259,7 @@ pcl::visualization::PCLVisualizer::convertPointCloudToVTKPolyData (
     for (vtkIdType i = 0; i < nr_points; ++i)
     {
       // Check if the point is invalid
-      if (!std::isfinite ((*cloud)[i].x) ||
-          !std::isfinite ((*cloud)[i].y) ||
-          !std::isfinite ((*cloud)[i].z))
+      if (!pcl::isXYZFinite((*cloud)[i]))
         continue;
 
       std::copy (&(*cloud)[i].x, &(*cloud)[i].x + 3, &data[ptr]);
@@ -482,7 +480,7 @@ pcl::visualization::PCLVisualizer::addPolygon (
   const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
   const std::string &id, int viewport)
 {
-  return (!addPolygon<PointT> (cloud, 0.5, 0.5, 0.5, id, viewport));
+  return (addPolygon<PointT> (cloud, 0.5, 0.5, 0.5, id, viewport));
 }
 
 ////////////////////////////////////////////////////////////////////////////////////////////
@@ -603,7 +601,7 @@ pcl::visualization::PCLVisualizer::addArrow (const P1 &pt1, const P2 &pt2,
 template <typename P1, typename P2> bool
 pcl::visualization::PCLVisualizer::addLine (const P1 &pt1, const P2 &pt2, const std::string &id, int viewport)
 {
-  return (!addLine (pt1, pt2, 0.5, 0.5, 0.5, id, viewport));
+  return (addLine (pt1, pt2, 0.5, 0.5, 0.5, id, viewport));
 }
 
 ////////////////////////////////////////////////////////////////////////////////////////////
@@ -924,13 +922,15 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
         lines->InsertCellPoint (2 * cell_count + 1);
         cell_count ++;
     }
+    nr_normals = cell_count;
   }
   else
   {
     nr_normals = (cloud->size () - 1) / level + 1 ;
     pts = new float[2 * nr_normals * 3];
 
-    for (vtkIdType i = 0, j = 0; (j < nr_normals) && (i < static_cast<vtkIdType>(cloud->size())); i += level)
+    vtkIdType j = 0;
+    for (vtkIdType i = 0; (j < nr_normals) && (i < static_cast<vtkIdType>(cloud->size())); i += level)
     {
       if (!pcl::isFinite((*cloud)[i]) || !pcl::isNormalFinite((*normals)[i]))
         continue;
@@ -951,6 +951,7 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
       lines->InsertCellPoint (2 * j + 1);
       ++j;
     }
+    nr_normals = j;
   }
 
   data->SetArray (&pts[0], 2 * nr_normals * 3, 0, vtkFloatArray::VTK_DATA_ARRAY_DELETE);
@@ -1249,10 +1250,10 @@ pcl::visualization::PCLVisualizer::addCorrespondences (
 
   Eigen::Affine3f source_transformation;
   source_transformation.linear () = source_points->sensor_orientation_.matrix ();
-  source_transformation.translation () = source_points->sensor_origin_.head (3);
+  source_transformation.translation () = source_points->sensor_origin_.template head<3> ();
   Eigen::Affine3f target_transformation;
   target_transformation.linear () = target_points->sensor_orientation_.matrix ();
-  target_transformation.translation () = target_points->sensor_origin_.head (3);
+  target_transformation.translation () = target_points->sensor_origin_.template head<3> ();
 
   int j = 0;
   // Draw lines between the best corresponding points
index 991991db08f2d4c0af9a91c01b92e5604c1d5d27..4e5aa57b5c459f6310227c19e1bc74229f028b58 100644 (file)
@@ -171,9 +171,7 @@ PointCloudColorHandlerRGBField<PointT>::getColor () const
     for (vtkIdType cp = 0; cp < nr_points; ++cp)
     {
       // Copy the value at the specified field
-      if (!std::isfinite ((*cloud_)[cp].x) ||
-          !std::isfinite ((*cloud_)[cp].y) ||
-          !std::isfinite ((*cloud_)[cp].z))
+      if (!pcl::isXYZFinite((*cloud_)[cp]))
         continue;
       memcpy (&rgb, (reinterpret_cast<const char *> (&(*cloud_)[cp])) + rgba_offset, sizeof (pcl::RGB));
       colors[j    ] = rgb.r;
@@ -256,9 +254,7 @@ PointCloudColorHandlerHSVField<PointT>::getColor () const
     for (vtkIdType cp = 0; cp < nr_points; ++cp)
     {
       // Copy the value at the specified field
-      if (!std::isfinite ((*cloud_)[cp].x) ||
-          !std::isfinite ((*cloud_)[cp].y) ||
-          !std::isfinite ((*cloud_)[cp].z))
+      if (!pcl::isXYZFinite((*cloud_)[cp]))
         continue;
 
       ///@todo do this with the point_types_conversion in common, first template it!
@@ -372,10 +368,16 @@ PointCloudColorHandlerGenericField<PointT>::setInputCloud (
 {
   PointCloudColorHandler<PointT>::setInputCloud (cloud);
   field_idx_  = pcl::getFieldIndex<PointT> (field_name_, fields_);
-  if (field_idx_ != -1)
-    capable_ = true;
-  else
+  if (field_idx_ == -1) {
     capable_ = false;
+    return;
+  }
+  if (fields_[field_idx_].datatype != pcl::PCLPointField::PointFieldTypes::FLOAT32) {
+    capable_ = false;
+    PCL_ERROR("[pcl::PointCloudColorHandlerGenericField::setInputCloud] This currently only works with float32 fields, but field %s has a different type.\n", field_name_.c_str());
+    return;
+  }
+  capable_ = true;
 }
 
 
@@ -409,7 +411,7 @@ PointCloudColorHandlerGenericField<PointT>::getColor () const
     for (vtkIdType cp = 0; cp < nr_points; ++cp)
     {
       // Copy the value at the specified field
-      if (!std::isfinite ((*cloud_)[cp].x) || !std::isfinite ((*cloud_)[cp].y) || !std::isfinite ((*cloud_)[cp].z))
+      if (!pcl::isXYZFinite((*cloud_)[cp]))
         continue;
 
       const std::uint8_t* pt_data = reinterpret_cast<const std::uint8_t*> (&(*cloud_)[cp]);
@@ -479,9 +481,7 @@ PointCloudColorHandlerRGBAField<PointT>::getColor () const
     for (vtkIdType cp = 0; cp < nr_points; ++cp)
     {
       // Copy the value at the specified field
-      if (!std::isfinite ((*cloud_)[cp].x) ||
-          !std::isfinite ((*cloud_)[cp].y) ||
-          !std::isfinite ((*cloud_)[cp].z))
+      if (!pcl::isXYZFinite((*cloud_)[cp]))
         continue;
 
       colors[j    ] = (*cloud_)[cp].r;
index 4202b1952b7c29614a50018833b9d3e4a9ed6f2a..823235e0b8d84eb088711fd1303f941561da0c3f 100644 (file)
@@ -155,6 +155,7 @@ namespace pcl
           * buffer objects by default, transparently for the user.
           * \param[in] use_vbos set to true to use VBOs
           */
+        PCL_DEPRECATED(1, 18, "this function has no effect")
         inline void
         setUseVbos (const bool use_vbos) { use_vbos_ = use_vbos; }
 
index 8e5d42fa5651fd964e9efbfbd46862b814572dbf..bd76e4f05e0f60ac1a46ff6e89ba99bbc1e528f3 100644 (file)
@@ -111,7 +111,7 @@ namespace pcl
         PCLVisualizer (const std::string &name = "", const bool create_interactor = true);
 
         /** \brief PCL Visualizer constructor. It looks through the passed argv arguments to find the "-cam *.cam" argument.
-          *        If the search failed, the name for cam file is calculated with boost uuid. If there is no such file, camera is not initilalized.
+          *        If the search failed, the name for cam file is calculated with boost uuid. If there is no such file, camera is not initialized.
           * \param[in] argc
           * \param[in] argv
           * \param[in] name the window name (empty by default)
@@ -1818,11 +1818,6 @@ namespace pcl
         std::string
         getCameraFile () const;
 
-        /** \brief Update camera parameters and render. */
-        PCL_DEPRECATED(1,15,"updateCamera will be removed, as it does nothing.")
-        inline void
-        updateCamera () {};
-
         /** \brief Reset camera parameters and render. */
         void
         resetCamera ();
@@ -1966,6 +1961,7 @@ namespace pcl
           * buffer objects by default, transparently for the user.
           * \param[in] use_vbos set to true to use VBOs
           */
+        PCL_DEPRECATED(1, 18, "this function has no effect")
         void
         setUseVbos (bool use_vbos);
 
index b6ac0e72f2fe047f873c8a6b2d2b1b5b1b769c0a..8285bc6a87bad35670ef14eda84bc2f0c6d3a91b 100644 (file)
@@ -6,6 +6,8 @@
  *
  *  All rights reserved
  */
+#pragma once
+
 #include <pcl/pcl_macros.h>
 #include <pcl/pcl_config.h>
 
diff --git a/visualization/include/pcl/visualization/vtk.h b/visualization/include/pcl/visualization/vtk.h
deleted file mode 100644 (file)
index 1df02a3..0000000
+++ /dev/null
@@ -1,10 +0,0 @@
-/*
- * SPDX-License-Identifier: BSD-3-Clause
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2020-, Open Perception
- *
- *  All rights reserved
- */
-
-PCL_DEPRECATED_HEADER(1, 15, "Use required vtk includes instead.")
index b427e76d9d3005d657e49ab4fb5299d249e5e919..7958f80e61625669fc7e1300b9f388eb7449f34d 100644 (file)
@@ -38,5 +38,6 @@
 #pragma once
 
 #include <vtkRenderWindowInteractor.h>
+#include <pcl/pcl_exports.h>
 
-vtkRenderWindowInteractor* vtkRenderWindowInteractorFixNew ();
+PCL_EXPORTS vtkRenderWindowInteractor* vtkRenderWindowInteractorFixNew ();
index 58633fe59d4325888358bd8324f23c48025ecd49..3d1a89c1437b17b128e47dbf24c74d2b712c173f 100644 (file)
@@ -39,6 +39,7 @@
 #include <fstream>
 #include <list>
 #include <pcl/common/angles.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/visualization/common/io.h>
 #include <pcl/visualization/interactor_style.h>
 #include <vtkVersion.h>
@@ -69,7 +70,6 @@
 
 #include <boost/algorithm/string/classification.hpp> // for is_any_of
 #include <boost/algorithm/string/split.hpp> // for split
-#include <boost/filesystem.hpp> // for exists
 
 #define ORIENT_MODE 0
 #define SELECT_MODE 1
@@ -225,7 +225,7 @@ pcl::visualization::PCLVisualizerInteractorStyle::setCameraParameters (const Eig
   Eigen::Vector3f pos_vec = extrinsics.block<3, 1> (0, 3);
 
   // Rotate the view vector
-  Eigen::Matrix3f rotation = extrinsics.block<3, 3> (0, 0);
+  Eigen::Matrix3f rotation = extrinsics.topLeftCorner<3, 3> ();
   Eigen::Vector3f y_axis (0.f, 1.f, 0.f);
   Eigen::Vector3f up_vec (rotation * y_axis);
 
@@ -610,7 +610,7 @@ pcl::visualization::PCLVisualizerInteractorStyle::OnKeyDown ()
     }
     else
     {
-      if (boost::filesystem::exists (camera_file_))
+      if (pcl_fs::exists (camera_file_))
       {
         if (loadCameraParameters (camera_file_))
         {
index 85c4061fb45726f2d9bb0868363379adc963bdac..c7f2b4b78a982b6696ba25ef7fa11e4ce7ef8317 100644 (file)
@@ -93,6 +93,7 @@
 #endif
 
 #include <pcl/common/time.h>
+#include <pcl/common/pcl_filesystem.h>
 #include <pcl/visualization/common/shapes.h>
 #include <pcl/visualization/pcl_visualizer.h>
 
 #else
 #include <boost/uuid/sha1.hpp>
 #endif
-#include <boost/filesystem.hpp>
+
 #include <boost/algorithm/string.hpp> // for split
 #include <pcl/common/utils.h> // pcl::utils::ignore
 #include <pcl/console/parse.h>
@@ -438,7 +439,6 @@ void pcl::visualization::PCLVisualizer::setupStyle ()
   style_->setCloudActorMap (cloud_actor_map_);
   style_->setShapeActorMap (shape_actor_map_);
   style_->UseTimersOn ();
-  style_->setUseVbos (use_vbos_);
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////////
@@ -465,7 +465,7 @@ void pcl::visualization::PCLVisualizer::setupCamera (int argc, char **argv)
     std::string camera_file = getUniqueCameraFile (argc, argv);
     if (!camera_file.empty ())
     {
-      if (boost::filesystem::exists (camera_file) && style_->loadCameraParameters (camera_file))
+      if (pcl_fs::exists (camera_file) && style_->loadCameraParameters (camera_file))
       {
         camera_file_loaded_ = true;
       }
@@ -1759,7 +1759,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties (
   }
   // Get the actor pointer
   vtkActor* actor = vtkActor::SafeDownCast (am_it->second);
-  if (!actor)
+  if (!actor && property != PCL_VISUALIZER_FONT_SIZE) // vtkTextActor is not a subclass of vtkActor
     return (false);
 
   switch (property)
@@ -2179,7 +2179,7 @@ void
 pcl::visualization::PCLVisualizer::resetCameraViewpoint (const std::string &id)
 {
   vtkSmartPointer<vtkMatrix4x4> camera_pose;
-  const CloudActorMap::iterator it = cloud_actor_map_->find(id);
+  const auto it = cloud_actor_map_->find(id);
   if (it != cloud_actor_map_->end ())
     camera_pose = it->second.viewpoint_transformation_;
   else
@@ -3906,7 +3906,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere (
         trans_view (x, y) = static_cast<float> (view_transform->GetElement (x, y));
 
     //NOTE: vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right)
-    //thus, the fliping in y and z
+    //thus, the flipping in y and z
     for (auto &point : cloud->points)
     {
       point.getVector4fMap () = trans_view * point.getVector4fMap ();
@@ -3928,7 +3928,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere (
     transOCtoCC->Concatenate (cam_tmp->GetViewTransformMatrix ());
 
     //NOTE: vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right)
-    //thus, the fliping in y and z
+    //thus, the flipping in y and z
     vtkSmartPointer<vtkMatrix4x4> cameraSTD = vtkSmartPointer<vtkMatrix4x4>::New ();
     cameraSTD->Identity ();
     cameraSTD->SetElement (0, 0, 1);
@@ -4010,7 +4010,7 @@ pcl::visualization::PCLVisualizer::renderView (int xres, int yres, pcl::PointClo
 
       float w3 = 1.0f / world_coords[3];
       world_coords[0] *= w3;
-      // vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right), thus, the fliping in y and z
+      // vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right), thus, the flipping in y and z
       world_coords[1] *= -w3;
       world_coords[2] *= -w3;
 
@@ -4161,8 +4161,8 @@ pcl::visualization::PCLVisualizer::getTransformationMatrix (
     Eigen::Matrix4f &transformation)
 {
   transformation.setIdentity ();
-  transformation.block<3, 3> (0, 0) = orientation.toRotationMatrix ();
-  transformation.block<3, 1> (0, 3) = origin.head (3);
+  transformation.topLeftCorner<3, 3> () = orientation.toRotationMatrix ();
+  transformation.block<3, 1> (0, 3) = origin.head<3> ();
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -4358,7 +4358,7 @@ int
 pcl::visualization::PCLVisualizer::getGeometryHandlerIndex (const std::string &id)
 {
   auto am_it = style_->getCloudActorMap ()->find (id);
-  if (am_it != cloud_actor_map_->end ())
+  if (am_it == cloud_actor_map_->end ())
     return (-1);
 
   return (am_it->second.geometry_handler_index_);
@@ -4451,39 +4451,39 @@ pcl::visualization::PCLVisualizer::textureFromTexMaterial (const pcl::TexMateria
     return (-1);
   }
 
-  boost::filesystem::path full_path (tex_mat.tex_file.c_str ());
-  if (!boost::filesystem::exists (full_path))
+  pcl_fs::path full_path (tex_mat.tex_file.c_str ());
+  if (!pcl_fs::exists (full_path))
   {
-    boost::filesystem::path parent_dir = full_path.parent_path ();
+    pcl_fs::path parent_dir = full_path.parent_path ();
     std::string upper_filename = tex_mat.tex_file;
     boost::to_upper (upper_filename);
     std::string real_name;
 
     try
     {
-      if (!boost::filesystem::exists (parent_dir))
+      if (!pcl_fs::exists (parent_dir))
       {
         PCL_WARN ("[PCLVisualizer::textureFromTexMaterial] Parent directory '%s' doesn't exist!\n",
                    parent_dir.string ().c_str ());
         return (-1);
       }
 
-      if (!boost::filesystem::is_directory (parent_dir))
+      if (!pcl_fs::is_directory (parent_dir))
       {
         PCL_WARN ("[PCLVisualizer::textureFromTexMaterial] Parent '%s' is not a directory !\n",
                    parent_dir.string ().c_str ());
         return (-1);
       }
 
-      using paths_vector = std::vector<boost::filesystem::path>;
+      using paths_vector = std::vector<pcl_fs::path>;
       paths_vector paths;
-      std::copy (boost::filesystem::directory_iterator (parent_dir),
-                 boost::filesystem::directory_iterator (),
+      std::copy (pcl_fs::directory_iterator (parent_dir),
+                 pcl_fs::directory_iterator (),
                  back_inserter (paths));
 
       for (const auto& path : paths)
       {
-        if (boost::filesystem::is_regular_file (path))
+        if (pcl_fs::is_regular_file (path))
         {
           std::string name = path.string ();
           boost::to_upper (name);
@@ -4502,7 +4502,7 @@ pcl::visualization::PCLVisualizer::textureFromTexMaterial (const pcl::TexMateria
         return (-1);
       }
     }
-    catch (const boost::filesystem::filesystem_error& ex)
+    catch (const pcl_fs::filesystem_error& ex)
     {
 
       PCL_WARN ("[PCLVisualizer::textureFromTexMaterial] Error %s when looking for file %s\n!",
@@ -4577,10 +4577,10 @@ pcl::visualization::PCLVisualizer::getUniqueCameraFile (int argc, char **argv)
     // Calculate sha1 using canonical paths
     for (const int &p_file_index : p_file_indices)
     {
-      boost::filesystem::path path (argv[p_file_index]);
-      if (boost::filesystem::exists (path))
+      pcl_fs::path path (argv[p_file_index]);
+      if (pcl_fs::exists (path))
       {
-        path = boost::filesystem::canonical (path);
+        path = pcl_fs::canonical (path);
         const auto pathStr = path.string ();
         sha1.process_bytes (pathStr.c_str(), pathStr.size());
         valid = true;
@@ -4590,10 +4590,12 @@ pcl::visualization::PCLVisualizer::getUniqueCameraFile (int argc, char **argv)
     // Build camera filename
     if (valid)
     {
-      unsigned int digest[5];
+      boost::uuids::detail::sha1::digest_type digest;
       sha1.get_digest (digest);
       sstream << ".";
-      sstream << std::hex << digest[0] << digest[1] << digest[2] << digest[3] << digest[4];
+      for (int i = 0; i < static_cast<int>(sizeof(digest)/sizeof(unsigned int)); ++i) {
+        sstream << std::hex << *(reinterpret_cast<unsigned int*>(&digest[0]) + i);
+      }
       sstream << ".cam";
     }
   }
index 4b70dd9ec17a954e2da898d5348526006d0b2ca4..00dedb9b5ae50b4df6e725ee9bec80da64f336d2 100644 (file)
@@ -420,6 +420,10 @@ pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2>::Poi
 {
   field_idx_  = pcl::getFieldIndex (*cloud, field_name);
   capable_ = field_idx_ != -1;
+  if (field_idx_ != -1 && cloud_->fields[field_idx_].datatype != pcl::PCLPointField::PointFieldTypes::FLOAT32) {
+    capable_ = false;
+    PCL_ERROR("[pcl::PointCloudColorHandlerGenericField] This currently only works with float32 fields, but field %s has a different type.\n", field_name.c_str());
+  }
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////
@@ -575,6 +579,10 @@ pcl::visualization::PointCloudColorHandlerLabelField<pcl::PCLPointCloud2>::Point
   field_idx_ = pcl::getFieldIndex (*cloud, "label");
   capable_ = field_idx_ != -1;
   static_mapping_ = static_mapping;
+  if (field_idx_ != -1 && cloud_->fields[field_idx_].datatype != pcl::PCLPointField::PointFieldTypes::UINT32) {
+    capable_ = false;
+    PCL_ERROR("[pcl::PointCloudColorHandlerLabelField] This currently only works with uint32 fields, but label field has a different type.\n");
+  }
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////