New upstream version 1.14.0+dfsg
authorJochen Sprickerhof <git@jochen.sprickerhof.de>
Wed, 7 Feb 2024 07:16:54 +0000 (08:16 +0100)
committerJochen Sprickerhof <git@jochen.sprickerhof.de>
Wed, 7 Feb 2024 07:16:54 +0000 (08:16 +0100)
974 files changed:
.ci/azure-pipelines/azure-pipelines.yaml
.ci/azure-pipelines/env.yml
.ci/azure-pipelines/release.yaml
.ci/azure-pipelines/ubuntu-variety.yaml
.ci/scripts/build_tutorials.sh
.clang-format
.clang-tidy
.dev/docker/env/Dockerfile
.dev/docker/perception_pcl_ros/Dockerfile
.dev/docker/perception_pcl_ros/colcon.Dockerfile
.dev/docker/release/Dockerfile
.dev/docker/ubuntu-variety/Dockerfile
.dev/docker/windows/Dockerfile
.dev/scripts/bump_post_release.bash
.github/ISSUE_TEMPLATE/compilation-failure.md
.github/workflows/clang-tidy.yml
2d/include/pcl/2d/edge.h
2d/include/pcl/2d/impl/edge.hpp
2d/include/pcl/2d/impl/kernel.hpp
2d/include/pcl/2d/kernel.h
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/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/pipeline/local_recognizer.h
apps/CMakeLists.txt
apps/cloud_composer/include/pcl/apps/cloud_composer/items/cloud_composer_item.h
apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h
apps/cloud_composer/include/pcl/apps/cloud_composer/tool_interface/tool_factory.h
apps/cloud_composer/include/pcl/apps/cloud_composer/tools/organized_segmentation.h
apps/cloud_composer/src/cloud_composer.cpp
apps/cloud_composer/src/items/cloud_item.cpp
apps/cloud_composer/src/point_selectors/click_trackball_interactor_style.cpp
apps/in_hand_scanner/CMakeLists.txt
apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h
apps/in_hand_scanner/src/icp.cpp
apps/in_hand_scanner/src/integration.cpp
apps/in_hand_scanner/src/main_window.cpp
apps/in_hand_scanner/src/offline_integration.cpp
apps/in_hand_scanner/src/opengl_viewer.cpp
apps/include/pcl/apps/manual_registration.h
apps/include/pcl/apps/pcl_viewer_dialog.h [new file with mode: 0644]
apps/include/pcl/apps/render_views_tesselated_sphere.h
apps/modeler/include/pcl/apps/modeler/cloud_mesh.h
apps/modeler/src/channel_actor_item.cpp
apps/modeler/src/main_window.cpp
apps/modeler/src/render_window.cpp
apps/point_cloud_editor/CMakeLists.txt
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/command.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/localTypes.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/mainWindow.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select1DTool.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/statistics.h
apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/toolInterface.h
apps/point_cloud_editor/src/cloud.cpp
apps/point_cloud_editor/src/cloudEditorWidget.cpp
apps/point_cloud_editor/src/select1DTool.cpp
apps/point_cloud_editor/src/select2DTool.cpp
apps/point_cloud_editor/src/transformCommand.cpp
apps/src/face_detection/openni_face_detection.cpp
apps/src/feature_matching.cpp
apps/src/manual_registration/manual_registration.cpp
apps/src/manual_registration/manual_registration.ui
apps/src/manual_registration/pcl_viewer_dialog.cpp [new file with mode: 0644]
apps/src/manual_registration/pcl_viewer_dialog.ui [new file with mode: 0644]
apps/src/multiscale_feature_persistence_example.cpp
apps/src/openni_3d_concave_hull.cpp
apps/src/openni_3d_convex_hull.cpp
apps/src/openni_boundary_estimation.cpp
apps/src/openni_color_filter.cpp
apps/src/openni_fast_mesh.cpp
apps/src/openni_feature_persistence.cpp
apps/src/openni_grab_frame.cpp
apps/src/openni_grab_images.cpp
apps/src/openni_ii_normal_estimation.cpp
apps/src/openni_klt.cpp
apps/src/openni_mls_smoothing.cpp
apps/src/openni_mobile_server.cpp
apps/src/openni_organized_edge_detection.cpp
apps/src/openni_passthrough.cpp
apps/src/openni_planar_convex_hull.cpp
apps/src/openni_planar_segmentation.cpp
apps/src/openni_shift_to_depth_conversion.cpp
apps/src/openni_tracking.cpp
apps/src/openni_uniform_sampling.cpp
apps/src/openni_voxel_grid.cpp
apps/src/organized_segmentation_demo.cpp
apps/src/pcd_organized_edge_detection.cpp
apps/src/pcd_video_player/pcd_video_player.cpp
apps/src/ppf_object_recognition.cpp
apps/src/pyramid_surface_matching.cpp
apps/src/render_views_tesselated_sphere.cpp
apps/src/statistical_multiscale_interest_region_extraction_example.cpp
benchmarks/CMakeLists.txt
benchmarks/search/radius_search.cpp [new file with mode: 0644]
cmake/Modules/FindEigen.cmake [deleted file]
cmake/Modules/FindFLANN.cmake
cmake/Modules/FindOpenMP.cmake
cmake/Modules/FindPcap.cmake
cmake/Modules/Findlibusb.cmake
cmake/pcl_all_in_one_installer.cmake
cmake/pcl_find_boost.cmake
cmake/pcl_find_qt.cmake
cmake/pcl_pclconfig.cmake
cmake/pcl_targets.cmake
common/CMakeLists.txt
common/include/pcl/PCLPointCloud2.h
common/include/pcl/PolygonMesh.h
common/include/pcl/common/bivariate_polynomial.h
common/include/pcl/common/boost.h
common/include/pcl/common/centroid.h
common/include/pcl/common/eigen.h
common/include/pcl/common/gaussian.h
common/include/pcl/common/generate.h
common/include/pcl/common/impl/bivariate_polynomial.hpp
common/include/pcl/common/impl/centroid.hpp
common/include/pcl/common/impl/common.hpp
common/include/pcl/common/impl/copy_point.hpp
common/include/pcl/common/impl/eigen.hpp
common/include/pcl/common/impl/gaussian.hpp
common/include/pcl/common/impl/generate.hpp
common/include/pcl/common/impl/intersections.hpp
common/include/pcl/common/impl/io.hpp
common/include/pcl/common/impl/pca.hpp
common/include/pcl/common/impl/random.hpp
common/include/pcl/common/io.h
common/include/pcl/common/pca.h
common/include/pcl/common/polynomial_calculations.h
common/include/pcl/conversions.h
common/include/pcl/exceptions.h
common/include/pcl/impl/cloud_iterator.hpp
common/include/pcl/impl/pcl_base.hpp
common/include/pcl/impl/point_types.hpp
common/include/pcl/pcl_macros.h
common/include/pcl/point_cloud.h
common/include/pcl/point_representation.h
common/include/pcl/point_types_conversion.h
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/include/pcl/register_point_struct.h
common/src/PCLPointCloud2.cpp
common/src/bearing_angle_image.cpp
common/src/colors.cpp
common/src/gaussian.cpp
common/src/io.cpp
common/src/pcl_base.cpp
common/src/range_image.cpp
common/src/range_image_planar.cpp
cuda/common/include/pcl/cuda/point_cloud.h
cuda/features/CMakeLists.txt
cuda/features/include/pcl/cuda/features/normal_3d_kernels.h
cuda/io/CMakeLists.txt
cuda/segmentation/CMakeLists.txt
doc/advanced/.readthedocs.yaml [new file with mode: 0644]
doc/advanced/content/exceptions_guide.rst
doc/advanced/content/pcl_style_guide.rst
doc/doxygen/pcl.doxy
doc/requirements.txt
doc/tutorials/.readthedocs.yaml [new file with mode: 0644]
doc/tutorials/content/building_pcl.rst
doc/tutorials/content/cluster_extraction.rst
doc/tutorials/content/compiling_pcl_posix.rst
doc/tutorials/content/depth_sense_grabber.rst
doc/tutorials/content/dinast_grabber.rst
doc/tutorials/content/ensenso_cameras.rst
doc/tutorials/content/fpfh_estimation.rst
doc/tutorials/content/function_filter.rst
doc/tutorials/content/gasd_estimation.rst
doc/tutorials/content/global_hypothesis_verification.rst
doc/tutorials/content/gpu_install.rst
doc/tutorials/content/hdl_grabber.rst
doc/tutorials/content/images/vcpkg/cmake_configure_1.png [new file with mode: 0644]
doc/tutorials/content/images/vcpkg/cmake_configure_2.png [new file with mode: 0644]
doc/tutorials/content/index.rst
doc/tutorials/content/kdtree_search.rst
doc/tutorials/content/min_cut_segmentation.rst
doc/tutorials/content/moment_of_inertia.rst
doc/tutorials/content/normal_estimation.rst
doc/tutorials/content/normal_estimation_using_integral_images.rst
doc/tutorials/content/openni_grabber.rst
doc/tutorials/content/pcd_file_format.rst
doc/tutorials/content/pcl_plotter.rst
doc/tutorials/content/pcl_vcpkg_windows.rst [new file with mode: 0644]
doc/tutorials/content/pcl_visualizer.rst
doc/tutorials/content/pfh_estimation.rst
doc/tutorials/content/planar_segmentation.rst
doc/tutorials/content/qt_colorize_cloud.rst
doc/tutorials/content/qt_visualizer.rst
doc/tutorials/content/random_sample_consensus.rst
doc/tutorials/content/registration_api.rst
doc/tutorials/content/sources/cloud_viewer/cloud_viewer.cpp
doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp
doc/tutorials/content/sources/cmake_test/CMakeLists.txt [new file with mode: 0644]
doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp
doc/tutorials/content/sources/gpu/people_detect/src/people_detect.cpp
doc/tutorials/content/sources/iccv2011/include/feature_estimation.h
doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp
doc/tutorials/content/sources/iccv2011/src/tutorial.cpp
doc/tutorials/content/sources/implicit_shape_model/implicit_shape_model.cpp
doc/tutorials/content/sources/iros2011/include/feature_estimation.h
doc/tutorials/content/sources/iros2011/include/solution/feature_estimation.h
doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp
doc/tutorials/content/sources/normal_estimation_using_integral_images/normal_estimation_using_integral_images.cpp
doc/tutorials/content/sources/pairwise_incremental_registration/pairwise_incremental_registration.cpp
doc/tutorials/content/sources/pcl_plotter/pcl_plotter_demo.cpp
doc/tutorials/content/sources/vfh_recognition/build_tree.cpp
doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp
doc/tutorials/content/tracking.rst
doc/tutorials/content/using_pcl_pcl_config.rst
doc/tutorials/content/vfh_estimation.rst
doc/tutorials/content/visualization.rst
doc/tutorials/content/walkthrough.rst
doc/tutorials/content/writing_new_classes.rst
examples/features/example_difference_of_normals.cpp
examples/keypoints/example_sift_keypoint_estimation.cpp
examples/keypoints/example_sift_normal_keypoint_estimation.cpp
examples/keypoints/example_sift_z_keypoint_estimation.cpp
examples/segmentation/example_cpc_segmentation.cpp
examples/segmentation/example_extract_clusters_normals.cpp
examples/segmentation/example_lccp_segmentation.cpp
examples/segmentation/example_supervoxels.cpp
features/CMakeLists.txt
features/include/pcl/features/3dsc.h
features/include/pcl/features/board.h
features/include/pcl/features/boundary.h
features/include/pcl/features/brisk_2d.h
features/include/pcl/features/crh.h
features/include/pcl/features/cvfh.h
features/include/pcl/features/flare.h
features/include/pcl/features/fpfh.h
features/include/pcl/features/fpfh_omp.h
features/include/pcl/features/gfpfh.h
features/include/pcl/features/grsd.h
features/include/pcl/features/impl/brisk_2d.hpp
features/include/pcl/features/impl/esf.hpp
features/include/pcl/features/impl/flare.hpp
features/include/pcl/features/impl/gasd.hpp
features/include/pcl/features/impl/integral_image2D.hpp
features/include/pcl/features/impl/integral_image_normal.hpp
features/include/pcl/features/impl/intensity_spin.hpp
features/include/pcl/features/impl/moment_of_inertia_estimation.hpp
features/include/pcl/features/impl/multiscale_feature_persistence.hpp
features/include/pcl/features/impl/normal_3d_omp.hpp
features/include/pcl/features/impl/organized_edge_detection.hpp
features/include/pcl/features/impl/range_image_border_extractor.hpp
features/include/pcl/features/impl/rops_estimation.hpp
features/include/pcl/features/impl/rsd.hpp
features/include/pcl/features/impl/shot.hpp
features/include/pcl/features/impl/spin_image.hpp
features/include/pcl/features/integral_image2D.h
features/include/pcl/features/integral_image_normal.h
features/include/pcl/features/intensity_gradient.h
features/include/pcl/features/intensity_spin.h
features/include/pcl/features/linear_least_squares_normal.h
features/include/pcl/features/moment_of_inertia_estimation.h
features/include/pcl/features/multiscale_feature_persistence.h
features/include/pcl/features/narf.h
features/include/pcl/features/narf_descriptor.h
features/include/pcl/features/normal_3d.h
features/include/pcl/features/normal_3d_omp.h
features/include/pcl/features/normal_based_signature.h
features/include/pcl/features/organized_edge_detection.h
features/include/pcl/features/our_cvfh.h
features/include/pcl/features/pfh.h
features/include/pcl/features/pfhrgb.h
features/include/pcl/features/range_image_border_extractor.h
features/include/pcl/features/rift.h
features/include/pcl/features/rops_estimation.h
features/include/pcl/features/rsd.h
features/include/pcl/features/shot.h
features/include/pcl/features/spin_image.h
features/include/pcl/features/usc.h
features/include/pcl/features/vfh.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/bilateral.h
filters/include/pcl/filters/box_clipper3D.h
filters/include/pcl/filters/conditional_removal.h
filters/include/pcl/filters/convolution.h
filters/include/pcl/filters/crop_hull.h
filters/include/pcl/filters/fast_bilateral.h
filters/include/pcl/filters/filter_indices.h
filters/include/pcl/filters/frustum_culling.h
filters/include/pcl/filters/impl/box_clipper3D.hpp
filters/include/pcl/filters/impl/conditional_removal.hpp
filters/include/pcl/filters/impl/convolution.hpp
filters/include/pcl/filters/impl/covariance_sampling.hpp
filters/include/pcl/filters/impl/crop_hull.hpp
filters/include/pcl/filters/impl/extract_indices.hpp
filters/include/pcl/filters/impl/frustum_culling.hpp
filters/include/pcl/filters/impl/grid_minimum.hpp
filters/include/pcl/filters/impl/local_maximum.hpp
filters/include/pcl/filters/impl/radius_outlier_removal.hpp
filters/include/pcl/filters/impl/sampling_surface_normal.hpp
filters/include/pcl/filters/impl/statistical_outlier_removal.hpp
filters/include/pcl/filters/impl/voxel_grid_covariance.hpp
filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp
filters/include/pcl/filters/local_maximum.h
filters/include/pcl/filters/median_filter.h
filters/include/pcl/filters/model_outlier_removal.h
filters/include/pcl/filters/normal_refinement.h
filters/include/pcl/filters/passthrough.h
filters/include/pcl/filters/plane_clipper3D.h
filters/include/pcl/filters/project_inliers.h
filters/include/pcl/filters/pyramid.h
filters/include/pcl/filters/radius_outlier_removal.h
filters/include/pcl/filters/random_sample.h
filters/include/pcl/filters/sampling_surface_normal.h
filters/include/pcl/filters/shadowpoints.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/extract_indices.cpp
filters/src/passthrough.cpp
filters/src/statistical_outlier_removal.cpp
filters/src/voxel_grid.cpp
filters/src/voxel_grid_label.cpp
geometry/include/pcl/geometry/mesh_base.h
geometry/include/pcl/geometry/mesh_conversion.h
geometry/include/pcl/geometry/organized_index_iterator.h
geometry/include/pcl/geometry/planar_polygon.h
gpu/containers/CMakeLists.txt
gpu/containers/include/pcl/gpu/containers/device_array.h
gpu/containers/include/pcl/gpu/containers/device_memory.h
gpu/examples/segmentation/src/seg.cpp
gpu/features/src/features.cpp
gpu/kinfu/CMakeLists.txt
gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h
gpu/kinfu/src/cuda/extract.cu
gpu/kinfu/src/cuda/marching_cubes.cu
gpu/kinfu/src/internal.h
gpu/kinfu/tools/evaluation.h
gpu/kinfu/tools/kinfu_app.cpp
gpu/kinfu/tools/kinfu_app_sim.cpp
gpu/kinfu/tools/plot_camera_poses.m
gpu/kinfu/tools/record_tsdfvolume.cpp
gpu/kinfu/tools/tsdf_volume.h
gpu/kinfu_large_scale/CMakeLists.txt
gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h
gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h
gpu/kinfu_large_scale/src/cuda/extract.cu
gpu/kinfu_large_scale/src/cuda/marching_cubes.cu
gpu/kinfu_large_scale/src/cyclical_buffer.cpp
gpu/kinfu_large_scale/src/internal.h
gpu/kinfu_large_scale/tools/evaluation.h
gpu/kinfu_large_scale/tools/kinfuLS_app.cpp
gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp
gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp
gpu/kinfu_large_scale/tools/record_maps_rgb.cpp
gpu/kinfu_large_scale/tools/record_tsdfvolume.cpp
gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp
gpu/octree/include/pcl/gpu/octree/octree.hpp
gpu/octree/src/octree.cpp
gpu/people/include/pcl/gpu/people/tree.h
gpu/people/src/bodyparts_detector.cpp
gpu/people/src/cuda/elec.cu
gpu/people/src/cuda/nvidia/NCV.hpp
gpu/people/src/face_detector.cpp
gpu/people/tools/people_app.cpp
gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h
gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h
gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h
gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp
gpu/segmentation/src/extract_clusters.cpp
gpu/surface/src/cuda/convex_hull.cu
io/CMakeLists.txt
io/include/pcl/compression/color_coding.h
io/include/pcl/compression/impl/entropy_range_coder.hpp
io/include/pcl/compression/impl/organized_pointcloud_compression.hpp
io/include/pcl/compression/octree_pointcloud_compression.h
io/include/pcl/compression/point_coding.h
io/include/pcl/io/boost.h
io/include/pcl/io/dinast_grabber.h
io/include/pcl/io/ensenso_grabber.h
io/include/pcl/io/file_io.h
io/include/pcl/io/grabber.h
io/include/pcl/io/impl/lzf_image_io.hpp
io/include/pcl/io/impl/pcd_io.hpp
io/include/pcl/io/impl/point_cloud_image_extractors.hpp
io/include/pcl/io/impl/synchronized_queue.hpp
io/include/pcl/io/io.h
io/include/pcl/io/io_exception.h
io/include/pcl/io/lzf_image_io.h
io/include/pcl/io/oni_grabber.h
io/include/pcl/io/openni2/openni2_device.h
io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h
io/include/pcl/io/openni2_grabber.h
io/include/pcl/io/openni_camera/openni_depth_image.h
io/include/pcl/io/openni_camera/openni_device.h
io/include/pcl/io/openni_camera/openni_device_kinect.h
io/include/pcl/io/openni_camera/openni_device_oni.h
io/include/pcl/io/openni_camera/openni_device_primesense.h
io/include/pcl/io/openni_camera/openni_device_xtion.h
io/include/pcl/io/openni_camera/openni_driver.h
io/include/pcl/io/openni_camera/openni_exception.h
io/include/pcl/io/openni_camera/openni_image.h
io/include/pcl/io/openni_camera/openni_image_bayer_grbg.h
io/include/pcl/io/openni_camera/openni_ir_image.h
io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h
io/include/pcl/io/openni_grabber.h
io/include/pcl/io/pcd_io.h
io/include/pcl/io/ply/ply_parser.h
io/include/pcl/io/ply_io.h
io/include/pcl/io/point_cloud_image_extractors.h
io/include/pcl/io/real_sense_2_grabber.h
io/include/pcl/io/split.h
io/include/pcl/io/tar.h
io/include/pcl/io/tim_grabber.h
io/include/pcl/io/timestamp.h [new file with mode: 0644]
io/io.doxy
io/src/ascii_io.cpp
io/src/davidsdk_grabber.cpp
io/src/dinast_grabber.cpp
io/src/ensenso_grabber.cpp
io/src/hdl_grabber.cpp
io/src/ifs_io.cpp
io/src/image_grabber.cpp
io/src/io_exception.cpp
io/src/libpng_wrapper.cpp
io/src/lzf_image_io.cpp
io/src/obj_io.cpp
io/src/oni_grabber.cpp
io/src/openni2/openni2_device.cpp
io/src/openni2/openni2_video_mode.cpp
io/src/openni2_grabber.cpp
io/src/openni_camera/openni_device.cpp
io/src/openni_camera/openni_device_kinect.cpp
io/src/openni_camera/openni_device_oni.cpp
io/src/openni_camera/openni_device_primesense.cpp
io/src/openni_camera/openni_device_xtion.cpp
io/src/openni_camera/openni_driver.cpp
io/src/openni_camera/openni_exception.cpp
io/src/openni_grabber.cpp
io/src/pcd_io.cpp
io/src/ply/ply_parser.cpp
io/src/ply_io.cpp
io/src/png_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
io/tools/CMakeLists.txt [deleted file]
io/tools/convert_pcd_ascii_binary.cpp [deleted file]
io/tools/converter.cpp [deleted file]
io/tools/hdl_grabber_example.cpp [deleted file]
io/tools/openni_grabber_depth_example.cpp [deleted file]
io/tools/openni_grabber_example.cpp [deleted file]
io/tools/openni_pcd_recorder.cpp [deleted file]
io/tools/pcd_convert_NaN_nan.cpp [deleted file]
io/tools/pcd_introduce_nan.cpp [deleted file]
io/tools/ply/CMakeLists.txt [deleted file]
io/tools/ply/ply2obj.cpp [deleted file]
io/tools/ply/ply2ply.cpp [deleted file]
io/tools/ply/ply2raw.cpp [deleted file]
io/tools/ply/plyheader.cpp [deleted file]
kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp
kdtree/include/pcl/kdtree/kdtree.h
kdtree/include/pcl/kdtree/kdtree_flann.h
kdtree/kdtree.doxy
keypoints/CMakeLists.txt
keypoints/include/pcl/keypoints/agast_2d.h
keypoints/include/pcl/keypoints/brisk_2d.h
keypoints/include/pcl/keypoints/harris_2d.h
keypoints/include/pcl/keypoints/harris_3d.h
keypoints/include/pcl/keypoints/harris_6d.h
keypoints/include/pcl/keypoints/impl/brisk_2d.hpp
keypoints/include/pcl/keypoints/impl/harris_3d.hpp
keypoints/include/pcl/keypoints/impl/harris_6d.hpp
keypoints/include/pcl/keypoints/impl/iss_3d.hpp
keypoints/include/pcl/keypoints/impl/sift_keypoint.hpp
keypoints/include/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp
keypoints/include/pcl/keypoints/impl/trajkovic_2d.hpp
keypoints/include/pcl/keypoints/iss_3d.h
keypoints/include/pcl/keypoints/keypoint.h
keypoints/include/pcl/keypoints/narf_keypoint.h
keypoints/include/pcl/keypoints/sift_keypoint.h
keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h
keypoints/include/pcl/keypoints/susan.h
keypoints/include/pcl/keypoints/trajkovic_2d.h
keypoints/include/pcl/keypoints/trajkovic_3d.h
keypoints/keypoints.doxy
keypoints/src/agast_2d.cpp
keypoints/src/brisk_2d.cpp
keypoints/src/narf_keypoint.cpp
ml/include/pcl/ml/densecrf.h
ml/include/pcl/ml/dt/decision_forest_trainer.h
ml/include/pcl/ml/dt/decision_tree_trainer.h
ml/include/pcl/ml/ferns/fern_trainer.h
ml/include/pcl/ml/impl/dt/decision_forest_trainer.hpp
ml/include/pcl/ml/impl/dt/decision_tree_trainer.hpp
ml/include/pcl/ml/permutohedral.h
ml/include/pcl/ml/point_xy_32f.h
ml/include/pcl/ml/point_xy_32i.h
ml/include/pcl/ml/stats_estimator.h
ml/include/pcl/ml/svm.h
ml/include/pcl/ml/svm_wrapper.h
ml/src/densecrf.cpp
ml/src/permutohedral.cpp
ml/src/svm.cpp
ml/src/svm_wrapper.cpp
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/octree2buf_base.h
octree/include/pcl/octree/octree_base.h
octree/include/pcl/octree/octree_container.h
octree/include/pcl/octree/octree_iterator.h
octree/include/pcl/octree/octree_key.h
octree/include/pcl/octree/octree_nodes.h
octree/include/pcl/octree/octree_pointcloud.h
octree/include/pcl/octree/octree_pointcloud_density.h
octree/include/pcl/octree/octree_search.h
outofcore/include/pcl/outofcore/impl/lru_cache.hpp
outofcore/include/pcl/outofcore/impl/octree_base.hpp
outofcore/include/pcl/outofcore/impl/octree_base_node.hpp
outofcore/include/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp
outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp
outofcore/include/pcl/outofcore/octree_base_node.h
outofcore/include/pcl/outofcore/octree_disk_container.h
outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h
outofcore/include/pcl/outofcore/outofcore_node_data.h
outofcore/include/pcl/outofcore/visualization/camera.h
outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h
outofcore/src/outofcore_node_data.cpp
outofcore/src/visualization/camera.cpp
outofcore/src/visualization/grid.cpp
outofcore/src/visualization/outofcore_cloud.cpp
outofcore/src/visualization/viewport.cpp
outofcore/tools/outofcore_print.cpp
outofcore/tools/outofcore_process.cpp
outofcore/tools/outofcore_viewer.cpp
pcl_config.h.in
people/apps/main_ground_based_people_detection.cpp
people/include/pcl/people/impl/ground_based_people_detection_app.hpp
people/include/pcl/people/impl/head_based_subcluster.hpp
people/include/pcl/people/impl/height_map_2d.hpp
people/include/pcl/people/impl/person_classifier.hpp
people/src/hog.cpp
recognition/include/pcl/recognition/3rdparty/metslib/abstract-search.hh
recognition/include/pcl/recognition/3rdparty/metslib/model.hh
recognition/include/pcl/recognition/3rdparty/metslib/simulated-annealing.hh
recognition/include/pcl/recognition/3rdparty/metslib/tabu-search.hh
recognition/include/pcl/recognition/cg/geometric_consistency.h
recognition/include/pcl/recognition/cg/hough_3d.h
recognition/include/pcl/recognition/color_gradient_modality.h
recognition/include/pcl/recognition/crh_alignment.h
recognition/include/pcl/recognition/distance_map.h
recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h
recognition/include/pcl/recognition/face_detection/rf_face_utils.h
recognition/include/pcl/recognition/impl/cg/hough_3d.hpp
recognition/include/pcl/recognition/impl/hv/hv_go.hpp
recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp
recognition/include/pcl/recognition/impl/hv/occlusion_reasoning.hpp
recognition/include/pcl/recognition/impl/implicit_shape_model.hpp
recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp
recognition/include/pcl/recognition/impl/ransac_based/simple_octree.hpp
recognition/include/pcl/recognition/implicit_shape_model.h
recognition/include/pcl/recognition/linemod.h
recognition/include/pcl/recognition/linemod/line_rgbd.h
recognition/include/pcl/recognition/quantized_map.h
recognition/include/pcl/recognition/ransac_based/hypothesis.h
recognition/include/pcl/recognition/ransac_based/model_library.h
recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h
recognition/include/pcl/recognition/ransac_based/orr_octree.h
recognition/include/pcl/recognition/ransac_based/orr_octree_zprojection.h
recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h
recognition/include/pcl/recognition/ransac_based/simple_octree.h
recognition/include/pcl/recognition/ransac_based/trimmed_icp.h
recognition/include/pcl/recognition/region_xy.h
recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h
recognition/include/pcl/recognition/surface_normal_modality.h
recognition/src/cg/hough_3d.cpp
recognition/src/dotmod.cpp
recognition/src/face_detection/face_detector_data_provider.cpp
recognition/src/face_detection/rf_face_detector_trainer.cpp
recognition/src/linemod.cpp
recognition/src/ransac_based/model_library.cpp
recognition/src/ransac_based/obj_rec_ransac.cpp
recognition/src/ransac_based/orr_octree.cpp
registration/CMakeLists.txt
registration/include/pcl/registration/bfgs.h
registration/include/pcl/registration/correspondence_estimation.h
registration/include/pcl/registration/correspondence_estimation_backprojection.h
registration/include/pcl/registration/correspondence_estimation_normal_shooting.h
registration/include/pcl/registration/correspondence_estimation_organized_projection.h
registration/include/pcl/registration/correspondence_rejection.h
registration/include/pcl/registration/correspondence_rejection_median_distance.h
registration/include/pcl/registration/correspondence_rejection_organized_boundary.h
registration/include/pcl/registration/correspondence_rejection_poly.h
registration/include/pcl/registration/correspondence_rejection_sample_consensus.h
registration/include/pcl/registration/correspondence_rejection_surface_normal.h
registration/include/pcl/registration/correspondence_rejection_trimmed.h
registration/include/pcl/registration/correspondence_rejection_var_trimmed.h
registration/include/pcl/registration/default_convergence_criteria.h
registration/include/pcl/registration/elch.h
registration/include/pcl/registration/gicp.h
registration/include/pcl/registration/ia_fpcs.h
registration/include/pcl/registration/ia_kfpcs.h
registration/include/pcl/registration/ia_ransac.h
registration/include/pcl/registration/icp.h
registration/include/pcl/registration/impl/correspondence_estimation.hpp
registration/include/pcl/registration/impl/correspondence_estimation_backprojection.hpp
registration/include/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp
registration/include/pcl/registration/impl/correspondence_rejection_poly.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.hpp
registration/include/pcl/registration/impl/joint_icp.hpp
registration/include/pcl/registration/impl/lum.hpp
registration/include/pcl/registration/impl/ndt.hpp
registration/include/pcl/registration/impl/ndt_2d.hpp
registration/include/pcl/registration/impl/ppf_registration.hpp
registration/include/pcl/registration/impl/pyramid_feature_matching.hpp
registration/include/pcl/registration/impl/registration.hpp
registration/include/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp
registration/include/pcl/registration/impl/transformation_estimation_lm.hpp
registration/include/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp
registration/include/pcl/registration/incremental_registration.h
registration/include/pcl/registration/lum.h
registration/include/pcl/registration/ndt.h
registration/include/pcl/registration/ndt_2d.h
registration/include/pcl/registration/ppf_registration.h
registration/include/pcl/registration/pyramid_feature_matching.h
registration/include/pcl/registration/registration.h
registration/include/pcl/registration/sample_consensus_prerejective.h
registration/include/pcl/registration/transformation_estimation_lm.h
registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h
registration/include/pcl/registration/transformation_estimation_svd.h
registration/include/pcl/registration/transformation_estimation_symmetric_point_to_plane_lls.h
registration/include/pcl/registration/transformation_validation_euclidean.h
registration/include/pcl/registration/vertex_estimates.h
registration/src/correspondence_rejection_trimmed.cpp
registration/src/correspondence_rejection_var_trimmed.cpp
registration/src/gicp6d.cpp
registration/src/icp.cpp
registration/src/transformation_estimation_svd.cpp
sample_consensus/include/pcl/sample_consensus/impl/msac.hpp
sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp
sample_consensus/include/pcl/sample_consensus/impl/sac_model_sphere.hpp
sample_consensus/include/pcl/sample_consensus/method_types.h
sample_consensus/include/pcl/sample_consensus/sac_model.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_sphere.h
sample_consensus/include/pcl/sample_consensus/sac_model_stick.h
sample_consensus/sample_consensus.doxy
sample_consensus/src/sac_model_cone.cpp
sample_consensus/src/sac_model_cylinder.cpp
sample_consensus/src/sac_model_sphere.cpp
sample_consensus/src/sac_model_stick.cpp
search/include/pcl/search/flann_search.h
search/include/pcl/search/impl/flann_search.hpp
search/include/pcl/search/impl/kdtree.hpp
search/include/pcl/search/impl/organized.hpp
search/include/pcl/search/impl/search.hpp
search/include/pcl/search/kdtree.h
search/include/pcl/search/octree.h
search/include/pcl/search/organized.h
search/include/pcl/search/search.h
segmentation/CMakeLists.txt
segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h
segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h
segmentation/include/pcl/segmentation/cpc_segmentation.h
segmentation/include/pcl/segmentation/crf_normal_segmentation.h
segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h
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/grabcut_segmentation.h
segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp
segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp
segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp
segmentation/include/pcl/segmentation/impl/extract_clusters.hpp
segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp
segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp
segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp
segmentation/include/pcl/segmentation/impl/organized_connected_component_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/sac_segmentation.hpp
segmentation/include/pcl/segmentation/impl/segment_differences.hpp
segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp
segmentation/include/pcl/segmentation/impl/unary_classifier.hpp
segmentation/include/pcl/segmentation/lccp_segmentation.h
segmentation/include/pcl/segmentation/min_cut_segmentation.h
segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h
segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h
segmentation/include/pcl/segmentation/planar_region.h
segmentation/include/pcl/segmentation/progressive_morphological_filter.h
segmentation/include/pcl/segmentation/region_growing.h
segmentation/include/pcl/segmentation/region_growing_rgb.h
segmentation/include/pcl/segmentation/sac_segmentation.h
segmentation/include/pcl/segmentation/seeded_hue_segmentation.h
segmentation/include/pcl/segmentation/segment_differences.h
segmentation/include/pcl/segmentation/supervoxel_clustering.h
segmentation/include/pcl/segmentation/unary_classifier.h
segmentation/src/crf_normal_segmentation.cpp [deleted file]
segmentation/src/extract_clusters.cpp
segmentation/src/grabcut_segmentation.cpp
simulation/include/pcl/simulation/camera.h
simulation/include/pcl/simulation/model.h
simulation/include/pcl/simulation/range_likelihood.h
simulation/src/glsl_shader.cpp
simulation/src/model.cpp
simulation/src/range_likelihood.cpp
simulation/src/sum_reduce.cpp
simulation/tools/README_about_tools
simulation/tools/sim_terminal_demo.cpp
simulation/tools/sim_test_simple.cpp
simulation/tools/sim_viewer.cpp
stereo/include/pcl/stereo/digital_elevation_map.h
stereo/include/pcl/stereo/disparity_map_converter.h
stereo/include/pcl/stereo/impl/disparity_map_converter.hpp
stereo/include/pcl/stereo/stereo_matching.h
stereo/src/digital_elevation_map.cpp
stereo/src/stereo_adaptive_cost_so.cpp
stereo/src/stereo_grabber.cpp
surface/CMakeLists.txt
surface/include/pcl/surface/3rdparty/opennurbs/crc32.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/deflate.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/inffast.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/inffixed.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/inflate.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/inftrees.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_array_defs.h
surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_system.h
surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_zlib.h
surface/include/pcl/surface/3rdparty/opennurbs/trees.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/zconf.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/zlib.h [deleted file]
surface/include/pcl/surface/3rdparty/opennurbs/zutil.h [deleted file]
surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp
surface/include/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp
surface/include/pcl/surface/bilateral_upsampling.h
surface/include/pcl/surface/concave_hull.h
surface/include/pcl/surface/convex_hull.h
surface/include/pcl/surface/ear_clipping.h
surface/include/pcl/surface/gp3.h
surface/include/pcl/surface/grid_projection.h
surface/include/pcl/surface/impl/concave_hull.hpp
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/impl/mls.hpp
surface/include/pcl/surface/impl/organized_fast_mesh.hpp
surface/include/pcl/surface/impl/poisson.hpp
surface/include/pcl/surface/impl/texture_mapping.hpp
surface/include/pcl/surface/marching_cubes.h
surface/include/pcl/surface/marching_cubes_hoppe.h
surface/include/pcl/surface/marching_cubes_rbf.h
surface/include/pcl/surface/mls.h
surface/include/pcl/surface/organized_fast_mesh.h
surface/include/pcl/surface/poisson.h
surface/include/pcl/surface/reconstruction.h
surface/include/pcl/surface/texture_mapping.h
surface/include/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h
surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h
surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h
surface/include/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h
surface/src/3rdparty/opennurbs/adler32.c [deleted file]
surface/src/3rdparty/opennurbs/compress.c [deleted file]
surface/src/3rdparty/opennurbs/crc32.c [deleted file]
surface/src/3rdparty/opennurbs/deflate.c [deleted file]
surface/src/3rdparty/opennurbs/infback.c [deleted file]
surface/src/3rdparty/opennurbs/inffast.c [deleted file]
surface/src/3rdparty/opennurbs/inflate.c [deleted file]
surface/src/3rdparty/opennurbs/inftrees.c [deleted file]
surface/src/3rdparty/opennurbs/openNURBS.cmake
surface/src/3rdparty/opennurbs/opennurbs_zlib.cpp
surface/src/3rdparty/opennurbs/trees.c [deleted file]
surface/src/3rdparty/opennurbs/uncompr.c [deleted file]
surface/src/3rdparty/opennurbs/zlib.cmake [new file with mode: 0644]
surface/src/3rdparty/opennurbs/zutil.c [deleted file]
surface/src/3rdparty/poisson4/bspline_data.cpp
surface/src/3rdparty/poisson4/geometry.cpp
surface/src/mls.cpp
surface/src/on_nurbs/nurbs_solve_eigen.cpp
surface/src/on_nurbs/sequential_fitter.cpp
surface/src/vtk_smoothing/vtk_mesh_quadric_decimation.cpp
surface/src/vtk_smoothing/vtk_mesh_subdivision.cpp
surface/src/vtk_smoothing/vtk_utils.cpp
test/common/test_centroid.cpp
test/common/test_eigen.cpp
test/common/test_io.cpp
test/common/test_macros.cpp
test/common/test_parse.cpp
test/common/test_plane_intersection.cpp
test/common/test_polygon_mesh.cpp
test/common/test_spring.cpp
test/common/test_transforms.cpp
test/common/test_wrappers.cpp
test/features/test_boundary_estimation.cpp
test/features/test_brisk.cpp
test/features/test_flare_estimation.cpp
test/features/test_gasd_estimation.cpp
test/features/test_gradient_estimation.cpp
test/features/test_ii_normals.cpp
test/features/test_normal_estimation.cpp
test/features/test_pfh_estimation.cpp
test/filters/test_clipper.cpp
test/filters/test_convolution.cpp
test/filters/test_crop_hull.cpp
test/filters/test_farthest_point_sampling.cpp
test/filters/test_filters.cpp
test/filters/test_local_maximum.cpp
test/filters/test_uniform_sampling.cpp
test/geometry/test_iterator.cpp
test/geometry/test_mesh_common_functions.h
test/geometry/test_quad_mesh.cpp
test/gpu/octree/CMakeLists.txt
test/gpu/octree/perfomance.cpp [deleted file]
test/gpu/octree/performance.cpp [new file with mode: 0644]
test/gpu/octree/test_host_radius_search.cpp
test/gpu/octree/test_knn_search.cpp
test/gpu/octree/test_radius_search.cpp
test/io/CMakeLists.txt
test/io/test_grabbers.cpp
test/io/test_io.cpp
test/io/test_iterators.cpp
test/io/test_octree_compression.cpp
test/io/test_ply_io.cpp
test/io/test_ply_mesh_io.cpp
test/io/test_point_cloud_image_extractors.cpp
test/io/test_range_coder.cpp
test/io/test_tim_grabber.cpp
test/io/test_timestamp.cpp [new file with mode: 0644]
test/kdtree/test_kdtree.cpp
test/keypoints/test_iss_3d.cpp
test/keypoints/test_keypoints.cpp
test/octree/test_octree.cpp
test/octree/test_octree_iterator.cpp
test/outofcore/test_outofcore.cpp
test/recognition/test_recognition_cg.cpp
test/registration/test_correspondence_estimation.cpp
test/registration/test_correspondence_rejectors.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/registration/test_registration_api_data.h
test/sample_consensus/test_sample_consensus.cpp
test/sample_consensus/test_sample_consensus_line_models.cpp
test/sample_consensus/test_sample_consensus_plane_models.cpp
test/search/precise_distances.h [new file with mode: 0644]
test/search/test_flann_search.cpp
test/search/test_octree.cpp
test/search/test_organized.cpp
test/search/test_organized_index.cpp
test/search/test_search.cpp
test/surface/test_concave_hull.cpp
test/surface/test_convex_hull.cpp
test/surface/test_moving_least_squares.cpp
test/surface/test_poisson.cpp
test/visualization/test_visualization.cpp
tools/CMakeLists.txt
tools/convert_pcd_ascii_binary.cpp [new file with mode: 0644]
tools/converter.cpp [new file with mode: 0644]
tools/crop_to_hull.cpp
tools/elch.cpp
tools/fast_bilateral_filter.cpp
tools/gp3_surface.cpp
tools/grid_min.cpp
tools/hdl_grabber_example.cpp [new file with mode: 0644]
tools/icp.cpp
tools/icp2d.cpp
tools/image_grabber_saver.cpp
tools/image_grabber_viewer.cpp
tools/image_viewer.cpp
tools/local_max.cpp
tools/mesh_sampling.cpp
tools/mls_smoothing.cpp
tools/morph.cpp
tools/normal_estimation.cpp
tools/obj_rec_ransac_accepted_hypotheses.cpp
tools/obj_rec_ransac_model_opps.cpp
tools/obj_rec_ransac_result.cpp
tools/obj_rec_ransac_scene_opps.cpp
tools/octree_viewer.cpp
tools/openni2_viewer.cpp
tools/openni_grabber_depth_example.cpp [new file with mode: 0644]
tools/openni_grabber_example.cpp [new file with mode: 0644]
tools/openni_image.cpp
tools/openni_pcd_recorder.cpp [new file with mode: 0644]
tools/openni_save_image.cpp
tools/openni_viewer.cpp
tools/openni_viewer_simple.cpp
tools/outlier_removal.cpp
tools/passthrough_filter.cpp
tools/pcd_convert_NaN_nan.cpp [new file with mode: 0644]
tools/pcd_grabber_viewer.cpp
tools/pcd_introduce_nan.cpp [new file with mode: 0644]
tools/pcd_viewer.cpp
tools/pcl_video.cpp [deleted file]
tools/ply2obj.cpp [new file with mode: 0644]
tools/ply2ply.cpp [new file with mode: 0644]
tools/ply2raw.cpp [new file with mode: 0644]
tools/plyheader.cpp [new file with mode: 0644]
tools/progressive_morphological_filter.cpp
tools/radius_filter.cpp
tools/sac_segmentation_plane.cpp
tools/train_linemod_template.cpp
tools/transform_point_cloud.cpp
tools/unary_classifier_segment.cpp
tools/uniform_sampling.cpp
tools/virtual_scanner.cpp
tools/voxel_grid_occlusion_estimation.cpp
tools/xyz2pcd.cpp
tracking/CMakeLists.txt
tracking/include/pcl/tracking/coherence.h
tracking/include/pcl/tracking/distance_coherence.h
tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter.hpp
tracking/include/pcl/tracking/impl/particle_filter.hpp
tracking/include/pcl/tracking/impl/pyramidal_klt.hpp
tracking/include/pcl/tracking/impl/tracking.hpp
tracking/include/pcl/tracking/kld_adaptive_particle_filter.h
tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h
tracking/include/pcl/tracking/normal_coherence.h
tracking/include/pcl/tracking/particle_filter.h
tracking/include/pcl/tracking/pyramidal_klt.h
tracking/include/pcl/tracking/tracking.h
visualization/include/pcl/visualization/area_picking_event.h
visualization/include/pcl/visualization/boost.h
visualization/include/pcl/visualization/common/actor_map.h
visualization/include/pcl/visualization/common/float_image_utils.h
visualization/include/pcl/visualization/histogram_visualizer.h
visualization/include/pcl/visualization/image_viewer.h
visualization/include/pcl/visualization/impl/pcl_visualizer.hpp
visualization/include/pcl/visualization/interactor_style.h
visualization/include/pcl/visualization/keyboard_event.h
visualization/include/pcl/visualization/mouse_event.h
visualization/include/pcl/visualization/pcl_painter2D.h
visualization/include/pcl/visualization/pcl_plotter.h
visualization/include/pcl/visualization/pcl_visualizer.h
visualization/include/pcl/visualization/point_cloud_geometry_handlers.h
visualization/include/pcl/visualization/point_picking_event.h
visualization/include/pcl/visualization/registration_visualizer.h
visualization/include/pcl/visualization/vtk/vtkFixedXRenderWindowInteractor.h
visualization/include/pcl/visualization/window.h
visualization/src/cloud_viewer.cpp
visualization/src/common/common.cpp
visualization/src/common/float_image_utils.cpp
visualization/src/histogram_visualizer.cpp
visualization/src/image_viewer.cpp
visualization/src/pcl_painter2D.cpp
visualization/src/pcl_plotter.cpp
visualization/src/pcl_visualizer.cpp
visualization/src/point_cloud_handlers.cpp
visualization/src/point_picking_event.cpp
visualization/src/vtk/pcl_context_item.cpp
visualization/src/vtk/vtkFixedXRenderWindowInteractor.cxx
visualization/src/window.cpp

index 8f93718d5ce1fdcff9ca266936fd95643bf2edfb..bc6d750182067d022839fa3da0283c3f3bfe6bb8 100644 (file)
@@ -17,15 +17,15 @@ pr:
 resources:
   containers:
     - container: winx86
-      image: pointcloudlibrary/env:winx86
+      image: pointcloudlibrary/env:windows2022-x86
     - container: winx64
-      image: pointcloudlibrary/env:winx64
-    - container: env1804
-      image: pointcloudlibrary/env:18.04
+      image: pointcloudlibrary/env:windows2022-x64
     - container: env2004
       image: pointcloudlibrary/env:20.04
     - container: env2204
       image: pointcloudlibrary/env:22.04
+    - container: env2304
+      image: pointcloudlibrary/env:23.04
 
 stages:
   - stage: formatting
@@ -40,20 +40,20 @@ stages:
       - job: ubuntu
         displayName: Ubuntu
         pool:
-          vmImage: 'Ubuntu 20.04'
+          vmImage: 'ubuntu-22.04'
         strategy:
           matrix:
-            18.04 GCC:  # oldest LTS
-              CONTAINER: env1804
+            20.04 GCC:  # oldest LTS
+              CONTAINER: env2004
               CC: gcc
               CXX: g++
               BUILD_GPU: ON
               CMAKE_ARGS: '-DPCL_WARNINGS_ARE_ERRORS=ON'
-            22.04 GCC:  # latest Ubuntu
-              CONTAINER: env2204
+            23.04 GCC:  # latest Ubuntu
+              CONTAINER: env2304
               CC: gcc
               CXX: g++
-              BUILD_GPU: OFF # There are currently incompatibilities between GCC 11.2 and CUDA 11.5
+              BUILD_GPU: ON
         container: $[ variables['CONTAINER'] ]
         timeoutInMinutes: 0
         variables:
@@ -73,12 +73,12 @@ stages:
           vmImage: '$(VMIMAGE)'
         strategy:
           matrix:
-            Big Sur 11:
-              VMIMAGE: 'macOS-11'
-              OSX_VERSION: '11'
             Monterey 12:
               VMIMAGE: 'macOS-12'
               OSX_VERSION: '12'
+            Ventura 13:
+              VMIMAGE: 'macOS-13'
+              OSX_VERSION: '13'
         timeoutInMinutes: 0
         variables:
           BUILD_DIR: '$(Agent.WorkFolder)/build'
@@ -95,14 +95,14 @@ stages:
         dependsOn: osx
         condition: succeededOrFailed()
         pool:
-          vmImage: 'Ubuntu 20.04'
+          vmImage: 'ubuntu-22.04'
         strategy:
           matrix:
-            20.04 Clang:
-              CONTAINER: env2004
+            22.04 Clang:
+              CONTAINER: env2204
               CC: clang
               CXX: clang++
-              BUILD_GPU: ON
+              BUILD_GPU: OFF # There are currently incompatibilities between GCC 11.2 and CUDA 11.5 (Ubuntu 22.04)
               CMAKE_ARGS: ''
         container: $[ variables['CONTAINER'] ]
         timeoutInMinutes: 0
@@ -118,11 +118,11 @@ stages:
         dependsOn: osx
         condition: succeededOrFailed()
         pool:
-          vmImage: 'Ubuntu 20.04'
+          vmImage: 'ubuntu-22.04'
         strategy:
           matrix:
-            20.04 Clang:
-              CONTAINER: env2004
+            22.04 Clang:
+              CONTAINER: env2204
               CC: clang
               CXX: clang++
               INDEX_SIGNED: OFF
@@ -143,7 +143,7 @@ stages:
       - job: Windows
         displayName: Windows Build
         pool:
-          vmImage: 'windows-2019'
+          vmImage: 'windows-2022'
         strategy:
           matrix:
             x86:
index b5cde4c881b4db7540e2f1b71578715e8fee5e2f..a6559a223016493ef3b4b8511bb0e141dbd49fa4 100644 (file)
@@ -41,12 +41,7 @@ jobs:
     vmImage: 'ubuntu-latest'
   strategy:
     matrix:
-      Ubuntu 18.04:
-        # Test the oldest supported version of Ubuntu
-        UBUNTU_VERSION: 18.04
-        VTK_VERSION: 7
-        ENSENSOSDK_VERSION: 2.3.1570
-        TAG: 18.04
+      # Test the oldest supported version of Ubuntu
       Ubuntu 20.04:
         UBUNTU_VERSION: 20.04
         VTK_VERSION: 7
@@ -56,11 +51,11 @@ jobs:
         UBUNTU_VERSION: 22.04
         VTK_VERSION: 9
         TAG: 22.04
-      Ubuntu 22.10:
-        UBUNTU_VERSION: 22.10
+      Ubuntu 23.04:
+        UBUNTU_VERSION: 23.04
         USE_LATEST_CMAKE: true
         VTK_VERSION: 9
-        TAG: 22.10
+        TAG: 23.04
   steps:
   - script: |
       dockerBuildArgs="" ; \
@@ -112,17 +107,17 @@ jobs:
   timeoutInMinutes: 360
   displayName: "Env"
   pool:
-    vmImage: 'windows-2019'
+    vmImage: 'windows-2022'
   strategy:
     matrix:
       Winx86:
         PLATFORM: x86
-        TAG: winx86
+        TAG: windows2022-x86
         GENERATOR: "'Visual Studio 16 2019' -A Win32"
-        VCPKGCOMMIT: acc3bcf76b84ae5041c86ab55fe138ae7b8255c7
+        VCPKGCOMMIT: 8eb57355a4ffb410a2e94c07b4dca2dffbee8e50
       Winx64:
         PLATFORM: x64
-        TAG: winx64
+        TAG: windows2022-x64
         GENERATOR: "'Visual Studio 16 2019' -A x64"
         VCPKGCOMMIT: master
   steps:
@@ -137,7 +132,7 @@ jobs:
         -t $(dockerHubID)/env:$(TAG)
       dockerfile: '$(Build.SourcesDirectory)/.dev/docker/windows/Dockerfile'
       tags: "$(TAG)"
-      
+    
   - script: >
       docker run --rm -v "$(Build.SourcesDirectory)":c:\pcl $(dockerHubID)/env:$(TAG) 
       powershell -command "mkdir c:\pcl\build; cd c:\pcl\build; 
index b088cf29270b64288fb97c72c881132b16dd166e..81ba26c663e23ae66f1c4b15982c8921cf87c279 100644 (file)
@@ -204,8 +204,9 @@ stages:
       # find the commit hash on a quick non-forced update too
       fetchDepth: 10
     - bash: |
-        if [ -z $RC ] || [ $RC -eq 0 ]; then isPreRelease=false; else isPreRelease=true; fi
+        if [ -z $RC ] || [ $RC -eq 0 ]; then isPreRelease=false; tagName="pcl-$(VERSION)"; else isPreRelease=true; tagName="pcl-$(VERSION)-rc$(RC)"; fi
         echo "##vso[task.setvariable variable=isPreRelease]${isPreRelease}"
+        echo "##vso[task.setvariable variable=tagName]${tagName}"
     - task: DownloadBuildArtifacts@0
       inputs:
         downloadType: 'all'  # can be anything except single
@@ -223,7 +224,7 @@ stages:
         releaseNotesFilePath: '$(DOWNLOAD_LOCATION)/changelog/changelog.md'
         repositoryName: $(Build.Repository.Name)
         tagSource: 'userSpecifiedTag'
-        tag: "pcl-$(VERSION)-rc$(RC)"
+        tag: "$(tagName)"
         tagPattern: 'pcl-*'
         target: '$(Build.SourceVersion)'
         title: 'PCL $(VERSION)'
index 0910cd6f71dc1ead8b5e2d633b23ff6822409c38..24f34dbe349fff299f7c3a840ab2d32bfd1f7e5f 100644 (file)
@@ -29,12 +29,12 @@ jobs:
   displayName: "BuildUbuntuVariety"
   steps:
   - script: |
-      POSSIBLE_VTK_VERSION=("7" "9") \
+      POSSIBLE_VTK_VERSION=("9") \
       POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \
       POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \
-      POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "clang" "clang-11" "clang-12" "clang-13" "clang-14" "clang-15") \
-      POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "clang" "clang-11" "clang-12" "clang-13" "clang-14" "clang-15") \
-      POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "clang++" "clang++-11" "clang++-12" "clang++-13" "clang++-14" "clang++-15") \
+      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") \
       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]}" ; \
       echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs"
index c26d02d974e79619041295dbbba81c2d3651baf1..dac46f7444faa89c5fbd09ef452734716bc46d45 100755 (executable)
@@ -8,7 +8,7 @@ This script builds source code projects of PCL tutorials.
 
 Options:
 
-  -h             Dispaly this help and exit.
+  -h             Display this help and exit.
   -k             Keep going after a configuration/build error.
   -s             Print summary in the end.
   -e NAMES       Exclude tutorials from the build.
index 3578d7f1cad5b568801b9501101ded75c95aa1a3..42e50cdb1e294505add33de33ba4b8176934f455 100644 (file)
@@ -22,6 +22,7 @@ PointerAlignment: Left
 Standard: c++14
 TabWidth: 2
 UseTab: Never
+SortIncludes: CaseInsensitive
 IncludeBlocks: Regroup
 IncludeCategories:
 # Main PCL includes of common module should be sorted at end of PCL includes
@@ -44,6 +45,7 @@ IncludeCategories:
 # Major 3rd-Party components of apps
   - Regex:           '^<Q[^/]+>$'
     Priority:        300
+    CaseSensitive:   true
   - Regex:           '^<ui_[^/]+\.h>$'
     Priority:        300
   - Regex:           '^<vtk[^/]+\.h>$'
index c46134782b3beb76b3f24c16fc628ae9ed96df2b..b4a145f835380afe809fb2232a5f6260ca1d4ece 100644 (file)
@@ -1,5 +1,47 @@
 ---
-Checks: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast'
-WarningsAsErrors: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast'
+Checks: >
+    -*,
+    cppcoreguidelines-pro-type-cstyle-cast,
+    cppcoreguidelines-pro-type-static-cast-downcast,
+    google-readability-casting,
+    modernize-deprecated-headers,
+    modernize-loop-convert,
+    modernize-make-unique,
+    modernize-redundant-void-arg,
+    modernize-replace-random-shuffle,
+    modernize-return-braced-init-list,
+    modernize-shrink-to-fit,
+    modernize-use-auto,
+    modernize-use-bool-literals,
+    modernize-use-default-member-init,
+    modernize-use-emplace,
+    modernize-use-equals-default,
+    modernize-use-equals-delete,
+    modernize-use-noexcept,
+    modernize-use-nullptr,
+    modernize-use-override,
+    modernize-use-using,
+    performance-faster-string-find,
+    performance-for-range-copy,
+    performance-implicit-conversion-in-loop,
+    performance-inefficient-algorithm,
+    performance-inefficient-vector-operation,
+    performance-move-const-arg,
+    performance-move-constructor-init,
+    performance-no-automatic-move,
+    performance-noexcept-move-constructor,
+    performance-type-promotion-in-math-fn,
+    readability-container-data-pointer,
+    readability-container-size-empty,
+    readability-delete-null-pointer,
+    readability-duplicate-include,
+    readability-redundant-declaration,
+    readability-redundant-smartptr-get,
+    readability-redundant-string-cstr,
+    readability-redundant-string-init,
+    readability-simplify-boolean-expr,
+    readability-simplify-subscript-expr,
+WarningsAsErrors: '*'
 CheckOptions:
 - {key: modernize-use-auto.MinTypeNameLength, value: 7}
+UseColor: true
index 7ac070fc2073d69e6cdd613f3ea2d4246cd96463..27579269a1f554fceaa302298815beb57fccda7e 100644 (file)
@@ -2,7 +2,7 @@ ARG UBUNTU_VERSION=20.04
 
 FROM "ubuntu:${UBUNTU_VERSION}"
 
-# Eigen patch (https://eigen.tuxfamily.org/bz/show_bug.cgi?id=1462) to fix issue metioned
+# Eigen patch (https://eigen.tuxfamily.org/bz/show_bug.cgi?id=1462) to fix issue mentioned
 # in https://github.com/PointCloudLibrary/pcl/issues/3729 is available in Eigen 3.3.7.
 # Not needed from 20.04 since it is the default version from apt
 ARG EIGEN_MINIMUM_VERSION=3.3.7
@@ -14,7 +14,7 @@ ARG ENSENSOSDK_VERSION=3.2.489
 ARG REALSENSE_VERSION=2.50.0
 
 # Check https://packages.ubuntu.com/search?suite=all&arch=any&searchon=names&keywords=libvtk%20qt-dev
-# for available packes for choosen UBUNTU_VERSION
+# for available packages for chosen UBUNTU_VERSION
 ARG VTK_VERSION=6
 
 # Use the latest version of CMake by adding the Kitware repository if true,
@@ -30,14 +30,17 @@ RUN apt-get update \
       clang-tidy \
       libbenchmark-dev \
       libblas-dev \
-      libboost-date-time-dev \
+      libboost-serialization-dev \
       libboost-filesystem-dev \
       libboost-iostreams-dev \
+      libboost-system-dev \
       libflann-dev \
       libglew-dev \
       libgtest-dev \
+      libomp-dev \
       libopenni-dev \
       libopenni2-dev \
+      libpcap-dev \
       libproj-dev \
       libqhull-dev \
       libqt5opengl5-dev \
@@ -52,7 +55,14 @@ RUN apt-get update \
  && if [ "$USE_LATEST_CMAKE" = true ] ; then \
       cmake_ubuntu_version=$(lsb_release -cs) ; \
       if ! wget -q --method=HEAD "https://apt.kitware.com/ubuntu/dists/$cmake_ubuntu_version/Release"; then \
-        cmake_ubuntu_version="focal" ; \
+        ubuntu_version=$(lsb_release -sr) ; \
+        if dpkg --compare-versions ${ubuntu_version} ge 22.04; then \
+          cmake_ubuntu_version="jammy" ; \
+        elif dpkg --compare-versions ${ubuntu_version} ge 20.04; then \
+          cmake_ubuntu_version="focal" ; \
+        else \
+          cmake_ubuntu_version="bionic" ; \
+        fi ; \
       fi ; \
       wget -qO - https://apt.kitware.com/kitware-archive.sh | bash -s -- --release $cmake_ubuntu_version ; \
       apt-get update ; \
index 6d189fcbb2134da9f379a654b3b3426b4389b156..2541cc6837b198c9bd9fedbc30f551a41f83d46f 100644 (file)
@@ -10,7 +10,7 @@ COPY ${flavor}_rosinstall.yaml ${workspace}/src/.rosinstall
 
 # Be careful:
 # * ROS uses Python2
-# * source ROS setup file in evey RUN snippet
+# * source ROS setup file in every RUN snippet
 #
 # The dependencies of PCL can be reduced since
 # * we don't need to build visualization or docs
index ad38e549e0975d70d7f074f6fa31770ae218f66c..a215b025f433bf77e9120dd966cbc1e67d8a8560 100644 (file)
@@ -9,7 +9,7 @@ ARG workspace="/root/catkin_ws"
 COPY ${flavor}_rosinstall.yaml ${workspace}/src/.rosinstall
 
 # Be careful:
-# * source ROS setup file in evey RUN snippet
+# * source ROS setup file in every RUN snippet
 #
 # TODO: The dependencies of PCL can be reduced since
 # * we don't need to build visualization or docs
index 8b156a982c6a06c8693dbb0ec0e8cbf6e0682a24..64afbab8da73f7f2d1b64a4365c7310945b9bd55 100644 (file)
@@ -1,23 +1,22 @@
 FROM debian:testing
 
-ARG VTK_VERSION=7
+ARG VTK_VERSION=9
 ENV DEBIAN_FRONTEND=noninteractive
 
 ARG PCL_INDEX_SIGNED=true
 ARG PCL_INDEX_SIZE=32
 
-# Add sources so we can just install build-dependencies of PCL
-RUN sed -i 's/^deb \(.*\)$/deb \1\ndeb-src \1/' /etc/apt/sources.list \
- && apt update \
+RUN apt update \
  && apt install -y \
     bash \
     cmake \
     dpkg-dev \
     git \
     g++ \
-    libboost-date-time-dev \
+    libboost-serialization-dev \
     libboost-filesystem-dev \
     libboost-iostreams-dev \
+    libboost-system-dev \
     libeigen3-dev \
     libflann-dev \
     libglew-dev \
index 6eb149f903a03a6704be478da83da256638843bd..a84bb558d20a58cb721f27b36d87fdc2525d2eba 100644 (file)
@@ -15,7 +15,7 @@ ENV DEBIAN_FRONTEND=noninteractive
 RUN apt update
 RUN apt install -y git cmake ${COMPILER_PACKAGE}
 RUN apt install -y libeigen3-dev libflann-dev
-RUN apt install -y libboost-filesystem-dev libboost-date-time-dev libboost-iostreams-dev
+RUN apt install -y libboost-filesystem-dev libboost-serialization-dev libboost-iostreams-dev
 RUN apt install -y libgtest-dev libbenchmark-dev
 RUN apt install -y qtbase5-dev libvtk${VTK_VERSION}-dev libvtk${VTK_VERSION}-qt-dev
 
index 44fbd8aca62baa489d6c2362d5ff9a0641abbe7d..ae6fc94be867343cdf04fe6a9cb8b59f9ced3173 100644 (file)
@@ -1,6 +1,6 @@
 # escape=`
 
-FROM mcr.microsoft.com/windows/servercore:ltsc2019
+FROM mcr.microsoft.com/windows/servercore:ltsc2022
 
 # Use "--build-arg platform=x64" for 64 bit or x86 for 32 bit.
 ARG PLATFORM
@@ -30,7 +30,7 @@ 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.7.2.SDK",                            `
+    "Microsoft.Net.Component.4.8.SDK",                            `
     "Microsoft.VisualStudio.Component.VC.ATLMFC",                   `
     "--includeRecommended"                                          `
     -Wait -PassThru;                                                `
@@ -48,4 +48,5 @@ COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cm
 
 RUN cd .\vcpkg;                                                `
     .\bootstrap-vcpkg.bat;                                            `
-    .\vcpkg install boost flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 --triplet $Env:PLATFORM-windows-rel --clean-after-build;
+    .\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; `
+
index a89235c68a6dcba1154b789fcc44ec4333b2c976..4cca90af3dc614bab16930746f3b7825118b6896 100755 (executable)
@@ -1,10 +1,9 @@
 #! /usr/bin/env bash
 
-new_version=$(git tag | sort -rV | head -1 | cut -d- -f 2).99
-
 # Mac users either use gsed or add "" after -i
 if ls | grep README -q; then
-    sed -i "s,VERSION [0-9.]*),VERSION ${new_version})," CMakeLists.txt
+    # Just add .99 at the end of the version
+    sed -i "s,PCL VERSION [0-9.]*,&.99," CMakeLists.txt
 else
     echo "Don't think this is the root directory" 1>&2
     exit 4
index 77771e2865bd0a5e9336bf74b3337759d9d72492..1d5aa3cfe8bd1d702a58b5603cd8992d1b5ce08c 100644 (file)
@@ -15,9 +15,9 @@ Please paste the compilation results/errors.
 **To Reproduce**
 
 Provide a link to a live example, or an unambiguous set of steps to reproduce this bug. A reproducible example helps to provide faster answers. Custom OS, custom PCL configs or custom build systems make the issue difficult to reproduce.
-* Best reproducability: A docker image + code snippets provided here
-* Good reproducability: Common Linux OS + default PCL config + code snippets provided here
-* Poor reproducability: code snippets
+* Best reproducibility: A docker image + code snippets provided here
+* Good reproducibility: Common Linux OS + default PCL config + code snippets provided here
+* Poor reproducibility: code snippets
 
 Remember to reproduce the error in a clean rebuild (removing all build objects and starting build from scratch)
 
index 86845c0c80565a25fc2da625c1acb7e923c3bd96..a78a188185a875b464889d72a274c792fc997ff5 100755 (executable)
@@ -9,7 +9,7 @@ jobs:
       image: pointcloudlibrary/env:22.04
     
     steps:
-    - uses: actions/checkout@v2
+    - uses: actions/checkout@v3
 
     - name: Run clang-tidy
       run: |
index d606d91242a8f0cc3537e6573d650cacb75ef87a..23368155c9e8f203433c8ace396e9dc67455af0f 100644 (file)
@@ -116,25 +116,16 @@ public:
 private:
   OUTPUT_TYPE output_type_;
   DETECTOR_KERNEL_TYPE detector_kernel_type_;
-  bool non_maximal_suppression_;
-  bool hysteresis_thresholding_;
+  bool non_maximal_suppression_{false};
+  bool hysteresis_thresholding_{false};
 
-  float hysteresis_threshold_low_;
-  float hysteresis_threshold_high_;
-  float non_max_suppression_radius_x_;
-  float non_max_suppression_radius_y_;
+  float hysteresis_threshold_low_{20.0f};
+  float hysteresis_threshold_high_{80.0f};
+  float non_max_suppression_radius_x_{3.0f};
+  float non_max_suppression_radius_y_{3.0f};
 
 public:
-  Edge()
-  : output_type_(OUTPUT_X)
-  , detector_kernel_type_(SOBEL)
-  , non_maximal_suppression_(false)
-  , hysteresis_thresholding_(false)
-  , hysteresis_threshold_low_(20)
-  , hysteresis_threshold_high_(80)
-  , non_max_suppression_radius_x_(3)
-  , non_max_suppression_radius_y_(3)
-  {}
+  Edge() : output_type_(OUTPUT_X), detector_kernel_type_(SOBEL) {}
 
   /** \brief Set the output type.
    * \param[in] output_type the output type
index 22bdd74af7d286166549ff9246722f6785fb21e2..75e35f94641dae112e9eb3e1403ac0451530c3f1 100644 (file)
@@ -266,7 +266,7 @@ Edge<PointInT, PointOutT>::suppressNonMaxima(
   for (auto& point : maxima)
     point.intensity = 0.0f;
 
-  // tHigh and non-maximal supression
+  // tHigh and non-maximal suppression
   for (int i = 1; i < height - 1; i++) {
     for (int j = 1; j < width - 1; j++) {
       const PointXYZIEdge& ptedge = edges(j, i);
@@ -277,7 +277,7 @@ Edge<PointInT, PointOutT>::suppressNonMaxima(
 
       // maxima (j, i).intensity = 0;
 
-      switch (int(ptedge.direction)) {
+      switch (static_cast<int>(ptedge.direction)) {
       case 0: {
         if (ptedge.magnitude >= edges(j - 1, i).magnitude &&
             ptedge.magnitude >= edges(j + 1, i).magnitude)
@@ -339,7 +339,7 @@ Edge<PointInT, PointOutT>::detectEdgeCanny(pcl::PointCloud<PointOutT>& output)
   // Edge discretization
   discretizeAngles(*edges);
 
-  // tHigh and non-maximal supression
+  // tHigh and non-maximal suppression
   pcl::PointCloud<PointXYZI>::Ptr maxima(new pcl::PointCloud<PointXYZI>);
   suppressNonMaxima(*edges, *maxima, tLow);
 
index 0be57ff4302c2e5ed6b5eb680d2e1924fe9bed18..f813e9cf85436e37776bb9d85bcdbad2ce753836 100644 (file)
@@ -106,9 +106,9 @@ kernel<PointT>::gaussianKernel(pcl::PointCloud<PointT>& kernel)
     for (int j = 0; j < kernel_size_; j++) {
       int iks = (i - kernel_size_ / 2);
       int jks = (j - kernel_size_ / 2);
-      kernel(j, i).intensity =
-          std::exp(float(-double(iks * iks + jks * jks) / sigma_sqr));
-      sum += float(kernel(j, i).intensity);
+      kernel(j, i).intensity = std::exp(
+          static_cast<float>(-static_cast<double>(iks * iks + jks * jks) / sigma_sqr));
+      sum += (kernel(j, i).intensity);
     }
   }
 
@@ -132,7 +132,8 @@ kernel<PointT>::loGKernel(pcl::PointCloud<PointT>& kernel)
     for (int j = 0; j < kernel_size_; j++) {
       int iks = (i - kernel_size_ / 2);
       int jks = (j - kernel_size_ / 2);
-      float temp = float(double(iks * iks + jks * jks) / sigma_sqr);
+      float temp =
+          static_cast<float>(static_cast<double>(iks * iks + jks * jks) / sigma_sqr);
       kernel(j, i).intensity = (1.0f - temp) * std::exp(-temp);
       sum += kernel(j, i).intensity;
     }
index 499d3a383935254c0df3fb1b220a4fa184cea27c..a910b90f8c94ad4873d5a456dbda4a7aabd20659 100644 (file)
@@ -63,11 +63,11 @@ public:
     GAUSSIAN               //!< GAUSSIAN
   };
 
-  int kernel_size_;
-  float sigma_;
+  int kernel_size_{3};
+  float sigma_{1.0};
   KERNEL_ENUM kernel_type_;
 
-  kernel() : kernel_size_(3), sigma_(1.0), kernel_type_(GAUSSIAN) {}
+  kernel() : kernel_type_(GAUSSIAN) {}
 
   /**
    *
index c6679ae924e8a31c34d45591a41d7ca0ca54c516..1faa1b86236f4bdfe702cbf9e0ca70f4cb4dc4d2 100644 (file)
@@ -1,5 +1,230 @@
 # ChangeList
 
+## = 1.14.0 (03 January 2024) =
+
+### Notable changes
+
+**New features** *added to PCL*
+
+* **[registration]** GICP: add Newton optimizer [[#5825](https://github.com/PointCloudLibrary/pcl/pull/5825)]
+
+**Deprecation** *of public APIs, scheduled to be removed after two minor releases*
+
+* **[segmentation]** Deprecate CrfNormalSegmentation [[#5795](https://github.com/PointCloudLibrary/pcl/pull/5795)]
+* **[sample_consensus]** Deprecate SampleConsensusModelStick [[#5796](https://github.com/PointCloudLibrary/pcl/pull/5796)]
+
+**Removal** *of the public APIs deprecated in previous releases*
+
+* remove deprecated code for 1.14 release [[#5872](https://github.com/PointCloudLibrary/pcl/pull/5872)]
+
+**Behavior changes** *in classes, apps, or tools*
+
+* **[common]** Fix register macros to match struct definitions [[#5604](https://github.com/PointCloudLibrary/pcl/pull/5604)]
+* **[registration]** ICP: remove possibly inappropriate default setting of rotation convergence threshold when user does not set it. [[#5755](https://github.com/PointCloudLibrary/pcl/pull/5755)]
+* **[surface]** MovingLeastSquares: reduce the number of instantiations to reduce com… [[#5764](https://github.com/PointCloudLibrary/pcl/pull/5764)]
+* **[filters]** Fix behaviour of BoxClipper3D [[#5769](https://github.com/PointCloudLibrary/pcl/pull/5769)]
+* **[surface][cmake]** Prefer system zlib over vendored copy in opennurbs [[#5684](https://github.com/PointCloudLibrary/pcl/pull/5684)]
+
+### Changes grouped by module
+
+#### CMake:
+
+* Move /bigobj flag (Windows/MSVC) [[#5718](https://github.com/PointCloudLibrary/pcl/pull/5718)]
+* Make OpenMP available in downstream projects [[#5744](https://github.com/PointCloudLibrary/pcl/pull/5744)]
+* Eigen: switch to imported modules and NO_MODULE [[#5613](https://github.com/PointCloudLibrary/pcl/pull/5613)]
+* Make Flann optional [[#5772](https://github.com/PointCloudLibrary/pcl/pull/5772)]
+* **[behavior change]** Prefer system zlib over vendored copy in opennurbs [[#5684](https://github.com/PointCloudLibrary/pcl/pull/5684)]
+* fix build with GNU13 and Eigen3.4 [[#5783](https://github.com/PointCloudLibrary/pcl/pull/5783)]
+* Fix Eigen alignment problem when user project is compiled as C++17 or newer [[#5793](https://github.com/PointCloudLibrary/pcl/pull/5793)]
+* Allow compilation with Boost 1.83 [[#5810](https://github.com/PointCloudLibrary/pcl/pull/5810)]
+* Use real ALIAS target for flann to preserve properties on original target. [[#5861](https://github.com/PointCloudLibrary/pcl/pull/5861)]
+
+#### libpcl_common:
+
+* **[behavior change]** Fix register macros to match struct definitions [[#5604](https://github.com/PointCloudLibrary/pcl/pull/5604)]
+* Add computeCentroidAndOBB function [[#5690](https://github.com/PointCloudLibrary/pcl/pull/5690)]
+* Remove unnecessary pseudo-instantiations of checkCoordinateSystem [[#5765](https://github.com/PointCloudLibrary/pcl/pull/5765)]
+
+#### libpcl_features:
+
+* NormalEstimationOMP: use dynamic scheduling for faster computation [[#5775](https://github.com/PointCloudLibrary/pcl/pull/5775)]
+
+#### libpcl_filters:
+
+* **[behavior change]** Fix behaviour of BoxClipper3D [[#5769](https://github.com/PointCloudLibrary/pcl/pull/5769)]
+* Let setInputCloud of search methods indicate success or failure [[#5840](https://github.com/PointCloudLibrary/pcl/pull/5840)]
+* VoxelGridOcclusionEstimation: fix behaviour if sensor origin is inside the voxel grid [[#5867](https://github.com/PointCloudLibrary/pcl/pull/5867)]
+
+#### libpcl_gpu:
+
+* Some improvements to gpu/segmentation [[#5813](https://github.com/PointCloudLibrary/pcl/pull/5813)]
+
+#### libpcl_io:
+
+* Enable writing very large PCD files on Windows [[#5675](https://github.com/PointCloudLibrary/pcl/pull/5675)]
+* Make io more locale invariant [[#5699](https://github.com/PointCloudLibrary/pcl/pull/5699)]
+* Fix reading of origin and orientation from PLY files [[#5766](https://github.com/PointCloudLibrary/pcl/pull/5766)]
+* Add missing cassert include [[#5812](https://github.com/PointCloudLibrary/pcl/pull/5812)]
+* Fix PCD load crashes on empty files [[#5855](https://github.com/PointCloudLibrary/pcl/pull/5855)]
+* Fix freeze in hdl_grabber.cpp [[#5826](https://github.com/PointCloudLibrary/pcl/pull/5826)]
+
+#### libpcl_octree:
+
+* Octree: grow in positive direction instead of negative [[#5653](https://github.com/PointCloudLibrary/pcl/pull/5653)]
+
+#### libpcl_registration:
+
+* **[behavior change]** ICP: remove possibly inappropriate default setting of rotation convergence threshold when user does not set it. [[#5755](https://github.com/PointCloudLibrary/pcl/pull/5755)]
+* Improve PPFRegistration [[#5767](https://github.com/PointCloudLibrary/pcl/pull/5767)]
+* **[new feature]** GICP: add Newton optimizer [[#5825](https://github.com/PointCloudLibrary/pcl/pull/5825)]
+* Add instantiations for ICP and TransformationEstimationSVD [[#5894](https://github.com/PointCloudLibrary/pcl/pull/5894)]
+
+#### libpcl_sample_consensus:
+
+* Improve optimizeModelCoefficients for cone, cylinder, sphere models [[#5790](https://github.com/PointCloudLibrary/pcl/pull/5790)]
+* **[deprecation]** Deprecate SampleConsensusModelStick [[#5796](https://github.com/PointCloudLibrary/pcl/pull/5796)]
+* sac_model_cylinder: fix bug in projectPointToCylinder function [[#5821](https://github.com/PointCloudLibrary/pcl/pull/5821)]
+* Replace std::time with std::random_device as seed for random number generator [[#5824](https://github.com/PointCloudLibrary/pcl/pull/5824)]
+* MSAC and RMSAC: fix check array distances empty [[#5849](https://github.com/PointCloudLibrary/pcl/pull/5849)]
+
+#### libpcl_search:
+
+* OrganizedNeighbor: add additional check to make sure the cloud is sui… [[#5729](https://github.com/PointCloudLibrary/pcl/pull/5729)]
+* Modify FlannSearch to return Indices of Point Cloud (issue #5774) [[#5780](https://github.com/PointCloudLibrary/pcl/pull/5780)]
+* Let setInputCloud of search methods indicate success or failure [[#5840](https://github.com/PointCloudLibrary/pcl/pull/5840)]
+
+#### libpcl_segmentation:
+
+* ApproximateProgressiveMorphologicalFilter: check for finite-ness [[#5756](https://github.com/PointCloudLibrary/pcl/pull/5756)]
+* **[deprecation]** Deprecate CrfNormalSegmentation [[#5795](https://github.com/PointCloudLibrary/pcl/pull/5795)]
+
+#### libpcl_surface:
+
+* ConvexHull verbose info on stdout enabled only by pcl::console::L_DEBUG [[#5689](https://github.com/PointCloudLibrary/pcl/pull/5689)]
+* **[behavior change]** MovingLeastSquares: reduce the number of instantiations to reduce com… [[#5764](https://github.com/PointCloudLibrary/pcl/pull/5764)]
+* **[behavior change]** Prefer system zlib over vendored copy in opennurbs [[#5684](https://github.com/PointCloudLibrary/pcl/pull/5684)]
+* Fix memory leak bug of poisson reconstruction [[#5832](https://github.com/PointCloudLibrary/pcl/pull/5832)]
+* Speed up nurbs surface fitting [[#5873](https://github.com/PointCloudLibrary/pcl/pull/5873)]
+
+#### libpcl_visualization:
+
+* Improve spinOnce documentation [[#5716](https://github.com/PointCloudLibrary/pcl/pull/5716)]
+
+#### PCL Apps:
+
+* Add missing includes in cloud composer app [[#5777](https://github.com/PointCloudLibrary/pcl/pull/5777)]
+
+#### PCL Docs:
+
+* Add readthedocs config files [[#5878](https://github.com/PointCloudLibrary/pcl/pull/5878)]
+
+#### CI:
+
+* **[new feature][removal]** Remove 18.04 as its EOL. [[#5799](https://github.com/PointCloudLibrary/pcl/pull/5799)]
+* Use new windows images for CI [[#5892](https://github.com/PointCloudLibrary/pcl/pull/5892)]
+
+## = 1.13.1 (10 May 2023) =
+
+### Notable changes
+
+**New features** *added to PCL*
+
+* **[common]** Add overload to fromPCLPointCloud2 to avoid copying data [[#5608](https://github.com/PointCloudLibrary/pcl/pull/5608)]
+* **[io]** Add writeBinary to ostream for PCDWriter [[#5598](https://github.com/PointCloudLibrary/pcl/pull/5598)]
+* **[docs][io]** io/doc: add overview of file reading and writing functions [[#5657](https://github.com/PointCloudLibrary/pcl/pull/5657)]
+
+**Removal** *of the public APIs deprecated in previous releases*
+
+* **[gpu]** Remove CUDA code for already unsupported CUDA versions [[#5535](https://github.com/PointCloudLibrary/pcl/pull/5535)]
+* **[tools]** Remove pcl_video.cpp [[#5595](https://github.com/PointCloudLibrary/pcl/pull/5595)]
+* **[io][tools]** Remove last usage of boost::date_time and replace it with std::chrono [[#5596](https://github.com/PointCloudLibrary/pcl/pull/5596)]
+
+**Behavior changes** *in classes, apps, or tools*
+
+* **[cmake]** Require at least MSVC 2017 [[#5562](https://github.com/PointCloudLibrary/pcl/pull/5562)]
+
+### Changes grouped by module
+
+#### CMake:
+
+* Link to VTK::FiltersGeneral [[#5547](https://github.com/PointCloudLibrary/pcl/pull/5547)]
+* Add support for Boost 1.81 [[#5558](https://github.com/PointCloudLibrary/pcl/pull/5558)]
+* **[behavior change]** Require at least MSVC 2017 [[#5562](https://github.com/PointCloudLibrary/pcl/pull/5562)]
+* Make sure that find_package(PCL) does not leak internals or overwrite variables [[#5582](https://github.com/PointCloudLibrary/pcl/pull/5582)]
+* Misc small fixes and improvements [[#5624](https://github.com/PointCloudLibrary/pcl/pull/5624)]
+* Allow compilation with Boost 1.82 [[#5668](https://github.com/PointCloudLibrary/pcl/pull/5668)]
+
+#### libpcl_common:
+
+* **[new feature]** Add overload to fromPCLPointCloud2 to avoid copying data [[#5608](https://github.com/PointCloudLibrary/pcl/pull/5608)]
+
+#### libpcl_features:
+
+* Fix crash in SpinImageEstimation [[#5586](https://github.com/PointCloudLibrary/pcl/pull/5586)]
+* Fix access violation in IntegralImageNormalEstimation when using dept… [[#5585](https://github.com/PointCloudLibrary/pcl/pull/5585)]
+
+#### libpcl_filters:
+
+* Fix bug in LocalMaximum [[#5572](https://github.com/PointCloudLibrary/pcl/pull/5572)]
+
+#### libpcl_gpu:
+
+* **[removal]** Remove CUDA code for already unsupported CUDA versions [[#5535](https://github.com/PointCloudLibrary/pcl/pull/5535)]
+
+#### libpcl_io:
+
+* Link to VTK::FiltersGeneral [[#5547](https://github.com/PointCloudLibrary/pcl/pull/5547)]
+* Fix pcl:ply_reader_fuzzer: Crash in pcl::PLYReader::read [[#5552](https://github.com/PointCloudLibrary/pcl/pull/5552)]
+* **[new feature]** Add writeBinary to ostream for PCDWriter [[#5598](https://github.com/PointCloudLibrary/pcl/pull/5598)]
+* **[removal]** Remove last usage of boost::date_time and replace it with std::chrono [[#5596](https://github.com/PointCloudLibrary/pcl/pull/5596)]
+* **[new feature]** io/doc: add overview of file reading and writing functions [[#5657](https://github.com/PointCloudLibrary/pcl/pull/5657)]
+* fix MSVS not supporting unsigned int in for loop with openMP [[#5666](https://github.com/PointCloudLibrary/pcl/pull/5666)]
+
+#### libpcl_octree:
+
+* use PCL_ERROR instead of assert [[#5321](https://github.com/PointCloudLibrary/pcl/pull/5321)]
+
+#### libpcl_people:
+
+* People: fix segfault in SSE HoG computation [[#5658](https://github.com/PointCloudLibrary/pcl/pull/5658)]
+
+#### libpcl_registration:
+
+* Fix potential memory problems in GICP and IncrementalRegistration [[#5557](https://github.com/PointCloudLibrary/pcl/pull/5557)]
+
+#### libpcl_segmentation:
+
+* MinCutSegmentation: use correct allocation size, fix segfault [[#5651](https://github.com/PointCloudLibrary/pcl/pull/5651)]
+
+#### libpcl_visualization:
+
+* Fix Linux and Windows spinOnce behaviour [[#5542](https://github.com/PointCloudLibrary/pcl/pull/5542)]
+
+#### PCL Apps:
+
+* Make apps Qt6 compatible [[#5570](https://github.com/PointCloudLibrary/pcl/pull/5570)]
+* OpenNI apps: Improve handling of command line arguments [[#5494](https://github.com/PointCloudLibrary/pcl/pull/5494)]
+* Improved manual registration [[#5530](https://github.com/PointCloudLibrary/pcl/pull/5530)]
+* Improve pcl_openni_face_detector [[#5669](https://github.com/PointCloudLibrary/pcl/pull/5669)]
+* Point Cloud Editor: fix select2D after switch to QOpenGLWidget [[#5685](https://github.com/PointCloudLibrary/pcl/pull/5685)]
+
+#### PCL Docs:
+
+* Add tutorial for using VCPKG on Windows [[#4814](https://github.com/PointCloudLibrary/pcl/pull/4814)]
+* **[new feature]** io/doc: add overview of file reading and writing functions [[#5657](https://github.com/PointCloudLibrary/pcl/pull/5657)]
+
+#### PCL Tools:
+
+* radius filter: fix incorrect printf format specifier and typo [[#5536](https://github.com/PointCloudLibrary/pcl/pull/5536)]
+* Remove NaNs from clouds after loading in icp tool [[#5568](https://github.com/PointCloudLibrary/pcl/pull/5568)]
+* **[removal]** Remove pcl_video.cpp [[#5595](https://github.com/PointCloudLibrary/pcl/pull/5595)]
+* **[removal]** Remove last usage of boost::date_time and replace it with std::chrono [[#5596](https://github.com/PointCloudLibrary/pcl/pull/5596)]
+
+#### CI:
+
+* vcpkg: build only release for host-triplet [[#5614](https://github.com/PointCloudLibrary/pcl/pull/5614)]
+* Misc small fixes and improvements [[#5624](https://github.com/PointCloudLibrary/pcl/pull/5624)]
+
 ## = 1.13.0 (10 December 2022) =
 
 ### Notable changes
index 17020e162acc1ada49748fc2cdff2f618e5f9f93..1709af51df3b6b6f5159585f5c99c5e792cff82a 100644 (file)
@@ -23,9 +23,13 @@ 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.13.0)
+project(PCL VERSION 1.14.0)
 string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
 
+if(MSVC AND ("${MSVC_VERSION}" LESS 1910))
+  message(FATAL_ERROR "The compiler versions prior to Visual Studio version 2017 are not supported. Please upgrade to a newer version or another compiler!")
+endif()
+
 ### ---[ Find universal dependencies
 set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake/Modules/" ${CMAKE_MODULE_PATH})
 
@@ -115,7 +119,7 @@ if(CMAKE_COMPILER_IS_GNUCXX)
     else()
       string(APPEND CMAKE_CXX_FLAGS " -Wabi")
     endif()
-    string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra -Wno-unknown-pragmas -fno-strict-aliasing -Wno-format-extra-args -Wno-sign-compare -Wno-invalid-offsetof -Wno-conversion ${SSE_FLAGS} ${AVX_FLAGS}")
+    string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra -fno-strict-aliasing ${SSE_FLAGS} ${AVX_FLAGS}")
   endif()
 
   if(PCL_WARNINGS_ARE_ERRORS)
@@ -143,7 +147,7 @@ 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}")
   
   if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
-    string(APPEND CMAKE_CXX_FLAGS " /fp:precise ${SSE_FLAGS} ${AVX_FLAGS} /bigobj")
+    string(APPEND CMAKE_CXX_FLAGS " /fp:precise ${SSE_FLAGS} ${AVX_FLAGS}")
 
     # Add extra code generation/link optimizations
     if(CMAKE_MSVC_CODE_LINK_OPTIMIZATION AND (NOT BUILD_CUDA) AND (NOT BUILD_GPU))
@@ -198,6 +202,7 @@ if(CMAKE_COMPILER_IS_MSVC)
       endif()
     endif()
   endif()
+  string(APPEND CMAKE_CXX_FLAGS " /bigobj")
 
   if(CMAKE_GENERATOR STREQUAL "Ninja")
     string(APPEND CMAKE_C_FLAGS " /FS")
@@ -313,14 +318,20 @@ endif()
 # Threads (required)
 find_package(Threads REQUIRED)
 
-# Eigen (required)
-find_package(Eigen 3.3 REQUIRED)
-include_directories(SYSTEM ${EIGEN_INCLUDE_DIRS})
+# Eigen3 (required)
+find_package(Eigen3 3.3 REQUIRED NO_MODULE)
+if(NOT EIGEN3_FOUND AND Eigen3_FOUND)
+    set(EIGEN3_FOUND ${Eigen3_FOUND})
+endif()
 
-# FLANN (required)
-find_package(FLANN 1.9.1 REQUIRED)
-if(NOT (${FLANN_LIBRARY_TYPE} MATCHES ${PCL_FLANN_REQUIRED_TYPE}) AND NOT (${PCL_FLANN_REQUIRED_TYPE} MATCHES "DONTCARE"))
-  message(FATAL_ERROR "Flann was selected with ${PCL_FLANN_REQUIRED_TYPE} but found as ${FLANN_LIBRARY_TYPE}")
+# FLANN
+find_package(FLANN 1.9.1)
+if(NOT FLANN_FOUND)
+  message(WARNING "Flann was not found, so many PCL modules will not be built!")
+else()
+  if(NOT (${FLANN_LIBRARY_TYPE} MATCHES ${PCL_FLANN_REQUIRED_TYPE}) AND NOT (${PCL_FLANN_REQUIRED_TYPE} MATCHES "DONTCARE"))
+    message(FATAL_ERROR "Flann was selected with ${PCL_FLANN_REQUIRED_TYPE} but found as ${FLANN_LIBRARY_TYPE}")
+  endif()
 endif()
 
 # libusb
@@ -411,6 +422,15 @@ endif()
 # Boost (required)
 include("${PCL_SOURCE_DIR}/cmake/pcl_find_boost.cmake")
 
+# System zlib (for nurbs on surface)
+option(WITH_SYSTEM_ZLIB "Use system zlib" TRUE)
+if(WITH_SYSTEM_ZLIB)
+  find_package(ZLIB)
+  if(ZLIB_FOUND)
+    set(HAVE_ZLIB ON)
+  endif()
+endif()
+
 ### ---[ 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 ddf93eb64c1280e8668687b843de5e36c1d0c81a..cf21c443742d448be0f32d8a46164bf43912de16 100644 (file)
@@ -96,7 +96,7 @@ macro(find_boost)
   
   set(Boost_ADDITIONAL_VERSIONS
     "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@"
-    "1.80.0" "1.80"
+    "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")
@@ -112,14 +112,18 @@ macro(find_boost)
   endif()
 endmacro()
 
-#remove this as soon as eigen is shipped with FindEigen.cmake
-macro(find_eigen)
+macro(find_eigen3)
   if(PCL_ALL_IN_ONE_INSTALLER)
-    set(EIGEN_ROOT "${PCL_ROOT}/3rdParty/Eigen")
-  elseif(NOT EIGEN_ROOT)
-    get_filename_component(EIGEN_ROOT "@EIGEN_INCLUDE_DIRS@" ABSOLUTE)
+    set(Eigen3_DIR "${PCL_ROOT}/3rdParty/Eigen3/share/eigen3/cmake/")
+  endif()
+  find_package(Eigen3 3.3 REQUIRED NO_MODULE)
+  if(NOT EIGEN3_FOUND AND Eigen3_FOUND)
+    set(EIGEN3_FOUND ${Eigen3_FOUND})
+  endif()
+  # In very new Eigen versions, EIGEN3_INCLUDE_DIR(S) is not defined any more, only the target:
+  if(TARGET Eigen3::Eigen)
+    set(EIGEN3_LIBRARIES Eigen3::Eigen)
   endif()
-  find_package(Eigen 3.3)
 endmacro()
 
 #remove this as soon as qhull is shipped with FindQhull.cmake
@@ -268,11 +272,11 @@ endmacro()
 #                                       `--> component is induced ==> warn and remove it
 #                                                                     from the list
 
-macro(find_external_library _component _lib _is_optional)
+function(find_external_library _component _lib _is_optional)
   if("${_lib}" STREQUAL "boost")
     find_boost()
-  elseif("${_lib}" STREQUAL "eigen")
-    find_eigen()
+  elseif("${_lib}" STREQUAL "eigen3")
+    find_eigen3()
   elseif("${_lib}" STREQUAL "flann")
     find_flann()
   elseif("${_lib}" STREQUAL "qhull")
@@ -299,6 +303,17 @@ macro(find_external_library _component _lib _is_optional)
     find_glew()
   elseif("${_lib}" STREQUAL "opengl")
     find_package(OpenGL)
+  elseif("${_lib}" STREQUAL "pcap")
+    find_package(Pcap)
+  elseif("${_lib}" STREQUAL "png")
+    find_package(PNG)
+  elseif("${_lib}" STREQUAL "OpenMP")
+    find_package(OpenMP COMPONENTS CXX)
+    # the previous find_package call sets OpenMP_CXX_LIBRARIES, but not OPENMP_LIBRARIES, which is used further down
+    # we can link to the CMake target OpenMP::OpenMP_CXX by setting the following:
+    set(OPENMP_LIBRARIES OpenMP::OpenMP_CXX)
+  else()
+    message(WARNING "${_lib} is not handled by find_external_library")
   endif()
 
   string(TOUPPER "${_component}" COMPONENT)
@@ -306,6 +321,7 @@ macro(find_external_library _component _lib _is_optional)
   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)
@@ -317,12 +333,16 @@ macro(find_external_library _component _lib _is_optional)
       include(${${LIB}_USE_FILE})
     else()
       list(APPEND PCL_${COMPONENT}_LIBRARY_DIRS "${${LIB}_LIBRARY_DIRS}")
+      set(PCL_${COMPONENT}_LIBRARY_DIRS ${PCL_${COMPONENT}_LIBRARY_DIRS} PARENT_SCOPE)
     endif()
     if(${LIB}_LIBRARIES)
       list(APPEND PCL_${COMPONENT}_LINK_LIBRARIES "${${LIB}_LIBRARIES}")
+      set(PCL_${COMPONENT}_LINK_LIBRARIES ${PCL_${COMPONENT}_LINK_LIBRARIES} PARENT_SCOPE)
+      set(PCL_${LIB}_LIBRARIES ${${LIB}_LIBRARIES} PARENT_SCOPE) # Later appended to PCL_LIBRARIES
     endif()
     if(${LIB}_DEFINITIONS AND NOT ${LIB} STREQUAL "VTK")
       list(APPEND PCL_${COMPONENT}_DEFINITIONS ${${LIB}_DEFINITIONS})
+      set(PCL_${COMPONENT}_DEFINITIONS ${PCL_${COMPONENT}_DEFINITIONS} PARENT_SCOPE)
     endif()
   else()
     if("${_is_optional}" STREQUAL "OPTIONAL")
@@ -339,7 +359,7 @@ macro(find_external_library _component _lib _is_optional)
       endif()
     endif()
   endif()
-endmacro()
+endfunction()
 
 macro(pcl_check_external_dependency _component)
 endmacro()
@@ -658,7 +678,7 @@ endif()
 pcl_remove_duplicate_libraries(PCL_COMPONENTS PCL_LIBRARIES)
 
 # Add 3rd party libraries, as user code might include our .HPP implementations
-list(APPEND PCL_LIBRARIES ${BOOST_LIBRARIES} ${OPENNI_LIBRARIES} ${OPENNI2_LIBRARIES} ${ENSENSO_LIBRARIES} ${davidSDK_LIBRARIES} ${DSSDK_LIBRARIES} ${RSSDK_LIBRARIES} ${RSSDK2_LIBRARIES} ${VTK_LIBRARIES})
+list(APPEND PCL_LIBRARIES ${PCL_BOOST_LIBRARIES} ${PCL_OPENNI_LIBRARIES} ${PCL_OPENNI2_LIBRARIES} ${PCL_ENSENSO_LIBRARIES} ${PCL_davidSDK_LIBRARIES} ${PCL_DSSDK_LIBRARIES} ${PCL_RSSDK_LIBRARIES} ${PCL_RSSDK2_LIBRARIES} ${PCL_VTK_LIBRARIES})
 if (TARGET FLANN::FLANN)
   list(APPEND PCL_LIBRARIES FLANN::FLANN)
 endif()
index 1ba99d1ec8c439ac18851898f2faff7d3912b9c8..08318ebf317a23929fd512a1589e97091e32a692 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.13.0-green.svg?style=flat
+[release-image]: https://img.shields.io/badge/release-1.14.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
@@ -21,22 +21,23 @@ If you really need access to the old website, please use [the copy made by the i
 Continuous integration
 ----------------------
 [ci-latest-build]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=9&branchName=master
-[ci-ubuntu-18.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2018.04%20GCC&label=Ubuntu%2018.04%20GCC
-[ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2020.04%20Clang&label=Ubuntu%2020.04%20Clang
-[ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2022.04%20GCC&label=Ubuntu%2022.04%20GCC
+[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-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-11]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Big%20Sur%2011&label=macOS%20Big%20Sur%2011
 [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-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-18.04]][ci-latest-build] <br> [![Status][ci-ubuntu-20.04]][ci-latest-build] <br> [![Status][ci-ubuntu-22.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-23.04]][ci-latest-build] |
 Windows                  | [![Status][ci-windows-x86]][ci-latest-build]  <br> [![Status][ci-windows-x64]][ci-latest-build]   |
-macOS                    | [![Status][ci-macos-11]][ci-latest-build]  <br> [![Status][ci-macos-12]][ci-latest-build]   |
+macOS                    | [![Status][ci-macos-12]][ci-latest-build]  <br> [![Status][ci-macos-13]][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) |
 
 Community
 ---------
index 56e4ee7a66d4c20e12a5639f3197842460654fd1..3e8b8e997d7a2e27c8fdf31bd37b3eac7df273c6 100644 (file)
@@ -90,7 +90,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)
+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)
 
 if(WITH_OPENNI)
   target_link_libraries("${LIB_NAME}" ${OPENNI_LIBRARIES})
index d6ca7cd4f387641cf2671e2832a9c5b498ecbeb5..bf6607eeae7da6d659dfd3458cc6b855c0a8dafd 100644 (file)
@@ -297,7 +297,6 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer<Distance, PointInT, FeatureT>::reco
 
       // clang-format off
 #pragma omp parallel for \
-  default(none) \
   shared(VOXEL_SIZE_ICP_, cloud_voxelized_icp) \
   num_threads(omp_get_num_procs())
       // clang-format on
index b3ea5716e9d3f6443c7218589a7a294be12eaa3e..fdd83be86d7be779776ea101e8fb847f822e9e19 100644 (file)
@@ -456,7 +456,6 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::rec
 
       // clang-format off
 #pragma omp parallel for \
-  default(none) \
   shared(cloud_voxelized_icp, VOXEL_SIZE_ICP_) \
   num_threads(omp_get_num_procs())
       // clang-format on
index 0bd6b9d6ecff85181c4e3583346b325be48c870d..3561c3036cdde0a182dad87d0404a377476e6d08 100644 (file)
@@ -293,6 +293,8 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
         oh.feature_distances_ = feat_dist;
         object_hypotheses[oh.model_.id_] = oh;
       }
+      delete[] indices.ptr();
+      delete[] distances.ptr();
     }
   }
 
@@ -369,7 +371,6 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
 
     // clang-format off
 #pragma omp parallel for \
-  default(none) \
   shared(cloud_voxelized_icp) \
   schedule(dynamic,1) \
   num_threads(omp_get_num_procs())
index 32f9fbd7c01db3f2a6044107a479fff704029b6c..8aece90423d87394e4099c58352748ff4e209519 100644 (file)
@@ -195,13 +195,12 @@ class PCL_EXPORTS LocalRecognitionPipeline {
   }
 
 public:
-  LocalRecognitionPipeline()
+  LocalRecognitionPipeline() : search_model_("")
   {
     use_cache_ = false;
     threshold_accept_model_hypothesis_ = 0.2f;
     ICP_iterations_ = 30;
     kdtree_splits_ = 512;
-    search_model_ = "";
     VOXEL_SIZE_ICP_ = 0.0025f;
     compute_table_plane_ = false;
   }
index 85ae4a2dac8ac6ff4360ba51f584d745806b4ae2..670f2d8fac1abefa689c83e6da8cb87fa1d24fde 100644 (file)
@@ -85,11 +85,14 @@ if(VTK_FOUND)
       ${SUBSYS_NAME}
       SOURCES
       include/pcl/apps/manual_registration.h
+      include/pcl/apps/pcl_viewer_dialog.h
       src/manual_registration/manual_registration.cpp
+      src/manual_registration/pcl_viewer_dialog.cpp
       src/manual_registration/manual_registration.ui
+      src/manual_registration/pcl_viewer_dialog.ui
       BUNDLE)
-      
-    target_link_libraries(pcl_manual_registration pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets)
+
+    target_link_libraries(pcl_manual_registration pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface pcl_registration ${QTX}::Widgets)
 
     PCL_ADD_EXECUTABLE(pcl_pcd_video_player
       COMPONENT
@@ -99,7 +102,7 @@ if(VTK_FOUND)
       src/pcd_video_player/pcd_video_player.cpp
       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)
   endif()
 
@@ -163,7 +166,7 @@ if(VTK_FOUND)
           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")
index 7252b216b6dcff814f15a1aeef35c417eafcdf4a..07f9bc10355fb83c695634a907f9f16fd45612ff 100644 (file)
@@ -111,15 +111,15 @@ namespace pcl
     //    CloudPtrT
     //    getCloudPtr () const;
         
-        /** \brief Paint View function - reimpliment in item subclass if it can be displayed in PCLVisualizer*/
+        /** \brief Paint View function - reimplement in item subclass if it can be displayed in PCLVisualizer*/
         virtual void
         paintView (pcl::visualization::PCLVisualizer::Ptr vis) const;
         
-        /** \brief Remove from View function - reimpliment in item subclass if it can be displayed in PCLVisualizer*/
+        /** \brief Remove from View function - reimplement in item subclass if it can be displayed in PCLVisualizer*/
         virtual void
         removeFromView (pcl::visualization::PCLVisualizer::Ptr vis) const;
         
-        /** \brief Inspector additional tabs paint function - reimpliment in item subclass if item has additional tabs to show in Inspector*/
+        /** \brief Inspector additional tabs paint function - reimplement in item subclass if item has additional tabs to show in Inspector*/
         virtual QMap <QString, QWidget*>
         getInspectorTabs ();
               
index ee74b82a3f5a4fa6193acbd83d0f00746649a194..c8a5224f524a264c8ec0cf0c25b0c75cfe5d2f57 100644 (file)
@@ -42,6 +42,8 @@
 
 #pragma once
 
+#include <QList>
+#include <QObject>
 #include <QPointer>
 
 namespace pcl
@@ -94,7 +96,7 @@ namespace pcl
         connect (const char *signal, QObject *receiver, const char *slot);
 
         /**
-                Disconencts a signal from a multiplexed object to a receiving (action)
+                Disconnects a signal from a multiplexed object to a receiving (action)
                 object.
                 @see connect(const char *signal, QObject *receiver, const char *slot)
         */
index 6429f8d1f6bd3aa5f35e2482e4a56eefed905f37..65781efadcdc2f6888fe47480d98f6b4fb32ff32 100644 (file)
@@ -69,7 +69,7 @@ namespace pcl
         virtual QString 
         getIconName () const = 0;
         
-        /** \brief Reimpliment this function to return the proper number if tool requires more than one input item */
+        /** \brief Reimplement this function to return the proper number if tool requires more than one input item */
         inline virtual int
         getNumInputItems () const 
         { 
index 018c7a8e65f879daef02f884e4dcc73f7b7da257..a35d946d2ba585450bd4cf274938ae0fcbe2213d 100644 (file)
@@ -58,7 +58,7 @@
        performTemplatedAction (const QList <const CloudComposerItem*>& input_data);
        
        inline QString
-       getToolName () const override { return "Organized Segmenation Tool";}
+       getToolName () const override { return "Organized Segmentation Tool";}
      };
      
      
index 8529a667827378cdcb6184418d60397ada324cd1..1302b59819c6f6f62b8d0bd57725046d03536139 100644 (file)
@@ -10,6 +10,7 @@
 #include <pcl/apps/cloud_composer/signal_multiplexer.h>
 #include <pcl/apps/cloud_composer/point_selectors/interactor_style_switch.h>
 
+#include <QActionGroup>
 #include <QMessageBox>
 #include <QPluginLoader>
 #include <QUndoGroup>
index 8f70e6b0f0f232667a706e83a1d70502d0e1da18..d955fff374a3c36b6a9f72f1b95a849b8cc98498 100644 (file)
@@ -14,6 +14,7 @@ pcl::cloud_composer::CloudItem::CloudItem (QString name,
                                            const Eigen::Quaternionf& orientation,
                                            bool make_templated_cloud)
   : CloudComposerItem (std::move(name))
+  , cloud_blob_ptr_ (cloud_ptr)
   , origin_ (origin)
   , orientation_ (orientation)
   , template_cloud_set_ (false)
@@ -25,7 +26,6 @@ pcl::cloud_composer::CloudItem::CloudItem (QString name,
  // qDebug () << "Cloud size before passthrough : "<<cloud_ptr->width<<"x"<<cloud_ptr->height;
 
 //  qDebug () << "Cloud size after passthrough : "<<cloud_filtered->width<<"x"<<cloud_filtered->height;
-  cloud_blob_ptr_ = cloud_ptr;
   pcl::PCLPointCloud2::ConstPtr const_cloud_ptr = cloud_ptr;
   this->setData (QVariant::fromValue (const_cloud_ptr), ItemDataRole::CLOUD_BLOB);
   this->setData (QVariant::fromValue (origin_), ItemDataRole::ORIGIN);
index 141c5d3d79cbdd08408455349be99a70ceb5b9fd..791e0218ad682052b3b2b1a9bb14b494c929075b 100644 (file)
@@ -53,7 +53,6 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnLeftButtonUp ()
   vtkSmartPointer<vtkActor> selected_actor = vtkActor::SafeDownCast(this->InteractionProp);
   if (selected_actor)
   {
-    ManipulationEvent* manip_event = new ManipulationEvent ();
     //Fetch the actor we manipulated
     
     selected_actor->GetMatrix (end_matrix_);
@@ -71,6 +70,7 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnLeftButtonUp ()
     }
     if ( !manipulated_id.isEmpty() )
     {
+      ManipulationEvent* manip_event = new ManipulationEvent ();
       manip_event->addManipulation (manipulated_id, start_matrix_, end_matrix_);
       this->InvokeEvent (this->manipulation_complete_event_, manip_event);
     }
@@ -88,7 +88,6 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnRightButtonUp ()
   vtkSmartPointer<vtkActor> selected_actor = vtkActor::SafeDownCast(this->InteractionProp);
   if (selected_actor)
   {
-    ManipulationEvent* manip_event = new ManipulationEvent ();
     //Fetch the actor we manipulated
     
     selected_actor->GetMatrix (end_matrix_);
@@ -106,6 +105,7 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnRightButtonUp ()
     }
     if ( !manipulated_id.isEmpty() )
     {
+      ManipulationEvent* manip_event = new ManipulationEvent ();
       manip_event->addManipulation (manipulated_id, start_matrix_, end_matrix_);
       this->InvokeEvent (this->manipulation_complete_event_, manip_event);
     }
index 24d56ba65fbcde10635502372389995269e668b8..5c3350ff43b7973f15a0d635f403c742d00a2582 100644 (file)
@@ -91,7 +91,11 @@ PCL_ADD_EXECUTABLE(
     ${IMPL_INCS}
     ${UI}
   BUNDLE)
+
 target_link_libraries("${EXE_NAME}" ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL)
+if (${QTX} MATCHES "Qt6")
+  target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets)
+endif()
 
 pcl_add_includes("${SUBSUBSYS_NAME}" "${SUBSUBSYS_NAME}" ${INCS})
 pcl_add_includes("${SUBSUBSYS_NAME}" "${SUBSUBSYS_NAME}/impl" ${IMPL_INCS})
@@ -108,6 +112,9 @@ PCL_ADD_EXECUTABLE(
   BUNDLE)
 
 target_link_libraries(pcl_offline_integration ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL)
+if (${QTX} MATCHES "Qt6")
+  target_link_libraries(pcl_offline_integration ${QTX}::OpenGLWidgets)
+endif()
 
 # Add to the compound apps target
 list(APPEND PCL_APPS_ALL_TARGETS ${PCL_IN_HAND_SCANNER_ALL_TARGETS})
index d9b94d72fe87f5625c6a776d51a2e0e6feef7aa6..c1c86448c06d8058b6c1c67fcfe71cbf187799e3 100644 (file)
@@ -46,7 +46,7 @@
 #include <pcl/pcl_exports.h>
 #include <pcl/pcl_macros.h>
 
-#include <QGLWidget>
+#include <QOpenGLWidget>
 
 #include <iomanip>
 #include <mutex>
@@ -57,7 +57,7 @@ namespace pcl {
 namespace ihs {
 namespace detail {
 /** \brief Mesh format more efficient for visualization than the half-edge data
- * structure. \see http://en.wikipedia.org/wiki/Polygon_mesh#Face-vertex_meshes
+ * structure. \see https://en.wikipedia.org/wiki/Polygon_mesh#Face-vertex_meshes
  *
  * \note Only triangles are currently supported.
  */
@@ -102,7 +102,7 @@ public:
  * \note Currently you have to derive from this class to use it. Implement the
  * paintEvent: Call the paint event of this class and declare a QPainter.
  */
-class PCL_EXPORTS OpenGLViewer : public QGLWidget {
+class PCL_EXPORTS OpenGLViewer : public QOpenGLWidget {
   Q_OBJECT
 
 public:
index b3ae1372f41f0838aceaad1cb4394af7e8435e1c..cbd16668eaa2ca9e72e6f4148d7c80331139110f 100644 (file)
@@ -161,7 +161,7 @@ pcl::ihs::ICP::findTransformation(const MeshConstPtr& mesh_model,
 {
   // Check the input
   // TODO: Double check the minimum number of points necessary for icp
-  const std::size_t n_min = 4;
+  constexpr std::size_t n_min = 4;
 
   if (mesh_model->sizeVertices() < n_min || cloud_data->size() < n_min) {
     std::cerr << "ERROR in icp.cpp: Not enough input points!\n";
index 9b5bdc11ce76977c626efcb4b7279f25f7e595e5..3d7517ac145e103bef701f4436e1b0ece01cd893 100644 (file)
@@ -124,7 +124,7 @@ pcl::ihs::Integration::reconstructMesh(const CloudXYZRGBNormalConstPtr& cloud_da
   // *   3 - 0  //
   const int offset_1 = -width;
   const int offset_2 = -width - 1;
-  const int offset_3 = -1;
+  constexpr int offset_3 = -1;
   const int offset_4 = -width - 2;
 
   for (int r = 1; r < height; ++r) {
@@ -262,7 +262,7 @@ pcl::ihs::Integration::merge(const CloudXYZRGBNormalConstPtr& cloud_data,
   // *   3 - 0  //
   const int offset_1 = -width;
   const int offset_2 = -width - 1;
-  const int offset_3 = -1;
+  constexpr int offset_3 = -1;
   const int offset_4 = -width - 2;
 
   const float dot_min = std::cos(max_angle_ * 17.45329252e-3); // deg to rad
index f32601307db325c1248d9090ef43b49183ac9b79..d97e9c14bb95a95bbc6d985471bcd808fdb28238 100644 (file)
@@ -70,7 +70,7 @@ pcl::ihs::MainWindow::MainWindow(QWidget* parent)
   spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
   ui_->toolBar->insertWidget(ui_->actionHelp, spacer);
 
-  const double max = std::numeric_limits<double>::max();
+  constexpr double max = std::numeric_limits<double>::max();
 
   // In hand scanner
   QHBoxLayout* layout = new QHBoxLayout(ui_->placeholder_in_hand_scanner);
index f025e91a66900ed623562348145ff17dd0aa199f..853232dc7f6333b037dd65a395430d35c4fd4f9d 100644 (file)
@@ -50,6 +50,7 @@
 #include <QApplication>
 #include <QFileDialog>
 #include <QKeyEvent>
+#include <QPainter>
 #include <QtConcurrent>
 #include <QtCore>
 
@@ -194,7 +195,7 @@ pcl::ihs::OfflineIntegration::getFilesFromDirectory(
   boost::filesystem::directory_iterator it_end;
   for (boost::filesystem::directory_iterator it(path_dir); it != it_end; ++it) {
     if (!is_directory(it->status()) &&
-        boost::algorithm::to_upper_copy(boost::filesystem::extension(it->path())) ==
+        boost::algorithm::to_upper_copy(it->path().extension().string()) ==
             boost::algorithm::to_upper_copy(extension)) {
       files.push_back(it->path().string());
     }
index 054f601f1380338cc1dfab1d8cda09e7501a5832..2002d50276a48537a4352d77e65395b74a4ed648 100644 (file)
@@ -56,6 +56,7 @@
 #include <pcl/common/centroid.h>
 #include <pcl/common/impl/centroid.hpp> // TODO: PointIHS is not registered
 
+#include <QApplication>
 #include <QtOpenGL>
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -101,7 +102,7 @@ pcl::ihs::detail::FaceVertexMesh::FaceVertexMesh(const Mesh& mesh,
 ////////////////////////////////////////////////////////////////////////////////
 
 pcl::ihs::OpenGLViewer::OpenGLViewer(QWidget* parent)
-: QGLWidget(parent)
+: QOpenGLWidget(parent)
 , timer_vis_(new QTimer(this))
 , colormap_(Colormap::Constant(255))
 , vis_conf_norm_(1)
@@ -484,7 +485,7 @@ pcl::ihs::OpenGLViewer::addMesh(const CloudXYZRGBNormalConstPtr& cloud,
   const int h = cloud->height;
   const int offset_1 = -w;
   const int offset_2 = -w - 1;
-  const int offset_3 = -1;
+  constexpr int offset_3 = -1;
 
   FaceVertexMeshPtr mesh(new FaceVertexMesh());
   mesh->transformation = T;
@@ -1083,7 +1084,7 @@ pcl::ihs::OpenGLViewer::initializeGL()
 void
 pcl::ihs::OpenGLViewer::setupViewport(const int w, const int h)
 {
-  const float aspect_ratio = 4. / 3.;
+  constexpr float aspect_ratio = 4. / 3.;
 
   // Use the biggest possible area of the window to draw to
   //    case 1 (w < w_scaled):        case 2 (w >= w_scaled):
@@ -1195,8 +1196,8 @@ pcl::ihs::OpenGLViewer::wheelEvent(QWheelEvent* event)
         std::max((cam_pivot_ - R_cam_ * o - t_cam_).norm(), .1 / scaling_factor_) / d;
 
     // http://doc.qt.digia.com/qt/qwheelevent.html#delta
-    t_cam_ +=
-        scale * Eigen::Vector3d(R_cam_ * (ez * static_cast<double>(event->delta())));
+    t_cam_ += scale * Eigen::Vector3d(
+                          R_cam_ * (ez * static_cast<double>(event->angleDelta().y())));
   }
 }
 
index 466c230645f9dff8358412851bc5d7a7837a73dc..2a2d22fc5fb88d8c6a904b11a1a5b0b443ceaf73 100644 (file)
 #include <QMutex>
 #include <QTimer>
 
-using PointT = pcl::PointXYZRGBA;
-
-// Useful macros
-// clang-format off
-#define FPS_CALC(_WHAT_)                                                               \
-  do {                                                                                 \
-    static unsigned count = 0;                                                         \
-    static double last = pcl::getTime();                                               \
-    double now = pcl::getTime();                                                       \
-    ++count;                                                                           \
-    if (now - last >= 1.0) {                                                           \
-      std::cout << "Average framerate(" << _WHAT_ << "): "                             \
-                << double(count) / double(now - last) << " Hz" << std::endl;           \
-      count = 0;                                                                       \
-      last = now;                                                                      \
-    }                                                                                  \
-  } while (false)
-// clang-format on
+using PointT = pcl::PointXYZ;
 
 namespace Ui {
 class MainWindow;
@@ -76,25 +59,27 @@ public:
   using CloudPtr = Cloud::Ptr;
   using CloudConstPtr = Cloud::ConstPtr;
 
-  ManualRegistration();
+  PCL_MAKE_ALIGNED_OPERATOR_NEW
+
+  ManualRegistration(float voxel_size);
 
   ~ManualRegistration() override = default;
 
   void
-  setSrcCloud(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_src)
+  setSrcCloud(pcl::PointCloud<PointT>::Ptr cloud_src)
   {
     cloud_src_ = std::move(cloud_src);
-    cloud_src_present_ = true;
+    vis_src_->addPointCloud(cloud_src_, "cloud_src_");
   }
   void
-  setDstCloud(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_dst)
+  setDstCloud(pcl::PointCloud<PointT>::Ptr cloud_dst)
   {
     cloud_dst_ = std::move(cloud_dst);
-    cloud_dst_present_ = true;
+    vis_dst_->addPointCloud(cloud_dst_, "cloud_dst_");
   }
 
   void
-  SourcePointPickCallback(const pcl::visualization::PointPickingEvent& event, void*);
+  SrcPointPickCallback(const pcl::visualization::PointPickingEvent& event, void*);
   void
   DstPointPickCallback(const pcl::visualization::PointPickingEvent& event, void*);
 
@@ -105,21 +90,15 @@ protected:
   pcl::visualization::PCLVisualizer::Ptr vis_src_;
   pcl::visualization::PCLVisualizer::Ptr vis_dst_;
 
-  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_src_;
-  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_dst_;
+  pcl::PointCloud<PointT>::Ptr cloud_src_;
+  pcl::PointCloud<PointT>::Ptr cloud_dst_;
 
   QMutex mtx_;
   QMutex vis_mtx_;
   Ui::MainWindow* ui_;
-  QTimer* vis_timer_;
-
-  bool cloud_src_present_;
-  bool cloud_src_modified_;
-  bool cloud_dst_present_;
-  bool cloud_dst_modified_;
 
-  bool src_point_selected_;
-  bool dst_point_selected_;
+  bool src_point_selected_{false};
+  bool dst_point_selected_{false};
 
   pcl::PointXYZ src_point_;
   pcl::PointXYZ dst_point_;
@@ -127,7 +106,12 @@ protected:
   pcl::PointCloud<pcl::PointXYZ> src_pc_;
   pcl::PointCloud<pcl::PointXYZ> dst_pc_;
 
-  Eigen::Matrix4f transform_;
+  Eigen::Matrix4f transform_ = Eigen::Affine3f::Identity().matrix();
+
+  std::set<std::string> annotations_src_;
+  std::set<std::string> annotations_dst_;
+
+  const float voxel_size_;
 
 public Q_SLOTS:
   void
@@ -144,12 +128,4 @@ public Q_SLOTS:
   applyTransformPressed();
   void
   refinePressed();
-  void
-  undoPressed();
-  void
-  safePressed();
-
-private Q_SLOTS:
-  void
-  timeoutSlot();
 };
diff --git a/apps/include/pcl/apps/pcl_viewer_dialog.h b/apps/include/pcl/apps/pcl_viewer_dialog.h
new file mode 100644 (file)
index 0000000..0a3cff7
--- /dev/null
@@ -0,0 +1,34 @@
+#pragma once
+#include <pcl/visualization/pcl_visualizer.h>
+#include <pcl/point_cloud.h>
+#include <pcl/point_types.h>
+
+#include <Eigen/Geometry>
+
+#include <QDialog>
+#include <QTimer>
+
+using CloudT = pcl::PointCloud<pcl::PointXYZ>;
+
+namespace Ui {
+class PCLViewerDialogUi;
+}
+
+class PCLViewerDialog : public QDialog {
+  Q_OBJECT
+  Ui::PCLViewerDialogUi* ui_;
+  pcl::visualization::PCLVisualizer::Ptr vis_;
+
+public:
+  PCLViewerDialog(QWidget* parent = 0);
+
+  void
+  setPointClouds(CloudT::ConstPtr src_cloud,
+                 CloudT::ConstPtr tgt_cloud,
+                 const Eigen::Affine3f& t);
+
+public Q_SLOTS:
+
+  void
+  refreshView();
+};
index cc59e3b0b4c75be8aa0ea11fde2d6f9f982c6f64..b121e497b13a0608436fb26298f39c4b920aaf07 100644 (file)
@@ -51,7 +51,7 @@ private:
   };
 
 public:
-  RenderViewsTesselatedSphere()
+  RenderViewsTesselatedSphere() : campos_constraints_func_(camPosConstraintsAllTrue())
   {
     resolution_ = 150;
     tesselation_level_ = 1;
@@ -60,7 +60,6 @@ public:
     radius_sphere_ = 1.f;
     compute_entropy_ = false;
     gen_organized_ = false;
-    campos_constraints_func_ = camPosConstraintsAllTrue();
   }
 
   void
index aa1ee3a490df1c7c2db37a720b9ae72ec246c5ec..1823fdf15a8e05ee0ac1d6079746018d37a87ca1 100755 (executable)
@@ -36,9 +36,9 @@
 
 #pragma once
 
-#include <pcl/Vertices.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
+#include <pcl/Vertices.h>
 
 #include <vtkSmartPointer.h>
 
index fb254279d49673b01650522e84977bff9aa65617..6f383853cae90b10240aabcdaa6779409c856ecb 100755 (executable)
@@ -41,9 +41,9 @@
 #include <vtkCamera.h>
 #include <vtkMatrix4x4.h>
 #include <vtkPolyData.h>
-#include <vtkRenderWindow.h>
 #include <vtkRenderer.h>
 #include <vtkRendererCollection.h>
+#include <vtkRenderWindow.h>
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 pcl::modeler::ChannelActorItem::ChannelActorItem(
index b674cadf182886f2c488e48e7b038ad904d6d838..85381af7313287ff1b06e4dab120d9f183377247 100755 (executable)
@@ -282,7 +282,7 @@ pcl::modeler::MainWindow::updateRecentActions(
   }
 
   recent_items.removeDuplicates();
-  int recent_number = std::min(int(MAX_RECENT_NUMBER), recent_items.size());
+  int recent_number = std::min<int>(int(MAX_RECENT_NUMBER), recent_items.size());
   for (int i = 0; i < recent_number; ++i) {
     QString text = tr("%1 %2").arg(i + 1).arg(recent_items[i]);
     recent_actions[i]->setText(text);
index 9be04f77ce3227ddb048c77070bff361f1089e75..b63629b6ba1cd20fcfe7a01c1e84d0c853afa91e 100755 (executable)
@@ -43,9 +43,9 @@
 #include <vtkBoundingBox.h>
 #include <vtkCubeAxesActor.h>
 #include <vtkProp.h>
-#include <vtkRenderWindow.h>
 #include <vtkRenderer.h>
 #include <vtkRendererCollection.h>
+#include <vtkRenderWindow.h>
 #include <vtkSmartPointer.h>
 
 //////////////////////////////////////////////////////////////////////////////////////////////
index d46b49f53d25ac65bef31fdb242b15588c0949e2..7374b72e0d77628e5eb63721b8dfc98ffc1c0223 100644 (file)
@@ -87,6 +87,9 @@ PCL_ADD_EXECUTABLE(
     ${INCS})
 
 target_link_libraries("${EXE_NAME}" ${QTX}::Widgets ${QTX}::OpenGL ${OPENGL_LIBRARIES} ${BOOST_LIBRARIES} pcl_common pcl_io pcl_filters)
+if (${QTX} MATCHES "Qt6")
+  target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets)
+endif()
 
 PCL_ADD_INCLUDES("${SUBSUBSYS_NAME}" "${SUBSYS_NAME}/${SUBSUBSYS_NAME}" ${INCS})
 PCL_MAKE_PKGCONFIG(${EXE_NAME} COMPONENT ${SUBSUBSYS_NAME} DESC ${SUBSUBSYS_DESC})
index 7630d224e123ac8ba745dfcefe405289e5bd33ca..91ff49e32feef02012cf827c8f94cac1565413a0 100644 (file)
@@ -49,7 +49,7 @@
 
 #include <pcl/memory.h>  // for pcl::shared_ptr
 
-#include <QGLWidget>
+#include <QOpenGLWidget>
 
 #include <functional>
 
@@ -57,7 +57,7 @@ class Selection;
 
 /// @brief class declaration for the widget for editing and viewing
 /// point clouds.
-class CloudEditorWidget : public QGLWidget
+class CloudEditorWidget : public QOpenGLWidget
 {
   Q_OBJECT
   public:
@@ -319,5 +319,9 @@ class CloudEditorWidget : public QGLWidget
     /// a dialog displaying the statistics of the cloud editor
     StatisticsDialog stat_dialog_;
 
+    /// the viewport, set by resizeGL
+    std::array<GLint, 4> viewport_;
 
+    /// the projection matrix, set by resizeGL
+    std::array<GLfloat, 16> projection_matrix_;
 };
index e7dbdedd3a0d43be6cdd5763d3aa41e5172560dd..ca4ef7fb1289e9e73d89c9adc04624b39c51328c 100644 (file)
@@ -43,6 +43,8 @@
 
 #include <pcl/apps/point_cloud_editor/localTypes.h>
 
+#include <cassert>
+
 /// @brief The abstract parent class of all the command classes. Commands are
 /// non-copyable.
 class Command
index 93433339c06391bf0f6b000e3a6fc587d0384f55..f69d9fa05b427900ed8dde5f0314a77d59a49acb 100644 (file)
@@ -41,6 +41,7 @@
 
 #pragma once
 
+#include <cassert>
 #include <deque>
 #include <pcl/apps/point_cloud_editor/localTypes.h>
 
index 024d237ccea2f67ab1d01e6bb278ecab08a09f95..ed7fa8d76d22a35a8f9b0ba64afa194be150e31f 100644 (file)
@@ -167,25 +167,25 @@ struct IncIndex
 /// A helpful const representing the number of elements in our vectors.
 /// This is used for all operations that require the copying of the vector.
 /// Although this is used in a fairly generic way, the display requires 3D.
-const unsigned int XYZ_SIZE = 3;
+constexpr unsigned int XYZ_SIZE = 3;
 
 /// A helpful const representing the number of elements in each row/col in
 /// our matrices. This is used for all operations that require the copying of
 /// the matrix.
-const unsigned int MATRIX_SIZE_DIM = 4;
+constexpr unsigned int MATRIX_SIZE_DIM = 4;
 
 /// A helpful const representing the number of elements in our matrices.
 /// This is used for all operations that require the copying of the matrix.
-const unsigned int MATRIX_SIZE = MATRIX_SIZE_DIM * MATRIX_SIZE_DIM;
+constexpr unsigned int MATRIX_SIZE = MATRIX_SIZE_DIM * MATRIX_SIZE_DIM;
 
 /// The default window width
-const unsigned int WINDOW_WIDTH = 1200;
+constexpr unsigned int WINDOW_WIDTH = 1200;
 /// The default window height
-const unsigned int WINDOW_HEIGHT = 1000;
+constexpr unsigned int WINDOW_HEIGHT = 1000;
 
 /// The default z translation used to push the world origin in front of the
 /// display
-const float DISPLAY_Z_TRANSLATION = -2.0f;
+constexpr float DISPLAY_Z_TRANSLATION = -2.0f;
 
 /// The radius of the trackball given as a percentage of the screen width
-const float TRACKBALL_RADIUS_SCALE = 0.4f;
+constexpr float TRACKBALL_RADIUS_SCALE = 0.4f;
index bfa2e997079101a69ab3a6da566302187bd791d2..ded8c6b1c4f8807e83878642200562cbd33f046d 100644 (file)
@@ -68,7 +68,7 @@ class MainWindow : public QMainWindow
     /// @brief Constructor
     /// @param argc The number of c-strings to be expected in argv
     /// @param argv An array of c-strings.  The zero entry is expected to be
-    /// the name of the appliation.  Any additional strings will be interpreted
+    /// the name of the application.  Any additional strings will be interpreted
     /// as filenames designating point clouds to be loaded.
     MainWindow (int argc, char **argv);
 
index fc21d80aac404c09712b9f1d146627f3c13768e9..ee34d7d75026cf613ef6556b2cdc9e1c8ebad141 100644 (file)
@@ -44,6 +44,8 @@
 
 #include <pcl/memory.h>  // for pcl::shared_ptr
 
+#include <cassert>
+
 class Selection;
 
 class Select1DTool : public ToolInterface
index 985ec4e146921d0e6ba20f355d2170829265ea4d..2052f10e8e7e52d94b3d295d6cc018bfb75ebc49 100644 (file)
@@ -40,7 +40,7 @@
 
 #pragma once
 
-#include <qgl.h>
+#include <qopengl.h>
 #include <pcl/apps/point_cloud_editor/toolInterface.h>
 #include <pcl/apps/point_cloud_editor/localTypes.h>
 
@@ -57,7 +57,8 @@ class Select2DTool : public ToolInterface
     /// @brief Constructor
     /// @param selection_ptr a shared pointer pointing to the selection object.
     /// @param cloud_ptr a shared pointer pointing to the cloud object.
-    Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr);
+    /// @param get_viewport_and_projection_mat a function that can be used to get the viewport and the projection matrix
+    Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr, std::function<void(GLint*,GLfloat*)> get_viewport_and_projection_mat);
 
     /// @brief Destructor
     ~Select2DTool () override;
@@ -154,4 +155,6 @@ class Select2DTool : public ToolInterface
     /// switch for selection box rendering
     bool display_box_;
 
+    /// function to get the viewport and the projection matrix (initialized by ctor)
+    std::function<void(GLint*,GLfloat*)> get_viewport_and_projection_mat_;
 };
index 8618e4b965e667c1a90cfdfef2f4034fd9054286..80d3fc4744d4c894bb605c1cbe686ebfe0ef911f 100644 (file)
@@ -42,6 +42,7 @@
 
 #include <vector>
 #include <string>
+#include <cassert>
 #include <pcl/apps/point_cloud_editor/localTypes.h>
 
 class Statistics
index c5cc67c89eabb70ef37b659e68fec78306da5a6e..38111acba28352a6659c53a6208c5b9b7efad98d 100644 (file)
@@ -43,6 +43,8 @@
 
 #include <pcl/apps/point_cloud_editor/localTypes.h>
 
+#include <cassert>
+
 /// @brief the parent class of all the select and the transform tool classes
 class ToolInterface
 {
index 61e82e589f01e3ab03dd41d7f75cfa69e319ff1f..5a169e884587779b9eb36ba4b416a1cef81e4240 100644 (file)
@@ -38,7 +38,6 @@
 /// @author  Yue Li and Matthew Hielsberg
 
 #include <algorithm>
-#include <qgl.h>
 #include <pcl/apps/point_cloud_editor/cloud.h>
 #include <pcl/apps/point_cloud_editor/selection.h>
 #include <pcl/apps/point_cloud_editor/localTypes.h>
index 6a8d50f692f98ab025e0aa227754e19c86f0cb7f..f4cd6d4d03a513f8da7a3ae577add7a8cd8ec059 100644 (file)
 #include <QMessageBox>
 #include <QMouseEvent>
 #include <QApplication>
-#include <QDesktopWidget>
-#include <qgl.h>
 
 #include <pcl/pcl_config.h>
 
 #ifdef OPENGL_IS_A_FRAMEWORK
 # include <OpenGL/glu.h>
 #else
+# ifdef _WIN32
+#  include <windows.h>
+# endif // _WIN32
 # include <GL/glu.h>
 #endif
 
@@ -72,8 +73,7 @@
 #include <pcl/apps/point_cloud_editor/mainWindow.h>
 
 CloudEditorWidget::CloudEditorWidget (QWidget *parent)
-  : QGLWidget(QGLFormat(QGL::DoubleBuffer | QGL::DepthBuffer |
-                        QGL::Rgba | QGL::StencilBuffer), parent),
+  : QOpenGLWidget(parent),
     point_size_(2.0f), selected_point_size_(4.0f),
     cam_fov_(60.0), cam_aspect_(1.0), cam_near_(0.0001), cam_far_(100.0),
     color_scheme_(COLOR_BY_PURE), is_colored_(false)
@@ -116,7 +116,6 @@ CloudEditorWidget::load ()
                              tr("Can not load %1.").arg(file_path));
   }
   update();
-  updateGL();
 }
 
 void
@@ -205,7 +204,7 @@ CloudEditorWidget::select2D ()
   if (!cloud_ptr_)
     return;
   tool_ptr_ = std::shared_ptr<Select2DTool>(new Select2DTool(selection_ptr_,
-                                                               cloud_ptr_));
+                                                               cloud_ptr_, [this](GLint * viewport, GLfloat * projection_matrix){ std::copy_n(this->viewport_.begin(), 4, viewport); std::copy_n(this->projection_matrix_.begin(), 16, projection_matrix); }));
   update();
 }
 
@@ -476,11 +475,16 @@ CloudEditorWidget::paintGL ()
 void
 CloudEditorWidget::resizeGL (int width, int height)
 {
+  const auto ratio = this->devicePixelRatio();
+  width = static_cast<int>(width*ratio);
+  height = static_cast<int>(height*ratio);
   glViewport(0, 0, width, height);
+  viewport_ = {0, 0, width, height};
   cam_aspect_ = double(width) / double(height);
   glMatrixMode(GL_PROJECTION);
   glLoadIdentity();
   gluPerspective(cam_fov_, cam_aspect_, cam_near_, cam_far_);
+  glGetFloatv(GL_PROJECTION_MATRIX, projection_matrix_.data());
   glMatrixMode(GL_MODELVIEW);
   glLoadIdentity();
 }
index cdcf5ceff9e93be3b4ee536072820bf88addac66..b60d7ee3509b8c73f7402ba74bca75adf70b7742 100644 (file)
@@ -38,7 +38,6 @@
 /// @author  Yue Li and Matthew Hielsberg
 
 #include <algorithm>
-#include <qgl.h>
 #include <pcl/apps/point_cloud_editor/select1DTool.h>
 #include <pcl/apps/point_cloud_editor/cloud.h>
 #include <pcl/apps/point_cloud_editor/selection.h>
index 93e431027bfe12984062efe08673a0abc124f229..60025238bd28375feaebcfa40e1523cb05cfb9d3 100644 (file)
@@ -48,8 +48,8 @@ const float Select2DTool::DEFAULT_TOOL_DISPLAY_COLOR_GREEN_ = 1.0f;
 const float Select2DTool::DEFAULT_TOOL_DISPLAY_COLOR_BLUE_ = 1.0f;
 
 
-Select2DTool::Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr)
-  : selection_ptr_(std::move(selection_ptr)), cloud_ptr_(std::move(cloud_ptr)), display_box_(false)
+Select2DTool::Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr, std::function<void(GLint*,GLfloat*)> get_viewport_and_projection_mat)
+  : selection_ptr_(std::move(selection_ptr)), cloud_ptr_(std::move(cloud_ptr)), display_box_(false), get_viewport_and_projection_mat_(get_viewport_and_projection_mat)
 {
 }
 
@@ -88,10 +88,9 @@ Select2DTool::end (int x, int y, BitMask modifiers, BitMask)
     return;
 
   GLint viewport[4];
-  glGetIntegerv(GL_VIEWPORT,viewport);
   IndexVector indices;
   GLfloat project[16];
-  glGetFloatv(GL_PROJECTION_MATRIX, project);
+  get_viewport_and_projection_mat_(viewport, project);
 
   Point3DVector ptsvec;
   cloud_ptr_->getDisplaySpacePoints(ptsvec);
index 34da2014e5b1f7fdbb44caeb3f544c5ec0a6fbe0..8ed83d7a143ddddf3e02f883c12131ec40dc6b33 100644 (file)
@@ -50,9 +50,9 @@ TransformCommand::TransformCommand(const ConstSelectionPtr& selection_ptr,
                                    float translate_z)
   : selection_ptr_(selection_ptr), cloud_ptr_(std::move(cloud_ptr)),
     translate_x_(translate_x), translate_y_(translate_y),
-    translate_z_(translate_z)
+    translate_z_(translate_z),
+    internal_selection_ptr_(new Selection(*selection_ptr))
 {
-  internal_selection_ptr_ = SelectionPtr(new Selection(*selection_ptr));
   std::copy(matrix, matrix + MATRIX_SIZE, transform_matrix_);
   const float *cloud_matrix = cloud_ptr_->getMatrix();
   std::copy(cloud_matrix, cloud_matrix + MATRIX_SIZE, cloud_matrix_);
index 3af6d65961b196737230231af03c048d608c2c95..5a12081eb6a716eee6886795c1ab5668fa9c2dc5 100644 (file)
@@ -103,8 +103,9 @@ main(int argc, char** argv)
   int pose_refinement_ = 0;
   int icp_iterations = 5;
 
-  std::string forest_fn = "../data/forests/forest.txt";
-  std::string model_path_ = "../data/ply_models/face.pcd";
+  // Use for example biwi_face_database from https://github.com/PointCloudLibrary/data
+  std::string forest_fn = "../data/biwi_face_database/forest_example.txt";
+  std::string model_path_ = "../data/biwi_face_database/model.pcd";
 
   pcl::console::parse_argument(argc, argv, "-forest_fn", forest_fn);
   pcl::console::parse_argument(argc, argv, "-max_variance", trans_max_variance);
@@ -119,7 +120,6 @@ main(int argc, char** argv)
   pcl::console::parse_argument(argc, argv, "-icp_iterations", icp_iterations);
 
   pcl::RFFaceDetectorTrainer fdrf;
-  fdrf.setForestFilename(forest_fn);
   fdrf.setWSize(80);
   fdrf.setUseNormals(static_cast<bool>(use_normals));
   fdrf.setWStride(STRIDE_SW);
@@ -134,7 +134,10 @@ main(int argc, char** argv)
 
   // load forest from file and pass it to the detector
   std::filebuf fb;
-  fb.open(forest_fn.c_str(), std::ios::in);
+  if (!fb.open(forest_fn.c_str(), std::ios::in)) {
+    PCL_ERROR("Could not open file %s\n", forest_fn.c_str());
+    return 1;
+  }
   std::istream os(&fb);
 
   using NodeType = pcl::face_detection::RFTreeNode<pcl::face_detection::FeatureType>;
index 488af48cca16291a51a34488e0f54137ba4367d9..394ae3eef0d5141108e05c1a374f9deab6a845e0 100644 (file)
@@ -19,8 +19,8 @@
 #include <pcl/surface/gp3.h>
 #include <pcl/surface/marching_cubes_hoppe.h>
 #include <pcl/visualization/pcl_visualizer.h>
-#include <pcl/ModelCoefficients.h>
 #include <pcl/memory.h> // for pcl::dynamic_pointer_cast
+#include <pcl/ModelCoefficients.h>
 
 #include <string>
 #include <vector>
@@ -324,7 +324,7 @@ ICCVTutorial<FeatureType>::findCorrespondences(
 
   // Find the index of the best match for each keypoint, and store it in
   // "correspondences_out"
-  const int k = 1;
+  constexpr int k = 1;
   pcl::Indices k_indices(k);
   std::vector<float> k_squared_distances(k);
   for (int i = 0; i < static_cast<int>(source->size()); ++i) {
index 8dff3b9b5df9362732f0c52caf9aad3c80fb552c..b7cf5d8a009a4ffd30e32bfa24674acd9cc08196 100644 (file)
  */
 
 #include <pcl/apps/manual_registration.h>
+#include <pcl/apps/pcl_viewer_dialog.h>
+#include <pcl/filters/voxel_grid.h>
 #include <pcl/io/pcd_io.h> // for loadPCDFile
+#include <pcl/registration/gicp.h>
 
 #include <QApplication>
 #include <QEvent>
 
 #include <vtkCamera.h>
 #include <vtkGenericOpenGLRenderWindow.h>
-#include <vtkRenderWindow.h>
 #include <vtkRendererCollection.h>
+#include <vtkRenderWindow.h>
 
 using namespace pcl;
+using namespace pcl::visualization;
+using std::string;
+using std::to_string;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////
-ManualRegistration::ManualRegistration()
+ManualRegistration::ManualRegistration(float voxel_size) : voxel_size_(voxel_size)
 {
-  // Create a timer
-  vis_timer_ = new QTimer(this);
-  vis_timer_->start(5); // 5ms
-
-  connect(vis_timer_, SIGNAL(timeout()), this, SLOT(timeoutSlot()));
-
   ui_ = new Ui::MainWindow;
   ui_->setupUi(this);
 
@@ -91,7 +91,7 @@ ManualRegistration::ManualRegistration()
   vis_src_->getInteractorStyle()->setKeyboardModifier(
       pcl::visualization::INTERACTOR_KB_MOD_SHIFT);
 
-  vis_src_->registerPointPickingCallback(&ManualRegistration::SourcePointPickCallback,
+  vis_src_->registerPointPickingCallback(&ManualRegistration::SrcPointPickCallback,
                                          *this);
 
   // Set up the destination window
@@ -133,15 +133,10 @@ ManualRegistration::ManualRegistration()
           this,
           SLOT(applyTransformPressed()));
   connect(ui_->refineButton, SIGNAL(clicked()), this, SLOT(refinePressed()));
-  connect(ui_->undoButton, SIGNAL(clicked()), this, SLOT(undoPressed()));
-  connect(ui_->safeButton, SIGNAL(clicked()), this, SLOT(safePressed()));
-
-  cloud_src_modified_ = true; // first iteration is always a new pointcloud
-  cloud_dst_modified_ = true;
 }
 
 void
-ManualRegistration::SourcePointPickCallback(
+ManualRegistration::SrcPointPickCallback(
     const pcl::visualization::PointPickingEvent& event, void*)
 {
   // Check to see if we got a valid point. Early exit.
@@ -186,6 +181,15 @@ ManualRegistration::confirmSrcPointPressed()
     PCL_INFO("Selected %zu source points\n", static_cast<std::size_t>(src_pc_.size()));
     src_point_selected_ = false;
     src_pc_.width = src_pc_.size();
+    const string annotation = "marker-" + to_string(annotations_src_.size());
+    vis_src_->addSphere(src_point_, 0.02, annotation);
+    vis_src_->setShapeRenderingProperties(PCL_VISUALIZER_OPACITY, 0.2, annotation);
+    vis_src_->setShapeRenderingProperties(
+        PCL_VISUALIZER_COLOR, 0.5, 0.25, 0.25, annotation);
+    vis_src_->getShapeActorMap()->at(annotation)->SetPickable(false);
+    annotations_src_.emplace(annotation);
+
+    refreshView();
   }
   else {
     PCL_INFO("Please select a point in the source window first\n");
@@ -201,6 +205,16 @@ ManualRegistration::confirmDstPointPressed()
              static_cast<std::size_t>(dst_pc_.size()));
     dst_point_selected_ = false;
     dst_pc_.width = dst_pc_.size();
+
+    const string annotation = "marker-" + std::to_string(annotations_dst_.size());
+    vis_dst_->addSphere(dst_point_, 0.02, annotation);
+    vis_dst_->setShapeRenderingProperties(PCL_VISUALIZER_OPACITY, 0.2, annotation);
+    vis_dst_->setShapeRenderingProperties(
+        PCL_VISUALIZER_COLOR, 0.5, 0.25, 0.25, annotation);
+    vis_dst_->getShapeActorMap()->at(annotation)->SetPickable(false);
+    annotations_dst_.emplace(annotation);
+
+    refreshView();
   }
   else {
     PCL_INFO("Please select a point in the destination window first\n");
@@ -216,12 +230,13 @@ ManualRegistration::calculatePressed()
   }
   pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ> tfe;
   tfe.estimateRigidTransformation(src_pc_, dst_pc_, transform_);
-  std::cout << "Transform : " << std::endl << transform_ << std::endl;
+  PCL_INFO_STREAM("Calculated transform:\n" << transform_ << std::endl);
 }
 
 void
 ManualRegistration::clearPressed()
 {
+  PCL_INFO("Clearing points.");
   dst_point_selected_ = false;
   src_point_selected_ = false;
   src_pc_.clear();
@@ -230,6 +245,18 @@ ManualRegistration::clearPressed()
   src_pc_.width = 0;
   dst_pc_.height = 1;
   dst_pc_.width = 0;
+
+  for (const string& annotation : annotations_src_) {
+    vis_src_->removeShape(annotation);
+  }
+  annotations_src_.clear();
+
+  for (const string& annotation : annotations_dst_) {
+    vis_dst_->removeShape(annotation);
+  }
+  annotations_dst_.clear();
+
+  refreshView();
 }
 
 void
@@ -269,38 +296,42 @@ ManualRegistration::orthoChanged(int state)
 // TODO
 void
 ManualRegistration::applyTransformPressed()
-{}
+{
+  PCLViewerDialog* diag = new PCLViewerDialog(this);
+  diag->setModal(true);
+  diag->setGeometry(this->x(), this->y(), this->width(), this->height());
+  diag->setPointClouds(cloud_src_, cloud_dst_, Eigen::Affine3f(transform_));
+  diag->show();
+}
 
 void
 ManualRegistration::refinePressed()
-{}
-
-void
-ManualRegistration::undoPressed()
-{}
-
-void
-ManualRegistration::safePressed()
-{}
-
-void
-ManualRegistration::timeoutSlot()
 {
-  if (cloud_src_present_ && cloud_src_modified_) {
-    if (!vis_src_->updatePointCloud(cloud_src_, "cloud_src_")) {
-      vis_src_->addPointCloud(cloud_src_, "cloud_src_");
-      vis_src_->resetCameraViewpoint("cloud_src_");
-    }
-    cloud_src_modified_ = false;
-  }
-  if (cloud_dst_present_ && cloud_dst_modified_) {
-    if (!vis_dst_->updatePointCloud(cloud_dst_, "cloud_dst_")) {
-      vis_dst_->addPointCloud(cloud_dst_, "cloud_dst_");
-      vis_dst_->resetCameraViewpoint("cloud_dst_");
-    }
-    cloud_dst_modified_ = false;
-  }
-  refreshView();
+  PCL_INFO("Refining transform ...\n");
+  VoxelGrid<PointT> grid_filter;
+  grid_filter.setLeafSize(voxel_size_, voxel_size_, voxel_size_);
+  PointCloud<PointT>::Ptr src_copy{new PointCloud<PointT>(*cloud_src_)};
+  PointCloud<PointT>::Ptr dst_copy{new PointCloud<PointT>(*cloud_dst_)};
+  grid_filter.setInputCloud(src_copy);
+  grid_filter.filter(*src_copy);
+  grid_filter.setInputCloud(dst_copy);
+  grid_filter.filter(*dst_copy);
+
+  using ICP = GeneralizedIterativeClosestPoint<PointT, PointT>;
+  ICP::Ptr icp = pcl::make_shared<ICP>();
+  icp->setInputSource(src_copy);
+  icp->setInputTarget(dst_copy);
+
+  icp->setMaximumIterations(100);
+  icp->setMaxCorrespondenceDistance(0.3);
+  icp->setEuclideanFitnessEpsilon(0.01);
+  icp->setTransformationEpsilon(0.01);
+  icp->setTransformationRotationEpsilon(0.01);
+  PointCloud<PointT>::Ptr aligned{new PointCloud<PointT>};
+  icp->align(*aligned, transform_);
+  transform_ = icp->getFinalTransformation();
+
+  PCL_INFO_STREAM("Calculated transform:\n" << transform_ << std::endl);
 }
 
 void
@@ -308,8 +339,10 @@ ManualRegistration::refreshView()
 {
 #if VTK_MAJOR_VERSION > 8
   ui_->qvtk_widget_dst->renderWindow()->Render();
+  ui_->qvtk_widget_src->renderWindow()->Render();
 #else
   ui_->qvtk_widget_dst->update();
+  ui_->qvtk_widget_src->update();
 #endif // VTK_MAJOR_VERSION > 8
 }
 
@@ -319,6 +352,7 @@ print_usage()
   PCL_INFO("manual_registration cloud1.pcd cloud2.pcd\n");
   PCL_INFO("\t cloud1 \t source cloud\n");
   PCL_INFO("\t cloud2 \t destination cloud\n");
+  PCL_INFO("\t voxel_size \t voxel size for automatic refinement\n");
 }
 
 int
@@ -329,31 +363,30 @@ main(int argc, char** argv)
 #endif
   QApplication app(argc, argv);
 
-  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_src(
-      new pcl::PointCloud<pcl::PointXYZRGBA>);
-  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud_dst(
-      new pcl::PointCloud<pcl::PointXYZRGBA>);
+  pcl::PointCloud<PointT>::Ptr cloud_src(new pcl::PointCloud<PointT>);
+  pcl::PointCloud<PointT>::Ptr cloud_dst(new pcl::PointCloud<PointT>);
 
-  if (argc < 3) {
+  if (argc < 4) {
     PCL_ERROR("Incorrect usage\n");
     print_usage();
+    return -1;
   }
 
   // TODO do this with PCL console
-  if (pcl::io::loadPCDFile<pcl::PointXYZRGBA>(argv[1], *cloud_src) ==
-      -1) //* load the file
+  if (pcl::io::loadPCDFile<PointT>(argv[1], *cloud_src) == -1) //* load the file
   {
     PCL_ERROR("Couldn't read file %s \n", argv[1]);
     return -1;
   }
-  if (pcl::io::loadPCDFile<pcl::PointXYZRGBA>(argv[2], *cloud_dst) ==
-      -1) //* load the file
+  if (pcl::io::loadPCDFile<PointT>(argv[2], *cloud_dst) == -1) //* load the file
   {
     PCL_ERROR("Couldn't read file %s \n", argv[2]);
     return -1;
   }
 
-  ManualRegistration man_reg;
+  const float voxel_size = std::atof(argv[3]);
+
+  ManualRegistration man_reg(voxel_size);
 
   man_reg.setSrcCloud(cloud_src);
   man_reg.setDstCloud(cloud_dst);
index 1d4032f3715d62c1aa8a6cf8584caa18ff1c8fe1..f695cf763b81d4c840cbd77d53e7acefe3d5ed13 100644 (file)
         </property>
        </widget>
       </item>
-      <item>
-       <widget class="QPushButton" name="safeButton">
-        <property name="text">
-         <string>Safe Transform</string>
-        </property>
-       </widget>
-      </item>
-      <item>
-       <widget class="QPushButton" name="undoButton">
-        <property name="text">
-         <string>Undo</string>
-        </property>
-       </widget>
-      </item>
       <item>
        <widget class="QCheckBox" name="orthoButton">
         <property name="text">
-         <string>OrthoGraphic</string>
+         <string>Orthographic</string>
         </property>
        </widget>
       </item>
diff --git a/apps/src/manual_registration/pcl_viewer_dialog.cpp b/apps/src/manual_registration/pcl_viewer_dialog.cpp
new file mode 100644 (file)
index 0000000..f1dd1fb
--- /dev/null
@@ -0,0 +1,49 @@
+#include <pcl/apps/pcl_viewer_dialog.h>
+
+#include <ui_pcl_viewer_dialog.h>
+
+#include <vtkGenericOpenGLRenderWindow.h>
+#include <vtkRenderWindow.h>
+
+using namespace pcl::visualization;
+
+PCLViewerDialog::PCLViewerDialog(QWidget* parent) : QDialog(parent)
+{
+  ui_ = new Ui::PCLViewerDialogUi;
+  ui_->setupUi(this);
+
+  // Set up the source window
+#if VTK_MAJOR_VERSION > 8
+  auto renderer = vtkSmartPointer<vtkRenderer>::New();
+  auto renderWindow = vtkSmartPointer<vtkGenericOpenGLRenderWindow>::New();
+  renderWindow->AddRenderer(renderer);
+  vis_.reset(new pcl::visualization::PCLVisualizer(renderer, renderWindow, "", false));
+#else
+  vis_.reset(new pcl::visualization::PCLVisualizer("", false));
+#endif // VTK_MAJOR_VERSION > 8
+  setRenderWindowCompat(*(ui_->qvtk_widget), *(vis_->getRenderWindow()));
+  vis_->setupInteractor(getInteractorCompat(*(ui_->qvtk_widget)),
+                        getRenderWindowCompat(*(ui_->qvtk_widget)));
+}
+void
+PCLViewerDialog::setPointClouds(CloudT::ConstPtr src_cloud,
+                                CloudT::ConstPtr tgt_cloud,
+                                const Eigen::Affine3f& t)
+{
+  vis_->addPointCloud(tgt_cloud, "cloud_dst_");
+  vis_->addPointCloud(src_cloud, "cloud_src_");
+  vis_->updatePointCloudPose("cloud_src_", t);
+  vis_->setPointCloudRenderingProperties(PCL_VISUALIZER_COLOR, 1, 0, 0, "cloud_src_");
+
+  refreshView();
+}
+
+void
+PCLViewerDialog::refreshView()
+{
+#if VTK_MAJOR_VERSION > 8
+  ui_->qvtk_widget->renderWindow()->Render();
+#else
+  ui_->qvtk_widget->update();
+#endif // VTK_MAJOR_VERSION > 8
+}
diff --git a/apps/src/manual_registration/pcl_viewer_dialog.ui b/apps/src/manual_registration/pcl_viewer_dialog.ui
new file mode 100644 (file)
index 0000000..cc45c86
--- /dev/null
@@ -0,0 +1,38 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+    <class>PCLViewerDialogUi</class>
+    <widget class="PCLViewerDialog" name="dialog">
+        <layout class="QVBoxLayout" name="verticalLayout_2">
+            <property name="spacing">
+                <number>0</number>
+            </property>
+            <item>
+                <widget class="PCLQVTKWidget" name="qvtk_widget">
+                    <property name="sizePolicy">
+                        <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
+                            <!-- <horstretch>255</horstretch> -->
+                            <!-- <verstretch>255</verstretch> -->
+                        </sizepolicy>
+                    </property>
+                    <property name="styleSheet">
+                        <string notr="true">background-color: rgb(0, 0, 0);</string>
+                    </property>
+                </widget>
+            </item>
+        </layout>
+    </widget>
+    <customwidgets>
+        <customwidget>
+            <class>PCLQVTKWidget</class>
+            <extends>QOpenGLWidget</extends>
+            <header location="global">pcl/visualization/qvtk_compatibility.h</header>
+        </customwidget>
+        <customwidget>
+            <class>PCLViewerDialog</class>
+            <extends>QDialog</extends>
+            <header location="global">pcl/apps/pcl_viewer_dialog.h</header>
+        </customwidget>
+    </customwidgets>
+    <resources/>
+    <connections/>
+</ui>
index 5ae97db8dcc6c92527096dc3e62e456bc266fe67..a2bc67958d5bd0b4aaded3844b03e3f8046ba509 100644 (file)
@@ -47,7 +47,7 @@
 using namespace pcl;
 
 const Eigen::Vector4f subsampling_leaf_size(0.01f, 0.01f, 0.01f, 0.0f);
-const float normal_estimation_search_radius = 0.05f;
+constexpr float normal_estimation_search_radius = 0.05f;
 
 void
 subsampleAndCalculateNormals(PointCloud<PointXYZ>::Ptr& cloud,
index 822f7a81d7c74455a8f4a5138597cdc9976580ff..d4c0309704addb3bb3628d4e9e7ad91f1149e9b4 100644 (file)
@@ -34,6 +34,7 @@
  */
 
 #include <pcl/common/time.h>
+#include <pcl/console/parse.h>
 #include <pcl/filters/voxel_grid.h>
 #include <pcl/io/openni_camera/openni_driver.h>
 #include <pcl/io/openni_grabber.h>
@@ -165,19 +166,29 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
+  std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -186,24 +197,28 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  std::string arg;
-  if (argc > 1)
-    arg = std::string(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
-  pcl::OpenNIGrabber grabber(arg);
+  std::string device_id = "";
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  /////////////////////////////////////////////////////////////////////
+
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
     PCL_INFO("PointXYZRGBA mode enabled.\n");
-    OpenNI3DConcaveHull<pcl::PointXYZRGBA> v(arg);
+    OpenNI3DConcaveHull<pcl::PointXYZRGBA> v(device_id);
     v.run();
   }
   else {
     PCL_INFO("PointXYZ mode enabled.\n");
-    OpenNI3DConcaveHull<pcl::PointXYZ> v(arg);
+    OpenNI3DConcaveHull<pcl::PointXYZ> v(device_id);
     v.run();
   }
   return 0;
index 841e429a36f35537e49a0bba54d8e3f3ebbb2d9e..674ea43ead0d6f45f4b160d2c65156ad2d2a147b 100644 (file)
@@ -34,6 +34,7 @@
  */
 
 #include <pcl/common/time.h>
+#include <pcl/console/parse.h>
 #include <pcl/filters/passthrough.h>
 #include <pcl/io/openni_camera/openni_driver.h>
 #include <pcl/io/openni_grabber.h>
@@ -163,19 +164,29 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
+  std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -184,24 +195,28 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  std::string arg;
-  if (argc > 1)
-    arg = std::string(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
-  pcl::OpenNIGrabber grabber(arg);
+  std::string device_id = "";
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  /////////////////////////////////////////////////////////////////////
+
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
     PCL_INFO("PointXYZRGBA mode enabled.\n");
-    OpenNI3DConvexHull<pcl::PointXYZRGBA> v(arg);
+    OpenNI3DConvexHull<pcl::PointXYZRGBA> v(device_id);
     v.run();
   }
   else {
     PCL_INFO("PointXYZ mode enabled.\n");
-    OpenNI3DConvexHull<pcl::PointXYZ> v(arg);
+    OpenNI3DConvexHull<pcl::PointXYZ> v(device_id);
     v.run();
   }
   return 0;
index 89467dd0c278d0e766a34a1d9f41ae350115b176..d0e45444d3aa735de228afc3fe830105b0fa24b3 100644 (file)
@@ -36,6 +36,7 @@
  */
 
 #include <pcl/common/time.h>
+#include <pcl/console/parse.h>
 #include <pcl/features/boundary.h>
 #include <pcl/features/integral_image_normal.h>
 #include <pcl/filters/approximate_voxel_grid.h>
@@ -180,19 +181,29 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
+  std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -201,18 +212,22 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  std::string arg;
-  if (argc > 1)
-    arg = std::string(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
-  pcl::OpenNIGrabber grabber(arg);
+  std::string device_id = "";
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  /////////////////////////////////////////////////////////////////////
+
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb>()) {
-    OpenNIIntegralImageNormalEstimation v(arg);
+    OpenNIIntegralImageNormalEstimation v(device_id);
     v.run();
   }
   else
index e06e45f512190dc071de0717ad0c701231917e3c..56203ed36f6e73cb804a6b148d742460f88e661c 100644 (file)
@@ -159,21 +159,33 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0]
-            << " <device_id> [-rgb <red> <green> <blue> [-radius <radius>] ]\n\n"
-            << std::endl;
+  std::cout << "usage: " << argv[0] << " [options]\n\n"
+            << "where options are:\n"
+            << "    -device_id X: specify the device id (default: \"#1\").\n"
+            << "    -rgb R G B: -- (default: 0 0 0)\n"
+            << "    -radius X: -- (default: 442)\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << (int)driver.getBus (deviceIdx) << " @ " << (int)driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -182,22 +194,21 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  if (argc < 2) {
-    usage(argv);
-    return 1;
-  }
-
-  std::string arg(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
+  std::string device_id = "";
   unsigned char red = 0, green = 0, blue = 0;
   int rr, gg, bb;
   unsigned char radius = 442; // all colors!
 
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
   if (pcl::console::parse_3x_arguments(argc, argv, "-rgb", rr, gg, bb, true) != -1) {
     std::cout << "-rgb present" << std::endl;
     int rad;
@@ -213,8 +224,9 @@ main(int argc, char** argv)
     if (bb >= 0 && bb < 256)
       blue = (unsigned char)bb;
   }
+  /////////////////////////////////////////////////////////////////////
 
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
 
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
     OpenNIPassthrough<pcl::PointXYZRGBA> v(grabber, red, green, blue, radius);
index 63b1026c3101183adcb8cfe021bcb5c652f4e3a3..e370103394078d3b4fd33186a3fc71bf4c0588bc 100644 (file)
@@ -34,6 +34,7 @@
  */
 
 #include <pcl/common/time.h>
+#include <pcl/console/parse.h>
 #include <pcl/io/openni_camera/openni_driver.h>
 #include <pcl/io/openni_grabber.h>
 #include <pcl/surface/organized_fast_mesh.h>
@@ -151,27 +152,29 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
+  std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
-      std::cout << "Device: " << deviceIdx + 1
-                << ", vendor: " << driver.getVendorName(deviceIdx)
-                << ", product: " << driver.getProductName(deviceIdx)
-                << ", connected: " << driver.getBus(deviceIdx) << " @ "
-                << driver.getAddress(deviceIdx) << ", serial number: \'"
-                << driver.getSerialNumber(deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in "
-                   "the list or"
-                << std::endl
-                << "                 bus@address for the device connected to a "
-                   "specific usb-bus / address combination (works only in Linux) or"
-                << std::endl
-                << "                 <serial-number> (only in Linux and for devices "
-                   "which provide serial numbers)"
+      // clang-format off
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
                 << std::endl;
+      // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -180,24 +183,28 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  std::string arg;
-  if (argc > 1)
-    arg = std::string(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
-  pcl::OpenNIGrabber grabber(arg);
+  std::string device_id = "";
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  /////////////////////////////////////////////////////////////////////
+
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
     PCL_INFO("PointXYZRGBA mode enabled.\n");
-    OpenNIFastMesh<pcl::PointXYZRGBA> v(arg);
+    OpenNIFastMesh<pcl::PointXYZRGBA> v(device_id);
     v.run(argc, argv);
   }
   else {
     PCL_INFO("PointXYZ mode enabled.\n");
-    OpenNIFastMesh<pcl::PointXYZ> v(arg);
+    OpenNIFastMesh<pcl::PointXYZ> v(device_id);
     v.run(argc, argv);
   }
   return 0;
index 70b99cb604ffeacef54e059b1df5f6231f881034..0b397bffd51132ff403906b32294a5b9ad6e1d8d 100644 (file)
@@ -69,11 +69,11 @@ using namespace std::chrono_literals;
   } while (false)
 // clang-format on
 
-const float default_subsampling_leaf_size = 0.02f;
-const float default_normal_search_radius = 0.041f;
+constexpr float default_subsampling_leaf_size = 0.02f;
+constexpr float default_normal_search_radius = 0.041f;
 const double aux[] = {0.21, 0.32};
 const std::vector<double> default_scales_vector(aux, aux + 2);
-const float default_alpha = 1.2f;
+constexpr float default_alpha = 1.2f;
 
 template <typename PointType>
 class OpenNIFeaturePersistence {
@@ -232,12 +232,13 @@ void
 usage(char** argv)
 {
   // clang-format off
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
+  std::cout << "usage: " << argv[0] << " [options]\n\n"
             << "where options are:\n"
-            << "         -octree_leaf_size X = size of the leaf for the octree-based subsampling filter (default: " << default_subsampling_leaf_size << "\n"
-            << "         -normal_search_radius X = size of the neighborhood to consider for calculating the local plane and extracting the normals (default: " << default_normal_search_radius << "\n"
-            << "         -persistence_alpha X = value of alpha for the multiscale feature persistence (default: " << default_alpha << "\n"
-            << "         -scales X1 X2 ... = values for the multiple scales for extracting features (default: ";
+            << "    -device_id X: specify the device id (default: \"#1\").\n"
+            << "    -octree_leaf_size X: size of the leaf for the octree-based subsampling filter (default: " << default_subsampling_leaf_size << "\n"
+            << "    -normal_search_radius X: size of the neighborhood to consider for calculating the local plane and extracting the normals (default: " << default_normal_search_radius << "\n"
+            << "    -persistence_alpha X: value of alpha for the multiscale feature persistence (default: " << default_alpha << "\n"
+            << "    -scales X1 X2 ...: values for the multiple scales for extracting features (default: ";
   // clang-format on
   for (const double& i : default_scales_vector)
     std::cout << i << " ";
@@ -247,13 +248,23 @@ usage(char** argv)
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -266,41 +277,43 @@ main(int argc, char** argv)
                "MultiscaleFeaturePersistence class using the FPFH features\n"
             << "Use \"-h\" to get more info about the available options.\n";
 
-  std::string arg = "";
-  if ((argc > 1) && (argv[1][0] != '-'))
-    arg = std::string(argv[1]);
-
-  if (pcl::console::find_argument(argc, argv, "-h") == -1) {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
-  // Parse arguments
+  std::string device_id = "";
   float subsampling_leaf_size = default_subsampling_leaf_size;
-  pcl::console::parse_argument(argc, argv, "-octree_leaf_size", subsampling_leaf_size);
   double normal_search_radius = default_normal_search_radius;
+  std::vector<double> scales_vector_double = default_scales_vector;
+  std::vector<float> scales_vector(scales_vector_double.size());
+  float alpha = default_alpha;
+
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  pcl::console::parse_argument(argc, argv, "-octree_leaf_size", subsampling_leaf_size);
   pcl::console::parse_argument(
       argc, argv, "-normal_search_radius", normal_search_radius);
-  std::vector<double> scales_vector_double = default_scales_vector;
   pcl::console::parse_multiple_arguments(argc, argv, "-scales", scales_vector_double);
-  std::vector<float> scales_vector(scales_vector_double.size());
   for (std::size_t i = 0; i < scales_vector_double.size(); ++i)
     scales_vector[i] = float(scales_vector_double[i]);
-
-  float alpha = default_alpha;
   pcl::console::parse_argument(argc, argv, "-persistence_alpha", alpha);
+  /////////////////////////////////////////////////////////////////////
 
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
     PCL_INFO("PointXYZRGBA mode enabled.\n");
     OpenNIFeaturePersistence<pcl::PointXYZRGBA> v(
-        subsampling_leaf_size, normal_search_radius, scales_vector, alpha, arg);
+        subsampling_leaf_size, normal_search_radius, scales_vector, alpha, device_id);
     v.run();
   }
   else {
     PCL_INFO("PointXYZ mode enabled.\n");
     OpenNIFeaturePersistence<pcl::PointXYZ> v(
-        subsampling_leaf_size, normal_search_radius, scales_vector, alpha, arg);
+        subsampling_leaf_size, normal_search_radius, scales_vector, alpha, device_id);
     v.run();
   }
 
index f61ff61940545f256d2e72764f0d11d5ce42e67c..fbdc4d42ebf6ea0b3cc7b3208d964931c81d6c80 100644 (file)
@@ -40,6 +40,7 @@
 #include <pcl/console/print.h>
 #include <pcl/io/openni_grabber.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/io/timestamp.h>
 #include <pcl/visualization/pcl_visualizer.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
@@ -157,8 +158,7 @@ public:
   saveCloud()
   {
     FPS_CALC("I/O");
-    const std::string time = boost::posix_time::to_iso_string(
-        boost::posix_time::microsec_clock::local_time());
+    const std::string time = pcl::getTimestamp();
     const std::string filepath = dir_name_ + '/' + file_name_ + '_' + time + ".pcd";
 
     if (format_ & 1) {
index 68503d9df8c718ce9f7814f303a225ef4d6855ec..7a8645671296ac5880be6658ab54938e686e87f2 100644 (file)
@@ -117,8 +117,7 @@ public:
   void
   saveImages()
   {
-    std::string time = boost::posix_time::to_iso_string(
-        boost::posix_time::microsec_clock::local_time());
+    const std::string time = pcl::getTimestamp();
     openni_wrapper::Image::Ptr image;
     openni_wrapper::DepthImage::Ptr depth_image;
 
@@ -204,8 +203,7 @@ public:
 
     // wait until user quits program with Ctrl-C, but no busy-waiting -> sleep (1);
     while (!image_viewer_.wasStopped() && !quit_) {
-      std::string time = boost::posix_time::to_iso_string(
-          boost::posix_time::microsec_clock::local_time());
+      const std::string time = pcl::getTimestamp();
       openni_wrapper::Image::Ptr image;
       openni_wrapper::DepthImage::Ptr depth_image;
 
@@ -360,13 +358,15 @@ main(int argc, char** argv)
   std::string device_id("");
   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
 
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
+    usage(argv);
+    return 1;
+  }
+
   if (argc >= 2) {
     device_id = argv[1];
-    if (device_id == "--help" || device_id == "-h") {
-      usage(argv);
-      return 0;
-    }
-    else if (device_id == "-l") {
+    if (device_id == "-l") {
       if (argc >= 3) {
         pcl::OpenNIGrabber grabber(argv[2]);
         auto device = grabber.getDevice();
index ea9189169895ef7d9f581ac88895b137423ef1c2..942447f35b291e7ae8cbcf49fea7463ebec71070 100644 (file)
@@ -34,6 +34,7 @@
  */
 
 #include <pcl/common/time.h>
+#include <pcl/console/parse.h>
 #include <pcl/features/integral_image_normal.h>
 #include <pcl/io/openni_camera/openni_driver.h>
 #include <pcl/io/openni_grabber.h>
@@ -190,19 +191,29 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " [<device_id>]\n\n";
+  std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -211,16 +222,19 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  std::string arg;
-  if (argc > 1)
-    arg = std::string(argv[1]);
-
-  openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
-  if (arg == "--help" || arg == "-h" || driver.getNumberDevices() == 0) {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
+  std::string device_id = "";
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  /////////////////////////////////////////////////////////////////////
+
   // clang-format off
   std::cout << "Press following keys to switch to the different integral image normal estimation methods:\n";
   std::cout << "<1> COVARIANCE_MATRIX method\n";
@@ -230,15 +244,15 @@ main(int argc, char** argv)
   std::cout << "<Q,q> quit\n\n";
   // clang-format on
 
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
     PCL_INFO("PointXYZRGBA mode enabled.\n");
-    OpenNIIntegralImageNormalEstimation<pcl::PointXYZRGBA> v(arg);
+    OpenNIIntegralImageNormalEstimation<pcl::PointXYZRGBA> v(device_id);
     v.run();
   }
   else {
     PCL_INFO("PointXYZ mode enabled.\n");
-    OpenNIIntegralImageNormalEstimation<pcl::PointXYZ> v(arg);
+    OpenNIIntegralImageNormalEstimation<pcl::PointXYZ> v(device_id);
     v.run();
   }
 
index 6bab5e4e972127478e35cc8661214fc1b75c32e9..504d40dd665882116142f7805378525e9bd737da 100644 (file)
 #include <pcl/console/print.h>
 #include <pcl/io/openni_grabber.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/io/timestamp.h>
 #include <pcl/keypoints/harris_2d.h>
 #include <pcl/tracking/pyramidal_klt.h>
 #include <pcl/visualization/image_viewer.h>
 
-#include <boost/date_time/posix_time/posix_time.hpp> // for to_iso_string, local_time
-
 #include <mutex>
 
 #define SHOW_FPS 1
@@ -113,7 +112,7 @@ public:
   using CloudConstPtr = typename Cloud::ConstPtr;
 
   OpenNIViewer(pcl::Grabber& grabber)
-  : grabber_(grabber), rgb_data_(nullptr), rgb_data_size_(0)
+  : grabber_(grabber), rgb_data_(nullptr), rgb_data_size_(0), counter_(0)
   {}
 
   void
@@ -175,9 +174,7 @@ public:
       if ((event.getKeyCode() == 's') || (event.getKeyCode() == 'S')) {
         std::lock_guard<std::mutex> lock(cloud_mutex_);
         frame.str("frame-");
-        frame << boost::posix_time::to_iso_string(
-                     boost::posix_time::microsec_clock::local_time())
-              << ".pcd";
+        frame << pcl::getTimestamp() << ".pcd";
         writer.writeBinaryCompressed(frame.str(), *cloud_);
         PCL_INFO("Written cloud %s.\n", frame.str().c_str());
       }
@@ -312,12 +309,14 @@ main(int argc, char** argv)
   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
   bool xyz = false;
 
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
+    printHelp(argc, argv);
+    return 1;
+  }
+
   if (argc >= 2) {
     device_id = argv[1];
-    if (device_id == "--help" || device_id == "-h") {
-      printHelp(argc, argv);
-      return 0;
-    }
     if (device_id == "-l") {
       if (argc >= 3) {
         pcl::OpenNIGrabber grabber(argv[2]);
index c45514323c5829954e06d95a52e05f3f124a0551..641c341c745999cc7facc0f90a6d3c62e48defb6 100644 (file)
@@ -177,24 +177,35 @@ void
 usage(char** argv)
 {
   // clang-format off
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
+  std::cout << "usage: " << argv[0] << " [options]\n\n"
             << "where options are:\n"
-            << "                     -search_radius X = sphere radius to be used for finding the k-nearest neighbors used for fitting (default: " << default_search_radius << ")\n"
-            << "                     -sqr_gauss_param X = parameter used for the distance based weighting of neighbors (recommended = search_radius^2) (default: " << default_sqr_gauss_param << ")\n"
-            << "                     -polynomial_order X = order of the polynomial to be fit (0 means tangent estimation) (default: " << default_polynomial_order << ")\n";
+            << "    -device_id X: specify the device id (default: \"#1\").\n"
+            << "    -search_radius X: sphere radius to be used for finding the k-nearest neighbors used for fitting (default: " << default_search_radius << ")\n"
+            << "    -sqr_gauss_param X: parameter used for the distance based weighting of neighbors (recommended = search_radius^2) (default: " << default_sqr_gauss_param << ")\n"
+            << "    -polynomial_order X: order of the polynomial to be fit (0 means tangent estimation) (default: " << default_polynomial_order << ")\n\n";
   // clang-format on
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -203,39 +214,44 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  if (argc < 2) {
-    usage(argv);
-    return 1;
-  }
-
-  std::string arg(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
-  // Command line parsing
+  std::string device_id = "";
   double search_radius = default_search_radius;
   double sqr_gauss_param = default_sqr_gauss_param;
   bool sqr_gauss_param_set = true;
   int polynomial_order = default_polynomial_order;
 
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
   pcl::console::parse_argument(argc, argv, "-search_radius", search_radius);
   if (pcl::console::parse_argument(argc, argv, "-sqr_gauss_param", sqr_gauss_param) ==
       -1)
     sqr_gauss_param_set = false;
   pcl::console::parse_argument(argc, argv, "-polynomial_order", polynomial_order);
+  /////////////////////////////////////////////////////////////////////
 
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
-    OpenNISmoothing<pcl::PointXYZRGBA> v(
-        search_radius, sqr_gauss_param_set, sqr_gauss_param, polynomial_order, arg);
+    OpenNISmoothing<pcl::PointXYZRGBA> v(search_radius,
+                                         sqr_gauss_param_set,
+                                         sqr_gauss_param,
+                                         polynomial_order,
+                                         device_id);
     v.run();
   }
   else {
-    OpenNISmoothing<pcl::PointXYZ> v(
-        search_radius, sqr_gauss_param_set, sqr_gauss_param, polynomial_order, arg);
+    OpenNISmoothing<pcl::PointXYZ> v(search_radius,
+                                     sqr_gauss_param_set,
+                                     sqr_gauss_param,
+                                     polynomial_order,
+                                     device_id);
     v.run();
   }
 
index 5a1c8d62bf7fe0ca44bf818f4faf3f26791e08f5..bf6778d1ff5767efde50e44b16fe2902cc5859ee 100644 (file)
@@ -79,7 +79,7 @@ CopyPointCloudToBuffers(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& clou
         point.x > bounds_max.x || point.y > bounds_max.y || point.z > bounds_max.z)
       continue;
 
-    const int conversion_factor = 500;
+    constexpr int conversion_factor = 500;
 
     cloud_buffers.points[j * 3 + 0] = static_cast<short>(point.x * conversion_factor);
     cloud_buffers.points[j * 3 + 1] = static_cast<short>(point.y * conversion_factor);
@@ -221,29 +221,33 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n"
+  std::cout << "usage: " << argv[0] << " [options]\n\n"
             << "where options are:\n"
-            << "  -port p :: set the server port (default: 11111)\n"
-            << "  -leaf x, y, z  :: set the voxel grid leaf size (default: 0.01)\n";
+            << "    -device_id X: specify the device id (default: \"#1\").\n"
+            << "    -port p: set the server port (default: 11111)\n"
+            << "    -leaf x, y, z: set the voxel grid leaf size (default: 0.01)\n";
 }
 
 int
 main(int argc, char** argv)
 {
-  std::string device_id = "";
-  if ((argc > 1) && (argv[1][0] != '-'))
-    device_id = std::string(argv[1]);
-
-  if (pcl::console::find_argument(argc, argv, "-h") != -1) {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
-    return 0;
+    return 1;
   }
 
+  std::string device_id = "";
   int port = 11111;
   float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f;
 
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
   pcl::console::parse_argument(argc, argv, "-port", port);
   pcl::console::parse_3x_arguments(argc, argv, "-leaf", leaf_x, leaf_y, leaf_z, false);
+  /////////////////////////////////////////////////////////////////////
 
   pcl::OpenNIGrabber grabber(device_id);
   if (!grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
index caf01aae7c82d7e38277fe94b9b0e9ea8a15a5f3..0042f36ffcb1329436a3ffd624beb7b66f152d67 100644 (file)
@@ -34,6 +34,7 @@
  */
 
 #include <pcl/common/time.h>
+#include <pcl/console/parse.h>
 #include <pcl/features/integral_image_normal.h>
 #include <pcl/features/organized_edge_detection.h>
 #include <pcl/io/openni_grabber.h>
@@ -68,7 +69,7 @@ public:
                                      *this);
     viewer->resetCameraViewpoint("cloud");
 
-    const int point_size = 2;
+    constexpr int point_size = 2;
     viewer->addPointCloud<PointT>(cloud, "nan boundary edges");
     viewer->setPointCloudRenderingProperties(
         pcl::visualization::PCL_VISUALIZER_POINT_SIZE,
@@ -286,19 +287,29 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
+  std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -307,15 +318,19 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  std::string arg;
-  if (argc > 1)
-    arg = std::string(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
+  std::string device_id = "";
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  /////////////////////////////////////////////////////////////////////
+
   // clang-format off
   std::cout << "Press following keys to enable/disable the different edge types:" << std::endl;
   std::cout << "<1> EDGELABEL_NAN_BOUNDARY edge" << std::endl;
@@ -325,7 +340,7 @@ main(int argc, char** argv)
   //std::cout << "<5> EDGELABEL_RGB_CANNY edge" << std::endl;
   std::cout << "<Q,q> quit" << std::endl;
   // clang-format on
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb>()) {
     OpenNIOrganizedEdgeDetection app;
     app.run();
index b516e68e59f6fdddd561acaf1df7b37bfbec4276..862ee8b499dc4ed78b1f69e247d5408d7b8efe5d 100644 (file)
@@ -44,8 +44,8 @@
 #include <ui_openni_passthrough.h>
 
 #include <vtkGenericOpenGLRenderWindow.h>
-#include <vtkRenderWindow.h>
 #include <vtkRendererCollection.h>
+#include <vtkRenderWindow.h>
 
 #include <thread>
 
index 0cc1223f1360bb142ffe9cb43dd66c3e7da7e877..d42481a2caaf0a63d2c6782f7c0f61dcca4bdbef 100644 (file)
@@ -150,9 +150,11 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
-            << "where options are:\n         -thresh X        :: set the planar "
-               "segmentation threshold (default: 0.5)\n";
+  std::cout
+      << "usage: " << argv[0] << " [options]\n\n"
+      << "where options are:\n"
+      << "    -device_id X: specify the device id (default: \"#1\").\n"
+      << "    -thresh X: set the planar segmentation threshold (default: 0.5)\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
@@ -161,10 +163,20 @@ usage(char** argv)
       std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
       std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (wotks only in Linux) or" << std::endl
+           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -173,28 +185,29 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  if (argc < 2) {
-    usage(argv);
-    return 1;
-  }
-
-  std::string arg(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
+  std::string device_id = "";
   double threshold = 0.05;
+
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
   pcl::console::parse_argument(argc, argv, "-thresh", threshold);
+  /////////////////////////////////////////////////////////////////////
 
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
-    OpenNIPlanarSegmentation<pcl::PointXYZRGBA> v(arg, threshold);
+    OpenNIPlanarSegmentation<pcl::PointXYZRGBA> v(device_id, threshold);
     v.run();
   }
   else {
-    OpenNIPlanarSegmentation<pcl::PointXYZ> v(arg, threshold);
+    OpenNIPlanarSegmentation<pcl::PointXYZ> v(device_id, threshold);
     v.run();
   }
 
index cb9afd704beb372fe07b590a2f4f7bcd77496b73..d06d4fde3b05a0e2216ecec022306b1430b6ab3f 100644 (file)
@@ -143,21 +143,33 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
-            << "where options are:\n         -thresh X        :: set the planar "
-               "segmentation threshold (default: 0.5)\n";
+  std::cout
+      << "usage: " << argv[0] << " [options]\n\n"
+      << "where options are:\n"
+      << "    -device_id X: specify the device id (default: \"#1\").\n"
+      << "    -thresh X: set the planar segmentation threshold (default: 0.5)\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -166,28 +178,29 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  if (argc < 2) {
-    usage(argv);
-    return 1;
-  }
-
-  std::string arg(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
+  std::string device_id = "";
   double threshold = 0.05;
+
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
   pcl::console::parse_argument(argc, argv, "-thresh", threshold);
+  /////////////////////////////////////////////////////////////////////
 
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
-    OpenNIPlanarSegmentation<pcl::PointXYZRGBA> v(arg, threshold);
+    OpenNIPlanarSegmentation<pcl::PointXYZRGBA> v(device_id, threshold);
     v.run();
   }
   else {
-    OpenNIPlanarSegmentation<pcl::PointXYZ> v(arg, threshold);
+    OpenNIPlanarSegmentation<pcl::PointXYZ> v(device_id, threshold);
     v.run();
   }
 
index 292a06ef3d453b257b92cced94a3e00dab877e3e..7de78e4f2eb3f5a12a8ac8baaf9dd2e8fd57efb4 100644 (file)
@@ -164,7 +164,7 @@ protected:
     int centerY = static_cast<int>(height_arg / 2);
 
     const float fl_const = 1.0f / focalLength_arg;
-    static const float bad_point = std::numeric_limits<float>::quiet_NaN();
+    constexpr float bad_point = std::numeric_limits<float>::quiet_NaN();
 
     std::size_t i = 0;
     for (int y = -centerY; y < +centerY; ++y)
index 1ea742c688fc61d1e0f0261cea8653bc7db086ba..174f889a19c7165d78270e71bf86c64389f7ab29 100644 (file)
@@ -646,46 +646,49 @@ public:
 void
 usage(char** argv)
 {
-  // clang-format off
-  std::cout << "usage: " << argv[0] << " <device_id> [-C] [-g]\n\n";
-  std::cout << "  -C:  initialize the pointcloud to track without plane segmentation\n";
-  std::cout << "  -D: visualizing with non-downsampled pointclouds.\n";
-  std::cout << "  -P: not visualizing particle cloud.\n";
-  std::cout << "  -fixed: use the fixed number of the particles.\n";
-  std::cout << "  -d <value>: specify the grid size of downsampling (defaults to 0.01)." << std::endl;
-  // clang-format on
+  // clang format off
+  std::cout
+      << "usage: " << argv[0] << " [options]\n\n"
+      << "where options are:\n"
+      << "    -device_id device_id: specify the device id (defaults to \"#1\").\n"
+      << "    -C: initialize the pointcloud to track without plane segmentation.\n"
+      << "    -D: visualizing with non-downsampled pointclouds.\n"
+      << "    -P: not visualizing particle cloud.\n"
+      << "    -fixed: use the fixed number of the particles.\n"
+      << "    -d: specify the grid size of downsampling (defaults to 0.01).";
+  // clang format on
 }
 
 int
 main(int argc, char** argv)
 {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
+    usage(argv);
+    return 1;
+  }
+
+  std::string device_id = "";
   bool use_convex_hull = true;
   bool visualize_non_downsample = false;
   bool visualize_particles = true;
   bool use_fixed = false;
-
   double downsampling_grid_size = 0.01;
 
-  if (pcl::console::find_argument(argc, argv, "-C") > 0)
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+  if (pcl::console::find_argument(argc, argv, "-C") != -1)
     use_convex_hull = false;
-  if (pcl::console::find_argument(argc, argv, "-D") > 0)
+  if (pcl::console::find_argument(argc, argv, "-D") != -1)
     visualize_non_downsample = true;
-  if (pcl::console::find_argument(argc, argv, "-P") > 0)
+  if (pcl::console::find_argument(argc, argv, "-P") != -1)
     visualize_particles = false;
-  if (pcl::console::find_argument(argc, argv, "-fixed") > 0)
+  if (pcl::console::find_argument(argc, argv, "-fixed") != -1)
     use_fixed = true;
   pcl::console::parse_argument(argc, argv, "-d", downsampling_grid_size);
-  if (argc < 2) {
-    usage(argv);
-    exit(1);
-  }
-
-  std::string device_id = std::string(argv[1]);
-
-  if (device_id == "--help" || device_id == "-h") {
-    usage(argv);
-    exit(1);
-  }
+  /////////////////////////////////////////////////////////////////////
 
   // open kinect
   OpenNISegmentTracking<pcl::PointXYZRGBA> v(device_id,
index fbce9edc77296903362160155aaf1a8bb36ea7d0..6167cdacb3c778cc239d17bb0088b2ac790baac7 100644 (file)
@@ -147,22 +147,32 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
+  std::cout << "usage: " << argv[0] << " [options]\n\n"
             << "where options are:\n"
-            << "                             -leaf X  :: set the UniformSampling leaf "
-               "size (default: 0.01)\n";
+            << "    -device_id X: specify the device id (default: \"#1\").\n"
+            << "    -leaf X: set the UniformSampling leaf size (default: 0.01)\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -171,24 +181,24 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  if (argc < 2) {
-    usage(argv);
-    return 1;
-  }
-
-  std::string arg(argv[1]);
-
-  if (arg == "--help" || arg == "-h") {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
+  std::string device_id = "";
   float leaf_res = 0.05f;
+
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
   pcl::console::parse_argument(argc, argv, "-leaf", leaf_res);
   PCL_INFO("Using %f as a leaf size for UniformSampling.\n", leaf_res);
+  /////////////////////////////////////////////////////////////////////
 
-  pcl::OpenNIGrabber grabber(arg);
-  OpenNIUniformSampling v(arg, leaf_res);
+  OpenNIUniformSampling v(device_id, leaf_res);
   v.run();
 
   return 0;
index 91274e7312e055b4e16067df6aa34a339831e336..27749cbe325e6dde4e948dd7eae2a250ef893d00 100644 (file)
@@ -141,26 +141,37 @@ public:
 void
 usage(char** argv)
 {
-  std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
-            << "where options are:\n         -minmax min-max  :: set the "
-               "ApproximateVoxelGrid min-max cutting values (default: 0-5.0)\n"
-            << "         -field  X        :: use field/dimension 'X' to filter data on "
-               "(default: 'z')\n"
-
-            << "                             -leaf x, y, z    :: set the "
-               "ApproximateVoxelGrid leaf size (default: 0.01)\n";
+  std::cout
+      << "usage: " << argv[0] << " [options]\n\n"
+      << "where options are:\n"
+      << "    -device_id X: specify the device id (default: \"#1\").\n"
+      << "    -minmax min-max: set the ApproximateVoxelGrid min-max cutting values "
+         "(default: 0-5.0)\n"
+      << "    -field X: use field/dimension 'X' to filter data on (default: 'z')\n"
+      << "    -leaf x, y, z: set the ApproximateVoxelGrid leaf size (default: "
+         "0.01)\n\n";
 
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
   if (driver.getNumberDevices() > 0) {
     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
       // clang-format off
-      std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-      std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
-           << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
-           << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << std::endl;
+      std::cout << "Device: " << deviceIdx + 1 
+                << ", vendor: " << driver.getVendorName (deviceIdx) 
+                << ", product: " << driver.getProductName (deviceIdx)
+                << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" 
+                << std::endl;
       // clang-format on
     }
+
+    std::cout << "\ndevice_id may be:" << std::endl
+              << "    #1, #2, ... for the first second etc device in the list or"
+              << std::endl
+
+              << "    bus@address for the device connected to a specific "
+                 "usb-bus/address combination (works only in Linux) or"
+
+              << "    <serial-number> (only in Linux and for devices which provide "
+                 "serial numbers)";
   }
   else
     std::cout << "No devices connected." << std::endl;
@@ -169,34 +180,40 @@ usage(char** argv)
 int
 main(int argc, char** argv)
 {
-  std::string arg = "";
-  if ((argc > 1) && (argv[1][0] != '-'))
-    arg = std::string(argv[1]);
-
-  if (pcl::console::find_argument(argc, argv, "-h") != -1) {
+  /////////////////////////////////////////////////////////////////////
+  if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
+      pcl::console::find_argument(argc, argv, "--help") != -1) {
     usage(argv);
     return 1;
   }
 
+  std::string device_id = "";
   float min_v = 0.0f, max_v = 5.0f;
+  std::string field_name = "z";
+  float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f;
+
+  if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
+      argc > 1 && argv[1][0] != '-')
+    device_id = argv[1];
+
   pcl::console::parse_2x_arguments(argc, argv, "-minmax", min_v, max_v);
-  std::string field_name("z");
   pcl::console::parse_argument(argc, argv, "-field", field_name);
   PCL_INFO(
       "Filtering data on %s between %f -> %f.\n", field_name.c_str(), min_v, max_v);
-  float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f;
+
   pcl::console::parse_3x_arguments(argc, argv, "-leaf", leaf_x, leaf_y, leaf_z);
   PCL_INFO("Using %f, %f, %f as a leaf size for VoxelGrid.\n", leaf_x, leaf_y, leaf_z);
+  /////////////////////////////////////////////////////////////////////
 
-  pcl::OpenNIGrabber grabber(arg);
+  pcl::OpenNIGrabber grabber(device_id);
   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
     OpenNIVoxelGrid<pcl::PointXYZRGBA> v(
-        arg, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
+        device_id, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
     v.run();
   }
   else {
     OpenNIVoxelGrid<pcl::PointXYZ> v(
-        arg, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
+        device_id, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
     v.run();
   }
 
index e4ce56193aa000c87a6927b54a1506c2033ddc0b..480817345a44503c916b0dd2af157ad6f99df006 100644 (file)
@@ -12,8 +12,8 @@
 #include <QObject>
 
 #include <vtkGenericOpenGLRenderWindow.h>
-#include <vtkRenderWindow.h>
 #include <vtkRendererCollection.h>
+#include <vtkRenderWindow.h>
 
 // #include <boost/filesystem.hpp>  // for boost::filesystem::directory_iterator
 #include <boost/signals2/connection.hpp> // for boost::signals2::connection
index 6eb0c222c0a827804bbab64a713625064b29d22d..e1eb6f9af11d1284162c2b05d4aa8e8b9f51b795 100644 (file)
@@ -227,7 +227,7 @@ compute(const pcl::PCLPointCloud2::ConstPtr& input,
   pcl::copyPointCloud(*cloud, label_indices[3].indices, *high_curvature_edges);
   pcl::copyPointCloud(*cloud, label_indices[4].indices, *rgb_edges);
 
-  const int point_size = 2;
+  constexpr int point_size = 2;
   viewer.addPointCloud<pcl::PointXYZRGBA>(nan_boundary_edges, "nan boundary edges");
   viewer.setPointCloudRenderingProperties(
       pcl::visualization::PCL_VISUALIZER_POINT_SIZE, point_size, "nan boundary edges");
index 527a1872e08a55ed9ddcfd941837111ce3ef780e..aa6157e3678400c51317d9010fb7bb53d2ad2849 100644 (file)
@@ -55,8 +55,8 @@
 
 #include <vtkCamera.h>
 #include <vtkGenericOpenGLRenderWindow.h>
-#include <vtkRenderWindow.h>
 #include <vtkRendererCollection.h>
+#include <vtkRenderWindow.h>
 
 #include <fstream>
 #include <iostream>
index e02d9d62b1a2a7c571594fbe40407edf2a6340b7..b12ac2a0f437b132e00a4e1d08e17f863f17699a 100644 (file)
@@ -15,7 +15,7 @@ using namespace pcl;
 using namespace std::chrono_literals;
 
 const Eigen::Vector4f subsampling_leaf_size(0.02f, 0.02f, 0.02f, 0.0f);
-const float normal_estimation_search_radius = 0.05f;
+constexpr float normal_estimation_search_radius = 0.05f;
 
 PointCloud<PointNormal>::Ptr
 subsampleAndCalculateNormals(const PointCloud<PointXYZ>::Ptr& cloud)
index 6580262a8f9d33dcce5e6040ac7956ea96875ed5..b325b4473d9337672bd5b1518aa8a1e3f4f8c47c 100644 (file)
@@ -9,7 +9,7 @@ using namespace pcl;
 #include <iostream>
 
 const Eigen::Vector4f subsampling_leaf_size(0.02f, 0.02f, 0.02f, 0.0f);
-const float normal_estimation_search_radius = 0.05f;
+constexpr float normal_estimation_search_radius = 0.05f;
 
 void
 subsampleAndCalculateNormals(PointCloud<PointXYZ>::Ptr& cloud,
index ac248ac0ff9dd3fbd8773bea855b87f0c5580fbc..896b101544ef82269a2e0d5c7234e540f58e515f 100644 (file)
@@ -20,8 +20,8 @@
 #include <vtkPointPicker.h>
 #include <vtkPolyDataMapper.h>
 #include <vtkPropPicker.h>
-#include <vtkRenderWindow.h>
 #include <vtkRenderer.h>
+#include <vtkRenderWindow.h>
 #include <vtkSelection.h>
 #include <vtkSelectionNode.h>
 #include <vtkTransform.h>
index ecc55a77c82be3c5edef74fb96ab5065ef78e016..b966c39a29f80cdaf798ef0b63791e61e5bda8f7 100644 (file)
@@ -42,8 +42,8 @@
 
 using namespace pcl;
 
-const float subsampling_leaf_size = 0.003f;
-const float base_scale = 0.005f;
+constexpr float subsampling_leaf_size = 0.003f;
+constexpr float base_scale = 0.005f;
 
 int
 main(int, char** argv)
index b85bc0354cad308e20a94dbcc3703a9353625e46..95f421db5f6d4f1fab966185ad5a41cd07171396 100644 (file)
@@ -25,3 +25,8 @@ 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(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"
+                            "${PCL_SOURCE_DIR}/test/milk_cartoon_all_small_clorox.pcd")
+
diff --git a/benchmarks/search/radius_search.cpp b/benchmarks/search/radius_search.cpp
new file mode 100644 (file)
index 0000000..9641375
--- /dev/null
@@ -0,0 +1,62 @@
+#include <pcl/io/pcd_io.h>
+#include <pcl/search/organized.h>
+#include <pcl/point_cloud.h>
+#include <pcl/point_types.h>
+
+#include <benchmark/benchmark.h>
+
+#include <chrono>
+
+static void
+BM_OrganizedNeighborSearch(benchmark::State& state, const std::string& file)
+{
+  pcl::PointCloud<pcl::PointXYZ>::Ptr cloudIn(new pcl::PointCloud<pcl::PointXYZ>);
+  pcl::PCDReader reader;
+  reader.read(file, *cloudIn);
+
+  pcl::search::OrganizedNeighbor<pcl::PointXYZ> organizedNeighborSearch;
+  organizedNeighborSearch.setInputCloud(cloudIn);
+
+  double radiusSearchTime = 0;
+  std::vector<int> indices(cloudIn->size()); // Fixed indices from 0 to cloud size
+  std::iota(indices.begin(), indices.end(), 0);
+  int radiusSearchIdx = 0;
+
+  for (auto _ : state) {
+    int searchIdx = indices[radiusSearchIdx++ % indices.size()];
+    double searchRadius = 0.1; // or any fixed radius like 0.05
+
+    std::vector<int> k_indices;
+    std::vector<float> k_sqr_distances;
+
+    auto start_time = std::chrono::high_resolution_clock::now();
+    organizedNeighborSearch.radiusSearch(
+        (*cloudIn)[searchIdx], searchRadius, k_indices, k_sqr_distances);
+    auto end_time = std::chrono::high_resolution_clock::now();
+
+    radiusSearchTime +=
+        std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - start_time)
+            .count();
+  }
+
+  state.SetItemsProcessed(state.iterations());
+  state.SetIterationTime(
+      radiusSearchTime /
+      (state.iterations() * indices.size())); // Normalize by total points processed
+}
+
+int
+main(int argc, char** argv)
+{
+  if (argc < 2) {
+    std::cerr << "No test file given. Please provide a PCD file for the benchmark."
+              << std::endl;
+    return -1;
+  }
+
+  benchmark::RegisterBenchmark(
+      "BM_OrganizedNeighborSearch", &BM_OrganizedNeighborSearch, argv[1])
+      ->Unit(benchmark::kMillisecond);
+  benchmark::Initialize(&argc, argv);
+  benchmark::RunSpecifiedBenchmarks();
+}
diff --git a/cmake/Modules/FindEigen.cmake b/cmake/Modules/FindEigen.cmake
deleted file mode 100644 (file)
index e1fb6ab..0000000
+++ /dev/null
@@ -1,41 +0,0 @@
-###############################################################################
-# Find Eigen3
-#
-# This sets the following variables:
-# EIGEN_FOUND - True if Eigen was found.
-# EIGEN_INCLUDE_DIRS - Directories containing the Eigen include files.
-# EIGEN_DEFINITIONS - Compiler flags for Eigen.
-# EIGEN_VERSION - Package version
-
-find_package(PkgConfig QUIET)
-pkg_check_modules(PC_EIGEN eigen3)
-set(EIGEN_DEFINITIONS ${PC_EIGEN_CFLAGS_OTHER})
-
-find_path(EIGEN_INCLUDE_DIR Eigen/Core
-    HINTS "${EIGEN_ROOT}" "$ENV{EIGEN_ROOT}" ${PC_EIGEN_INCLUDEDIR} ${PC_EIGEN_INCLUDE_DIRS}
-    PATHS "$ENV{PROGRAMFILES}/Eigen" "$ENV{PROGRAMW6432}/Eigen"
-          "$ENV{PROGRAMFILES}/Eigen3" "$ENV{PROGRAMW6432}/Eigen3"
-    PATH_SUFFIXES eigen3 include/eigen3 include)
-
-if(EIGEN_INCLUDE_DIR)
-  file(READ "${EIGEN_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen_version_header)
-
-  string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen_world_version_match "${_eigen_version_header}")
-  set(EIGEN_WORLD_VERSION "${CMAKE_MATCH_1}")
-  string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen_major_version_match "${_eigen_version_header}")
-  set(EIGEN_MAJOR_VERSION "${CMAKE_MATCH_1}")
-  string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen_minor_version_match "${_eigen_version_header}")
-  set(EIGEN_MINOR_VERSION "${CMAKE_MATCH_1}")
-  set(EIGEN_VERSION ${EIGEN_WORLD_VERSION}.${EIGEN_MAJOR_VERSION}.${EIGEN_MINOR_VERSION})
-endif()
-
-set(EIGEN_INCLUDE_DIRS ${EIGEN_INCLUDE_DIR})
-
-include(FindPackageHandleStandardArgs)
-find_package_handle_standard_args(Eigen DEFAULT_MSG EIGEN_INCLUDE_DIR)
-
-mark_as_advanced(EIGEN_INCLUDE_DIR)
-
-if(EIGEN_FOUND)
-  message(STATUS "Eigen found (include: ${EIGEN_INCLUDE_DIRS}, version: ${EIGEN_VERSION})")
-endif()
index 9b46b2256f7962f7772a9291007a0dcfc3dc3b9c..f42bca3f76ef0d2d4fc75b72c4c461b06df22859 100644 (file)
@@ -37,6 +37,7 @@
 # Early return if FLANN target is already defined. This makes it safe to run
 # this script multiple times.
 if(TARGET FLANN::FLANN)
+  set(FLANN_FOUND ON)
   return()
 endif()
 
@@ -47,33 +48,41 @@ if(flann_FOUND)
   unset(flann_FOUND)
   set(FLANN_FOUND ON)
 
-  # Create interface library that effectively becomes an alias for the appropriate (static/dynamic) imported FLANN target
-  add_library(FLANN::FLANN INTERFACE IMPORTED)
-
   if(TARGET flann::flann_cpp_s AND TARGET flann::flann_cpp)
     if(PCL_FLANN_REQUIRED_TYPE MATCHES "SHARED")
-      set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp)
       set(FLANN_LIBRARY_TYPE SHARED)
     elseif(PCL_FLANN_REQUIRED_TYPE MATCHES "STATIC")
-      set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s)
       set(FLANN_LIBRARY_TYPE STATIC)
     else()
       if(PCL_SHARED_LIBS)
-        set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp)
         set(FLANN_LIBRARY_TYPE SHARED)
       else()
-        set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s)
         set(FLANN_LIBRARY_TYPE STATIC)
       endif()
     endif()
   elseif(TARGET flann::flann_cpp_s)
-    set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s)
     set(FLANN_LIBRARY_TYPE STATIC)
   else()
-    set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp)
     set(FLANN_LIBRARY_TYPE SHARED)
   endif()
 
+  if(CMAKE_VERSION VERSION_LESS 3.18.0)
+    # Create interface library that effectively becomes an alias for the appropriate (static/dynamic) imported FLANN target
+    add_library(FLANN::FLANN INTERFACE IMPORTED)
+
+    if(FLANN_LIBRARY_TYPE MATCHES SHARED)
+      set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp)
+    else()
+      set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s)
+    endif()
+  else()
+    if(FLANN_LIBRARY_TYPE MATCHES SHARED)
+      add_library(FLANN::FLANN ALIAS flann::flann_cpp)
+    else()
+      add_library(FLANN::FLANN ALIAS flann::flann_cpp_s)
+    endif()
+  endif()
+
   # Determine FLANN installation root based on the path to the processed Config file
   get_filename_component(_config_dir "${flann_CONFIG}" DIRECTORY)
   get_filename_component(FLANN_ROOT "${_config_dir}/../../.." ABSOLUTE)
index cd17a179fcf72ce8c34a80308d1d039766353fb1..b4f6a6a1d82491e1e7ed25021143cf8435daf38f 100644 (file)
@@ -154,7 +154,7 @@ int main(void) {
 
 # in Fortran, an implementation may provide an omp_lib.h header
 # or omp_lib module, or both (OpenMP standard, section 3.1)
-# Furthmore !$ is the Fortran equivalent of #ifdef _OPENMP (OpenMP standard, 2.2.2)
+# 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
index 65f84b38c2771df3055709f77e4c7c328f2ccf58..ecc2e781b43bf66365af9797704c6d66bbad65d8 100644 (file)
@@ -38,7 +38,7 @@
 # Find the PCAP includes and library
 # http://www.tcpdump.org/
 #
-# The environment variable PCAPDIR allows to specficy where to find
+# The environment variable PCAPDIR allows to specify where to find
 # libpcap in non standard location.
 #
 # 2012/01/02 - KEVEN RING
index aab8226901854122f92f40a0a813933628e46126..8edd001281f9ccb8d07db0ced3c3551d6be42f81 100644 (file)
@@ -36,6 +36,8 @@
 # Early return if libusb target is already defined. This makes it safe to run
 # this script multiple times.
 if(TARGET libusb::libusb)
+  set(libusb_FOUND ON)
+  set(LIBUSB_FOUND ON)
   return()
 endif()
 
@@ -67,6 +69,7 @@ find_package_handle_standard_args(libusb DEFAULT_MSG libusb_LIBRARIES libusb_INC
 mark_as_advanced(libusb_INCLUDE_DIRS libusb_LIBRARIES)
 
 if(libusb_FOUND)
+  set(LIBUSB_FOUND ON)
   add_library(libusb::libusb UNKNOWN IMPORTED)
   set_target_properties(libusb::libusb PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${libusb_INCLUDE_DIR}")
   set_target_properties(libusb::libusb PROPERTIES IMPORTED_LOCATION "${libusb_LIBRARIES}")
index 52309dc412b7b9fa4fb3b28a99b83c5dca83d659..22cf0948686dff1a44d1b8d1937bd5411f1468a1 100644 (file)
@@ -10,7 +10,6 @@ endif()
 # get root directory of each dependency libraries to be copied to PCL/3rdParty
 get_filename_component(BOOST_ROOT "${Boost_INCLUDE_DIR}" PATH)  # ../Boost/include/boost-x_x/ -> ../Boost/include/
 get_filename_component(BOOST_ROOT "${BOOST_ROOT}" PATH)         # ../Boost/include/           -> ../Boost/
-get_filename_component(EIGEN_ROOT "${EIGEN_INCLUDE_DIRS}" PATH) # ../Eigen3/include/          -> ../Eigen3/
 get_filename_component(QHULL_ROOT "${Qhull_DIR}" PATH)          # ../qhull/lib/cmake/Qhull/   -> ../qhull/lib/cmake
 get_filename_component(QHULL_ROOT "${QHULL_ROOT}" PATH)         # ../qhull/lib/cmake/         -> ../qhull/lib/
 get_filename_component(QHULL_ROOT "${QHULL_ROOT}" PATH)         # ../qhull/lib/               -> ../qhull/
@@ -19,7 +18,7 @@ get_filename_component(VTK_ROOT "${VTK_ROOT}" PATH)             # ../VTK/lib/cma
 get_filename_component(VTK_ROOT "${VTK_ROOT}" PATH)             # ../VTK/lib/                 -> ../VTK/
 
 set(PCL_3RDPARTY_COMPONENTS)
-foreach(dep Eigen Boost Qhull FLANN VTK)
+foreach(dep Boost Qhull FLANN VTK)
   string(TOUPPER ${dep} DEP)
   install(
     DIRECTORY "${${DEP}_ROOT}/"
@@ -30,6 +29,57 @@ foreach(dep Eigen Boost Qhull FLANN VTK)
   list(APPEND PCL_3RDPARTY_COMPONENTS ${dep})
 endforeach()
 
+# Try to set EIGEN3_INCLUDE_DIR in case it is
+# no longer exported by Eigen3 itself.
+if (NOT EXISTS ${EIGEN3_INCLUDE_DIR})
+  if (EXISTS ${EIGEN3_INCLUDE_DIRS})
+    set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS})
+  else()
+    set(EIGEN3_INCLUDE_DIR "${Eigen3_DIR}/../../../include/eigen3/")
+  endif()
+endif()
+if(NOT EXISTS ${EIGEN3_INCLUDE_DIR})
+  message(FATAL_ERROR "EIGEN3_INCLUDE_DIR is not existing: ${EIGEN3_INCLUDE_DIR}")
+endif()
+
+# Try to find EIGEN3_COMMON_ROOT_PATH, which is meant to hold
+# the first common root folder of Eigen3_DIR and EIGEN3_INCLUDE_DIR.
+# E.g. Eigen3_DIR              = /usr/local/share/eigen3/cmake/
+#      EIGEN3_INCLUDE_DIR      = /usr/local/include/eigen3/
+#   => EIGEN3_COMMON_ROOT_PATH = /usr/local/
+file(TO_CMAKE_PATH ${Eigen3_DIR} Eigen3_DIR)
+file(TO_CMAKE_PATH ${EIGEN3_INCLUDE_DIR} EIGEN3_INCLUDE_DIR)
+set(EIGEN3_INCLUDE_PATH_LOOP ${EIGEN3_INCLUDE_DIR})
+set(PREVIOUS_EIGEN3_INCLUDE_PATH_LOOP "INVALID")
+while (NOT ${PREVIOUS_EIGEN3_INCLUDE_PATH_LOOP} STREQUAL ${EIGEN3_INCLUDE_PATH_LOOP})
+  if (${Eigen3_DIR} MATCHES ${EIGEN3_INCLUDE_PATH_LOOP})
+    set(EIGEN3_COMMON_ROOT_PATH ${EIGEN3_INCLUDE_PATH_LOOP})
+    break()
+  endif()
+  set(PREVIOUS_EIGEN3_INCLUDE_PATH_LOOP ${EIGEN3_INCLUDE_PATH_LOOP})
+  get_filename_component(EIGEN3_INCLUDE_PATH_LOOP ${EIGEN3_INCLUDE_PATH_LOOP} DIRECTORY)
+endwhile()
+if(NOT EXISTS ${EIGEN3_COMMON_ROOT_PATH})
+  message(FATAL_ERROR "Could not copy Eigen3.")
+endif()
+
+# Install Eigen3 to 3rdParty directory
+string(LENGTH ${EIGEN3_COMMON_ROOT_PATH} LENGTH_OF_EIGEN3_COMMON_ROOT_PATH)
+string(SUBSTRING ${Eigen3_DIR} ${LENGTH_OF_EIGEN3_COMMON_ROOT_PATH} -1 DESTINATION_EIGEN3_DIR)
+string(SUBSTRING ${EIGEN3_INCLUDE_DIR} ${LENGTH_OF_EIGEN3_COMMON_ROOT_PATH} -1 DESTINATION_EIGEN3_INCLUDE_DIR)
+set(dep_Eigen3 Eigen3)
+install(
+  DIRECTORY "${Eigen3_DIR}/"
+  DESTINATION 3rdParty/${dep_Eigen3}${DESTINATION_EIGEN3_DIR}
+  COMPONENT ${dep_Eigen3}
+)
+install(
+  DIRECTORY "${EIGEN3_INCLUDE_DIR}/"
+  DESTINATION 3rdParty/${dep_Eigen3}${DESTINATION_EIGEN3_INCLUDE_DIR}
+  COMPONENT ${dep_Eigen3}
+)
+list(APPEND PCL_3RDPARTY_COMPONENTS ${dep_Eigen3})
+
 if(WITH_RSSDK2)
   get_filename_component(RSSDK2_ROOT "${RSSDK2_INCLUDE_DIRS}" PATH)
   install(
index b60fafae456470680caa571e17ba73be2f1da8e1..770607f82dcf0d5c8088a6fc233e0325c67ef452 100644 (file)
@@ -14,7 +14,7 @@ else()
 endif()
 
 set(Boost_ADDITIONAL_VERSIONS
-  "1.80.0" "1.80"
+  "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")
@@ -26,7 +26,7 @@ if(Boost_SERIALIZATION_FOUND)
 endif()
 
 # Required boost modules
-set(BOOST_REQUIRED_MODULES filesystem date_time iostreams system)
+set(BOOST_REQUIRED_MODULES filesystem iostreams system)
 find_package(Boost 1.65.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES})
 
 if(Boost_FOUND)
index 09192e30d1b96f24b1f9b072b753fa92425f3ad1..b88758fc3965340e9b453f3a5ca0964e2ad423d4 100644 (file)
@@ -25,7 +25,7 @@ if(NOT WITH_QT_STR MATCHES "^(AUTO|YES|QT6|QT5)$")
 endif()
 
 if(WITH_QT_STR MATCHES "^(AUTO|YES|QT6)$")
-  find_package(Qt6 QUIET COMPONENTS Concurrent OpenGL Widgets)
+  find_package(Qt6 QUIET COMPONENTS Concurrent OpenGL Widgets OpenGLWidgets)
   set(QT6_FOUND ${Qt6_FOUND})
   set(QT_FOUND ${QT6_FOUND})
   if (QT6_FOUND)
index 40e5ad80ba62258b6c172cf568907289816ccba4..f0656e6ec3bf3c2443951fd4f7f3e7316059d55c 100644 (file)
@@ -16,6 +16,13 @@ set(PCLCONFIG_SSE_DEFINITIONS "${SSE_DEFINITIONS}")
 set(PCLCONFIG_SSE_COMPILE_OPTIONS ${SSE_FLAGS})
 set(PCLCONFIG_AVX_COMPILE_OPTIONS ${AVX_FLAGS})
 
+# Eigen has a custom mechanism to guarantee aligned memory (used for everything older than C++17, see Memory.h in the Eigen project)
+# If PCL is compiled with C++14 and the user project is compiled with C++17, this will lead to problems (e.g. memory allocated with the custom mechanism but freed without it)
+# Defining EIGEN_HAS_CXX17_OVERALIGN=0 forces Eigen in the user project to use Eigen's custom mechanism, even in C++17 and newer.
+if(${CMAKE_CXX_STANDARD} LESS 17)
+  string(APPEND PCLCONFIG_SSE_DEFINITIONS " -DEIGEN_HAS_CXX17_OVERALIGN=0")
+endif()
+
 foreach(_ss ${PCL_SUBSYSTEMS_MODULES})
   PCL_GET_SUBSYS_STATUS(_status ${_ss})
 
@@ -78,7 +85,7 @@ foreach(_ss ${PCL_SUBSYSTEMS_MODULES})
 endforeach()
 
 #Boost modules
-set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system filesystem date_time iostreams")
+set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system filesystem iostreams")
 if(Boost_SERIALIZATION_FOUND)
   string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " serialization")
 endif()
index 86d06d0c836c8a0a4f75dd93b070645316a3b66d..2da076c23c5c40d2a46e4b2615d655e50a07a2cd 100644 (file)
@@ -310,7 +310,7 @@ function(PCL_ADD_EXECUTABLE _name)
   endif()
 
   # Some app targets report are defined with subsys other than apps
-  # It's simpler check for tools and assume everythin else as an app
+  # It's simpler check for tools and assume everything else as an app
   if(${ARGS_COMPONENT} STREQUAL "tools")
     set_target_properties(${_name} PROPERTIES FOLDER "Tools")
   else()
index 9c7067332d650a435ae1e4ae5c9e6d56bff2a3af..fe0ad8fa3eac71d457381a9bacbeb5883325b2dd 100644 (file)
@@ -4,7 +4,7 @@ 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 eigen boost)
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS eigen3 boost)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
@@ -172,10 +172,14 @@ set(kissfft_srcs
 )
 
 set(LIB_NAME "pcl_${SUBSYS_NAME}")
-include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include")
 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_link_libraries(${LIB_NAME} Boost::boost)
+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))
   # MSVC resolved a byte alignment issue in compiler version 15.9
index cf78ad396b171cd8024624d67f3f098a0f2c4387..ec3f95627852abe15b7cfbf04f892c8dd0e78875 100644 (file)
@@ -143,7 +143,7 @@ namespace pcl
     for (std::size_t i = 0; i < v.data.size (); ++i)
     {
       s << "  data[" << i << "]: ";
-      s << "  " << v.data[i] << std::endl;
+      s << "  " << static_cast<int>(v.data[i]) << std::endl;
     }
     s << "is_dense: ";
     s << "  " << v.is_dense << std::endl;
index dd15962f828eaecc2eb6463111d22d28f945c11b..53626db2c27c11e788abcc4c2b6a1fcf5acd5fc5 100644 (file)
@@ -32,7 +32,7 @@ namespace pcl
       const auto point_offset = mesh1.cloud.width * mesh1.cloud.height;
       
       bool success = pcl::PCLPointCloud2::concatenate(mesh1.cloud, mesh2.cloud);
-      if (success == false) {
+      if (!success) {
         return false;
       }
       // Make the resultant polygon mesh take the newest stamp
index 615320b4094627ae11a4aa66871b0c710f7a8450..b347872040e83b8894eb8ef68572e8704404aa6d 100644 (file)
@@ -114,9 +114,10 @@ namespace pcl
       getNoOfParametersFromDegree (int n) { return ((n+2)* (n+1))/2;}
 
       //-----VARIABLES-----
-      int degree;
-      real* parameters;
-      BivariatePolynomialT<real>* gradient_x, * gradient_y;
+      int degree{0};
+      real* parameters{nullptr};
+      BivariatePolynomialT<real>* gradient_x{nullptr};
+      BivariatePolynomialT<real>* gradient_y{nullptr};
 
     protected:
       //-----METHODS-----
index 232d1df5f3b48820a0cfb4fc2d24172715a0003d..068e48999fd4862c8fb7cf8651d0f01b4953c4a1 100644 (file)
@@ -47,7 +47,6 @@ PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly."
 // 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/date_time/posix_time/posix_time.hpp>
 #include <boost/signals2.hpp>
 #include <boost/signals2/slot.hpp>
 #include <boost/algorithm/string.hpp>
index 0f456f16b4b7b7aaa7e7bfc4c08043929429840e..c3a32300a31fab2f39fe50a417c775d123fd024a 100644 (file)
@@ -89,18 +89,18 @@ namespace pcl
     * \ingroup common
     */
   template <typename PointT, typename Scalar> inline unsigned int
-  compute3DCentroid (const pcl::PointCloud<PointT> &cloud, 
+  compute3DCentroid (const pcl::PointCloud<PointT> &cloud,
                      Eigen::Matrix<Scalar, 4, 1> &centroid);
 
   template <typename PointT> inline unsigned int
-  compute3DCentroid (const pcl::PointCloud<PointT> &cloud, 
+  compute3DCentroid (const pcl::PointCloud<PointT> &cloud,
                      Eigen::Vector4f &centroid)
   {
     return (compute3DCentroid <PointT, float> (cloud, centroid));
   }
 
   template <typename PointT> inline unsigned int
-  compute3DCentroid (const pcl::PointCloud<PointT> &cloud, 
+  compute3DCentroid (const pcl::PointCloud<PointT> &cloud,
                      Eigen::Vector4d &centroid)
   {
     return (compute3DCentroid <PointT, double> (cloud, centroid));
@@ -589,6 +589,61 @@ namespace pcl
     return (computeCovarianceMatrix<PointT, double> (cloud, indices, covariance_matrix));
   }
 
+
+  /** \brief Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points.
+  * OBB is oriented like the three axes (major, middle and minor) with
+  * major_axis  = obb_rotational_matrix.col(0)
+  * middle_axis = obb_rotational_matrix.col(1)
+  * minor_axis  = obb_rotational_matrix.col(2)
+  * one way to visualize OBB when Scalar is float:
+  * Eigen::Vector3f position(obb_position(0), obb_position(1), obb_position(2));
+  * Eigen::Quaternionf quat(obb_rotational_matrix);
+  * viewer->addCube(position, quat, obb_dimensions(0), obb_dimensions(1), obb_dimensions(2), .....);
+  * \param[in] cloud the input point cloud
+  * \param[out] centroid the centroid (mean value of the XYZ coordinates) of the set of points in the cloud
+  * \param[out] obb_center position of the center of the OBB (it is the same as centroid if the cloud is centrally symmetric)
+  * \param[out] obb_dimensions (width, height and depth) of the OBB 
+  * \param[out] obb_rotational_matrix rotational matrix of the OBB 
+  * \return number of valid points used to determine the output.
+  * In case of dense point clouds, this is the same as the size of the input cloud.
+  * \ingroup common
+  */
+  template <typename PointT, typename Scalar> inline unsigned int
+    computeCentroidAndOBB(const pcl::PointCloud<PointT>& cloud,
+                    Eigen::Matrix<Scalar, 3, 1>& centroid,
+                    Eigen::Matrix<Scalar, 3, 1>& obb_center,
+                    Eigen::Matrix<Scalar, 3, 1>& obb_dimensions,
+                    Eigen::Matrix<Scalar, 3, 3>& obb_rotational_matrix);
+
+
+  /** \brief Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points.
+  * OBB is oriented like the three axes (major, middle and minor) with
+  * major_axis  = obb_rotational_matrix.col(0)
+  * middle_axis = obb_rotational_matrix.col(1)
+  * minor_axis  = obb_rotational_matrix.col(2)
+  * one way to visualize OBB when Scalar is float:
+  * Eigen::Vector3f position(obb_position(0), obb_position(1), obb_position(2));
+  * Eigen::Quaternionf quat(obb_rotational_matrix);
+  * viewer->addCube(position, quat, obb_dimensions(0), obb_dimensions(1), obb_dimensions(2), .....);
+  * \param[in] cloud the input point cloud
+  * \param[in] indices subset of points given by their indices 
+  * \param[out] centroid the centroid (mean value of the XYZ coordinates) of the set of points in the cloud
+  * \param[out] obb_center position of the center of the OBB (it is the same as centroid if the cloud is centrally symmetric)
+  * \param[out] obb_dimensions (width, height and depth) of the OBB 
+  * \param[out] obb_rotational_matrix rotational matrix of the OBB 
+  * \return number of valid points used to determine the output.
+  * In case of dense point clouds, this is the same as the size of the input cloud.
+  * \ingroup common
+  */
+  template <typename PointT, typename Scalar> inline unsigned int
+    computeCentroidAndOBB(const pcl::PointCloud<PointT>& cloud,
+                    const Indices &indices,
+                    Eigen::Matrix<Scalar, 3, 1>& centroid,
+                    Eigen::Matrix<Scalar, 3, 1>& obb_center,
+                    Eigen::Matrix<Scalar, 3, 1>& obb_dimensions,
+                    Eigen::Matrix<Scalar, 3, 3>& obb_rotational_matrix);
+
+
   /** \brief Subtract a centroid from a point cloud and return the de-meaned representation
     * \param[in] cloud_iterator an iterator over the input point cloud
     * \param[in] centroid the centroid of the point cloud
@@ -844,8 +899,7 @@ namespace pcl
     using Pod = typename traits::POD<PointT>::type;
 
     NdCentroidFunctor (const PointT &p, Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &centroid)
-      : f_idx_ (0),
-        centroid_ (centroid),
+      : centroid_ (centroid),
         p_ (reinterpret_cast<const Pod&>(p)) { }
 
     template<typename Key> inline void operator() ()
@@ -865,7 +919,7 @@ namespace pcl
     }
 
     private:
-      int f_idx_;
+      int f_idx_{0};
       Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &centroid_;
       const Pod &p_;
   };
@@ -877,18 +931,18 @@ namespace pcl
     * \ingroup common
     */
   template <typename PointT, typename Scalar> inline void
-  computeNDCentroid (const pcl::PointCloud<PointT> &cloud, 
+  computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
                      Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &centroid);
 
   template <typename PointT> inline void
-  computeNDCentroid (const pcl::PointCloud<PointT> &cloud, 
+  computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
                      Eigen::VectorXf &centroid)
   {
     return (computeNDCentroid<PointT, float> (cloud, centroid));
   }
 
   template <typename PointT> inline void
-  computeNDCentroid (const pcl::PointCloud<PointT> &cloud, 
+  computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
                      Eigen::VectorXd &centroid)
   {
     return (computeNDCentroid<PointT, double> (cloud, centroid));
@@ -907,7 +961,7 @@ namespace pcl
                      Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &centroid);
 
   template <typename PointT> inline void
-  computeNDCentroid (const pcl::PointCloud<PointT> &cloud, 
+  computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
                      const Indices &indices,
                      Eigen::VectorXf &centroid)
   {
@@ -915,7 +969,7 @@ namespace pcl
   }
 
   template <typename PointT> inline void
-  computeNDCentroid (const pcl::PointCloud<PointT> &cloud, 
+  computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
                      const Indices &indices,
                      Eigen::VectorXd &centroid)
   {
@@ -935,7 +989,7 @@ namespace pcl
                      Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &centroid);
 
   template <typename PointT> inline void
-  computeNDCentroid (const pcl::PointCloud<PointT> &cloud, 
+  computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
                      const pcl::PointIndices &indices,
                      Eigen::VectorXf &centroid)
   {
@@ -943,7 +997,7 @@ namespace pcl
   }
 
   template <typename PointT> inline void
-  computeNDCentroid (const pcl::PointCloud<PointT> &cloud, 
+  computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
                      const pcl::PointIndices &indices,
                      Eigen::VectorXd &centroid)
   {
index 15b079a19fa8c2452f80f2ddabe0407f47034a6b..a1259e9d6a91c09e33b7373825fb24e54638c317 100644 (file)
@@ -503,41 +503,11 @@ namespace pcl
   {
     Eigen::Matrix<Scalar, Eigen::Dynamic, 1> line_x;
     Eigen::Matrix<Scalar, Eigen::Dynamic, 1> line_y;
-    line_x << origin, x_direction;
-    line_y << origin, y_direction;
-    return (checkCoordinateSystem<Scalar> (line_x, line_y, norm_limit, dot_limit));
-  }
-
-  inline bool
-  checkCoordinateSystem (const Eigen::Matrix<double, 3, 1> &origin,
-                         const Eigen::Matrix<double, 3, 1> &x_direction,
-                         const Eigen::Matrix<double, 3, 1> &y_direction,
-                         const double norm_limit = 1e-3,
-                         const double dot_limit = 1e-3)
-  {
-    Eigen::Matrix<double, Eigen::Dynamic, 1> line_x;
-    Eigen::Matrix<double, Eigen::Dynamic, 1> line_y;
-    line_x.resize (6);
-    line_y.resize (6);
-    line_x << origin, x_direction;
-    line_y << origin, y_direction;
-    return (checkCoordinateSystem<double> (line_x, line_y, norm_limit, dot_limit));
-  }
-
-  inline bool
-  checkCoordinateSystem (const Eigen::Matrix<float, 3, 1> &origin,
-                         const Eigen::Matrix<float, 3, 1> &x_direction,
-                         const Eigen::Matrix<float, 3, 1> &y_direction,
-                         const float norm_limit = 1e-3,
-                         const float dot_limit = 1e-3)
-  {
-    Eigen::Matrix<float, Eigen::Dynamic, 1> line_x;
-    Eigen::Matrix<float, Eigen::Dynamic, 1> line_y;
     line_x.resize (6);
     line_y.resize (6);
     line_x << origin, x_direction;
     line_y << origin, y_direction;
-    return (checkCoordinateSystem<float> (line_x, line_y, norm_limit, dot_limit));
+    return (checkCoordinateSystem<Scalar> (line_x, line_y, norm_limit, dot_limit));
   }
 
 /** \brief Compute the transformation between two coordinate systems
index 9c7e0130b1eab39ba2da0ec24becf7e55931f5fb..8742ed32b2b5d19a97059d594a48347bfa28f3de 100644 (file)
@@ -59,7 +59,7 @@ namespace pcl
     public:
 
       static const unsigned MAX_KERNEL_WIDTH = 71;
-      /** Computes the gaussian kernel and dervative assiociated to sigma.
+      /** Computes the gaussian kernel and dervative associated to sigma.
         * The kernel and derivative width are adjusted according.
         * \param[in] sigma
         * \param[out] kernel the computed gaussian kernel
@@ -71,7 +71,7 @@ namespace pcl
                Eigen::VectorXf &kernel,
                unsigned kernel_width = MAX_KERNEL_WIDTH) const;
 
-      /** Computes the gaussian kernel and dervative assiociated to sigma.
+      /** Computes the gaussian kernel and dervative associated to sigma.
         * The kernel and derivative width are adjusted according.
         * \param[in] sigma
         * \param[out] kernel the computed gaussian kernel
index 4e4fb1c4822aa418fb5ef9ef717ed1510bbc650b..b3c4ae68e6904ae52fc0378a1ffe1f662280a054 100644 (file)
@@ -48,7 +48,7 @@ namespace pcl
 
   namespace common
   {
-    /** \brief CloudGenerator class generates a point cloud using some randoom number generator.
+    /** \brief CloudGenerator class generates a point cloud using some random number generator.
       * Generators can be found in \file common/random.h and easily extensible.
       *  
       * \ingroup common
@@ -79,7 +79,7 @@ namespace pcl
                       const GeneratorParameters& z_params);
 
       /** Set parameters for x, y and z values. Uniqueness is ensured through seed incrementation.
-        * \param params parameteres for X, Y and Z values generation. 
+        * \param params parameters for X, Y and Z values generation. 
         */
       void
       setParameters (const GeneratorParameters& params);
index 7e527a6ccf8cce5551d00873f51a0b18c9f7b8aa..6ae8db6fd0ad779367828211a5555096f38184cc 100644 (file)
@@ -52,16 +52,14 @@ namespace pcl
 {
 
 template<typename real>
-BivariatePolynomialT<real>::BivariatePolynomialT (int new_degree) :
-  degree(0), parameters(nullptr), gradient_x(nullptr), gradient_y(nullptr)
+BivariatePolynomialT<real>::BivariatePolynomialT (int new_degree)
 {
   setDegree(new_degree);
 }
 
 
 template<typename real>
-BivariatePolynomialT<real>::BivariatePolynomialT (const BivariatePolynomialT& other) :
-  degree(0), parameters(NULL), gradient_x(NULL), gradient_y(NULL)
+BivariatePolynomialT<real>::BivariatePolynomialT (const BivariatePolynomialT& other)
 {
   deepCopy (other);
 }
@@ -140,11 +138,11 @@ BivariatePolynomialT<real>::deepCopy (const pcl::BivariatePolynomialT<real>& oth
 template<typename real> void
 BivariatePolynomialT<real>::calculateGradient (bool forceRecalc)
 {
-  if (gradient_x!=NULL && !forceRecalc) return;
+  if (gradient_x!=nullptr && !forceRecalc) return;
 
-  if (gradient_x == NULL)
+  if (gradient_x == nullptr)
     gradient_x = new pcl::BivariatePolynomialT<real> (degree-1);
-  if (gradient_y == NULL)
+  if (gradient_y == nullptr)
     gradient_y = new pcl::BivariatePolynomialT<real> (degree-1);
 
   unsigned int parameterPosDx=0, parameterPosDy=0;
@@ -208,19 +206,19 @@ BivariatePolynomialT<real>::findCriticalPoints (std::vector<real>& x_values, std
 
   if (degree == 2)
   {
-    real x = (real(2)*parameters[2]*parameters[3] - parameters[1]*parameters[4]) /
-             (parameters[1]*parameters[1] - real(4)*parameters[0]*parameters[3]),
-         y = (real(-2)*parameters[0]*x - parameters[2]) / parameters[1];
+    real x = (static_cast<real>(2)*parameters[2]*parameters[3] - parameters[1]*parameters[4]) /
+             (parameters[1]*parameters[1] - static_cast<real>(4)*parameters[0]*parameters[3]),
+         y = (static_cast<real>(-2)*parameters[0]*x - parameters[2]) / parameters[1];
 
     if (!std::isfinite(x) || !std::isfinite(y))
       return;
 
     int type = 2;
-    real det_H = real(4)*parameters[0]*parameters[3] - parameters[1]*parameters[1];
+    real det_H = static_cast<real>(4)*parameters[0]*parameters[3] - parameters[1]*parameters[1];
     //std::cout << "det(H) = "<<det_H<<"\n";
-    if (det_H > real(0))  // Check Hessian determinant
+    if (det_H > static_cast<real>(0))  // Check Hessian determinant
     {
-      if (parameters[0]+parameters[3] < real(0))  // Check Hessian trace
+      if (parameters[0]+parameters[3] < static_cast<real>(0))  // Check Hessian trace
         type = 0;
       else
         type = 1;
index f83b12ca2be4908f01f306e375a10260a8ac4eea..36d4317a14e4f479e2986f3d555ac0022d5f6758 100644 (file)
@@ -43,6 +43,7 @@
 #include <pcl/common/centroid.h>
 #include <pcl/conversions.h>
 #include <pcl/common/point_tests.h> // for pcl::isFinite
+#include <Eigen/Eigenvalues> // for EigenSolver
 
 #include <boost/fusion/algorithm/transformation/filter_if.hpp> // for boost::fusion::filter_if
 #include <boost/fusion/algorithm/iteration/for_each.hpp> // for boost::fusion::for_each
@@ -560,17 +561,17 @@ computeMeanAndCovarianceMatrix (const pcl::PointCloud<PointT> &cloud,
   if (point_count != 0)
   {
     accu /= static_cast<Scalar> (point_count);
-    centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z();
+    centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z();//effective mean E[P=(x,y,z)]
     centroid[3] = 1;
-    covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6];
-    covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7];
-    covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8];
-    covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7];
-    covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8];
-    covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8];
-    covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1);
-    covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2);
-    covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5);
+    covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6];//(0,0)xx : E[(x-E[x])^2]=E[x^2]-E[x]^2=E[(x-Kx)^2]-E[x-Kx]^2
+    covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7];//(0,1)xy : E[(x-E[x])(y-E[y])]=E[xy]-E[x]E[y]=E[(x-Kx)(y-Ky)]-E[x-Kx]E[y-Ky]
+    covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8];//(0,2)xz
+    covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7];//(1,1)yy
+    covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8];//(1,2)yz
+    covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8];//(2,2)zz
+    covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1);   //(1,0)yx
+    covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2);   //(2,0)zx
+    covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5);   //(2,1)zy
   }
   return (static_cast<unsigned int> (point_count));
 }
@@ -633,17 +634,17 @@ computeMeanAndCovarianceMatrix (const pcl::PointCloud<PointT> &cloud,
   if (point_count != 0)
   {
     accu /= static_cast<Scalar> (point_count);
-    centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z();
+    centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z();//effective mean E[P=(x,y,z)]
     centroid[3] = 1;
-    covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6];
-    covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7];
-    covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8];
-    covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7];
-    covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8];
-    covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8];
-    covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1);
-    covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2);
-    covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5);
+    covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6];//(0,0)xx : E[(x-E[x])^2]=E[x^2]-E[x]^2=E[(x-Kx)^2]-E[x-Kx]^2
+    covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7];//(0,1)xy : E[(x-E[x])(y-E[y])]=E[xy]-E[x]E[y]=E[(x-Kx)(y-Ky)]-E[x-Kx]E[y-Ky]
+    covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8];//(0,2)xz
+    covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7];//(1,1)yy
+    covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8];//(1,2)yz
+    covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8];//(2,2)zz
+    covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1);   //(1,0)yx
+    covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2);   //(2,0)zx
+    covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5);   //(2,1)zy
   }
   return (static_cast<unsigned int> (point_count));
 }
@@ -658,6 +659,275 @@ computeMeanAndCovarianceMatrix (const pcl::PointCloud<PointT> &cloud,
   return (computeMeanAndCovarianceMatrix (cloud, indices.indices, covariance_matrix, centroid));
 }
 
+template <typename PointT, typename Scalar> inline unsigned int
+computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
+  Eigen::Matrix<Scalar, 3, 1> &centroid,
+  Eigen::Matrix<Scalar, 3, 1> &obb_center,
+  Eigen::Matrix<Scalar, 3, 1> &obb_dimensions,
+  Eigen::Matrix<Scalar, 3, 3> &obb_rotational_matrix)
+{
+  Eigen::Matrix<Scalar, 3, 3> covariance_matrix;
+  Eigen::Matrix<Scalar, 4, 1> centroid4;
+  const auto point_count = computeMeanAndCovarianceMatrix(cloud, covariance_matrix, centroid4);
+  if (!point_count)
+    return (0);
+  centroid(0) = centroid4(0);
+  centroid(1) = centroid4(1);
+  centroid(2) = centroid4(2);
+
+  const Eigen::SelfAdjointEigenSolver<Eigen::Matrix<Scalar, 3, 3>> evd(covariance_matrix);
+  const Eigen::Matrix<Scalar, 3, 3> eigenvectors_ = evd.eigenvectors();
+  const Eigen::Matrix<Scalar, 3, 1> minor_axis = eigenvectors_.col(0);//the eigenvectors do not need to be normalized (they are already)
+  const Eigen::Matrix<Scalar, 3, 1> middle_axis = eigenvectors_.col(1);
+  // Enforce right hand rule:
+  const Eigen::Matrix<Scalar, 3, 1> major_axis = middle_axis.cross(minor_axis);
+
+  obb_rotational_matrix <<
+    major_axis(0), middle_axis(0), minor_axis(0),
+    major_axis(1), middle_axis(1), minor_axis(1),
+    major_axis(2), middle_axis(2), minor_axis(2);
+  //obb_rotational_matrix.col(0)==major_axis
+  //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
+  //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;
+
+  //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
+  Scalar obb_min_pointx, obb_min_pointy, obb_min_pointz;
+  Scalar obb_max_pointx, obb_max_pointy, obb_max_pointz;
+  obb_min_pointx = obb_min_pointy = obb_min_pointz = std::numeric_limits<Scalar>::max();
+  obb_max_pointx = obb_max_pointy = obb_max_pointz = std::numeric_limits<Scalar>::min();
+
+  if (cloud.is_dense)
+  {
+    const auto& point = cloud[0];
+    Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+    Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+    obb_min_pointx = obb_max_pointx = P(0);
+    obb_min_pointy = obb_max_pointy = P(1);
+    obb_min_pointz = obb_max_pointz = P(2);
+
+    for (size_t i=1; i<cloud.size();++i)
+    {
+      const auto&  point = cloud[i];
+      Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+      Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+      if (P(0) < obb_min_pointx)
+        obb_min_pointx = P(0);
+      else if (P(0) > obb_max_pointx)
+        obb_max_pointx = P(0);
+      if (P(1) < obb_min_pointy)
+        obb_min_pointy = P(1);
+      else if (P(1) > obb_max_pointy)
+        obb_max_pointy = P(1);
+      if (P(2) < obb_min_pointz)
+        obb_min_pointz = P(2);
+      else if (P(2) > obb_max_pointz)
+        obb_max_pointz = P(2);
+    }
+  }
+  else
+  {
+    size_t i = 0;
+    for (; i < cloud.size(); ++i)
+    {
+      const auto&  point = cloud[i];
+      if (!isFinite(point))
+        continue;
+      Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+      Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+      obb_min_pointx = obb_max_pointx = P(0);
+      obb_min_pointy = obb_max_pointy = P(1);
+      obb_min_pointz = obb_max_pointz = P(2);
+      ++i;
+      break;
+    }
+
+    for (; i<cloud.size();++i)
+    {
+      const auto&  point = cloud[i];
+      if (!isFinite(point))
+        continue;
+      Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+      Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+      if (P(0) < obb_min_pointx)
+        obb_min_pointx = P(0);
+      else if (P(0) > obb_max_pointx)
+        obb_max_pointx = P(0);
+      if (P(1) < obb_min_pointy)
+        obb_min_pointy = P(1);
+      else if (P(1) > obb_max_pointy)
+        obb_max_pointy = P(1);
+      if (P(2) < obb_min_pointz)
+        obb_min_pointz = P(2);
+      else if (P(2) > obb_max_pointz)
+        obb_max_pointz = P(2);
+    }
+
+  }
+
+  const Eigen::Matrix<Scalar, 3, 1>  //shift between point cloud centroid and OBB center (position of the OBB center relative to (p.c.centroid, major_axis, middle_axis, minor_axis))
+    shift((obb_max_pointx + obb_min_pointx) / 2.0f,
+      (obb_max_pointy + obb_min_pointy) / 2.0f,
+      (obb_max_pointz + obb_min_pointz) / 2.0f);
+
+  obb_dimensions(0) = obb_max_pointx - obb_min_pointx;
+  obb_dimensions(1) = obb_max_pointy - obb_min_pointy;
+  obb_dimensions(2) = obb_max_pointz - obb_min_pointz;
+
+  obb_center = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud
+
+  return (point_count);
+}
+
+
+template <typename PointT, typename Scalar> inline unsigned int
+computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
+  const Indices &indices,
+  Eigen::Matrix<Scalar, 3, 1> &centroid,
+  Eigen::Matrix<Scalar, 3, 1> &obb_center,
+  Eigen::Matrix<Scalar, 3, 1> &obb_dimensions,
+  Eigen::Matrix<Scalar, 3, 3> &obb_rotational_matrix)
+{
+  Eigen::Matrix<Scalar, 3, 3> covariance_matrix;
+  Eigen::Matrix<Scalar, 4, 1> centroid4;
+  const auto point_count = computeMeanAndCovarianceMatrix(cloud, indices, covariance_matrix, centroid4);
+  if (!point_count)
+    return (0);
+  centroid(0) = centroid4(0);
+  centroid(1) = centroid4(1);
+  centroid(2) = centroid4(2);
+
+  const Eigen::SelfAdjointEigenSolver<Eigen::Matrix<Scalar, 3, 3>> evd(covariance_matrix);
+  const Eigen::Matrix<Scalar, 3, 3> eigenvectors_ = evd.eigenvectors();
+  const Eigen::Matrix<Scalar, 3, 1> minor_axis = eigenvectors_.col(0);//the eigenvectors do not need to be normalized (they are already)
+  const Eigen::Matrix<Scalar, 3, 1> middle_axis = eigenvectors_.col(1);
+  // Enforce right hand rule:
+  const Eigen::Matrix<Scalar, 3, 1> major_axis = middle_axis.cross(minor_axis);
+
+  obb_rotational_matrix <<
+    major_axis(0), middle_axis(0), minor_axis(0),
+    major_axis(1), middle_axis(1), minor_axis(1),
+    major_axis(2), middle_axis(2), minor_axis(2);
+  //obb_rotational_matrix.col(0)==major_axis
+  //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
+  //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;
+
+  //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
+  Scalar obb_min_pointx, obb_min_pointy, obb_min_pointz;
+  Scalar obb_max_pointx, obb_max_pointy, obb_max_pointz;
+  obb_min_pointx = obb_min_pointy = obb_min_pointz = std::numeric_limits<Scalar>::max();
+  obb_max_pointx = obb_max_pointy = obb_max_pointz = std::numeric_limits<Scalar>::min();
+
+  if (cloud.is_dense)
+  {
+    const auto&  point = cloud[indices[0]];
+    Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+    Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+    obb_min_pointx = obb_max_pointx = P(0);
+    obb_min_pointy = obb_max_pointy = P(1);
+    obb_min_pointz = obb_max_pointz = P(2);
+
+    for (size_t i=1; i<indices.size();++i)
+    {
+      const auto &  point = cloud[indices[i]];
+
+      Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+      Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+      if (P(0) < obb_min_pointx)
+        obb_min_pointx = P(0);
+      else if (P(0) > obb_max_pointx)
+        obb_max_pointx = P(0);
+      if (P(1) < obb_min_pointy)
+        obb_min_pointy = P(1);
+      else if (P(1) > obb_max_pointy)
+        obb_max_pointy = P(1);
+      if (P(2) < obb_min_pointz)
+        obb_min_pointz = P(2);
+      else if (P(2) > obb_max_pointz)
+        obb_max_pointz = P(2);
+    }
+  }
+  else
+  {
+    size_t i = 0;
+    for (; i<indices.size();++i)
+    {
+      const auto&  point = cloud[indices[i]];
+      if (!isFinite(point))
+        continue;
+      Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+      Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+      obb_min_pointx = obb_max_pointx = P(0);
+      obb_min_pointy = obb_max_pointy = P(1);
+      obb_min_pointz = obb_max_pointz = P(2);
+      ++i;
+      break;
+    }
+
+    for (; i<indices.size();++i)
+    {
+      const auto&  point = cloud[indices[i]];
+      if (!isFinite(point))
+        continue;
+
+      Eigen::Matrix<Scalar, 4, 1> P0(static_cast<Scalar>(point.x), static_cast<Scalar>(point.y) , static_cast<Scalar>(point.z), 1.0);
+      Eigen::Matrix<Scalar, 4, 1> P = transform * P0;
+
+      if (P(0) < obb_min_pointx)
+        obb_min_pointx = P(0);
+      else if (P(0) > obb_max_pointx)
+        obb_max_pointx = P(0);
+      if (P(1) < obb_min_pointy)
+        obb_min_pointy = P(1);
+      else if (P(1) > obb_max_pointy)
+        obb_max_pointy = P(1);
+      if (P(2) < obb_min_pointz)
+        obb_min_pointz = P(2);
+      else if (P(2) > obb_max_pointz)
+        obb_max_pointz = P(2);
+    }
+
+  }
+
+  const Eigen::Matrix<Scalar, 3, 1>  //shift between point cloud centroid and OBB center (position of the OBB center relative to (p.c.centroid, major_axis, middle_axis, minor_axis))
+    shift((obb_max_pointx + obb_min_pointx) / 2.0f,
+      (obb_max_pointy + obb_min_pointy) / 2.0f,
+      (obb_max_pointz + obb_min_pointz) / 2.0f);
+
+  obb_dimensions(0) = obb_max_pointx - obb_min_pointx;
+  obb_dimensions(1) = obb_max_pointy - obb_min_pointy;
+  obb_dimensions(2) = obb_max_pointz - obb_min_pointz;
+
+  obb_center = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud
+
+  return (point_count);
+}
+
+
 
 template <typename PointT, typename Scalar> void
 demeanPointCloud (ConstCloudIterator<PointT> &cloud_iterator,
index b4e80224abaffa7a9f16e0127633942f9c7db896..10326f0be3655c14ecfac8cf5e8029965274a00e 100644 (file)
@@ -168,7 +168,7 @@ pcl::getPointsInBox (const pcl::PointCloud<PointT> &cloud,
         continue;
       if (cloud[i].x > max_pt[0] || cloud[i].y > max_pt[1] || cloud[i].z > max_pt[2])
         continue;
-      indices[l++] = int (i);
+      indices[l++] = static_cast<int>(i);
     }
   }
   // NaN or Inf values could exist => check for them
@@ -186,7 +186,7 @@ pcl::getPointsInBox (const pcl::PointCloud<PointT> &cloud,
         continue;
       if (cloud[i].x > max_pt[0] || cloud[i].y > max_pt[1] || cloud[i].z > max_pt[2])
         continue;
-      indices[l++] = int (i);
+      indices[l++] = static_cast<int>(i);
     }
   }
   indices.resize (l);
@@ -210,7 +210,7 @@ pcl::getMaxDistance (const pcl::PointCloud<PointT> &cloud, const Eigen::Vector4f
       dist = (pivot_pt3 - pt).norm ();
       if (dist > max_dist)
       {
-        max_idx = int (i);
+        max_idx = static_cast<int>(i);
         max_dist = dist;
       }
     }
@@ -227,7 +227,7 @@ pcl::getMaxDistance (const pcl::PointCloud<PointT> &cloud, const Eigen::Vector4f
       dist = (pivot_pt3 - pt).norm ();
       if (dist > max_dist)
       {
-        max_idx = int (i);
+        max_idx = static_cast<int>(i);
         max_dist = dist;
       }
     }
@@ -388,7 +388,7 @@ pcl::getCircumcircleRadius (const PointT &pa, const PointT &pb, const PointT &pc
 
   double p2p1 = (p2 - p1).norm (), p3p2 = (p3 - p2).norm (), p1p3 = (p1 - p3).norm ();
   // Calculate the area of the triangle using Heron's formula 
-  // (http://en.wikipedia.org/wiki/Heron's_formula)
+  // (https://en.wikipedia.org/wiki/Heron's_formula)
   double semiperimeter = (p2p1 + p3p2 + p1p3) / 2.0;
   double area = sqrt (semiperimeter * (semiperimeter - p2p1) * (semiperimeter - p3p2) * (semiperimeter - p1p3));
   // Compute the radius of the circumscribed circle
index d5978f539d7ccd28d8307b38d86f13b964f0fd7b..42843d090e377f60f44c9edd664a39baed92fa83 100644 (file)
@@ -118,10 +118,10 @@ struct CopyPointHelper<PointInT, PointOutT,
     using FieldListInT = typename pcl::traits::fieldList<PointInT>::type;
     using FieldListOutT = typename pcl::traits::fieldList<PointOutT>::type;
     using FieldList = typename pcl::intersect<FieldListInT, FieldListOutT>::type;
-    const std::uint32_t offset_in  = boost::mpl::if_<pcl::traits::has_field<PointInT, pcl::fields::rgb>,
+    constexpr std::uint32_t offset_in  = boost::mpl::if_<pcl::traits::has_field<PointInT, pcl::fields::rgb>,
                                                 pcl::traits::offset<PointInT, pcl::fields::rgb>,
                                                 pcl::traits::offset<PointInT, pcl::fields::rgba> >::type::value;
-    const std::uint32_t offset_out = boost::mpl::if_<pcl::traits::has_field<PointOutT, pcl::fields::rgb>,
+    constexpr std::uint32_t offset_out = boost::mpl::if_<pcl::traits::has_field<PointOutT, pcl::fields::rgb>,
                                                 pcl::traits::offset<PointOutT, pcl::fields::rgb>,
                                                 pcl::traits::offset<PointOutT, pcl::fields::rgba> >::type::value;
     pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (point_in, point_out));
index fbc9eb8a2b4304bdd7ab85affcf25e60b6ac69ef..031a8ee0b7cb4f1ad3c55bd9685503d94e31a031 100644 (file)
@@ -89,7 +89,7 @@ computeRoots (const Matrix& m, Roots& roots)
     computeRoots2 (c2, c1, roots);
   else
   {
-    const Scalar s_inv3 = Scalar (1.0 / 3.0);
+    constexpr Scalar s_inv3 = Scalar(1.0 / 3.0);
     const Scalar s_sqrt3 = std::sqrt (Scalar (3.0));
     // Construct the parameters used in classifying the roots of the equation
     // and in solving the equation for the roots in closed form.
@@ -285,8 +285,7 @@ getLargest3x3Eigenvector (const Matrix scaledMatrix)
 
   Index index;
   const Scalar length = len.maxCoeff (&index);  // <- first evaluation
-  return EigenVector<Vector, Scalar> {crossProduct.row (index) / length,
-                                      length};
+  return {crossProduct.row (index) / length, length};
 }
 
 }  // namespace detail
index 3b9c20b22c9f5d81a983ac395750a71b9cd506df..f8ecab25c023bfbe5812aab7c4b2f7e0d06491f7 100644 (file)
@@ -40,6 +40,7 @@
 #pragma once
 
 #include <pcl/common/gaussian.h>
+#include <cassert>
 
 namespace pcl
 {
index 3337d49a754f831640eef8c468c4085ec7548193..ea137ae316d391152fe19a4f502908100eada248 100644 (file)
@@ -111,21 +111,21 @@ CloudGenerator<PointT, GeneratorT>::setParametersForZ (const GeneratorParameters
 template <typename PointT, typename GeneratorT> const typename CloudGenerator<PointT, GeneratorT>::GeneratorParameters& 
 CloudGenerator<PointT, GeneratorT>::getParametersForX () const
 {
-  x_generator_.getParameters ();
+  return x_generator_.getParameters ();
 }
 
 
 template <typename PointT, typename GeneratorT> const typename CloudGenerator<PointT, GeneratorT>::GeneratorParameters& 
 CloudGenerator<PointT, GeneratorT>::getParametersForY () const
 {
-  y_generator_.getParameters ();
+  return y_generator_.getParameters ();
 }
 
 
 template <typename PointT, typename GeneratorT> const typename CloudGenerator<PointT, GeneratorT>::GeneratorParameters& 
 CloudGenerator<PointT, GeneratorT>::getParametersForZ () const
 {
-  z_generator_.getParameters ();
+  return z_generator_.getParameters ();
 }
 
 
@@ -230,14 +230,14 @@ CloudGenerator<pcl::PointXY, GeneratorT>::setParametersForY (const GeneratorPara
 template <typename GeneratorT> const typename CloudGenerator<pcl::PointXY, GeneratorT>::GeneratorParameters&
 CloudGenerator<pcl::PointXY, GeneratorT>::getParametersForX () const
 {
-  x_generator_.getParameters ();
+  return x_generator_.getParameters ();
 }
 
 
 template <typename GeneratorT> const typename CloudGenerator<pcl::PointXY, GeneratorT>::GeneratorParameters&
 CloudGenerator<pcl::PointXY, GeneratorT>::getParametersForY () const
 {
-  y_generator_.getParameters ();
+  return y_generator_.getParameters ();
 }
 
 
index ba7686ed792db9df3b0dd90dbf1a219fb367863a..75bbf74f77c7db71f0c2081f45227045ce993b68 100644 (file)
@@ -70,8 +70,8 @@ lineWithLineIntersection (const pcl::ModelCoefficients &line_a,
                           const pcl::ModelCoefficients &line_b,
                           Eigen::Vector4f &point, double sqr_eps)
 {
-  Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (&line_a.values[0], line_a.values.size ());
-  Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (&line_b.values[0], line_b.values.size ());
+  Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (line_a.values.data(), line_a.values.size ());
+  Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (line_b.values.data(), line_b.values.size ());
   return (lineWithLineIntersection (coeff1, coeff2, point, sqr_eps));
 }
 
index be77397dab300b58e349c664500285e3e995679f..aa40a9a4f7a0ab1c2e85184c95d3b16e62e914f2 100644 (file)
@@ -133,7 +133,7 @@ namespace detail
                         pcl::PointCloud<PointT> &cloud_out)
   {
     // Use std::copy directly, if the point types of two clouds are same
-    std::copy (&cloud_in[0], (&cloud_in[0]) + cloud_in.size (), &cloud_out[0]);
+    std::copy (cloud_in.data(), cloud_in.data() + cloud_in.size (), cloud_out.data());
   }
 
 } // namespace detail
@@ -360,8 +360,8 @@ copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT>
 
     if (border_type == pcl::BORDER_TRANSPARENT)
     {
-      const PointT* in = &(cloud_in[0]);
-      PointT* out = &(cloud_out[0]);
+      const PointT* in = cloud_in.data();
+      PointT* out = cloud_out.data();
       PointT* out_inner = out + cloud_out.width*top + left;
       for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width)
       {
@@ -387,8 +387,8 @@ copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT>
           for (int i = 0; i < right; i++)
             padding[i+left] = pcl::interpolatePointIndex (cloud_in.width+i, cloud_in.width, border_type);
 
-          const PointT* in = &(cloud_in[0]);
-          PointT* out = &(cloud_out[0]);
+          const PointT* in = cloud_in.data();
+          PointT* out = cloud_out.data();
           PointT* out_inner = out + cloud_out.width*top + left;
 
           for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width)
@@ -428,9 +428,9 @@ copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT>
         int right = cloud_out.width - cloud_in.width - left;
         int bottom = cloud_out.height - cloud_in.height - top;
         std::vector<PointT> buff (cloud_out.width, value);
-        PointT* buff_ptr = &(buff[0]);
-        const PointT* in = &(cloud_in[0]);
-        PointT* out = &(cloud_out[0]);
+        PointT* buff_ptr = buff.data();
+        const PointT* in = cloud_in.data();
+        PointT* out = cloud_out.data();
         PointT* out_inner = out + cloud_out.width*top + left;
 
         for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width)
index fac30862be0f381eaaa6e8a719dcd58c485f2f2d..3bebb2be1ea1ebff563ac5875c830256cdf415fe 100644 (file)
@@ -71,7 +71,7 @@ PCA<PointT>::initCompute ()
   demeanPointCloud (*input_, *indices_, mean_, cloud_demean);
   assert (cloud_demean.cols () == int (indices_->size ()));
   // Compute the product cloud_demean * cloud_demean^T
-  const Eigen::Matrix3f alpha = (1.f / (float (indices_->size ()) - 1.f))
+  const Eigen::Matrix3f alpha = (1.f / (static_cast<float>(indices_->size ()) - 1.f))
                                   * cloud_demean.topRows<3> () * cloud_demean.topRows<3> ().transpose ();
 
   // Compute eigen vectors and values
@@ -102,7 +102,7 @@ PCA<PointT>::update (const PointT& input_point, FLAG flag)
 
   Eigen::Vector3f input (input_point.x, input_point.y, input_point.z);
   const std::size_t n = eigenvectors_.cols ();// number of eigen vectors
-  Eigen::VectorXf meanp = (float(n) * (mean_.head<3>() + input)) / float(n + 1);
+  Eigen::VectorXf meanp = (static_cast<float>(n) * (mean_.head<3>() + input)) / static_cast<float>(n + 1);
   Eigen::VectorXf a = eigenvectors_.transpose() * (input - mean_.head<3>());
   Eigen::VectorXf y = (eigenvectors_ * a) + mean_.head<3>();
   Eigen::VectorXf h = y - input;
@@ -113,12 +113,12 @@ PCA<PointT>::update (const PointT& input_point, FLAG flag)
   float gamma = h.dot(input - mean_.head<3>());
   Eigen::MatrixXf D = Eigen::MatrixXf::Zero (a.size() + 1, a.size() + 1);
   D.block(0,0,n,n) = a * a.transpose();
-  D /=  float(n)/float((n+1) * (n+1));
+  D /=  static_cast<float>(n)/static_cast<float>((n+1) * (n+1));
   for(std::size_t i=0; i < a.size(); i++) {
-    D(i,i)+= float(n)/float(n+1)*eigenvalues_(i);
-    D(D.rows()-1,i) = float(n) / float((n+1) * (n+1)) * gamma * a(i);
+    D(i,i)+= static_cast<float>(n)/static_cast<float>(n+1)*eigenvalues_(i);
+    D(D.rows()-1,i) = static_cast<float>(n) / static_cast<float>((n+1) * (n+1)) * gamma * a(i);
     D(i,D.cols()-1) = D(D.rows()-1,i);
-    D(D.rows()-1,D.cols()-1) = float(n)/float((n+1) * (n+1)) * gamma * gamma;
+    D(D.rows()-1,D.cols()-1) = static_cast<float>(n)/static_cast<float>((n+1) * (n+1)) * gamma * gamma;
   }
 
   Eigen::MatrixXf R(D.rows(), D.cols());
index a53d5226cb938fe987bc9e711d2a487c398bc1f9..68f9ab9133d32d7c7d8652cf2325fbabf0d7d59d 100644 (file)
@@ -51,9 +51,9 @@ namespace common
 
 template <typename T>
 UniformGenerator<T>::UniformGenerator(T min, T max, std::uint32_t seed)
-  : distribution_ (min, max)
+  : parameters_ ({min, max, seed})
+  , distribution_ (min, max)
 {
-  parameters_ = Parameters (min, max, seed);
   if(parameters_.seed != static_cast<std::uint32_t> (-1))
     rng_.seed (seed);
 }
@@ -111,9 +111,9 @@ UniformGenerator<T>::setParameters (const Parameters& parameters)
 
 template <typename T>
 NormalGenerator<T>::NormalGenerator(T mean, T sigma, std::uint32_t seed)
-  : distribution_ (mean, sigma)
+  : parameters_ ({mean, sigma, seed})
+  , distribution_ (mean, sigma)
 {
-  parameters_ = Parameters (mean, sigma, seed);
   if(parameters_.seed != static_cast<std::uint32_t> (-1))
     rng_.seed (seed);
 }
index 5ff5370ae6f36ea4e7223d2eab6c88683ccca094..984b73065538b36815d575d40709b96c50151e76 100644 (file)
@@ -54,6 +54,7 @@ namespace pcl
   /** \brief Get the index of a specified field (i.e., dimension/channel)
     * \param[in] cloud the point cloud message
     * \param[in] field_name the string defining the field name
+    * \return the index of the field or a negative integer if no field with the given name exists
     * \ingroup common
     */
   inline int
@@ -71,6 +72,7 @@ namespace pcl
     * \tparam PointT datatype for which fields is being queries
     * \param[in] field_name the string defining the field name
     * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains
+    * \return the index of the field or a negative integer if no field with the given name exists
     * \ingroup common
     */
   template <typename PointT> inline int
@@ -107,8 +109,14 @@ namespace pcl
   inline std::string
   getFieldsList (const pcl::PCLPointCloud2 &cloud)
   {
-    return std::accumulate(std::next (cloud.fields.begin ()), cloud.fields.end (), cloud.fields[0].name,
-        [](const auto& acc, const auto& field) { return acc + " " + field.name; });
+    if (cloud.fields.empty())
+    {
+      return "";
+    } else
+    {
+      return std::accumulate(std::next (cloud.fields.begin ()), cloud.fields.end (), cloud.fields[0].name,
+          [](const auto& acc, const auto& field) { return acc + " " + field.name; });
+    }
   }
 
   /** \brief Obtains the size of a specific field data type in bytes
index f48f0e1084a8f111e00f235015481174a4b703d3..c253a2b8f5ccae856ee15e63978e57ff2905e786 100644 (file)
 #include <pcl/pcl_base.h>
 #include <pcl/pcl_macros.h>
 
-namespace pcl 
+namespace pcl
 {
   /** Principal Component analysis (PCA) class.\n
-    *  Principal components are extracted by singular values decomposition on the 
-    * covariance matrix of the centered input cloud. Available data after pca computation 
+    *  Principal components are extracted by singular values decomposition on the
+    * covariance matrix of the centered input cloud. Available data after pca computation
     * are:\n
     * - The Mean of the input data\n
     * - The Eigenvectors: Ordered set of vectors representing the resultant principal components and the eigenspace cartesian basis (right-handed coordinate system).\n
     * - The Eigenvalues: Eigenvectors correspondent loadings ordered in descending order.\n\n
-    * Other methods allow projection in the eigenspace, reconstruction from eigenspace and 
-    *  update of the eigenspace with a new datum (according Matej Artec, Matjaz Jogan and 
+    * Other methods allow projection in the eigenspace, reconstruction from eigenspace and
+    *  update of the eigenspace with a new datum (according Matej Artec, Matjaz Jogan and
     * Ales Leonardis: "Incremental PCA for On-line Visual Learning and Recognition").
     *
     * \author Nizar Sallem
@@ -74,30 +74,29 @@ namespace pcl
       using Base::setInputCloud;
 
       /** Updating method flag */
-      enum FLAG 
+      enum FLAG
       {
         /** keep the new basis vectors if possible */
-        increase, 
+        increase,
         /** preserve subspace dimension */
         preserve
       };
-    
+
       /** \brief Default Constructor
         * \param basis_only flag to compute only the PCA basis
         */
       PCA (bool basis_only = false)
         : Base ()
-        , compute_done_ (false)
-        , basis_only_ (basis_only) 
+        , basis_only_ (basis_only)
       {}
 
       /** Copy Constructor
         * \param[in] pca PCA object
         */
-      PCA (PCA const & pca) 
+      PCA (PCA const & pca)
         : Base (pca)
         , compute_done_ (pca.compute_done_)
-        , basis_only_ (pca.basis_only_) 
+        , basis_only_ (pca.basis_only_)
         , eigenvectors_ (pca.eigenvectors_)
         , coefficients_ (pca.coefficients_)
         , mean_ (pca.mean_)
@@ -107,8 +106,8 @@ namespace pcl
       /** Assignment operator
         * \param[in] pca PCA object
         */
-      inline PCA& 
-      operator= (PCA const & pca) 
+      inline PCA&
+      operator= (PCA const & pca)
       {
         eigenvectors_ = pca.eigenvectors_;
         coefficients_ = pca.coefficients_;
@@ -116,13 +115,13 @@ namespace pcl
         mean_         = pca.mean_;
         return (*this);
       }
-      
+
       /** \brief Provide a pointer to the input dataset
         * \param cloud the const boost shared pointer to a PointCloud message
         */
-      inline void 
-      setInputCloud (const PointCloudConstPtr &cloud) override 
-      { 
+      inline void
+      setInputCloud (const PointCloudConstPtr &cloud) override
+      {
         Base::setInputCloud (cloud);
         compute_done_ = false;
       }
@@ -175,74 +174,74 @@ namespace pcl
       /** \brief Mean accessor
         * \throw InitFailedException
         */
-      inline Eigen::Vector4f& 
-      getMean () 
+      inline Eigen::Vector4f&
+      getMean ()
       {
         if (!compute_done_)
           initCompute ();
         if (!compute_done_)
-          PCL_THROW_EXCEPTION (InitFailedException, 
+          PCL_THROW_EXCEPTION (InitFailedException,
                                "[pcl::PCA::getMean] PCA initCompute failed");
         return (mean_);
       }
 
       /** Eigen Vectors accessor
-        * \return Column ordered eigenvectors, representing the eigenspace cartesian basis (right-handed coordinate system).        
+        * \return Column ordered eigenvectors, representing the eigenspace cartesian basis (right-handed coordinate system).
         * \throw InitFailedException
         */
-      inline Eigen::Matrix3f& 
-      getEigenVectors () 
+      inline Eigen::Matrix3f&
+      getEigenVectors ()
       {
         if (!compute_done_)
           initCompute ();
         if (!compute_done_)
-          PCL_THROW_EXCEPTION (InitFailedException, 
+          PCL_THROW_EXCEPTION (InitFailedException,
                                "[pcl::PCA::getEigenVectors] PCA initCompute failed");
         return (eigenvectors_);
       }
-      
+
       /** Eigen Values accessor
         * \throw InitFailedException
         */
-      inline Eigen::Vector3f& 
+      inline Eigen::Vector3f&
       getEigenValues ()
       {
         if (!compute_done_)
           initCompute ();
         if (!compute_done_)
-          PCL_THROW_EXCEPTION (InitFailedException, 
+          PCL_THROW_EXCEPTION (InitFailedException,
                                "[pcl::PCA::getEigenVectors] PCA getEigenValues failed");
         return (eigenvalues_);
       }
-      
+
       /** Coefficients accessor
         * \throw InitFailedException
         */
-      inline Eigen::MatrixXf& 
-      getCoefficients () 
+      inline Eigen::MatrixXf&
+      getCoefficients ()
       {
         if (!compute_done_)
           initCompute ();
         if (!compute_done_)
-          PCL_THROW_EXCEPTION (InitFailedException, 
+          PCL_THROW_EXCEPTION (InitFailedException,
                                "[pcl::PCA::getEigenVectors] PCA getCoefficients failed");
         return (coefficients_);
       }
-            
+
       /** update PCA with a new point
-        * \param[in] input input point 
+        * \param[in] input input point
         * \param[in] flag update flag
         * \throw InitFailedException
         */
-      inline void 
+      inline void
       update (const PointT& input, FLAG flag = preserve);
-      
+
       /** Project point on the eigenspace.
         * \param[in] input point from original dataset
         * \param[out] projection the point in eigen vectors space
         * \throw InitFailedException
         */
-      inline void 
+      inline void
       project (const PointT& input, PointT& projection);
 
       /** Project cloud on the eigenspace.
@@ -252,13 +251,13 @@ namespace pcl
         */
       inline void
       project (const PointCloud& input, PointCloud& projection);
-      
+
       /** Reconstruct point from its projection
         * \param[in] projection point from eigenvector space
         * \param[out] input reconstructed point
         * \throw InitFailedException
         */
-      inline void 
+      inline void
       reconstruct (const PointT& projection, PointT& input);
 
       /** Reconstruct cloud from its projection
@@ -272,7 +271,7 @@ namespace pcl
       inline bool
       initCompute ();
 
-      bool compute_done_;
+      bool compute_done_{false};
       bool basis_only_;
       Eigen::Matrix3f eigenvectors_;
       Eigen::MatrixXf coefficients_;
index 26d5cc7be135c667775af9a5b88cba6b6c25bcfa..7e91206ef9184166720c6d8689892160b0fae435 100644 (file)
@@ -64,17 +64,17 @@ namespace pcl
       
       // =====PUBLIC METHODS=====
       /** Solves an equation of the form ax^4 + bx^3 + cx^2 +dx + e = 0
-       *  See http://en.wikipedia.org/wiki/Quartic_equation#Summary_of_Ferrari.27s_method */
+       *  See https://en.wikipedia.org/wiki/Quartic_equation#Summary_of_Ferrari.27s_method */
       inline void
       solveQuarticEquation (real a, real b, real c, real d, real e, std::vector<real>& roots) const;
 
       /** Solves an equation of the form ax^3 + bx^2 + cx + d = 0
-       *  See http://en.wikipedia.org/wiki/Cubic_equation */
+       *  See https://en.wikipedia.org/wiki/Cubic_equation */
       inline void
       solveCubicEquation (real a, real b, real c, real d, std::vector<real>& roots) const;
 
       /** Solves an equation of the form ax^2 + bx + c = 0
-       *  See http://en.wikipedia.org/wiki/Quadratic_equation */
+       *  See https://en.wikipedia.org/wiki/Quadratic_equation */
       inline void
       solveQuadraticEquation (real a, real b, real c, std::vector<real>& roots) const;
 
index 7e9fdf40b5d6086591af5b58d64a65c1550f1efc..631b7443c685bf2cc30a244e5969f0f2b453068c 100644 (file)
@@ -151,21 +151,17 @@ namespace pcl
   }
 
   /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
-    * \param[in] msg the PCLPointCloud2 binary blob
+    * \param[in] msg the PCLPointCloud2 binary blob (note that the binary point data in msg.data will not be used!)
     * \param[out] cloud the resultant pcl::PointCloud<T>
     * \param[in] field_map a MsgFieldMap object
+    * \param[in] msg_data pointer to binary blob data, used instead of msg.data
     *
-    * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) directly or create you
-    * own MsgFieldMap using:
-    *
-    * \code
-    * MsgFieldMap field_map;
-    * createMapping<PointT> (msg.fields, field_map);
-    * \endcode
+    * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) instead, except if you have a binary blob of
+    * point data that you do not want to copy into a pcl::PCLPointCloud2 in order to use fromPCLPointCloud2.
     */
   template <typename PointT> void
   fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud,
-              const MsgFieldMap& field_map)
+              const MsgFieldMap& field_map, const std::uint8_t* msg_data)
   {
     // Copy info fields
     cloud.header   = msg.header;
@@ -173,9 +169,18 @@ namespace pcl
     cloud.height   = msg.height;
     cloud.is_dense = msg.is_dense == 1;
 
-    // Copy point data
+    // Resize cloud
     cloud.resize (msg.width * msg.height);
-    std::uint8_t* cloud_data = reinterpret_cast<std::uint8_t*>(&cloud[0]);
+
+    // check if there is data to copy
+    if (msg.width * msg.height == 0)
+    {
+      PCL_WARN("[pcl::fromPCLPointCloud2] No data to copy.\n");
+      return;
+    }
+
+    // Copy point data
+    std::uint8_t* cloud_data = reinterpret_cast<std::uint8_t*>(cloud.data());
 
     // Check if we can copy adjacent points in a single memcpy.  We can do so if there
     // is exactly one field to copy and it is the same size as the source and destination
@@ -187,11 +192,10 @@ namespace pcl
         field_map[0].size == sizeof(PointT))
     {
       const auto cloud_row_step = (sizeof (PointT) * cloud.width);
-      const std::uint8_t* msg_data = &msg.data[0];
       // Should usually be able to copy all rows at once
       if (msg.row_step == cloud_row_step)
       {
-        std::copy(msg.data.cbegin(), msg.data.cend(), cloud_data);
+        memcpy (cloud_data, msg_data, msg.width * msg.height * sizeof(PointT));
       }
       else
       {
@@ -203,10 +207,10 @@ namespace pcl
     else
     {
       // If not, memcpy each group of contiguous fields separately
-      for (uindex_t row = 0; row < msg.height; ++row)
+      for (std::size_t row = 0; row < msg.height; ++row)
       {
-        const std::uint8_t* row_data = &msg.data[row * msg.row_step];
-        for (uindex_t col = 0; col < msg.width; ++col)
+        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 (const detail::FieldMapping& mapping : field_map)
@@ -220,6 +224,26 @@ namespace pcl
     }
   }
 
+  /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
+    * \param[in] msg the PCLPointCloud2 binary blob
+    * \param[out] cloud the resultant pcl::PointCloud<T>
+    * \param[in] field_map a MsgFieldMap object
+    *
+    * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud<T>) directly or create you
+    * own MsgFieldMap using:
+    *
+    * \code
+    * MsgFieldMap field_map;
+    * createMapping<PointT> (msg.fields, field_map);
+    * \endcode
+    */
+  template <typename PointT> void
+  fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud,
+              const MsgFieldMap& field_map)
+  {
+    fromPCLPointCloud2 (msg, cloud, field_map, msg.data.data());
+  }
+
   /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object.
     * \param[in] msg the PCLPointCloud2 binary blob
     * \param[out] cloud the resultant pcl::PointCloud<T>
@@ -257,7 +281,7 @@ namespace pcl
     msg.data.resize (data_size);
     if (data_size)
     {
-      memcpy(&msg.data[0], &cloud[0], data_size);
+      memcpy(msg.data.data(), cloud.data(), data_size);
     }
 
     // Fill fields metadata
index 5053d887c047fc3c3b92795587af6b874080c0f4..3814839c89cd86102ac51d88efcc23b7e40e136d 100644 (file)
@@ -78,25 +78,25 @@ namespace pcl
       {}
       
       const char*
-      getFileName () const throw ()
+      getFileName () const noexcept
       {
         return (file_name_);
       }
 
       const char*
-      getFunctionName () const throw ()
+      getFunctionName () const noexcept
       {
         return (function_name_);
       }
 
       unsigned
-      getLineNumber () const throw ()
+      getLineNumber () const noexcept
       {
         return (line_number_);
       }
 
       const char*
-      detailedMessage () const throw ()
+      detailedMessage () const noexcept
       {
         return (what ());
       }
index c7671b822b373b3145d0d82d69142e47e6e7ff4b..04c3affaf5488564087f1bd06323b6131c70c338 100644 (file)
@@ -218,12 +218,12 @@ namespace pcl
 
       unsigned getCurrentPointIndex () const override
       {
-        return (unsigned (iterator_ - cloud_.begin ()));
+        return (static_cast<unsigned>(iterator_ - cloud_.begin ()));
       }
 
       unsigned getCurrentIndex () const override
       {
-        return (unsigned (iterator_ - cloud_.begin ()));
+        return (static_cast<unsigned>(iterator_ - cloud_.begin ()));
       }
 
       std::size_t size () const override
@@ -292,12 +292,12 @@ namespace pcl
 
       unsigned getCurrentPointIndex () const override
       {
-        return (unsigned (*iterator_));
+        return (static_cast<unsigned>(*iterator_));
       }
 
       unsigned getCurrentIndex () const override
       {
-        return (unsigned (iterator_ - indices_.begin ()));
+        return (static_cast<unsigned>(iterator_ - indices_.begin ()));
       }
 
       std::size_t size () const override
index 3caf96c4304f9635377c8a702c0303297f7c5a52..6e5489588286ca5235a4755335092e9a97d34326 100644 (file)
@@ -162,6 +162,7 @@ pcl::PCLBase<PointT>::initCompute ()
     catch (const std::bad_alloc&)
     {
       PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", input_->size ());
+      return (false);
     }
     for (auto i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = static_cast<int>(i); }
   }
index a3aee983201fc1414b1ab87e6a6d0419e568726c..cb08b4deb25262a6f415188909d9797991a071ae 100644 (file)
@@ -338,7 +338,7 @@ namespace pcl
 
   struct _PointXYZ
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
 
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
@@ -365,7 +365,7 @@ namespace pcl
 #endif
   struct _RGB
   {
-    PCL_ADD_RGB;
+    PCL_ADD_RGB
   };
 
   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const RGB& p);
@@ -401,7 +401,7 @@ namespace pcl
 
   struct _Intensity
   {
-    PCL_ADD_INTENSITY;
+    PCL_ADD_INTENSITY
   };
 
   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity& p);
@@ -469,7 +469,7 @@ namespace pcl
     */
   struct EIGEN_ALIGN16 _PointXYZI
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -496,7 +496,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointXYZL
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
     std::uint32_t label;
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
@@ -527,8 +527,8 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointXYZRGBA
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_RGB;
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_RGB
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
 
@@ -574,15 +574,15 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointXYZRGB
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_RGB;
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_RGB
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
 
   struct EIGEN_ALIGN16 _PointXYZRGBL
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_RGB;
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_RGB
     std::uint32_t label;
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
@@ -666,7 +666,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointXYZLAB
   {
-    PCL_ADD_POINT4D; // this adds the members x,y,z
+    PCL_ADD_POINT4D // this adds the members x,y,z
     union
     {
       struct
@@ -701,7 +701,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointXYZHSV
   {
-    PCL_ADD_POINT4D;    // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D    // This adds the members x,y,z which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -740,26 +740,28 @@ namespace pcl
   /** \brief A 2D point structure representing Euclidean xy coordinates.
     * \ingroup common
     */
+  // NOLINTBEGIN(modernize-use-default-member-init)
   struct PointXY
   {
     union 
     { 
       float data[2]; 
       struct 
-      { 
-        float x; 
-        float y; 
+      {
+        float x;
+        float y;
       };
     };
 
     inline constexpr PointXY(float _x, float _y): x(_x), y(_y) {}
     inline constexpr PointXY(): x(0.0f), y(0.0f) {}
-    
+
     inline pcl::Vector2fMap getVector2fMap () { return (pcl::Vector2fMap (data)); }
     inline pcl::Vector2fMapConst getVector2fMap () const { return (pcl::Vector2fMapConst (data)); }
     
     friend std::ostream& operator << (std::ostream& os, const PointXY& p);
   };
+  // NOLINTEND(modernize-use-default-member-init)
 
   PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointUV& p);
   /** \brief A 2D point structure representing pixel image coordinates.
@@ -785,7 +787,7 @@ namespace pcl
   // @TODO: inheritance trick like on other PointTypes
   struct EIGEN_ALIGN16 InterestPoint
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -801,7 +803,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _Normal
   {
-    PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
+    PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -833,7 +835,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _Axis
   {
-    PCL_ADD_NORMAL4D;
+    PCL_ADD_NORMAL4D
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
 
@@ -856,8 +858,8 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointNormal
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -891,18 +893,18 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointXYZRGBNormal
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4])
     union
     {
       struct
       {
-        PCL_ADD_UNION_RGB;
+        PCL_ADD_UNION_RGB
         float curvature;
       };
       float data_c[4];
     };
-    PCL_ADD_EIGEN_MAPS_RGB;
+    PCL_ADD_EIGEN_MAPS_RGB
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
 
@@ -977,8 +979,8 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointXYZINormal
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -1020,8 +1022,8 @@ namespace pcl
 //----
   struct EIGEN_ALIGN16 _PointXYZLNormal
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -1065,7 +1067,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointWithRange
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -1096,7 +1098,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointWithViewpoint
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
     union
     {
       struct
@@ -1614,7 +1616,6 @@ namespace pcl
     inline constexpr IntensityGradient (): IntensityGradient (0.f, 0.f, 0.f) {}
 
     inline constexpr IntensityGradient (float _x, float _y, float _z): gradient_x (_x), gradient_y (_y), gradient_z (_z) {}
-
     friend std::ostream& operator << (std::ostream& os, const IntensityGradient& p);
   };
 
@@ -1631,7 +1632,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointWithScale
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
 
     union
     {
@@ -1671,20 +1672,20 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointSurfel
   {
-    PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4])
-    PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4])
+    PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4])
+    PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4])
     union
     {
       struct
       {
-        PCL_ADD_UNION_RGB;
+        PCL_ADD_UNION_RGB
         float radius;
         float confidence;
         float curvature;
       };
       float data_c[4];
     };
-    PCL_ADD_EIGEN_MAPS_RGB;
+    PCL_ADD_EIGEN_MAPS_RGB
     PCL_MAKE_ALIGNED_OPERATOR_NEW
   };
 
@@ -1715,7 +1716,7 @@ namespace pcl
 
   struct EIGEN_ALIGN16 _PointDEM
   {
-    PCL_ADD_POINT4D;
+    PCL_ADD_POINT4D
     float intensity;
     float intensity_variance;
     float height_variance;
@@ -1894,10 +1895,10 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBNormal,
     (float, x, x)
     (float, y, y)
     (float, z, z)
-    (float, rgb, rgb)
     (float, normal_x, normal_x)
     (float, normal_y, normal_y)
     (float, normal_z, normal_z)
+    (float, rgb, rgb)
     (float, curvature, curvature)
 )
 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBNormal, pcl::_PointXYZRGBNormal)
@@ -1905,20 +1906,20 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZINormal,
     (float, x, x)
     (float, y, y)
     (float, z, z)
-    (float, intensity, intensity)
     (float, normal_x, normal_x)
     (float, normal_y, normal_y)
     (float, normal_z, normal_z)
+    (float, intensity, intensity)
     (float, curvature, curvature)
 )
 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZLNormal,
     (float, x, x)
     (float, y, y)
     (float, z, z)
-    (std::uint32_t, label, label)
     (float, normal_x, normal_x)
     (float, normal_y, normal_y)
     (float, normal_z, normal_z)
+    (std::uint32_t, label, label)
     (float, curvature, curvature)
 )
 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithRange,
index 298c58b37aa9c34412ea27164b4994a14c61e4ae..da487b5e1bcff322f11016a837dc05675cbc65b3 100644 (file)
@@ -49,7 +49,7 @@
 
 #if defined _MSC_VER
   // 4244 : conversion from 'type1' to 'type2', possible loss of data
-  // 4661 : no suitable definition provided for explicit template instantiation reques
+  // 4661 : no suitable definition provided for explicit template instantiation request
   // 4503 : decorated name length exceeded, name was truncated
   // 4146 : unary minus operator applied to unsigned type, result still unsigned
   #pragma warning (disable: 4018 4244 4267 4521 4251 4661 4305 4503 4146)
index fa2172df178d82596d037e66dc58c8575d20a7b3..a5607bffced1a05b805abbe117491a71bd5a370f 100644 (file)
@@ -204,7 +204,7 @@ namespace pcl
         , height (height_)
       {}
 
-      //TODO: check if copy/move contructors/assignment operators are needed
+      //TODO: check if copy/move constructors/assignment operators are needed
 
       /** \brief Add a point cloud to the current cloud.
         * \param[in] rhs the cloud to add to the current cloud
index 5acdd9eb448d24ee14e1e45667b0a6abee8dcd75..17b2a0d422cde7245092504ad4ebf7bc10c5f0f0 100644 (file)
@@ -158,6 +158,24 @@ namespace pcl
         delete [] temp;
       }
 
+      void
+      vectorize (const PointT &p, float* out) const
+      {
+        copyToFloatArray (p, out);
+        if (!alpha_.empty ())
+          for (int i = 0; i < nr_dimensions_; ++i)
+            out[i] *= alpha_[i];
+      }
+
+      void
+      vectorize (const PointT &p, std::vector<float> &out) const
+      {
+        copyToFloatArray (p, out.data());
+        if (!alpha_.empty ())
+          for (int i = 0; i < nr_dimensions_; ++i)
+            out[i] *= alpha_[i];
+      }
+
       /** \brief Set the rescale values to use when vectorizing points
         * \param[in] rescale_array The array/vector of rescale values.  Can be of any type that implements the [] operator.
         */
@@ -245,12 +263,12 @@ namespace pcl
       using Pod = typename traits::POD<PointDefault>::type;
 
       NdCopyPointFunctor (const PointDefault &p1, float * p2)
-        : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
+        : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2) {}
 
       template<typename Key> inline void operator() ()
       {
         using FieldT = typename pcl::traits::datatype<PointDefault, Key>::type;
-        const int NrDims = pcl::traits::datatype<PointDefault, Key>::size;
+        constexpr int NrDims = pcl::traits::datatype<PointDefault, Key>::size;
         Helper<Key, FieldT, NrDims>::copyPoint (p1_, p2_, f_idx_);
       }
 
@@ -285,7 +303,7 @@ namespace pcl
     private:
       const Pod &p1_;
       float * p2_;
-      int f_idx_;
+      int f_idx_{0};
     };
 
     public:
index a4afdace33930d601253003436e2dc970d41c81f..23f8e68d860b826ea16f8d640eab77da4c987c20 100644 (file)
@@ -173,12 +173,12 @@ namespace pcl
     f[2] /= 1.08883;
 
     // CIEXYZ -> CIELAB
-    for (int i = 0; i < 3; ++i) {
-      if (f[i] > 0.008856) {
-        f[i] = std::pow(f[i], 1.0 / 3.0);
+    for (float & xyz : f) {
+      if (xyz > 0.008856) {
+        xyz = std::pow(xyz, 1.0 / 3.0);
       }
       else {
-        f[i] = 7.787 * f[i] + 16.0 / 116.0;
+        xyz = 7.787 * xyz + 16.0 / 116.0;
       }
     }
 
index 5731b4cc70a476c240f1197638e7858fb4efe33b..01e396e290e34d0be3799abc811956e3b75f53e7 100644 (file)
@@ -661,7 +661,7 @@ RangeImage::getAcutenessValue (const PointWithRange& point1, const PointWithRang
   float impact_angle = getImpactAngle (point1, point2);
   if (std::isinf (impact_angle))
     return -std::numeric_limits<float>::infinity ();
-  float ret = 1.0f - float (std::fabs (impact_angle)/ (0.5f*M_PI));
+  float ret = 1.0f - static_cast<float>(std::fabs (impact_angle)/ (0.5f*M_PI));
   if (impact_angle < 0.0f)
     ret = -ret;
   //if (std::abs (ret)>1)
@@ -682,7 +682,7 @@ RangeImage::getAcutenessValue (int x1, int y1, int x2, int y2) const
 const Eigen::Vector3f 
 RangeImage::getSensorPos () const
 {
-  return Eigen::Vector3f (to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3));
+  return {to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3)};
 }
 
 /////////////////////////////////////////////////////////////////////////
@@ -801,7 +801,7 @@ RangeImage::getMaxAngleSize (const Eigen::Affine3f& viewer_pose, const Eigen::Ve
 Eigen::Vector3f 
 RangeImage::getEigenVector3f (const PointWithRange& point)
 {
-  return Eigen::Vector3f (point.x, point.y, point.z);
+  return {point.x, point.y, point.z};
 }
 
 /////////////////////////////////////////////////////////////////////////
index 782516d564b8eaf489f2787f46f72b2955db33e0..051979fe91feea5913b4de4d1fbb05f220c25b99 100644 (file)
@@ -397,7 +397,7 @@ namespace pcl
       inline PointWithRange&
       getPoint (float image_x, float image_y);
 
-      /** \brief Return the 3D point with range at the given image position.  This methd performs no error checking
+      /** \brief Return the 3D point with range at the given image position.  This method performs no error checking
         * to make sure the specified image position is inside of the image!
         * \param image_x the x coordinate
         * \param image_y the y coordinate
@@ -590,13 +590,13 @@ namespace pcl
       getAcutenessValueImages (int pixel_distance, float*& acuteness_value_image_x,
                                float*& acuteness_value_image_y) const;
 
-      /** Calculates, how much the surface changes at a point. Pi meaning a flat suface and 0.0f
+      /** Calculates, how much the surface changes at a point. Pi meaning a flat surface and 0.0f
        *  would be a needle point */
       //inline float
       //  getSurfaceChange (const PointWithRange& point, const PointWithRange& neighbor1,
       //                   const PointWithRange& neighbor2) const;
 
-      /** Calculates, how much the surface changes at a point. 1 meaning a 90deg angle and 0 a flat suface */
+      /** Calculates, how much the surface changes at a point. 1 meaning a 90deg angle and 0 a flat surface */
       PCL_EXPORTS float
       getSurfaceChange (int x, int y, int radius) const;
 
@@ -767,13 +767,13 @@ namespace pcl
       // =====PROTECTED MEMBER VARIABLES=====
       Eigen::Affine3f to_range_image_system_;  /**< Inverse of to_world_system_ */
       Eigen::Affine3f to_world_system_;        /**< Inverse of to_range_image_system_ */
-      float angular_resolution_x_;             /**< Angular resolution of the range image in x direction in radians per pixel */
-      float angular_resolution_y_;             /**< Angular resolution of the range image in y direction in radians per pixel */
-      float angular_resolution_x_reciprocal_;  /**< 1.0/angular_resolution_x_ - provided for better performance of
+      float angular_resolution_x_{0.0f};             /**< Angular resolution of the range image in x direction in radians per pixel */
+      float angular_resolution_y_{0.0f};             /**< Angular resolution of the range image in y direction in radians per pixel */
+      float angular_resolution_x_reciprocal_{0.0f};  /**< 1.0/angular_resolution_x_ - provided for better performance of
                                                 *   multiplication compared to division */
-      float angular_resolution_y_reciprocal_;  /**< 1.0/angular_resolution_y_ - provided for better performance of
+      float angular_resolution_y_reciprocal_{0.0f};  /**< 1.0/angular_resolution_y_ - provided for better performance of
                                                 *   multiplication compared to division */
-      int image_offset_x_, image_offset_y_;    /**< Position of the top left corner of the range image compared to
+      int image_offset_x_{0}, image_offset_y_{0};    /**< Position of the top left corner of the range image compared to
                                                 *   an image of full size (360x180 degrees) */
       PointWithRange unobserved_point;         /**< This point is used to be able to return
                                                 *   a reference to a non-existing point */
index 3d2cac0704878647ae8f2e7dd278a4517c14ec00..85afe3889b37c8b3be558ed8e5d75a8d22302e22 100644 (file)
@@ -206,9 +206,9 @@ namespace pcl
 
 
     protected:
-      float focal_length_x_, focal_length_y_; //!< The focal length of the image in pixels
-      float focal_length_x_reciprocal_, focal_length_y_reciprocal_;  //!< 1/focal_length -> for internal use
-      float center_x_, center_y_;      //!< The principle point of the image
+      float focal_length_x_{0.0f}, focal_length_y_{0.0f}; //!< The focal length of the image in pixels
+      float focal_length_x_reciprocal_{0.0f}, focal_length_y_reciprocal_{0.0f};  //!< 1/focal_length -> for internal use
+      float center_x_{0.0f}, center_y_{0.0f};      //!< The principle point of the image
   };
 }  // namespace end
 
index 1a09228b834113fae33b8faf3a86d9132f811537..af9d32a0662ebcf096d47edb9dca0fb791bc8da4 100644 (file)
@@ -100,7 +100,7 @@ namespace pcl
     plus (std::remove_const_t<T> &l, const T &r)
     {
       using type = std::remove_all_extents_t<T>;
-      static const std::uint32_t count = sizeof (T) / sizeof (type);
+      constexpr std::uint32_t count = sizeof(T) / sizeof(type);
       for (std::uint32_t i = 0; i < count; ++i)
         l[i] += r[i];
     }
@@ -117,7 +117,7 @@ namespace pcl
     plusscalar (T1 &p, const T2 &scalar)
     {
       using type = std::remove_all_extents_t<T1>;
-      static const std::uint32_t count = sizeof (T1) / sizeof (type);
+      constexpr std::uint32_t count = sizeof(T1) / sizeof(type);
       for (std::uint32_t i = 0; i < count; ++i)
         p[i] += scalar;
     }
@@ -134,7 +134,7 @@ namespace pcl
     minus (std::remove_const_t<T> &l, const T &r)
     {
       using type = std::remove_all_extents_t<T>;
-      static const std::uint32_t count = sizeof (T) / sizeof (type);
+      constexpr std::uint32_t count = sizeof(T) / sizeof(type);
       for (std::uint32_t i = 0; i < count; ++i)
         l[i] -= r[i];
     }
@@ -151,7 +151,7 @@ namespace pcl
     minusscalar (T1 &p, const T2 &scalar)
     {
       using type = std::remove_all_extents_t<T1>;
-      static const std::uint32_t count = sizeof (T1) / sizeof (type);
+      constexpr std::uint32_t count = sizeof(T1) / sizeof(type);
       for (std::uint32_t i = 0; i < count; ++i)
         p[i] -= scalar;
     }
@@ -168,7 +168,7 @@ namespace pcl
     mulscalar (T1 &p, const T2 &scalar)
     {
       using type = std::remove_all_extents_t<T1>;
-      static const std::uint32_t count = sizeof (T1) / sizeof (type);
+      constexpr std::uint32_t count = sizeof(T1) / sizeof(type);
       for (std::uint32_t i = 0; i < count; ++i)
         p[i] *= scalar;
     }
@@ -185,7 +185,7 @@ namespace pcl
     divscalar (T1 &p, const T2 &scalar)
     {
       using type = std::remove_all_extents_t<T1>;
-      static const std::uint32_t count = sizeof (T1) / sizeof (type);
+      constexpr std::uint32_t count = sizeof (T1) / sizeof (type);
       for (std::uint32_t i = 0; i < count; ++i)
         p[i] /= scalar;
     }
@@ -202,7 +202,7 @@ namespace pcl
     divscalar2 (ArrayT &p, const ScalarT &scalar)
     {
       using type = std::remove_all_extents_t<ArrayT>;
-      static const std::uint32_t count = sizeof (ArrayT) / sizeof (type);
+      constexpr std::uint32_t count = sizeof (ArrayT) / sizeof (type);
       for (std::uint32_t i = 0; i < count; ++i)
         p[i] = scalar / p[i];
     }
index 20d18d66c3af646f9351292eebe366c72f38ec2c..f5a47a2acfafc2404ef45822bc2c86e2fd4d3525 100644 (file)
@@ -58,17 +58,13 @@ pcl::PCLPointCloud2::concatenate (pcl::PCLPointCloud2 &cloud1, const pcl::PCLPoi
   const auto size1 = cloud1.width * cloud1.height;
   const auto size2 = cloud2.width * cloud2.height;
   //if one input cloud has no points, but the other input does, just select the cloud with points
-  switch ((bool (size1) << 1) + bool (size2))
-  {
-    case 1:
-      cloud1 = cloud2;
-      PCL_FALLTHROUGH
-    case 0:
-    case 2:
-      cloud1.header.stamp = std::max (cloud1.header.stamp, cloud2.header.stamp);
-      return (true);
-    default:
-      break;
+  if ((size1 == 0) && (size2 != 0)) {
+    cloud1 = cloud2;
+  }
+
+  if ((size1 == 0) || (size2 == 0)) {
+    cloud1.header.stamp = std::max (cloud1.header.stamp, cloud2.header.stamp);
+    return true;
   }
 
   // Ideally this should be in PCLPointField class since this is global behavior
index 7c20c81e405404df7e2be01e4f657e7b21e8bdcd..085c20fb9b42131256f3546cbcdb7e4035ce0a7f 100644 (file)
@@ -114,7 +114,7 @@ BearingAngleImage::generateBAImage (PointCloud<PointXYZ>& point_cloud)
       points[(i + 1) * width + j].y = point_cloud.at (j, i + 1).y;
       points[(i + 1) * width + j].z = point_cloud.at (j, i + 1).z;
       // set the gray value for every pixel point
-      points[(i + 1) * width + j].rgba = ((int)r) << 24 | ((int)g) << 16 | ((int)b) << 8 | 0xff;
+      points[(i + 1) * width + j].rgba = (static_cast<int>(r)) << 24 | (static_cast<int>(g)) << 16 | (static_cast<int>(b)) << 8 | 0xff;
     }
   }
 }
index 24987bcee8499881c54df1e630b9b1e7b4f2de9f..77970055fd2c4210c35b4e32c1fff2890e665d4e 100644 (file)
@@ -38,6 +38,7 @@
 #include <pcl/point_types.h>
 #include <pcl/common/colors.h>
 
+#include <cassert>
 #include <array>
 
 /// Glasbey lookup table
@@ -609,9 +610,9 @@ pcl::getRandomColor (double min, double max)
   }
   while (sum <= min || sum >= max);
   pcl::RGB color;
-  color.r = std::uint8_t (r * 255.0);
-  color.g = std::uint8_t (g * 255.0);
-  color.b = std::uint8_t (b * 255.0);
+  color.r = static_cast<std::uint8_t>(r * 255.0);
+  color.g = static_cast<std::uint8_t>(g * 255.0);
+  color.b = static_cast<std::uint8_t>(b * 255.0);
   return (color);
 }
 
index e5fef1993b4d7899e4b0170315225b31a041c78b..2b6a667164f2d1bc5a2eed26c87f77a7ee0ceb3c 100644 (file)
@@ -36,6 +36,7 @@
  */
 
 #include <pcl/common/gaussian.h>
+#include <cassert>
 
 void 
 pcl::GaussianKernel::compute (float sigma, 
@@ -83,7 +84,7 @@ pcl::GaussianKernel::compute (float sigma,
   kernel.resize (kernel_width);
   derivative.resize (kernel_width);
   const float factor = 0.01f;
-  float max_gauss = 1.0f, max_deriv = float (sigma * std::exp (-0.5));
+  float max_gauss = 1.0f, max_deriv = static_cast<float>(sigma * std::exp (-0.5));
   int hw = kernel_width / 2;
 
   float sigma_sqr = 1.0f / (2.0f * sigma * sigma);
index c59ef0099a8e9b7e28302cfd8160acb8d772ef53..85d6f27dc3ae10ca4ce444869e757bc854003c2e 100644 (file)
@@ -93,9 +93,6 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
   cloud_out.height = cloud2.height;
   cloud_out.is_bigendian = cloud2.is_bigendian;
 
-  //We need to find how many fields overlap between the two clouds
-  std::size_t total_fields = cloud2.fields.size ();
-
   //for the non-matching fields in cloud1, we need to store the offset
   //from the beginning of the point
   std::vector<const pcl::PCLPointField*> cloud1_unique_fields;
@@ -142,8 +139,6 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
         size = cloud1.point_step - cloud1_fields_sorted[i]->offset;
 
       field_sizes.push_back (size);
-
-      total_fields++;
     }
   }
 
@@ -206,10 +201,7 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
     point_offset += field_offset;
   }
 
-  if (!cloud1.is_dense || !cloud2.is_dense)
-    cloud_out.is_dense = false;
-  else
-    cloud_out.is_dense = true;
+  cloud_out.is_dense = cloud1.is_dense && cloud2.is_dense;
 
   return (true);
 }
index 4b3f18da9a160e2dbfe071f2f404e1be11d72a5a..b53d0a87ead8bec749810293d30d8f25b791ec5d 100644 (file)
@@ -124,6 +124,7 @@ pcl::PCLBase<pcl::PCLPointCloud2>::initCompute ()
     catch (const std::bad_alloc&)
     {
       PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", (input_->width * input_->height));
+      return (false);
     }
     if (indices_size < indices_->size ())
       std::iota(indices_->begin () + indices_size, indices_->end (), indices_size);
index 342bad4e3450085c1b73d0033b20998f9f6bb35a..91ba59bf5fcf89fffb758e2dacfea874540651a5 100644 (file)
@@ -105,10 +105,7 @@ RangeImage::getCoordinateFrameTransformation (RangeImage::CoordinateFrame coordi
 /////////////////////////////////////////////////////////////////////////
 RangeImage::RangeImage () : 
   to_range_image_system_ (Eigen::Affine3f::Identity ()),
-  to_world_system_ (Eigen::Affine3f::Identity ()),
-  angular_resolution_x_ (0), angular_resolution_y_ (0),
-  angular_resolution_x_reciprocal_ (0), angular_resolution_y_reciprocal_ (0),
-  image_offset_x_ (0), image_offset_y_ (0)
+  to_world_system_ (Eigen::Affine3f::Identity ())
 {
   createLookupTables ();
   reset ();
@@ -459,9 +456,9 @@ float*
 RangeImage::getInterpolatedSurfaceProjection (const Eigen::Affine3f& pose, int pixel_size, float world_size) const
 {
   float max_dist = 0.5f*world_size,
-        cell_size = world_size/float (pixel_size);
+        cell_size = world_size/static_cast<float>(pixel_size);
   float world2cell_factor = 1.0f/cell_size,
-        world2cell_offset = 0.5f*float (pixel_size)-0.5f;
+        world2cell_offset = 0.5f*static_cast<float>(pixel_size)-0.5f;
   float cell2world_factor = cell_size,
         cell2world_offset = -max_dist + 0.5f*cell_size;
   Eigen::Affine3f inverse_pose = pose.inverse (Eigen::Isometry);
@@ -537,11 +534,11 @@ RangeImage::getInterpolatedSurfaceProjection (const Eigen::Affine3f& pose, int p
               cell3_y = world2cell_factor*point3[1] + world2cell_offset,
               cell3_z = point3[2];
         
-        int min_cell_x = (std::max) (0, int (pcl_lrint (std::ceil ( (std::min) (cell1_x, (std::min) (cell2_x, cell3_x)))))),
-            max_cell_x = (std::min) (pixel_size-1, int (pcl_lrint (std::floor ( (std::max) (cell1_x,
+        int min_cell_x = (std::max) (0, static_cast<int>(pcl_lrint (std::ceil ( (std::min) (cell1_x, (std::min) (cell2_x, cell3_x)))))),
+            max_cell_x = (std::min) (pixel_size-1, static_cast<int>(pcl_lrint (std::floor ( (std::max) (cell1_x,
                                                                        (std::max) (cell2_x, cell3_x)))))),
-            min_cell_y = (std::max) (0, int (pcl_lrint (std::ceil ( (std::min) (cell1_y, (std::min) (cell2_y, cell3_y)))))),
-            max_cell_y = (std::min) (pixel_size-1, int (pcl_lrint (std::floor ( (std::max) (cell1_y,
+            min_cell_y = (std::max) (0, static_cast<int>(pcl_lrint (std::ceil ( (std::min) (cell1_y, (std::min) (cell2_y, cell3_y)))))),
+            max_cell_y = (std::min) (pixel_size-1, static_cast<int>(pcl_lrint (std::floor ( (std::max) (cell1_y,
                                                                        (std::max) (cell2_y, cell3_y))))));
         if (max_cell_x<min_cell_x || max_cell_y<min_cell_y)
           continue;
@@ -720,9 +717,9 @@ RangeImage::getSurfaceAngleChangeImages (int radius, float*& angle_change_image_
   int size = width*height;
   angle_change_image_x = new float[size];
   angle_change_image_y = new float[size];
-  for (int y=0; y<int (height); ++y)
+  for (int y=0; y<static_cast<int>(height); ++y)
   {
-    for (int x=0; x<int (width); ++x)
+    for (int x=0; x<static_cast<int>(width); ++x)
     {
       int index = y*width+x;
       getSurfaceAngleChange (x, y, radius, angle_change_image_x[index], angle_change_image_y[index]);
@@ -739,9 +736,9 @@ RangeImage::getAcutenessValueImages (int pixel_distance, float*& acuteness_value
   int size = width*height;
   acuteness_value_image_x = new float[size];
   acuteness_value_image_y = new float[size];
-  for (int y=0; y<int (height); ++y)
+  for (int y=0; y<static_cast<int>(height); ++y)
   {
-    for (int x=0; x<int (width); ++x)
+    for (int x=0; x<static_cast<int>(width); ++x)
     {
       int index = y*width+x;
       acuteness_value_image_x[index] = getAcutenessValue (x, y, x+pixel_distance, y);
@@ -757,9 +754,9 @@ RangeImage::getImpactAngleImageBasedOnLocalNormals (int radius) const
   MEASURE_FUNCTION_TIME;
   int size = width*height;
   float* impact_angle_image = new float[size];
-  for (int y=0; y<int (height); ++y)
+  for (int y=0; y<static_cast<int>(height); ++y)
   {
-    for (int x=0; x<int (width); ++x)
+    for (int x=0; x<static_cast<int>(width); ++x)
     {
       impact_angle_image[y*width+x] = getImpactAngleBasedOnLocalNormal (x, y, radius);
     }
@@ -776,9 +773,9 @@ RangeImage::getRangeImageWithSmoothedSurface (int radius, RangeImage& smoothed_r
   
   smoothed_range_image = *this;
   Eigen::Vector3f sensor_pos = getSensorPos ();
-  for (int y=0; y<int (height); ++y)
+  for (int y=0; y<static_cast<int>(height); ++y)
   {
-    for (int x=0; x<int (width); ++x)
+    for (int x=0; x<static_cast<int>(width); ++x)
     {
       PointWithRange& point = smoothed_range_image.getPoint (x, y);
       if (std::isinf (point.range))
@@ -826,7 +823,7 @@ RangeImage::extractFarRanges (const pcl::PCLPointCloud2& point_cloud_data,
   }
   
   int point_step = point_cloud_data.point_step;
-  const unsigned char* data = &point_cloud_data.data[0];
+  const unsigned char* data = point_cloud_data.data.data();
   int x_offset = point_cloud_data.fields[x_idx].offset,
       y_offset = point_cloud_data.fields[y_idx].offset,
       z_offset = point_cloud_data.fields[z_idx].offset,
@@ -868,15 +865,14 @@ RangeImage::getOverlap (const RangeImage& other_range_image, const Eigen::Affine
   float max_distance_squared = max_distance*max_distance;
   
 #pragma omp parallel for \
-  default(none) \
   shared(max_distance_squared, other_range_image, pixel_step, relative_transformation, search_radius) \
   schedule(dynamic, 1) \
   reduction(+ : valid_points_counter) \
   reduction(+ : hits_counter) \
   num_threads(max_no_of_threads)
-  for (int other_y=0; other_y<int (other_range_image.height); other_y+=pixel_step)
+  for (int other_y=0; other_y<static_cast<int>(other_range_image.height); other_y+=pixel_step)
   {
-    for (int other_x=0; other_x<int (other_range_image.width); other_x+=pixel_step)
+    for (int other_x=0; other_x<static_cast<int>(other_range_image.width); other_x+=pixel_step)
     {
       const PointWithRange& point = other_range_image.getPoint (other_x, other_y);
       if (!std::isfinite (point.range))
@@ -920,9 +916,9 @@ RangeImage::getBlurredImageUsingIntegralImage (int blur_radius, float* integral_
                                                RangeImage& blurred_image) const
 {
   this->copyTo(blurred_image);
-  for (int y=0; y<int (height); ++y)
+  for (int y=0; y<static_cast<int>(height); ++y)
   {
-    for (int x=0; x<int (width); ++x)
+    for (int x=0; x<static_cast<int>(width); ++x)
     {
       const PointWithRange& old_point = getPoint (x, y);
       PointWithRange& new_point = blurred_image.getPoint (x, y);
index 97b249bc77acfb6d5a200a13d7c2d23ce9fe824f..206288016eae85329629927be400e27219a05f8e 100644 (file)
@@ -34,6 +34,7 @@
 
 /** \author Bastian Steder */
 
+#include <cassert>
 #include <iostream>
 using std::cout;
 using std::cerr;
@@ -43,11 +44,7 @@ using std::cerr;
 namespace pcl 
 {
   /////////////////////////////////////////////////////////////////////////
-  RangeImagePlanar::RangeImagePlanar () : focal_length_x_ (0.0f), focal_length_y_ (0.0f),
-                                          focal_length_x_reciprocal_ (0.0f), focal_length_y_reciprocal_ (0.0f),
-                                          center_x_ (0.0f), center_y_ (0.0f)
-  {
-  }
+  RangeImagePlanar::RangeImagePlanar () = default;
 
   /////////////////////////////////////////////////////////////////////////
   RangeImagePlanar::~RangeImagePlanar () = default;
index 4435f61f5b38a9e2ee4cdcc3e87e6e7c20b71ad0..16e7f249033ec6e7d22152db6fb6da3c7d2ebeb0 100644 (file)
@@ -255,7 +255,7 @@ namespace pcl
           return (points_x.size ());
         }
   
-        /** \brief Check if the internal pooint data vectors are valid. */
+        /** \brief Check if the internal point data vectors are valid. */
         bool 
         sane () const
         {
index 0932378c62d8395e800538fd05d6c526d7927953..7d2710297086f1ec1ad8665ecca1caeab96c3906 100644 (file)
@@ -26,6 +26,7 @@ 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)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
index ec6473eef8563f7fa9ed54e56cd3e8e64208e5fb..2b4c9720ad5ca7e72bb862673c63cdbc154d8f62 100644 (file)
@@ -80,7 +80,7 @@ namespace pcl
         float curvature = evals.x / (query_pt.z * (0.2f / 4.0f) * query_pt.z * (0.2f / 4.0f));
   
         float3 mc = normalize (evecs.data[0]);
-        // TODO: this should be an optional step, as it slows down eveything
+        // TODO: this should be an optional step, as it slows down everything
         // btw, this flips the normals to face the origin (assumed to be the view point)
         if ( dot (query_pt, mc) > 0 )
           mc = -mc;
index 8361560bbf316c1ce59dde077a431edf7300c33e..fcf78689437d40a763e21da2131efe48a91d8667 100644 (file)
@@ -37,6 +37,7 @@ 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)
 
 PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${SUBSYS_EXT_DEPS})
 
index b96cf182e5cd8bfc501d4b61e6b435999be68517..38a17aa490f16b3a4bc54026c6e349c578393059 100644 (file)
@@ -27,6 +27,7 @@ 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)
 
 set(EXT_DEPS "")
 #set(EXT_DEPS CUDA)
diff --git a/doc/advanced/.readthedocs.yaml b/doc/advanced/.readthedocs.yaml
new file mode 100644 (file)
index 0000000..c8d6adf
--- /dev/null
@@ -0,0 +1,22 @@
+# .readthedocs.yaml
+# Read the Docs configuration file
+# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details
+
+# Required
+version: 2
+
+build:
+  os: ubuntu-22.04
+  tools:
+    python: "3.11"
+
+sphinx:
+  configuration: doc/advanced/content/conf.py
+
+formats:
+  - epub
+  - pdf
+
+python:
+  install:
+    - requirements: doc/requirements.txt
index d337a6481a145fabd4ca3295ff5023749bcef254..18eadc8ccb11155fea226dac0ba0a99fc0015eb8 100644 (file)
@@ -102,6 +102,6 @@ rule that can be applied but here are some of the most used guidelines:
 
   * exit with some error if the exception is critical
   * modify the parameters for the function that threw the exception and recall it again
-  * throw an exception with a meaningful message saying that you encountred an exception
+  * throw an exception with a meaningful message saying that you encountered an exception
   * continue (really bad)
 
index 34bbe40d667fa8f82f138c749db13414b6e9a103..19b10bd6cc571903a7afbe54ca3c2a8aecc276a2 100644 (file)
@@ -397,7 +397,7 @@ For get/set type methods the following rules apply:
 * If large amounts of data needs to be set (usually the case with input data
   in PCL) it is preferred to pass a boost shared pointer instead of the actual
   data.
-* Getters always need to pass exactly the same types as their repsective setters
+* Getters always need to pass exactly the same types as their respective setters
   and vice versa.
 * For getters, if only one argument needs to be passed this will be done via
   the return keyword. If two or more arguments need to be passed they will
index 94a39d69719c0defb4b1d9470af7841fb04a28ca..359856681b3f1d42c945fd07eaba258ea7408bfa 100644 (file)
@@ -12,7 +12,7 @@ recognize objects in the world based on their geometric appearance, and create
 surfaces from point clouds and visualize them -- to name a few.
 
 PCL is released under the terms of the <a
-href="http://en.wikipedia.org/wiki/BSD_licenses#3-clause_license_.28.22New_BSD_License.22_or_.22Modified_BSD_License.22.29">
+href="https://en.wikipedia.org/wiki/BSD_licenses#3-clause_license_.28.22New_BSD_License.22_or_.22Modified_BSD_License.22.29">
 BSD license</a> and is open source software.  <b>It is free for commercial and
 research use.</b>
 
index bf23e751b29a6d1f2dfb4653c7bb96fc8cccab18..d8fb1391eff298e4a74bf46909bced1c0e9de6b7 100644 (file)
@@ -1,2 +1,3 @@
 sphinx>=3
 sphinxcontrib-doxylink
+sphinx-rtd-theme
diff --git a/doc/tutorials/.readthedocs.yaml b/doc/tutorials/.readthedocs.yaml
new file mode 100644 (file)
index 0000000..e0ee8c8
--- /dev/null
@@ -0,0 +1,22 @@
+# .readthedocs.yaml
+# Read the Docs configuration file
+# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details
+
+# Required
+version: 2
+
+build:
+  os: ubuntu-22.04
+  tools:
+    python: "3.11"
+
+sphinx:
+  configuration: doc/tutorials/content/conf.py
+
+formats:
+  - epub
+  - pdf
+
+python:
+  install:
+    - requirements: doc/requirements.txt
index 95f2e3bb16d4e82013162716ba3f23337f446ef6..d0b07ce1ffd855dec9c00cab4ef7002b394c070e 100644 (file)
@@ -176,7 +176,6 @@ The available ROOTs you can set are as follow:
 * **CMINPACK_ROOT**: for cminpack with value `C:/Program Files/CMINPACK 1.1.13` for instance
 * **QHULL_ROOT**: for qhull with value `C:/Program Files/qhull 6.2.0.1373` for instance
 * **FLANN_ROOT**: for flann with value `C:/Program Files/flann 1.6.8` for instance
-* **EIGEN_ROOT**: for eigen with value `C:/Program Files/Eigen 3.0.0` for instance
 
 To ensure that all the dependencies were correctly found, beside the
 message you get from CMake, you can check or edit each dependency specific
@@ -198,31 +197,31 @@ then a sample value is given for reference.
 
 * Boost
 
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+ 
-| cache variable                   | meaning                                                       | sample value                             |
-+==================================+===============================================================+==========================================+
-| Boost_DATE_TIME_LIBRARY          | full path to boost_date-time.[so,lib,a]                       | /usr/local/lib/libboost_date_time.so     |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_DATE_TIME_LIBRARY_DEBUG    | full path to boost_date-time.[so,lib,a] (debug version)       | /usr/local/lib/libboost_date_time-gd.so  |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_DATE_TIME_LIBRARY_RELEASE  | full path to boost_date-time.[so,lib,a] (release version)     | /usr/local/lib/libboost_date_time.so     |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_FILESYSTEM_LIBRARY         | full path to boost_filesystem.[so,lib,a]                      | /usr/local/lib/libboost_filesystem.so    |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_FILESYSTEM_LIBRARY_DEBUG   | full path to boost_filesystem.[so,lib,a] (debug version)      | /usr/local/lib/libboost_filesystem-gd.so |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_FILESYSTEM_LIBRARY_RELEASE | full path to boost_filesystem.[so,lib,a] (release version)    | /usr/local/lib/libboost_filesystem.so    |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_INCLUDE_DIR                | path to boost headers directory                               | /usr/local/include                       |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_LIBRARY_DIRS               | path to boost libraries directory                             | /usr/local/lib                           |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_SYSTEM_LIBRARY             | full path to boost_system.[so,lib,a]                          | /usr/local/lib/libboost_system.so        |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_SYSTEM_LIBRARY_DEBUG       | full path to boost_system.[so,lib,a] (debug version)          | /usr/local/lib/libboost_system-gd.so     |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
-| Boost_SYSTEM_LIBRARY_RELEASE     | full path to boost_system.[so,lib,a] (release version)        | /usr/local/lib/libboost_system.so        |
-+----------------------------------+---------------------------------------------------------------+------------------------------------------+
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ 
+| cache variable                      | meaning                                                       | sample value                                |
++=====================================+===============================================================+=============================================+
+| Boost_SERIALIZATION_LIBRARY         | full path to boost_serialization.[so,lib,a]                   | /usr/local/lib/libboost_serialization.so    |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_SERIALIZATION_LIBRARY_DEBUG   | full path to boost_serialization.[so,lib,a] (debug version)   | /usr/local/lib/libboost_serialization-gd.so |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_SERIALIZATION_LIBRARY_RELEASE | full path to boost_serialization.[so,lib,a] (release version) | /usr/local/lib/libboost_serialization.so    |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_FILESYSTEM_LIBRARY            | full path to boost_filesystem.[so,lib,a]                      | /usr/local/lib/libboost_filesystem.so       |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_FILESYSTEM_LIBRARY_DEBUG      | full path to boost_filesystem.[so,lib,a] (debug version)      | /usr/local/lib/libboost_filesystem-gd.so    |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_FILESYSTEM_LIBRARY_RELEASE    | full path to boost_filesystem.[so,lib,a] (release version)    | /usr/local/lib/libboost_filesystem.so       |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_INCLUDE_DIR                   | path to boost headers directory                               | /usr/local/include                          |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_LIBRARY_DIRS                  | path to boost libraries directory                             | /usr/local/lib                              |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_SYSTEM_LIBRARY                | full path to boost_system.[so,lib,a]                          | /usr/local/lib/libboost_system.so           |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_SYSTEM_LIBRARY_DEBUG          | full path to boost_system.[so,lib,a] (debug version)          | /usr/local/lib/libboost_system-gd.so        |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
+| Boost_SYSTEM_LIBRARY_RELEASE        | full path to boost_system.[so,lib,a] (release version)        | /usr/local/lib/libboost_system.so           |
++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+
 
 
 * CMinpack
@@ -253,9 +252,8 @@ then a sample value is given for reference.
 
 * Eigen
 
-+------------------+---------------------------------+---------------------------+
-| cache variable   | meaning                         | sample value              |
-+==================+=================================+===========================+ 
-| EIGEN_INCLUDE_DIR| path to eigen headers directory | /usr/local/include/eigen3 |
-+------------------+---------------------------------+---------------------------+
-
++--------------------+---------------------------------+-------------------------------+
+| cache variable     | meaning                         | sample value                  |
++====================+=================================+===============================+ 
+| Eigen3_DIR         | path to eigen cmake directory   | /usr/local/share/eigen3/cmake |
++--------------------+---------------------------------+-------------------------------+
index 1cc459b0619f5324a01846f0cf46733da7bfbf2e..7b2dbe6fb1096e8942b2b1d7797226b9500ea2b8 100644 (file)
@@ -171,10 +171,10 @@ You will see something similar to::
   PointCloud representing the Cluster: 290 data points.
   PointCloud representing the Cluster: 120 data points.
 
-You can also look at your outputs cloud_cluster_0.pcd, cloud_cluster_1.pcd,
-cloud_cluster_2.pcd, cloud_cluster_3.pcd and cloud_cluster_4.pcd::
+You can also look at your outputs cloud_cluster_0000.pcd, cloud_cluster_0001.pcd,
+cloud_cluster_0002.pcd, cloud_cluster_0003.pcd and cloud_cluster_0004.pcd::
 
-       $ ./pcl_viewer cloud_cluster_0.pcd cloud_cluster_1.pcd cloud_cluster_2.pcd cloud_cluster_3.pcd cloud_cluster_4.pcd
+       $ ./pcl_viewer cloud_cluster_0000.pcd cloud_cluster_0001.pcd cloud_cluster_0002.pcd cloud_cluster_0003.pcd cloud_cluster_0004.pcd
 
 You are now able to see the different clusters in one viewer. You should see
 something similar to this:
index 3265435ef8008d543f10fff9f6a32e5aad332b2f..b77120c819a105c2bcd932a536a763f575240b3b 100644 (file)
@@ -89,14 +89,13 @@ The following code libraries are **required** for the compilation and usage of t
 +---------------------------------------------------------------+-----------------+-------------------------+-------------------+
 | Logo                                                          | Library         | Minimum version         | Mandatory         |
 +===============================================================+=================+=========================+===================+
-| .. image:: images/posix_building_pcl/boost_logo.png           | Boost           | | 1.40 (without OpenNI) | pcl_*             |
-|                                                               |                 | | 1.47 (with OpenNI)    |                   |
+| .. image:: images/posix_building_pcl/boost_logo.png           | Boost           | 1.65                    | pcl_*             |
 +---------------------------------------------------------------+-----------------+-------------------------+-------------------+
-| .. image:: images/posix_building_pcl/eigen_logo.png           | Eigen           | 3.0                     | pcl_*             |
+| .. image:: images/posix_building_pcl/eigen_logo.png           | Eigen           | 3.3                     | pcl_*             |
 +---------------------------------------------------------------+-----------------+-------------------------+-------------------+
-| .. image:: images/posix_building_pcl/flann_logo.png           | FLANN           | 1.7.1                   | pcl_*             |
+| .. image:: images/posix_building_pcl/flann_logo.png           | FLANN           | 1.9.1                   | pcl_*             |
 +---------------------------------------------------------------+-----------------+-------------------------+-------------------+
-| .. image:: images/posix_building_pcl/vtk_logo.png             | VTK             | 5.6                     | pcl_visualization |
+| .. image:: images/posix_building_pcl/vtk_logo.png             | VTK             | 6.2                     | pcl_visualization |
 +---------------------------------------------------------------+-----------------+-------------------------+-------------------+
 
 Optional
index f03456e7724bf96de61715600c48214f75aa7008..41125fb50e971eac2d5b8ba21458f9ea8d0a60e7 100644 (file)
@@ -71,7 +71,7 @@ DepthSense Viewer
 
 The grabber is accompanied by an example tool `pcl_depth_sense_viewer <https://github.com/PointCloudLibrary/pcl/blob/master/visualization/tools/depth_sense_viewer.cpp>`_
 which can be used to view and save point clouds coming from a DepthSense device.
-Internally it uses the `DepthSenseGrabber <http://docs.pointclouds.org/trunk/classpcl_1_1_depth_sense_grabber.html>`_
+Internally it uses the `DepthSenseGrabber <https://pointclouds.org/documentation/classpcl_1_1_depth_sense_grabber.html>`_
 class that implements the standard PCL grabber interface.
 
 You can run the tool with `--help` option to view the usage guide.
index 5f3c0c4fcce334dcaabdc1978d395ad2e827893e..d83c1e47879c2b74cd9faa7f22c7c8915600159f 100644 (file)
@@ -41,69 +41,73 @@ The code from *apps/src/dinast_grabber_example.cpp* will be used for this tutori
   :linenos:
 
   #include <pcl/common/time.h>
-  #include <pcl/point_types.h>
   #include <pcl/io/dinast_grabber.h>
   #include <pcl/visualization/cloud_viewer.h>
+  #include <pcl/point_types.h>
+
+  #include <chrono>
+  #include <thread>
+
+  using namespace std::chrono_literals;
 
   template <typename PointType>
-  class DinastProcessor
-  {
-    public:
-      
-      typedef pcl::PointCloud<PointType> Cloud;
-      typedef typename Cloud::ConstPtr CloudConstPtr;
-      
-      DinastProcessor(pcl::Grabber& grabber) : interface(grabber), viewer("Dinast Cloud Viewer") {}
-
-      void 
-      cloud_cb_ (CloudConstPtr cloud_cb)
-      {
-        static unsigned count = 0;
-        static double last = pcl::getTime ();
-        if (++count == 30)
-        {
-          double now = pcl::getTime ();
-          std::cout << "Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
-          count = 0;
-          last = now;
-        }
-        if (!viewer.wasStopped())
-          viewer.showCloud(cloud_cb);
+  class DinastProcessor {
+  public:
+    using Cloud = pcl::PointCloud<PointType>;
+    using CloudConstPtr = typename Cloud::ConstPtr;
+
+    DinastProcessor(pcl::Grabber& grabber)
+    : interface(grabber), viewer("Dinast Cloud Viewer")
+    {}
+
+    void
+    cloud_cb_(CloudConstPtr cloud_cb)
+    {
+      static unsigned count = 0;
+      static double last = pcl::getTime();
+      if (++count == 30) {
+        double now = pcl::getTime();
+        std::cout << "Average framerate: " << double(count) / double(now - last) << " Hz"
+                  << std::endl;
+        count = 0;
+        last = now;
       }
-      
-      int 
-      run ()
-      {
-              
-        std::function<void (const CloudConstPtr&)> f =
-          [this] (const CloudConstPtr& cloud) { cloud_cb_ (cloud); };
-        
-        boost::signals2::connection c = interface.registerCallback (f);
+      if (!viewer.wasStopped())
+        viewer.showCloud(cloud_cb);
+    }
 
-        interface.start ();
-        
-        while (!viewer.wasStopped())
-        {
-          boost::this_thread::sleep (boost::posix_time::seconds (1));
-        }
-        
-        interface.stop ();
-        
-        return(0);
+    int
+    run()
+    {
+
+      std::function<void(const CloudConstPtr&)> f = [this](const CloudConstPtr& cloud) {
+        cloud_cb_(cloud);
+      };
+
+      boost::signals2::connection c = interface.registerCallback(f);
+
+      interface.start();
+
+      while (!viewer.wasStopped()) {
+        std::this_thread::sleep_for(1s);
       }
-      
-      pcl::Grabber& interface;
-      pcl::visualization::CloudViewer viewer;  
-      
+
+      interface.stop();
+
+      return 0;
+    }
+
+    pcl::Grabber& interface;
+    pcl::visualization::CloudViewer viewer;
   };
 
   int
-  main () 
+  main()
   {
     pcl::DinastGrabber grabber;
-    DinastProcessor<pcl::PointXYZI> v (grabber);
-    v.run ();
-    return (0);
+    DinastProcessor<pcl::PointXYZI> v(grabber);
+    v.run();
+    return 0;
   }
 
 The explanation
index a69d75904aae5407b09ace9c95af1bff338fac59..1f59383c1f30e2c74b4709c81a556ead7b2b1e17 100644 (file)
@@ -37,8 +37,8 @@ Compile and install PCL.
 Using the example
 =================
 
-The `pcl_ensenso_viewer <https://github.com/PointCloudLibrary/pcl/blob/master/visualization/tools/ensenso_viewer.cpp>`_ example shows how to
-display a point cloud grabbed from an Ensenso device using the `EnsensoGrabber <http://docs.pointclouds.org/trunk/classpcl_1_1_ensenso_grabber.html>`_ class.
+The `pcl_ensenso_viewer <https://github.com/PointCloudLibrary/pcl/blob/master/tools/ensenso_viewer.cpp>`_ example shows how to
+display a point cloud grabbed from an Ensenso device using the `EnsensoGrabber <https://pointclouds.org/documentation/classpcl_1_1_ensenso_grabber.html>`_ class.
 
 Note that this program opens the TCP port of the nxLib tree, this allows you to open the nxLib tree with the nxTreeEdit program (port 24000).
 The capture parameters (exposure, gain etc..) are set to default values.
index cdc9711ea83312d46cf67f0b23db2c0a12732474..1ee1d797590796f5adeead9ead9601544168675d 100644 (file)
@@ -84,13 +84,13 @@ Estimating FPFH features
 ------------------------
 
 Fast Point Feature Histograms are implemented in PCL as part of the
-`pcl_features <http://docs.pointclouds.org/trunk/a02944.html>`_
+`pcl_features <https://pointclouds.org/documentation/group__features.html>`_
 library. 
 
 The default FPFH implementation uses 11 binning subdivisions (e.g., each of the
 four feature values will use this many bins from its value interval), and a
 decorrelated scheme (see above: the feature histograms are computed separately
-and concantenated) which results in a 33-byte array of float values. These are
+and concatenated) which results in a 33-byte array of float values. These are
 stored in a **pcl::FPFHSignature33** point type.
 
 The following code snippet will estimate a set of FPFH features for all the
index 59ed23355c261b8adf04ba227a7f223e75842053..c8b3b8450c7d698c6cce39a6c7fcc67b75177cee 100644 (file)
@@ -4,7 +4,7 @@ Removing outliers using a custom non-destructive condition
 ----------------------------------------------------------
 
 This document demonstrates how to use the FunctionFilter class to remove points from a PointCloud that do not satisfy a custom criteria. This is a cleaner
-and faster appraoch compared to ConditionalRemoval filter or a `custom Condition class <https://cpp-optimizations.netlify.app/pcl_filter/>`_.
+and faster approach compared to ConditionalRemoval filter or a `custom Condition class <https://cpp-optimizations.netlify.app/pcl_filter/>`_.
 
 .. note::
    Advanced users can use the FunctorFilter class that can provide a small but measurable speedup when used with a `lambda <https://en.cppreference.com/w/cpp/language/lambda>`_.
index d8d1aa640787898ed5dfca988dae4c6276b45b35..f725e4ea69fc0db26f45b19b6874c55cacab76e0 100644 (file)
@@ -69,7 +69,7 @@ Estimating GASD features
 ------------------------
 
 The Globally Aligned Spatial Distribution is implemented in PCL as part of the
-`pcl_features <http://docs.pointclouds.org/trunk/group__features.html>`_
+`pcl_features <https://pointclouds.org/documentation/group__features.html>`_
 library.
 
 The default values for color GASD parameters are: :math:`m_s=6` (half size of 3), :math:`l_s=1`, :math:`m_c=4` (half size of 2) and :math:`l_c=12` and no histogram interpolation (INTERP_NONE). This results in an array of 984 float values. These are stored in a **pcl::GASDSignature984** point type. The default values for shape only GASD parameters are: :math:`m_s=8` (half size of 4), :math:`l_s=1` and trilinear histogram interpolation (INTERP_TRILINEAR). This results in an array of 512 float values, which may be stored in a **pcl::GASDSignature512** point type. It is also possible to use quadrilinear histogram interpolation (INTERP_QUADRILINEAR).
@@ -98,7 +98,7 @@ The following code snippet will estimate a GASD shape + color descriptor for an
      gasd.compute (descriptor);
 
      // Get the alignment transform
-     Eigen::Matrix4f trans = gasd.getTransform (trans);
+     Eigen::Matrix4f trans = gasd.getTransform ();
 
      // Unpack histogram bins
      for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i)
@@ -131,7 +131,7 @@ The following code snippet will estimate a GASD shape only descriptor for an inp
      gasd.compute (descriptor);
 
      // Get the alignment transform
-     Eigen::Matrix4f trans = gasd.getTransform (trans);
+     Eigen::Matrix4f trans = gasd.getTransform ();
 
      // Unpack histogram bins
      for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i)
index e0a411213523c7f7753572e5d308be12243591da..d30b56cfba01b175e68962f4ca0678dd4c50f65f 100644 (file)
@@ -99,7 +99,7 @@ Take a look at the full pipeline:
    :lines: 245-374
    :emphasize-lines: 6,9
 
-For a full explanation of the above code see `3D Object Recognition based on Correspondence Grouping <http://pointclouds.org/documentation/tutorials/correspondence_grouping.php>`_.
+For a full explanation of the above code see `3D Object Recognition based on Correspondence Grouping <https://pcl.readthedocs.io/projects/tutorials/en/master/correspondence_grouping.html>`_.
 
 
 Model-in-Scene Projection
index 5b58a5ceb9add4b8988fecab001380e5d55d7ec1..a06eaf12ec0bc5f747ee601f04152324dc6e9bb4 100644 (file)
@@ -4,7 +4,7 @@ Configuring your PC to use your Nvidia GPU with PCL
 ---------------------------------------------------
 
 In this tutorial you will learn how to configure your system to make it compatible to run the GPU methods provided by PCL.
-This tutorial is for Ubuntu, other Linux distrubutions can follow a similar process to set it up.  
+This tutorial is for Ubuntu, other Linux distributions can follow a similar process to set it up.  
 
 Windows is currently  **not** officially supported for the GPU methods.
 
index 3b0401f58ac7993dfac646d771518617b5a8f664..ba1b9f500a4e1a5e881252166e854e3475be3d17 100644 (file)
@@ -46,7 +46,7 @@ PCAP Files
 
 `Wireshark <http://www.wireshark.org/>`_ is a popular Network Packet Analyzer Program which
 is available for most platforms, including Linux, MacOS and Windows.  This tool uses a defacto
-standard network packet capture file format called `PCAP <http://en.wikipedia.org/wiki/Pcap>`_.
+standard network packet capture file format called `PCAP <https://en.wikipedia.org/wiki/Pcap>`_.
 Many publicly available Velodyne HDL packet captures use this PCAP file format as a means of
 recording and playback.  These PCAP files can be used with the HDL Grabber if PCL is compiled with
 PCAP support.
diff --git a/doc/tutorials/content/images/vcpkg/cmake_configure_1.png b/doc/tutorials/content/images/vcpkg/cmake_configure_1.png
new file mode 100644 (file)
index 0000000..7fee2aa
Binary files /dev/null and b/doc/tutorials/content/images/vcpkg/cmake_configure_1.png differ
diff --git a/doc/tutorials/content/images/vcpkg/cmake_configure_2.png b/doc/tutorials/content/images/vcpkg/cmake_configure_2.png
new file mode 100644 (file)
index 0000000..b1d2e0f
Binary files /dev/null and b/doc/tutorials/content/images/vcpkg/cmake_configure_2.png differ
index 1175e3971d0b2c46c4efc5be0817f38e3a90cb44..9ef736a49e7625be97002cc2bab588215166dc7e 100644 (file)
@@ -97,6 +97,21 @@ Basic Usage
      .. |mi_3| image:: images/pcl_ccmake.png
                :height: 100px
 
+  * :ref:`pcl_vcpkg_windows`
+
+     ======  ======
+     |mi_4|  Title: **Install PCL using VCPKG**
+
+             Author: *Lars Glud*
+
+             Compatibility: PCL version available on VCPKG and Master, unless VCPKG updates a dependency before PCL is ready for it.
+
+             In this tutorial,it is explained how to install PCL or PCL dependencies.
+     ======  ======
+
+     .. |mi_4| image:: images/windows_logo.png
+               :height: 100px
+
   * :ref:`compiling_pcl_dependencies_windows`
 
      ======  ======
index c6cf9db8688cff6571e4b8ea393d9c09059cfd41..08183c911cc5ce795b0d2f3733c70ab13f213a0c 100644 (file)
@@ -146,4 +146,4 @@ Once you have run it you should see something similar to this::
     356.962 247.285 514.959 (squared distance: 50423.7)
     282.065 509.488 516.216 (squared distance: 50730.4)
 
-.. [Wikipedia] http://en.wikipedia.org/wiki/K-d_tree
+.. [Wikipedia] https://en.wikipedia.org/wiki/K-d_tree
index 3fb1dd8823a371808bf0ac23f72e5fd14de18b60..109af80370c9e96cb07eec07fa2a4cad59c308a8 100644 (file)
@@ -78,7 +78,7 @@ The purpose of these lines is to show that ``pcl::MinCutSegmentation`` class can
    :lines: 21-21
 
 Here is the line where the instantiation of the ``pcl::MinCutSegmentation`` class takes place.
-It is the tamplate class that has only one parameter - PointT - which says what type of points will be used.
+It is the template class that has only one parameter - PointT - which says what type of points will be used.
 
 .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp
    :language: cpp
index a50834e286a456360970b123dcc310bde05b800c..262aacd9656ece772756919b1d3c6d6608053b77 100644 (file)
@@ -5,7 +5,8 @@ Moment of inertia and eccentricity based descriptors
 
 In this tutorial we will learn how to use the `pcl::MomentOfInertiaEstimation` class in order to obtain descriptors based on
 eccentricity and moment of inertia. This class also allows to extract axis aligned and oriented bounding boxes of the cloud.
-But keep in mind that extracted OBB is not the minimal possible bounding box.
+But keep in mind that extracted OBB is not the minimal possible bounding box. Users who only need the OBB or AABB, but not the descriptors,
+should use respectively computeCentroidAndOBB or getMinMax3D (faster).
 
 Theoretical Primer
 ------------------
@@ -33,7 +34,7 @@ The code
 --------
 
 First of all you will need the point cloud for this tutorial.
-`This <https://github.com/PointCloudLibrary/data/blob/master/tutorials/min_cut_segmentation_tutorial.pcd>`_ is the one presented on the screenshots.
+`This <https://github.com/PointCloudLibrary/data/blob/master/tutorials/lamppost.pcd>`_ is the one presented on the screenshots.
 Next what you need to do is to create a file ``moment_of_inertia.cpp`` in any editor you prefer and copy the following code inside of it:
 
 .. literalinclude:: sources/moment_of_inertia/moment_of_inertia.cpp
index c0885fa43d20d66545ab2578bf1906ee7f9163ff..702176ff85aeb913c911c61eb0d0ff5a9ec5595a 100644 (file)
@@ -250,8 +250,8 @@ normal estimation which uses multi-core/multi-threaded paradigms using OpenMP
 to speed the computation. The name of the class is
 **pcl::NormalEstimationOMP**, and its API is 100% compatible to the
 single-threaded **pcl::NormalEstimation**, which makes it suitable as a drop-in
-replacement. On a system with 8 cores, you should get anything between 6-8
-times faster computation times.
+replacement. On a system with n cores, you should get m times faster computation, with m<=n depending on several factors including CPU architecture, 
+point cloud characteristics, search parameters chosen, CPU global load.
 
 .. note::
 
index 662bdbe117ec750ee5cb291b45aa9de1b77f1ded..1ddb809a798fe00b9bc092fe15b4649ccdb3dcce 100644 (file)
@@ -46,7 +46,8 @@ The following normal estimation methods are available:
      {
        COVARIANCE_MATRIX,
        AVERAGE_3D_GRADIENT,
-       AVERAGE_DEPTH_CHANGE
+       AVERAGE_DEPTH_CHANGE,
+       SIMPLE_3D_GRADIENT
      };
         
 The COVARIANCE_MATRIX mode creates 9 integral images to compute the normal for
index 885f1247b03f40f2333de08a1f8d14dd309cf9ab..56fdb84e7c034aa559aa1fbcf7e13e8184e5df76 100644 (file)
@@ -36,13 +36,20 @@ the OpenNI Grabber.
   
   <iframe title="PCL OpenNI Viewer example" width="480" height="390" src="https://www.youtube.com/embed/x3SaWQkPsPI?rel=0" frameborder="0" allowfullscreen></iframe>
 
-So let's look at the code. From *visualization/tools/openni_viewer_simple.cpp*
+So let's look at the code. From *tools/openni_viewer_simple.cpp*
 
 .. code-block:: cpp
    :linenos:
 
     #include <pcl/io/openni_grabber.h>
     #include <pcl/visualization/cloud_viewer.h>
+
+
+    #include <chrono>
+    #include <thread>
+
+    using namespace std::chrono_literals;
+
     
     class SimpleOpenNIViewer
     {
@@ -68,7 +75,7 @@ So let's look at the code. From *visualization/tools/openni_viewer_simple.cpp*
               
           while (!viewer.wasStopped())
           {   
-            boost::this_thread::sleep (boost::posix_time::seconds (1));
+            std::this_thread::sleep_for(1s);
           }   
 
           interface->stop (); 
index 688da23b86f8a8b0656151ab669afceee686f4b6..3413e28c618dde7c361ec5538458351923668261 100644 (file)
@@ -22,15 +22,15 @@ graphics and computational geometry communities in particular, have created
 numerous formats to describe arbitrary polygons and point clouds acquired using
 laser scanners. Some of these formats include:
 
-* `PLY <http://en.wikipedia.org/wiki/PLY_(file_format)>`_ - a polygon file format, developed at Stanford University by Turk et al
+* `PLY <https://en.wikipedia.org/wiki/PLY_(file_format)>`_ - a polygon file format, developed at Stanford University by Turk et al
 
-* `STL <http://en.wikipedia.org/wiki/STL_(file_format)>`_ - a file format native to the stereolithography CAD software created by 3D Systems
+* `STL <https://en.wikipedia.org/wiki/STL_(file_format)>`_ - a file format native to the stereolithography CAD software created by 3D Systems
 
-* `OBJ <http://en.wikipedia.org/wiki/Wavefront_.obj_file>`_ - a geometry definition file format first developed by Wavefront Technologies 
+* `OBJ <https://en.wikipedia.org/wiki/Wavefront_.obj_file>`_ - a geometry definition file format first developed by Wavefront Technologies
 
-* `X3D <http://en.wikipedia.org/wiki/X3D>`_ - the ISO standard XML-based file format for representing 3D computer graphics data
+* `X3D <https://en.wikipedia.org/wiki/X3D>`_ - the ISO standard XML-based file format for representing 3D computer graphics data
 
-* `and many others <http://en.wikipedia.org/wiki/Category:Graphics_file_formats>`_
+* `and many others <https://en.wikipedia.org/wiki/Category:Graphics_file_formats>`_
 
 All the above file formats suffer from several shortcomings, as explained in
 the next sections -- which is natural, as they were created for a different
index 97cdd49e4f14bc049dbaa231ac7aa61d70ee257a..68f66de8317fddb4cd86d016e4847ab729d3326f 100644 (file)
@@ -5,7 +5,7 @@ PCLPlotter
 
 PCLPlotter provides a very straightforward and easy interface for plotting graphs. One can visualize all sort of important plots - 
 from polynomial functions to histograms - inside the library without going to any other software (like MATLAB). 
-Please go through the `documentation <http://docs.pointclouds.org/trunk/a01175.html>`_ when some specific concepts are introduced in this tutorial to know the exact method signatures.
+Please go through the `documentation <https://pointclouds.org/documentation/group__visualization.html>`_ when some specific concepts are introduced in this tutorial to know the exact method signatures.
 
 The code for the visualization of a plot are usually as simple as the following snippet.
 
diff --git a/doc/tutorials/content/pcl_vcpkg_windows.rst b/doc/tutorials/content/pcl_vcpkg_windows.rst
new file mode 100644 (file)
index 0000000..f97ebd7
--- /dev/null
@@ -0,0 +1,153 @@
+.. _pcl_vcpkg_windows:
+
+Using PCL on windows with VCPKG and CMake
+-----------------------------------------
+
+This tutorial explains how to acquire Point Cloud Library on
+Microsoft Windows platforms using `VCPKG <https://github.com/microsoft/vcpkg>`_.
+
+For additional information how to use VCPKG, please see their `documentation <https://github.com/microsoft/vcpkg/blob/master/docs/README.md>`_.
+
+Last updated: 22. December 2021
+
+.. image:: images/windows_logo.png
+   :alt: Microsoft Windows logo
+   :align: right
+
+.. contents::
+
+
+Requirements
+==================
+
+Download VCPKG sources to eg. *c:\\vcpkg* preferably by cloning their repository.
+
+Navigate to *c:\\vcpkg* in **powershell** and run 
+
+  .\\bootstrap-vcpkg.bat
+  
+This will download vcpkg.exe.
+
+
+PCL's dependencies
+==================
+
+PCL's required dependencies available on VCPKG are:
+
+* Boost
+* FLANN
+* Eigen3
+
+PCL's optional dependencies available on VCPKG are:
+
+* VTK - for visualization module
+  
+  * Feature OpenGL - required
+  * Feature Qt - optional for QVTK, used in apps
+  
+* GLEW - for simulation module
+* Qhull - for convex/concave in surface module
+* Qt - for apps that use Qt for GUI
+* Google Test - for unit tests
+* Google Benchmark - for benchmarks
+* OpenNI2
+* Realsense2
+* PNG - for a single openni app
+* Pcap - for Velodyne HDL driver
+
+PCL's optional dependencies not on VCPKG
+
+* CUDA - only a port that verify its installed (version 10.1).
+* GLUT
+* OpenNI
+* Ensenso
+* davidSDK
+* DSSDK
+* RSSDK
+
+
+Install PCL for usage
+=====================
+
+Running the following command in powershell in the VCPKG directory,
+will install PCL with default options as well as default triplet type (ie. x86).
+
+  ./vcpkg install pcl
+  
+.. note::
+  This will build executables 2 times in release mode, as default host triplet is x64-windows
+  on most modern PC systems, but vcpkg install x86 by default. So to fix it you can set
+  host-triplet same as default triplet.
+
+    ./vcpkg install pcl --host-triplet x86-windows 
+
+  Or, you can use same custom triplet for both --triplet and --host-triplet
+
+    ./vcpkg install pcl --triplet <same_custom_triplet_type> --host-triplet <same_custom_triplet_type>
+
+.. 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 see the available PCL version and options in VCPKG `here <https://github.com/microsoft/vcpkg/blob/master/ports/pcl/vcpkg.json>`_.
+
+To enable specific features, you need to write:
+
+  ./vcpkg install pcl[qt,vtk]
+
+And all features:
+
+  ./vcpkg install pcl[*]
+
+If you want to install with a different triplet type, the easiest way is:
+
+  ./vcpkg install pcl --triplet triplet_type
+  
+ie.
+  ./vcpkg install pcl --triplet x64-windows
+
+This will acquire all the dependencies, build them and place the binaries
+in vcpkg/installed/triplet_type/bin for release and vcpkg/installed/triplet_type/debug/bin for debug.
+
+
+Using dependencies installed with VCPKG in CMake projects
+=========================================================
+
+Use `CMake <https://cmake.org/download>`_ to configure projects and remember to pass **vcpkg\\scripts\\buildsystems\\vcpkg.cmake** as toolchain file
+to enable CMake to find all the dependencies installed with VCPKG.
+
+See example below using the cmake window:
+
+.. list-table:: 
+
+    * - .. figure:: images/vcpkg/cmake_configure_1.png
+
+           Fig 1. Cmake configuration
+
+      - .. figure:: images/vcpkg/cmake_configure_2.png
+
+           Fig 2. Cmake configuration with vcpkg tool chain
+           
+
+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>`_
+
+
+Install PCL dependencies for contributions
+==========================================
+
+If you want to contribute to PCL, the easiest way to get dependencies
+using vcpkg is to run the install command from our `docker file <https://github.com/PointCloudLibrary/pcl/blob/master/.dev/docker/windows/Dockerfile>`_
+
+  ./vcpkg install dependencies_here --triplet triplet_type
+
+Remember to omit the *--clean-after-build*, as this removes the source code of the dependencies and limit debugging capabilities for those.
+
+To build PCL, you would have to get the `source <https://github.com/PointCloudLibrary/pcl>`_, preferably clone it using git.
+
+Use `CMake <https://cmake.org/download>`_ to configure PCL.
+
index 1cedca26ac7a0e0cbe1b2dd819230df37730f7b2..af0a39d55af01ae9cea145562199e773f2adc0dd 100644 (file)
@@ -145,7 +145,7 @@ found at the bottom of the sample:
     while (!viewer->wasStopped ())
     {
       viewer->spinOnce (100);
-      boost::this_thread::sleep (boost::posix_time::microseconds (100000));
+      std::this_thread::sleep_for(100ms);
     }
     ...
 
index 423d2a8ef9dfc60109a1092e857925261edfafaa..0f67e4571bf050aa486d4a24f88fa1fae9de6b58 100644 (file)
@@ -116,7 +116,7 @@ Estimating PFH features
 -----------------------
 
 Point Feature Histograms are implemented in PCL as part of the `pcl_features
-<http://docs.pointclouds.org/trunk/a02944.html>`_ library. 
+<https://pointclouds.org/documentation/group__features.html>`_ library. 
 
 The default PFH implementation uses 5 binning subdivisions (e.g., each of the
 four feature values will use this many bins from its value interval), and does
index c5b5b17a0442ee14ca0e66d336cd8eecbb703d99..c12e26bf36e01167ebc764836b6979e3eb36829c 100644 (file)
@@ -63,7 +63,7 @@ In this tutorial, we will use the RANSAC method (pcl::SAC_RANSAC) as the robust
 Our decision is motivated by RANSAC's simplicity (other robust estimators use it as
 a base and add additional, more complicated concepts). For more information
 about RANSAC, check its `Wikipedia page
-<http://en.wikipedia.org/wiki/RANSAC>`_.
+<https://en.wikipedia.org/wiki/RANSAC>`_.
 
 Finally:
 
index 443fe23b195f6309f34c707cf6f2c04a83889ff8..9043766ae4c006e1b73be328d8726d58a6944aa6 100644 (file)
@@ -82,7 +82,7 @@ pclviewer.cpp
    :language: cpp
    :lines: 8-12
 
-We initialize the members of our class to default values (note that theses values should match with the UI buttons ticked)
+We initialize the members of our class to default values (note that these values should match with the UI buttons ticked)
 
 .. literalinclude:: sources/qt_colorize_cloud/pclviewer.cpp
    :language: cpp
index 08c2b75d187c4be69ccb8781640bd69c933b1e10..ee8a774f7353f8ed56da6398a020f44c4099daed 100644 (file)
@@ -52,7 +52,7 @@ Use relative paths like this is better than absolute paths; this project should
 We specify in the general section that we want to build in the folder ``../build`` (this is a relative path from the ``.pro`` file).
 
 The first step of the building is to call ``cmake`` (from the ``build`` folder) with argument ``../src``; this is gonna create all files in the
-``build`` folder without modifying anything in the ``src`` foler; thus keeping it clean.
+``build`` folder without modifying anything in the ``src`` folder; thus keeping it clean.
 
 Then we just have to compile our program; the argument ``-j2`` allow to specify how many thread of your CPU you want to use for compilation. The more thread you use
 the faster the compilation will be (especially on big projects); but if you take all threads from the CPU your OS will likely be unresponsive during 
@@ -192,7 +192,7 @@ Here we connect slots and signals, this links UI actions to functions. Here is a
 
 | This is the last part of our constructor; we add the point cloud to the visualizer, call the method ``pSliderValueChanged`` to change the point size to 2.
 
-We finally reset the camera within the PCL Visualizer not avoid the user having to zoom out and refesh the view to be 
+We finally reset the camera within the PCL Visualizer not avoid the user having to zoom out and refresh the view to be 
 sure the modifications will be displayed.
 
 .. literalinclude:: sources/qt_visualizer/pclviewer.cpp
index ed5dad498aedb3b9f5eb45fd6ef3a84a3c903af8..fb9ceb018a9ff9235fcefcb36d5d0f943cbed4e3 100644 (file)
@@ -123,4 +123,4 @@ It will show you the result of applying RandomSampleConsensus to this data set w
    :align: center
    :height: 400px
 
-.. [WikipediaRANSAC] http://en.wikipedia.org/wiki/RANSAC
+.. [WikipediaRANSAC] https://en.wikipedia.org/wiki/RANSAC
index 1988e575cc6d9fa17b431db8ca809572480c432c..94a3afedfbf589969ecd80f885685bacbea2ecd4 100644 (file)
@@ -84,7 +84,7 @@ keypoints as well. The problem with "feeding two kinect datasets into a correspo
 Feature descriptors
 ===================
 
-Based on the keypoints found we have to extract [features](http://www.pointclouds.org/documentation/tutorials/how_features_work.php), where we assemble the information and generate vectors to compare them with each other. Again there
+Based on the keypoints found we have to extract `features <https://pcl.readthedocs.io/projects/tutorials/en/master/how_features_work.html>`_, where we assemble the information and generate vectors to compare them with each other. Again there
 is a number of feature options to choose from, for example NARF, FPFH, BRIEF or
 SIFT.
 
index d262b8dcffd48111a40f14066f244cafd74e6ca2..ac484b7f3f7cfa018702998328a37eae28ba25f3 100644 (file)
@@ -1,6 +1,6 @@
 #include <pcl/visualization/cloud_viewer.h>
 #include <iostream>
-#include <pcl/io/io.h>
+#include <pcl/common/io.h>
 #include <pcl/io/pcd_io.h>
     
 int user_data;
index c865cefdb3f1b47db803a8a694431842229b6669..b5953e8f15b473612fddc3a06781a94289e2b455 100644 (file)
@@ -9,7 +9,7 @@
 #include <pcl/sample_consensus/model_types.h>
 #include <pcl/segmentation/sac_segmentation.h>
 #include <pcl/segmentation/extract_clusters.h>
-
+#include <iomanip> // for setw, setfill
 
 int 
 main ()
@@ -94,8 +94,8 @@ main ()
 
     std::cout << "PointCloud representing the Cluster: " << cloud_cluster->size () << " data points." << std::endl;
     std::stringstream ss;
-    ss << "cloud_cluster_" << j << ".pcd";
-    writer.write<pcl::PointXYZ> (ss.str (), *cloud_cluster, false); //*
+    ss << std::setw(4) << std::setfill('0') << j;
+    writer.write<pcl::PointXYZ> ("cloud_cluster_" + ss.str () + ".pcd", *cloud_cluster, false); //*
     j++;
   }
 
diff --git a/doc/tutorials/content/sources/cmake_test/CMakeLists.txt b/doc/tutorials/content/sources/cmake_test/CMakeLists.txt
new file mode 100644 (file)
index 0000000..7e8db12
--- /dev/null
@@ -0,0 +1,15 @@
+cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
+
+# This is not really a tutorial, but instead tests the behaviour of find_package(PCL) when built together with the other tutorials
+project(cmake_test)
+
+set(BOOST_LIBRARIES "boost_dont_overwrite")
+set(Boost_LIBRARIES "boost_dont_overwrite")
+find_package(PCL REQUIRED)
+
+if(NOT "${BOOST_LIBRARIES}" STREQUAL "boost_dont_overwrite")
+  message(FATAL_ERROR "find_package(PCL) changed the value of BOOST_LIBRARIES")
+endif()
+if(NOT "${Boost_LIBRARIES}" STREQUAL "boost_dont_overwrite")
+  message(FATAL_ERROR "find_package(PCL) changed the value of Boost_LIBRARIES")
+endif()
index eb4eb13e59c1340ad55ed2b394d2a2415b5d7d97..158c38a0e835f82df0229a51b6a5e72b8739ab71 100644 (file)
@@ -37,7 +37,7 @@ customRegionGrowing (const PointTypeFull& point_a, const PointTypeFull& point_b,
   {
     if (std::abs (point_a.intensity - point_b.intensity) < 8.0f)
       return (true);
-    if (std::abs (point_a_normal.dot (point_b_normal)) < 0.06)
+    if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast<float> (M_PI)))
       return (true);
   }
   else
index 025ed22ae895890ff1f6e2e6fbaed839d661fa69..47d4ae6217553b465d82609e99247a70cc6886ff 100644 (file)
@@ -318,7 +318,7 @@ class PeoplePCDApp
 
 int main(int argc, char** argv)
 {
-  // selecting GPU and prining info
+  // selecting GPU and printing info
   int device = 0;
   pc::parse_argument (argc, argv, "-gpu", device);
   pcl::gpu::setDevice (device);
index 92d7d84c23fdbb4a0139e1c5d640e71f3a42a7ea..983c56a6f2cdb09ef80699ae762f308dff617841 100644 (file)
@@ -2,7 +2,7 @@
 
 #include "typedefs.h"
 
-#include <pcl/io/io.h>
+#include <pcl/common/io.h>
 #include <pcl/features/normal_3d.h>
 #include <pcl/keypoints/sift_keypoint.h>
 #include <pcl/features/fpfh.h>
index 3ba7056d2153e7c7e6ca6eb3c97f502e29cac94f..ba4465d66be3ca0fd5c7776c2b24f86a05747f09 100644 (file)
@@ -6,7 +6,7 @@
 #include <pcl/console/parse.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/kdtree/kdtree_flann.h>
-#include <pcl/registration/transforms.h>
+#include <pcl/common/transforms.h>
 #include <pcl/visualization/pcl_visualizer.h>
 
 /* A few functions to help load up the points */
index f5f8a7744a34e7397279497a38416279b2044f11..a0ffa106e08801d8ddcd62830ab0d92ec369c3f9 100644 (file)
@@ -3,7 +3,7 @@
 #include <sstream>
 
 #include <pcl/io/pcd_io.h>
-#include <pcl/registration/transforms.h>
+#include <pcl/common/transforms.h>
 #include <pcl/visualization/pcl_visualizer.h>
 #include <pcl/keypoints/sift_keypoint.h>
 
index 7343c9a11a2b0d1f4a04c1058ce8c1bdbc045c26..cfd8b9f597ea2c3eb876467c5b60b9b6455ffdf7 100644 (file)
@@ -11,7 +11,7 @@
 int
 main (int argc, char** argv)
 {
-  if (argc == 0 || argc % 2 == 0)
+  if (argc < 5 || argc % 2 == 0) // needs at least one training cloud with class id, plus testing cloud with class id (plus name of executable)
     return (-1);
 
   unsigned int number_of_training_clouds = (argc - 3) / 2;
index 0f2f40824f862497e2382786d74a71bdeb4649fe..764a13b20a2276debc7297bf534f8e89c0e679b8 100644 (file)
@@ -2,7 +2,7 @@
 
 #include "typedefs.h"
 
-#include <pcl/io/io.h>
+#include <pcl/common/io.h>
 #include <pcl/features/normal_3d.h>
 #include <pcl/keypoints/sift_keypoint.h>
 #include <pcl/features/fpfh.h>
index 6249aaa20daccaf6f929fd4841a95f52ba0abbdc..07dd3809ba456c7a20b67be9d66f9226fb2bd536 100644 (file)
@@ -2,7 +2,7 @@
 
 #include "typedefs.h"
 
-#include <pcl/io/io.h>
+#include <pcl/common/io.h>
 #include <pcl/features/normal_3d.h>
 #include <pcl/keypoints/sift_keypoint.h>
 #include <pcl/features/fpfh.h>
index 3ba7056d2153e7c7e6ca6eb3c97f502e29cac94f..ba4465d66be3ca0fd5c7776c2b24f86a05747f09 100644 (file)
@@ -6,7 +6,7 @@
 #include <pcl/console/parse.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/kdtree/kdtree_flann.h>
-#include <pcl/registration/transforms.h>
+#include <pcl/common/transforms.h>
 #include <pcl/visualization/pcl_visualizer.h>
 
 /* A few functions to help load up the points */
index 5d796a501c0275f2bac92d33a9b3e1aeba80d4a8..a5726fcc93cc6d823ff08ca1eb39560b91c62389 100644 (file)
@@ -1,6 +1,6 @@
 #include <pcl/visualization/pcl_visualizer.h>
 #include <iostream>
-#include <pcl/io/io.h>
+#include <pcl/common/io.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/features/integral_image_normal.h>
     
index 6f841165c1071399617a77e39ff4b021298cb481..834ea30122510e6d747102ffeaae4da1adac8e6d 100644 (file)
@@ -52,7 +52,7 @@
 
 #include <pcl/registration/icp.h>
 #include <pcl/registration/icp_nl.h>
-#include <pcl/registration/transforms.h>
+#include <pcl/common/transforms.h>
 
 #include <pcl/visualization/pcl_visualizer.h>
 
index d1e173abba35586ed70db162c447223aef58ce6d..218b3715a469f7c7fdead13c85888eae3959c30b 100644 (file)
@@ -47,7 +47,7 @@ main ()
   //setting some properties
   plotter->setShowLegend (true);
 
-  //generating point correspondances
+  //generating point correspondences
   int numPoints = 69;
   double ax[100], acos[100], asin[100];
   generateData (ax, acos, asin, numPoints);
index ecc6cf3e8a67afb444c021c9d61f236f565d608e..5ecb2325af5f34f036967364776f611e2d1e6bec 100644 (file)
@@ -78,7 +78,7 @@ loadFeatureModels (const boost::filesystem::path &base_dir, const std::string &e
       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 ()) && boost::filesystem::extension (it->path ()) == extension)
+    if (boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension)
     {
       vfh_model m;
       if (loadHist (base_dir / it->path ().filename (), m))
index 783c092bbd32ea603a253fa272ddaca4852e6b29..e377394bcd62f1fad09f784120bdbe45ae260479 100644 (file)
@@ -267,7 +267,7 @@ main (int argc, char** argv)
     // Add the cluster name
     p.addText (cloud_name, 20, 10, cloud_name, viewport);
   }
-  // Add coordianate systems to all viewports
+  // Add coordinate systems to all viewports
   p.addCoordinateSystem (0.1, "global", 0);
 
   p.spin ();
index 8625bfc3b7e191b076a73c89b9e0cd61dafacfa0..5ca1b1a15096470cc54433fe1b1a8c2b7b4659dc 100644 (file)
@@ -132,5 +132,5 @@ After few seconds, tracking will start working and you can move tracking object
 
 More Advanced
 -------------
-If you want to see more flexible and useful tracking code which starts tracking without preparing to make segemented model beforehand, you should refer a tracking code  https://github.com/PointCloudLibrary/pcl/blob/master/apps/src/openni_tracking.cpp. It will show you better and more legible code. The above Figures  are windows when you implement that code.
+If you want to see more flexible and useful tracking code which starts tracking without preparing to make segmented model beforehand, you should refer a tracking code  https://github.com/PointCloudLibrary/pcl/blob/master/apps/src/openni_tracking.cpp. It will show you better and more legible code. The above Figures  are windows when you implement that code.
 
index a138fd3c2f66d3f5f03bbfdc0058cab307a6246f..ae3fe9a18320bd7e874b9ee3e5c492b2c4c27225 100644 (file)
@@ -23,7 +23,7 @@ CMakeLists.txt that contains:
    
    cmake_minimum_required(VERSION 2.6 FATAL_ERROR)
    project(MY_GRAND_PROJECT)
-   find_package(PCL 1.3 REQUIRED COMPONENTS common io)
+   find_package(PCL 1.3 REQUIRED)
    include_directories(${PCL_INCLUDE_DIRS})
    link_directories(${PCL_LIBRARY_DIRS})
    add_definitions(${PCL_DEFINITIONS})
@@ -53,7 +53,7 @@ invoking cmake (MY_GRAND_PROJECT_BINARY_DIR).
 
 .. code-block:: cmake
 
-   find_package(PCL 1.3 REQUIRED COMPONENTS common io)
+   find_package(PCL 1.3 REQUIRED)
 
 We are requesting to find the PCL package at minimum version 1.3. We
 also say that it is ``REQUIRED`` meaning that cmake will fail
@@ -204,4 +204,4 @@ before this one:
 
 .. code-block:: cmake
 
-   find_package(PCL 1.3 REQUIRED COMPONENTS common io)
+   find_package(PCL 1.3 REQUIRED)
index 78fef51eceec03033b84fa5680b547fb30a9123c..f396770114f5d17f6cb4c1981055baad272cda52 100644 (file)
@@ -59,7 +59,7 @@ Estimating VFH features
 -----------------------
 
 The Viewpoint Feature Histogram is implemented in PCL as part of the
-`pcl_features <http://docs.pointclouds.org/trunk/a02944.html>`_
+`pcl_features <https://pointclouds.org/documentation/group__features.html>`_
 library.
 
 The default VFH implementation uses 45 binning subdivisions for each of the
index 19624090c968534fea4ce2a0e5bc058a787fbfa4..4754a7c55033f46ec80adcca4dca79ba0cf9aa91 100644 (file)
@@ -43,7 +43,7 @@ accompanying the library.
    Due to historical reasons, PCL 1.x stores RGB data as a packed float (to
    preserve backward compatibility). To learn more about this, please see the
    `PointXYZRGB
-   <http://docs.pointclouds.org/trunk/structpcl_1_1_point_x_y_z_r_g_b.html>`_.
+   <https://pointclouds.org/documentation/structpcl_1_1_point_x_y_z_r_g_b.html>`_.
 
 Simple Cloud Visualization
 --------------------------
index 33c26903a215b492cbfab13f6198fb468daab26e..971d9a8f78ebdfb7fd7cd5d614c39cb716b83987 100644 (file)
@@ -69,7 +69,7 @@ Filters
 
 .. image:: images/statistical_removal_2.jpg
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__filters.html
+**Documentation:** https://pointclouds.org/documentation/group__filters.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#filtering-tutorial
 
@@ -104,7 +104,7 @@ Features
 **Background**
 
        A theoretical primer explaining how features work in PCL can be found in the `3D Features tutorial
-       <http://pointclouds.org/documentation/tutorials/how_features_work.php>`_.
+       <https://pcl.readthedocs.io/projects/tutorials/en/master/how_features_work.html>`_.
        
        The *features* library contains data structures and mechanisms for 3D feature estimation from point cloud data. 3D features are representations at certain 3D points, or positions, in space, which describe geometrical patterns based on the information available around the point. The data space selected around the query point is usually referred to as the *k-neighborhood*.
 
@@ -118,7 +118,7 @@ Features
        
        |
        
-**Documentation:** http://docs.pointclouds.org/trunk/group__features.html
+**Documentation:** https://pointclouds.org/documentation/group__features.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#features-tutorial
 
@@ -154,7 +154,7 @@ Keypoints
 
 **Background**
 
-       The *keypoints* library contains implementations of two point cloud keypoint detection algorithms. Keypoints (also referred to as `interest points <http://en.wikipedia.org/wiki/Interest_point_detection>`_) are points in an image or point cloud that are stable, distinctive, and can be identified using a well-defined detection criterion. Typically, the number of interest points in a point cloud will be much smaller than the total number of points in the cloud, and when used in combination with local feature descriptors at each keypoint, the keypoints and descriptors can be used to form a compact—yet descriptive—representation of the original data.
+       The *keypoints* library contains implementations of two point cloud keypoint detection algorithms. Keypoints (also referred to as `interest points <https://en.wikipedia.org/wiki/Interest_point_detection>`_) are points in an image or point cloud that are stable, distinctive, and can be identified using a well-defined detection criterion. Typically, the number of interest points in a point cloud will be much smaller than the total number of points in the cloud, and when used in combination with local feature descriptors at each keypoint, the keypoints and descriptors can be used to form a compact—yet descriptive—representation of the original data.
        
        The figure below shows the output of NARF keypoints extraction from a range image:
        
@@ -162,7 +162,7 @@ Keypoints
 
 |
        
-**Documentation:** http://docs.pointclouds.org/trunk/group__keypoints.html
+**Documentation:** https://pointclouds.org/documentation/group__keypoints.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#keypoints-tutorial
 
@@ -212,7 +212,7 @@ Registration
 
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__registration.html
+**Documentation:** https://pointclouds.org/documentation/group__registration.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#registration-tutorial
 
@@ -247,11 +247,11 @@ Kd-tree
 
 **Background**
 
-       A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial <http://pointclouds.org/documentation/tutorials/kdtree_search.php#kdtree-search>`_.
+       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 <http://en.wikipedia.org/wiki/Nearest_neighbor_search>`_.
+       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>`_.
 
-       A `Kd-tree <http://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.
+       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.
 
        .. image:: images/3dtree.png
        
@@ -259,7 +259,7 @@ Kd-tree
 
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__kdtree.html
+**Documentation:** https://pointclouds.org/documentation/group__kdtree.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#kdtree-tutorial
 
@@ -299,7 +299,7 @@ Octree
 
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__octree.html
+**Documentation:** https://pointclouds.org/documentation/group__octree.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#octree-tutorial
 
@@ -331,7 +331,7 @@ Segmentation
 
        The *segmentation* library contains algorithms for segmenting a point cloud into distinct clusters. These algorithms are best suited for processing a point cloud that is composed of a number of spatially isolated regions. In such cases, clustering is often used to break the cloud down into its constituent parts, which can then be processed independently.
        
-       A theoretical primer explaining how clustering methods work can be found in the `cluster extraction tutorial <http://pointclouds.org/documentation/tutorials/cluster_extraction.php#cluster-extraction>`_.
+       A theoretical primer explaining how clustering methods work can be found in the `cluster extraction tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/cluster_extraction.html>`_.
        The two figures illustrate the results of plane model segmentation (left) and cylinder model segmentation (right). 
        
        .. image:: images/plane_model_seg.jpg
@@ -340,7 +340,7 @@ Segmentation
        
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__segmentation.html
+**Documentation:** https://pointclouds.org/documentation/group__segmentation.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#segmentation-tutorial
 
@@ -378,7 +378,7 @@ Sample Consensus
 
        The *sample_consensus* library holds SAmple Consensus (SAC) methods like RANSAC and models like planes and cylinders. These can be combined freely in order to detect specific models and their parameters in point clouds.
        
-       A theoretical primer explaining how sample consensus algorithms work can be found in the `Random Sample Consensus tutorial <http://pointclouds.org/documentation/tutorials/random_sample_consensus.php#random-sample-consensus>`_
+       A theoretical primer explaining how sample consensus algorithms work can be found in the `Random Sample Consensus tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/random_sample_consensus.html>`_
 
        Some of the models implemented in this library include: lines, planes, cylinders, and spheres. Plane fitting is often applied to the task of detecting common indoor surfaces, such as walls, floors, and table tops. Other models can be used to detect and segment objects with common geometric structures (e.g., fitting a cylinder model to a mug).
 
@@ -386,7 +386,7 @@ Sample Consensus
 
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__sample__consensus.html
+**Documentation:** https://pointclouds.org/documentation/group__sample__consensus.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#sample-consensus
 
@@ -432,7 +432,7 @@ Surface
 
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__surface.html
+**Documentation:** https://pointclouds.org/documentation/group__surface.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#surface-tutorial
 
@@ -505,15 +505,15 @@ I/O
 
        The *io* library contains classes and functions for reading and writing point cloud data (PCD) files, as well as capturing point clouds from a variety of sensing devices. An introduction to some of these capabilities can be found in the following tutorials:
 
-    * `The PCD (Point Cloud Data) file format <http://pointclouds.org/documentation/tutorials/pcd_file_format.php#pcd-file-format>`_
-    * `Reading PointCloud data from PCD files <http://pointclouds.org/documentation/tutorials/reading_pcd.php#reading-pcd>`_
-    * `Writing PointCloud data to PCD files <http://pointclouds.org/documentation/tutorials/writing_pcd.php#writing-pcd>`_
-    * `The OpenNI Grabber Framework in PCL <http://pointclouds.org/documentation/tutorials/openni_grabber.php#openni-grabber>`_
+    * `The PCD (Point Cloud Data) file format <https://pcl.readthedocs.io/projects/tutorials/en/master/pcd_file_format.html>`_
+    * `Reading PointCloud data from PCD files <https://pcl.readthedocs.io/projects/tutorials/en/master/reading_pcd.html>`_
+    * `Writing PointCloud data to PCD files <https://pcl.readthedocs.io/projects/tutorials/en/master/writing_pcd.html>`_
+    * `The OpenNI Grabber Framework in PCL <https://pcl.readthedocs.io/projects/tutorials/en/master/openni_grabber.html>`_
 
 
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__io.html
+**Documentation:** https://pointclouds.org/documentation/group__io.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#i-o
 
@@ -580,7 +580,7 @@ Visualization
 
 |
 
-**Documentation:** http://docs.pointclouds.org/trunk/group__visualization.html
+**Documentation:** https://pointclouds.org/documentation/group__visualization.html
 
 **Tutorials:** http://pointclouds.org/documentation/tutorials/#visualization-tutorial
 
@@ -682,7 +682,7 @@ Binaries
 This section provides a quick reference for some of the common tools in PCL. 
 
 
-       * ``pcl_viewer``: a quick way for visualizing PCD (Point Cloud Data) files. More information about PCD files can be found in the `PCD file format tutorial <http://pointclouds.org/documentation/tutorials/pcd_file_format.php>`_.
+       * ``pcl_viewer``: a quick way for visualizing PCD (Point Cloud Data) files. More information about PCD files can be found in the `PCD file format tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/pcd_file_format.html>`_.
 
                **Syntax is: pcl_viewer <file_name 1..N>.<pcd or vtk> <options>**, where options are:
                
@@ -730,7 +730,7 @@ This section provides a quick reference for some of the common tools in PCL.
                
                ``pcl_pcd_convert_NaN_nan input.pcd output.pcd``
        
-       * ``pcl_convert_pcd_ascii_binary``: converts PCD (Point Cloud Data) files from ASCII to binary and viceversa. 
+       * ``pcl_convert_pcd_ascii_binary``: converts PCD (Point Cloud Data) files from ASCII to binary and vice-versa. 
        
                **Usage example:**
                
@@ -751,7 +751,7 @@ This section provides a quick reference for some of the common tools in PCL.
                
                ``pcl_pcd2vtk input.pcd output.vtk``    
 
-       * ``pcl_pcd2ply``: converts PCD (Point Cloud Data) files to the `PLY format <http://en.wikipedia.org/wiki/PLY_%28file_format%29>`_. 
+       * ``pcl_pcd2ply``: converts PCD (Point Cloud Data) files to the `PLY format <https://en.wikipedia.org/wiki/PLY_%28file_format%29>`_. 
 
                **Usage example:**
 
index d823ddb84c0f55b2835758c6ac1890349d300dd1..45ac095c5e22064be71a892825f06485e25f99f0 100644 (file)
@@ -770,7 +770,7 @@ defines a way to define a region of interest / *list of point indices* that the
 algorithm should operate on, rather than the entire cloud, via
 :pcl:`setIndices<pcl::PCLBase::setIndices>`.
 
-All classes inheriting from :pcl:`PCLBase<pcl::PCLBase>` exhbit the following
+All classes inheriting from :pcl:`PCLBase<pcl::PCLBase>` exhibit the following
 behavior: in case no set of indices is given by the user, a fake one is created
 once and used for the duration of the algorithm. This means that we could
 easily change the implementation code above to operate on a *<cloud, indices>*
@@ -909,7 +909,7 @@ file, as follows:
    *  All rights reserved
    */
 
-An additional like can be inserted if additional copyright is needed (or the
+An additional line can be inserted if additional copyright is needed (or the
 original copyright can be changed):
 
 .. code-block:: cpp
@@ -986,7 +986,7 @@ class look like:
 
           /** \brief Compute the intensity average for a single point
             * \param[in] pid the point index to compute the weight for
-            * \param[in] indices the set of nearest neighor indices 
+            * \param[in] indices the set of nearest neighbor indices 
             * \param[in] distances the set of nearest neighbor distances
             * \return the intensity average at a given point index
             */
index fd7b505ca77a82e9e07eb927184c4a0f27c21844..d98d68cf5eb82a8ab549efc573cb19ff3dbcce7a 100644 (file)
@@ -99,7 +99,7 @@ int main (int argc, char *argv[])
 
     // Create downsampled point cloud for DoN NN search with large scale
     large_cloud_downsampled = PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
-    const float largedownsample = float (scale2/decimation);
+    constexpr float largedownsample = static_cast<float>(scale2/decimation);
     sor.setLeafSize (largedownsample, largedownsample, largedownsample);
     sor.filter (*large_cloud_downsampled);
     std::cout << "Using leaf size of " << largedownsample << " for large scale, " << large_cloud_downsampled->size() << " points" << std::endl;
index 612e070ea1157565e37dfb99e7a2e7c6a5edba97..34748942bdcced9c8e7bb66b45d0b62fccc9944b 100644 (file)
@@ -57,10 +57,10 @@ main(int, char** argv)
   std::cout << "points: " << cloud->size () <<std::endl;
   
   // Parameters for sift computation
-  const float min_scale = 0.1f;
-  const int n_octaves = 6;
-  const int n_scales_per_octave = 10;
-  const float min_contrast = 0.5f;
+  constexpr float min_scale = 0.1f;
+  constexpr int n_octaves = 6;
+  constexpr int n_scales_per_octave = 10;
+  constexpr float min_contrast = 0.5f;
   
   
   // Estimate the sift interest points using Intensity values from RGB values
index c4c1905bf03719252730a98bf509a191538cb72a..447ad4251d36e52ef3220c07b4a5f13298f7d67e 100644 (file)
@@ -63,10 +63,10 @@ main(int, char** argv)
   std::cout << "points: " << cloud_xyz->size () <<std::endl;
   
   // Parameters for sift computation
-  const float min_scale = 0.01f;
-  const int n_octaves = 3;
-  const int n_scales_per_octave = 4;
-  const float min_contrast = 0.001f;
+  constexpr float min_scale = 0.01f;
+  constexpr int n_octaves = 3;
+  constexpr int n_scales_per_octave = 4;
+  constexpr float min_contrast = 0.001f;
   
   // Estimate the normals of the cloud_xyz
   pcl::NormalEstimation<pcl::PointXYZ, pcl::PointNormal> ne;
index 146f03f5d460b152e00c7368e4a7ac3d8d9c87ba..036a8a6b39fb3f084289a7f5c7bc2d0c74286730 100644 (file)
@@ -75,10 +75,10 @@ main(int, char** argv)
   std::cout << "points: " << cloud_xyz->size () <<std::endl;
   
   // Parameters for sift computation
-  const float min_scale = 0.005f;
-  const int n_octaves = 6;
-  const int n_scales_per_octave = 4;
-  const float min_contrast = 0.005f;
+  constexpr float min_scale = 0.005f;
+  constexpr int n_octaves = 6;
+  constexpr int n_scales_per_octave = 4;
+  constexpr float min_contrast = 0.005f;
   
   // Estimate the sift interest points using z values from xyz as the Intensity variants
   pcl::SIFTKeypoint<pcl::PointXYZ, pcl::PointWithScale> sift;
index 8c9937f094d5ad02574d1effc9614693e007bb69..bbb357f673a5ba37b7a7e4fcf74547995b730be2 100644 (file)
@@ -77,39 +77,39 @@ keyboardEventOccurred (const pcl::visualization::KeyboardEvent& event_arg,
   if (event_arg.keyUp ())
     switch (key)
     {
-      case (int) '1':
+      case static_cast<int>('1'):
         show_normals = !show_normals;
         normals_changed = true;
         break;
-      case (int) '2':
+      case static_cast<int>('2'):
         show_adjacency = !show_adjacency;
         break;
-      case (int) '3':
+      case static_cast<int>('3'):
         show_supervoxels = !show_supervoxels;
         break;
-      case (int) '4':
+      case static_cast<int>('4'):
         show_segmentation = !show_segmentation;
         break;
-      case (int) '5':
+      case static_cast<int>('5'):
         normals_scale *= 1.25;
         normals_changed = true;
         break;
-      case (int) '6':
+      case static_cast<int>('6'):
         normals_scale *= 0.8;
         normals_changed = true;
         break;
-      case (int) '7':
+      case static_cast<int>('7'):
         line_width += 0.5;
         line_changed = true;
         break;
-      case (int) '8':
+      case static_cast<int>('8'):
         if (line_width <= 1)
           break;
         line_width -= 0.5;
         line_changed = true;
         break;
-      case (int) 'd':
-      case (int) 'D':
+      case static_cast<int>('d'):
+      case static_cast<int>('D'):
         show_help = !show_help;
         break;
       default:
index 30b3728d7b6895d3013614a639f4791258a84917..a4fec273ce1486cdd00d0382c64c7a188876d3ce 100644 (file)
@@ -79,9 +79,9 @@ main (int argc, char **argv)
   
   // Extracting Euclidean clusters using cloud and its normals
   std::vector<pcl::PointIndices> cluster_indices;
-  const float tolerance = 0.5f; // 50cm tolerance in (x, y, z) coordinate system
-  const double eps_angle = 5 * (M_PI / 180.0); // 5degree tolerance in normals
-  const unsigned int min_cluster_size = 50;
+  constexpr float tolerance = 0.5f; // 50cm tolerance in (x, y, z) coordinate system
+  constexpr double eps_angle = 5 * (M_PI / 180.0); // 5degree tolerance in normals
+  constexpr unsigned int min_cluster_size = 50;
  
   pcl::extractEuclideanClusters (*cloud_ptr, *cloud_normals, tolerance, tree_ec, cluster_indices, eps_angle, min_cluster_size);
 
index 7b92dc79c41e5713510d22037ce7d802f98fb4ad..09a811e567e5b94ed583ff417ad7d0141a5f5fb2 100644 (file)
@@ -73,26 +73,26 @@ keyboardEventOccurred (const pcl::visualization::KeyboardEvent& event_arg,
   if (event_arg.keyUp ())
     switch (key)
     {
-      case (int) '1':
+      case static_cast<int>('1'):
         show_normals = !show_normals;
         normals_changed = true;
         break;
-      case (int) '2':
+      case static_cast<int>('2'):
         show_adjacency = !show_adjacency;
         break;
-      case (int) '3':
+      case static_cast<int>('3'):
         show_supervoxels = !show_supervoxels;
         break;
-      case (int) '4':
+      case static_cast<int>('4'):
         normals_scale *= 1.25;
         normals_changed = true;
         break;
-      case (int) '5':
+      case static_cast<int>('5'):
         normals_scale *= 0.8;
         normals_changed = true;
         break;
-      case (int) 'd':
-      case (int) 'D':
+      case static_cast<int>('d'):
+      case static_cast<int>('D'):
         show_help = !show_help;
         break;
       default:
index 76188bee4f54fce4f7879afb25a5f23aa0a478b0..11d8ec1420a606a979710ab59da591a0be30dd59 100644 (file)
@@ -42,13 +42,13 @@ keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
   if (event.keyUp ())    
     switch (key)
     {
-      case (int)'1': show_voxel_centroids = !show_voxel_centroids; break;
-      case (int)'2': show_supervoxels = !show_supervoxels; break;
-      case (int)'3': show_graph = !show_graph; break;
-      case (int)'4': show_normals = !show_normals; break;
-      case (int)'5': show_supervoxel_normals = !show_supervoxel_normals; break;
-      case (int)'0': show_refined = !show_refined; break;
-      case (int)'h': case (int)'H': show_help = !show_help; break;
+      case static_cast<int>('1'): show_voxel_centroids = !show_voxel_centroids; break;
+      case static_cast<int>('2'): show_supervoxels = !show_supervoxels; break;
+      case static_cast<int>('3'): show_graph = !show_graph; break;
+      case static_cast<int>('4'): show_normals = !show_normals; break;
+      case static_cast<int>('5'): show_supervoxel_normals = !show_supervoxel_normals; break;
+      case static_cast<int>('0'): show_refined = !show_refined; break;
+      case static_cast<int>('h'): case static_cast<int>('H'): show_help = !show_help; break;
       default: break;
     }
     
index e04bdab72767337a78e7dcf750a073226ad6ec4d..b5f902aece8b96d0c2bcc9a951d3c0d06db74018 100644 (file)
@@ -4,7 +4,7 @@ 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})
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
index cf743a13d42693da78c6cbb914d2ad2372726019..65bac7c1cf306cebc00020b5037a4eed9c918e56 100644 (file)
@@ -97,12 +97,7 @@ namespace pcl
         theta_divisions_(0),
         phi_divisions_(0),
         volume_lut_(0),
-        azimuth_bins_(12),
-        elevation_bins_(11),
-        radius_bins_(15),
-        min_radius_(0.1),
-        point_density_radius_(0.2),
-        descriptor_length_ (),
+        
         rng_dist_ (0.0f, 1.0f)
       {
         feature_name_ = "ShapeContext3DEstimation";
@@ -197,22 +192,22 @@ namespace pcl
       std::vector<float> volume_lut_;
 
       /** \brief Bins along the azimuth dimension */
-      std::size_t azimuth_bins_;
+      std::size_t azimuth_bins_{12};
 
       /** \brief Bins along the elevation dimension */
-      std::size_t elevation_bins_;
+      std::size_t elevation_bins_{11};
 
       /** \brief Bins along the radius dimension */
-      std::size_t radius_bins_;
+      std::size_t radius_bins_{15};
 
       /** \brief Minimal radius value */
-      double min_radius_;
+      double min_radius_{0.1};
 
       /** \brief Point density radius */
-      double point_density_radius_;
+      double point_density_radius_{0.2};
 
       /** \brief Descriptor length */
-      std::size_t descriptor_length_;
+      std::size_t descriptor_length_{};
 
       /** \brief Random number generator algorithm. */
       std::mt19937 rng_;
index 2e323ca4775951a8d90da467a822d16b3e0b96b9..2debbf0f24ba1ebc8cd2a83555110a21ed2fcf1f 100644 (file)
@@ -62,13 +62,7 @@ namespace pcl
       using ConstPtr = shared_ptr<const BOARDLocalReferenceFrameEstimation<PointInT, PointNT, PointOutT> >;
 
       /** \brief Constructor. */
-      BOARDLocalReferenceFrameEstimation () :
-        tangent_radius_ (0.0f),
-        find_holes_ (false),
-        margin_thresh_ (0.85f),
-        check_margin_array_size_ (24),
-        hole_size_prob_thresh_ (0.2f),
-        steep_thresh_ (0.1f)
+      BOARDLocalReferenceFrameEstimation ()
       {
         feature_name_ = "BOARDLocalReferenceFrameEstimation";
         setCheckMarginArraySize (check_margin_array_size_);
@@ -331,22 +325,22 @@ namespace pcl
 
     private:
       /** \brief Radius used to find tangent axis. */
-      float tangent_radius_;
+      float tangent_radius_{0.0f};
 
       /** \brief If true, check if support is complete or has missing regions because it is too near to mesh borders. */
-      bool find_holes_;
+      bool find_holes_{false};
 
       /** \brief Threshold that define if a support point is near the margins. */
-      float margin_thresh_; 
+      float margin_thresh_{0.85f}
 
       /** \brief Number of slices that divide the support in order to determine if a missing region is present. */
-      int check_margin_array_size_; 
+      int check_margin_array_size_{24}
 
       /** \brief Threshold used to determine a missing region */
-      float hole_size_prob_thresh_; 
+      float hole_size_prob_thresh_{0.2f}
 
       /** \brief Threshold that defines if a missing region contains a point with the most different normal. */
-      float steep_thresh_; 
+      float steep_thresh_{0.1f}
 
       std::vector<bool> check_margin_array_;
       std::vector<float> margin_array_min_angle_;
index c9bc22ade6a9779fd5948948dddf332bb9bad74d..a56be0abf1399c32d116308eac1c3aad21dd1639 100644 (file)
@@ -121,7 +121,7 @@ namespace pcl
       /** \brief Check whether a point is a boundary point in a planar patch of projected points given by indices.
         * \note A coordinate system u-v-n must be computed a-priori using \a getCoordinateSystemOnPlane
         * \param[in] cloud a pointer to the input point cloud
-        * \param[in] q_point a pointer to the querry point
+        * \param[in] q_point a pointer to the query point
         * \param[in] indices the estimated point neighbors of the query point
         * \param[in] u the u direction
         * \param[in] v the v direction
index 61433878c035455f0934f2d1819b75bdd66e183a..05950d6646caebe38c55a5e4f74a1a687a4a06dc 100644 (file)
@@ -161,13 +161,13 @@ namespace pcl
                     const float max_x, const float max_y, const KeypointT& key_pt);
 
       /** \brief Specifies whether rotation invariance is enabled. */
-      bool rotation_invariance_enabled_;
+      bool rotation_invariance_enabled_{true};
       
       /** \brief Specifies whether scale invariance is enabled. */
-      bool scale_invariance_enabled_;
+      bool scale_invariance_enabled_{true};
 
       /** \brief Specifies the scale of the pattern. */
-      const float pattern_scale_;
+      const float pattern_scale_{1.0f};
   
       /** \brief the input cloud. */
       PointCloudInTConstPtr input_cloud_;
@@ -176,7 +176,7 @@ namespace pcl
       KeypointPointCloudTPtr keypoints_;
 
       // TODO: set
-      float scale_range_;
+      float scale_range_{0.0f};
 
       // Some helper structures for the Brisk pattern representation
       struct BriskPatternPoint
@@ -214,41 +214,41 @@ namespace pcl
       BriskPatternPoint* pattern_points_;
       
       /** Total number of collocation points. */
-      unsigned int points_;
+      unsigned int points_{0u};
       
       /** Discretization of the rotation look-up. */
-                 const unsigned int n_rot_;
+                 const unsigned int n_rot_{1024};
       
       /** Lists the scaling per scale index [scale]. */
-      float* scale_list_;
+      float* scale_list_{nullptr};
       
       /** Lists the total pattern size per scale index [scale]. */
-      unsigned int* size_list_;
+      unsigned int* size_list_{nullptr};
       
       /** Scales discretization. */
-      const unsigned int scales_;
+      const unsigned int scales_{64};
       
       /** Span of sizes 40->4 Octaves - else, this needs to be adjusted... */
-      const float scalerange_;
+      const float scalerange_{30};
 
       // general
-      const float basic_size_;
+      const float basic_size_{12.0};
 
       // pairs
       /** Number of uchars the descriptor consists of. */
-      int strings_;
+      int strings_{0};
       /** Short pair maximum distance. */
-      float d_max_;
+      float d_max_{0.0f};
       /** Long pair maximum distance. */
-      float d_min_;
+      float d_min_{0.0f};
       /** d<_d_max. */
       BriskShortPair* short_pairs_;
       /** d>_d_min. */
       BriskLongPair* long_pairs_;
       /** Number of short pairs. */
-      unsigned int no_short_pairs_;
+      unsigned int no_short_pairs_{0};
       /** Number of long pairs. */
-      unsigned int no_long_pairs_;
+      unsigned int no_long_pairs_{0};
 
       /** \brief Intensity field accessor. */
       IntensityT intensity_;
index 6f64c5cccd0e93ffa8764af845a3941880db23ed..6a8d072e4c97809246b866b2a87ce2603c79466d 100644 (file)
@@ -74,13 +74,11 @@ namespace pcl
       using PointCloudOut = typename Feature<PointInT, PointOutT>::PointCloudOut;
 
       /** \brief Constructor. */
-      CRHEstimation () :
-        vpx_ (0), vpy_ (0), vpz_ (0), nbins_ (90)
+      CRHEstimation ()
       {
         k_ = 1;
         feature_name_ = "CRHEstimation";
       }
-      ;
 
       /** \brief Set the viewpoint.
        * \param[in] vpx the X coordinate of the viewpoint
@@ -118,10 +116,10 @@ namespace pcl
       /** \brief Values describing the viewpoint ("pinhole" camera model assumed). 
        * By default, the viewpoint is set to 0,0,0.
        */
-      float vpx_, vpy_, vpz_;
+      float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};
 
       /** \brief Number of bins, this should match the Output type */
-      int nbins_;
+      int nbins_{90};
 
       /** \brief Centroid to be used */
       Eigen::Vector4f centroid_;
index 98315b199c992b6665a56a419d1784c84d81c614..1fc498e945598593f49816db47ce7a3f7cb00e72 100644 (file)
@@ -79,13 +79,9 @@ namespace pcl
 
       /** \brief Empty constructor. */
       CVFHEstimation () :
-        vpx_ (0), vpy_ (0), vpz_ (0), 
-        leaf_size_ (0.005f), 
-        normalize_bins_ (false),
-        curv_threshold_ (0.03f), 
+         
         cluster_tolerance_ (leaf_size_ * 3), 
-        eps_angle_threshold_ (0.125f), 
-        min_points_ (50),
+        
         radius_normals_ (leaf_size_ * 3)
       {
         search_radius_ = 0;
@@ -216,29 +212,29 @@ namespace pcl
       /** \brief Values describing the viewpoint ("pinhole" camera model assumed). 
         * By default, the viewpoint is set to 0,0,0.
         */
-      float vpx_, vpy_, vpz_;
+      float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};
 
       /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel 
         * size of the training data or the normalize_bins_ flag must be set to true.
         */
-      float leaf_size_;
+      float leaf_size_{0.005f};
 
       /** \brief Whether to normalize the signatures or not. Default: false. */
-      bool normalize_bins_;
+      bool normalize_bins_{false};
 
       /** \brief Curvature threshold for removing normals. */
-      float curv_threshold_;
+      float curv_threshold_{0.03f};
 
       /** \brief allowed Euclidean distance between points to be added to the cluster. */
       float cluster_tolerance_;
 
       /** \brief deviation of the normals between two points so they can be clustered together. */
-      float eps_angle_threshold_;
+      float eps_angle_threshold_{0.125f};
 
       /** \brief Minimum amount of points in a clustered region to be considered stable for CVFH
         * computation.
         */
-      std::size_t min_points_;
+      std::size_t min_points_{50};
 
       /** \brief Radius for the normals computation. */
       float radius_normals_;
index b0f37e409ee2ff9d8740b982834f62b8499a2f6c..d03acd3b84549ba2242941c8d73233bf908e67d8 100644 (file)
@@ -90,13 +90,9 @@ namespace pcl
     public:
       /** \brief Constructor. */
       FLARELocalReferenceFrameEstimation () :
-        tangent_radius_ (0.0f),
-        margin_thresh_ (0.85f),
-        min_neighbors_for_normal_axis_ (6),
-        min_neighbors_for_tangent_axis_ (6),
+        
         sampled_surface_ (), 
-        sampled_tree_ (),
-        fake_sampled_surface_ (false)
+        sampled_tree_ ()
       {
         feature_name_ = "FLARELocalReferenceFrameEstimation";
       }
@@ -213,7 +209,7 @@ namespace pcl
       inline void 
       setSearchMethodForSampledSurface (const KdTreePtr &tree) { sampled_tree_ = tree; }
 
-      /** \brief Get a pointer to the search method used for the extimation of x axis. */
+      /** \brief Get a pointer to the search method used for the estimation of x axis. */
       inline const KdTreePtr&  
       getSearchMethodForSampledSurface () const
       {
@@ -253,16 +249,16 @@ namespace pcl
 
     private:
       /** \brief Radius used to find tangent axis. */
-      float tangent_radius_;
+      float tangent_radius_{0.0f};
 
       /** \brief Threshold that define if a support point is near the margins. */
-      float margin_thresh_; 
+      float margin_thresh_{0.85f}
 
       /** \brief Min number of neighbours required for the computation of Z axis. Otherwise, feature point normal is used. */
-      int min_neighbors_for_normal_axis_;
+      int min_neighbors_for_normal_axis_{6};
 
       /** \brief Min number of neighbours required for the computation of X axis. Otherwise, a random X axis is set */
-      int min_neighbors_for_tangent_axis_;
+      int min_neighbors_for_tangent_axis_{6};
 
       /** \brief An input point cloud describing the surface that is to be used
         * for nearest neighbor searches for the estimation of X axis.
@@ -279,7 +275,7 @@ namespace pcl
       std::vector<SignedDistanceT> signed_distances_from_highest_points_;
 
       /** \brief If no sampled_surface_ is given, we use surface_ as the sampled surface. */
-      bool fake_sampled_surface_;
+      bool fake_sampled_surface_{false};
 
   };
 
index f2e742750b9a759f980db021e390519aa09774d0..ee04bfef7ca69d1cfcceb6742eaaa4fedd830d2f 100644 (file)
@@ -93,7 +93,7 @@ namespace pcl
 
       /** \brief Empty constructor. */
       FPFHEstimation () : 
-        nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11), 
+         
         d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI)))
       {
         feature_name_ = "FPFHEstimation";
@@ -197,7 +197,7 @@ namespace pcl
       computeFeature (PointCloudOut &output) override;
 
       /** \brief The number of subdivisions for each angular feature interval. */
-      int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_;
+      int nr_bins_f1_{11}, nr_bins_f2_{11}, nr_bins_f3_{11};
 
       /** \brief Placeholder for the f1 histogram. */
       Eigen::MatrixXf hist_f1_;
index fd7e49a339f0a665dc2ed4b937b690ee2d69b850..2b7de4eaf96490e88f54eb217fcb1e6023d47b8a 100644 (file)
@@ -94,7 +94,7 @@ namespace pcl
       /** \brief Initialize the scheduler and set the number of threads to use.
         * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic)
         */
-      FPFHEstimationOMP (unsigned int nr_threads = 0) : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11)
+      FPFHEstimationOMP (unsigned int nr_threads = 0)
       {
         feature_name_ = "FPFHEstimationOMP";
 
@@ -118,7 +118,7 @@ namespace pcl
 
     public:
       /** \brief The number of subdivisions for each angular feature interval. */
-      int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_;
+      int nr_bins_f1_{11}, nr_bins_f2_{11}, nr_bins_f3_{11};
     private:
       /** \brief The number of threads the scheduler should use. */
       unsigned int threads_;
index 64426f4e616da7cc822dc6508b7d9c96b98d80af..dedcc41a4ea9b63ff4441a8cc536879e8024fd46 100644 (file)
@@ -82,8 +82,7 @@ namespace pcl
 
       /** \brief Empty constructor. */
       GFPFHEstimation () : 
-        octree_leaf_size_ (0.01),
-        number_of_classes_ (16),
+        
         descriptor_size_ (PointOutT::descriptorSize ())
       {
         feature_name_ = "GFPFHEstimation";
@@ -162,10 +161,10 @@ namespace pcl
 
     private:
       /** \brief Size of octree leaves. */
-      double octree_leaf_size_;
+      double octree_leaf_size_{0.01};
 
       /** \brief Number of possible classes/labels. */
-      std::uint32_t number_of_classes_;
+      std::uint32_t number_of_classes_{16};
 
       /** \brief Dimension of the descriptors. */
       int descriptor_size_;
index 9d4ba3b677c453421ff9612483287f9a133715fe..f9d18051c1d7c36aec1acc2e16ac69d8bf594077 100644 (file)
@@ -88,9 +88,9 @@ namespace pcl
 
       /** \brief Constructor. */
       GRSDEstimation ()
+        : relative_coordinates_all_(getAllNeighborCellIndices())
       {
         feature_name_ = "GRSDEstimation";
-        relative_coordinates_all_ = getAllNeighborCellIndices ();
       };
 
       /** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the feature
index b65fade791ae98d222c871ad3bcdfef613e9263f..8d22f39bd8718246fd0e79c8f4e0632e0c7a2147 100644 (file)
@@ -47,17 +47,10 @@ namespace pcl
 
 template <typename PointInT, typename PointOutT, typename KeypointT, typename IntensityT>
 BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::BRISK2DEstimation ()
-  : rotation_invariance_enabled_ (true)
-  , scale_invariance_enabled_ (true)
-  , pattern_scale_ (1.0f)
-  , input_cloud_ (), keypoints_ (), scale_range_ (), pattern_points_ (), points_ ()
-  , n_rot_ (1024), scale_list_ (nullptr), size_list_ (nullptr)
-  , scales_ (64)
-  , scalerange_ (30)
-  , basic_size_ (12.0)
-  , strings_ (0), d_max_ (0.0f), d_min_ (0.0f), short_pairs_ (), long_pairs_ ()
-  , no_short_pairs_ (0), no_long_pairs_ (0)
-  , intensity_ ()
+  : 
+   input_cloud_ (), keypoints_ (),  pattern_points_ (), 
+   short_pairs_ (), long_pairs_ ()
+  ,  intensity_ ()
   , name_ ("BRISK2Destimation")
 {
   // Since we do not assume pattern_scale_ should be changed by the user, we
@@ -119,29 +112,29 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
 
   // define the scale discretization:
   static const float lb_scale = std::log (scalerange_) / std::log (2.0);
-  static const float lb_scale_step = lb_scale / (float (scales_));
+  static const float lb_scale_step = lb_scale / (static_cast<float>(scales_));
 
   scale_list_ = new float[scales_];
   size_list_  = new unsigned int[scales_];
 
-  const float sigma_scale = 1.3f;
+  constexpr float sigma_scale = 1.3f;
 
   for (unsigned int scale = 0; scale < scales_; ++scale)
   {
-    scale_list_[scale] = static_cast<float> (pow (double (2.0), static_cast<double> (float (scale) * lb_scale_step)));
+    scale_list_[scale] = static_cast<float> (pow ((2.0), static_cast<double> (static_cast<float>(scale) * lb_scale_step)));
     size_list_[scale]  = 0;
 
     // generate the pattern points look-up
     for (std::size_t rot = 0; rot < n_rot_; ++rot)
     {
       // this is the rotation of the feature
-      double theta = double (rot) * 2 * M_PI / double (n_rot_);
+      double theta = static_cast<double>(rot) * 2 * M_PI / static_cast<double>(n_rot_);
       for (int ring = 0; ring < static_cast<int>(rings); ++ring)
       {
         for (int num = 0; num < number_list[ring]; ++num)
         {
           // the actual coordinates on the circle
-          double alpha = double (num) * 2 * M_PI / double (number_list[ring]);
+          double alpha = static_cast<double>(num) * 2 * M_PI / static_cast<double>(number_list[ring]);
 
           // feature rotation plus angle of the point
           pattern_iterator->x = scale_list_[scale] * radius_list[ring] * static_cast<float> (std::cos (alpha + theta));
@@ -150,7 +143,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
           if (ring == 0)
             pattern_iterator->sigma = sigma_scale * scale_list_[scale] * 0.5f;
           else
-            pattern_iterator->sigma = static_cast<float> (sigma_scale * scale_list_[scale] * (double (radius_list[ring])) * sin (M_PI / double (number_list[ring])));
+            pattern_iterator->sigma = static_cast<float> (sigma_scale * scale_list_[scale] * (static_cast<double>(radius_list[ring])) * sin (M_PI / static_cast<double>(number_list[ring])));
 
           // adapt the sizeList if necessary
           const auto size = static_cast<unsigned int> (std::ceil (((scale_list_[scale] * radius_list[ring]) + pattern_iterator->sigma)) + 1);
@@ -192,8 +185,8 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
       {
         // save to long pairs
         BriskLongPair& longPair = long_pairs_[no_long_pairs_];
-        longPair.weighted_dx = int ((dx / (norm_sq)) * 2048.0 + 0.5);
-        longPair.weighted_dy = int ((dy / (norm_sq)) * 2048.0 + 0.5);
+        longPair.weighted_dx = static_cast<int>((dx / (norm_sq)) * 2048.0 + 0.5);
+        longPair.weighted_dy = static_cast<int>((dy / (norm_sq)) * 2048.0 + 0.5);
         longPair.i = i;
         longPair.j = j;
         ++no_long_pairs_;
@@ -211,7 +204,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
   }
 
   // no bits:
-  strings_ = int (std::ceil ((float (no_short_pairs_)) / 128.0)) * 4 * 4;
+  strings_ = static_cast<int>(std::ceil ((static_cast<float>(no_short_pairs_)) / 128.0)) * 4 * 4;
 }
 
 
@@ -228,8 +221,8 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
   const BriskPatternPoint& brisk_point = pattern_points_[scale * n_rot_*points_ + rot * points_ + point];
   const float xf = brisk_point.x + key_x;
   const float yf = brisk_point.y + key_y;
-  const int x = int (xf);
-  const int y = int (yf);
+  const int x = static_cast<int>(xf);
+  const int y = static_cast<int>(yf);
   const int& imagecols = image_width;
 
   // get the sigma:
@@ -243,31 +236,31 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
   if (sigma_half < 0.5)
   {
     // interpolation multipliers:
-    const int r_x   = static_cast<int> ((xf - float (x)) * 1024);
-    const int r_y   = static_cast<int> ((yf - float (y)) * 1024);
+    const int r_x   = static_cast<int> ((xf - static_cast<float>(x)) * 1024);
+    const int r_y   = static_cast<int> ((yf - static_cast<float>(y)) * 1024);
     const int r_x_1 = (1024 - r_x);
     const int r_y_1 = (1024 - r_y);
 
     //+const unsigned char* ptr = static_cast<const unsigned char*> (&image[0].r) + x + y * imagecols;
-    const unsigned char* ptr = static_cast<const unsigned char*>(&image[0]) + x + y * imagecols;
+    const unsigned char* ptr = static_cast<const unsigned char*>(image.data()) + x + y * imagecols;
 
     // just interpolate:
-    ret_val = (r_x_1 * r_y_1 * int (*ptr));
+    ret_val = (r_x_1 * r_y_1 * static_cast<int>(*ptr));
 
     //+ptr += sizeof (PointInT);
     ptr++;
 
-    ret_val += (r_x * r_y_1 * int (*ptr));
+    ret_val += (r_x * r_y_1 * static_cast<int>(*ptr));
 
     //+ptr += (imagecols * sizeof (PointInT));
     ptr += imagecols;
 
-    ret_val += (r_x * r_y * int (*ptr));
+    ret_val += (r_x * r_y * static_cast<int>(*ptr));
 
     //+ptr -= sizeof (PointInT);
     ptr--;
 
-    ret_val += (r_x_1 * r_y * int (*ptr));
+    ret_val += (r_x_1 * r_y * static_cast<int>(*ptr));
     return (ret_val + 512) / 1024;
   }
 
@@ -275,7 +268,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
 
   // scaling:
   const int scaling  = static_cast<int> (4194304.0f / area);
-  const int scaling2 = static_cast<int> (float (scaling) * area / 1024.0f);
+  const int scaling2 = static_cast<int> (static_cast<float>(scaling) * area / 1024.0f);
 
   // the integral image is larger:
   const int integralcols = imagecols + 1;
@@ -286,55 +279,55 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
   const float y_1 = yf - sigma_half;
   const float y1  = yf + sigma_half;
 
-  const int x_left   = int (x_1 + 0.5);
-  const int y_top    = int (y_1 + 0.5);
-  const int x_right  = int (x1 + 0.5);
-  const int y_bottom = int (y1 + 0.5);
+  const int x_left   = static_cast<int>(x_1 + 0.5);
+  const int y_top    = static_cast<int>(y_1 + 0.5);
+  const int x_right  = static_cast<int>(x1 + 0.5);
+  const int y_bottom = static_cast<int>(y1 + 0.5);
 
   // overlap area - multiplication factors:
-  const float r_x_1 = float (x_left) - x_1  + 0.5f;
-  const float r_y_1 = float (y_top)  - y_1  + 0.5f;
-  const float r_x1  = x1 - float (x_right)  + 0.5f;
-  const float r_y1  = y1 - float (y_bottom) + 0.5f;
+  const float r_x_1 = static_cast<float>(x_left) - x_1  + 0.5f;
+  const float r_y_1 = static_cast<float>(y_top)  - y_1  + 0.5f;
+  const float r_x1  = x1 - static_cast<float>(x_right)  + 0.5f;
+  const float r_y1  = y1 - static_cast<float>(y_bottom) + 0.5f;
   const int dx = x_right  - x_left - 1;
   const int dy = y_bottom - y_top  - 1;
-  const int A = static_cast<int> ((r_x_1 * r_y_1) * float (scaling));
-  const int B = static_cast<int> ((r_x1  * r_y_1) * float (scaling));
-  const int C = static_cast<int> ((r_x1  * r_y1)  * float (scaling));
-  const int D = static_cast<int> ((r_x_1 * r_y1)  * float (scaling));
-  const int r_x_1_i = static_cast<int> (r_x_1 * float (scaling));
-  const int r_y_1_i = static_cast<int> (r_y_1 * float (scaling));
-  const int r_x1_i  = static_cast<int> (r_x1  * float (scaling));
-  const int r_y1_i  = static_cast<int> (r_y1  * float (scaling));
+  const int A = static_cast<int> ((r_x_1 * r_y_1) * static_cast<float>(scaling));
+  const int B = static_cast<int> ((r_x1  * r_y_1) * static_cast<float>(scaling));
+  const int C = static_cast<int> ((r_x1  * r_y1)  * static_cast<float>(scaling));
+  const int D = static_cast<int> ((r_x_1 * r_y1)  * static_cast<float>(scaling));
+  const int r_x_1_i = static_cast<int> (r_x_1 * static_cast<float>(scaling));
+  const int r_y_1_i = static_cast<int> (r_y_1 * static_cast<float>(scaling));
+  const int r_x1_i  = static_cast<int> (r_x1  * static_cast<float>(scaling));
+  const int r_y1_i  = static_cast<int> (r_y1  * static_cast<float>(scaling));
 
   if (dx + dy > 2)
   {
     // now the calculation:
 
     //+const unsigned char* ptr = static_cast<const unsigned char*> (&image[0].r) + x_left + imagecols * y_top;
-    const unsigned char* ptr = static_cast<const unsigned char*>(&image[0]) + x_left + imagecols * y_top;
+    const unsigned char* ptr = static_cast<const unsigned char*>(image.data()) + x_left + imagecols * y_top;
 
     // first the corners:
-    ret_val = A * int (*ptr);
+    ret_val = A * static_cast<int>(*ptr);
 
     //+ptr += (dx + 1) * sizeof (PointInT);
     ptr += dx + 1;
 
-    ret_val += B * int (*ptr);
+    ret_val += B * static_cast<int>(*ptr);
 
     //+ptr += (dy * imagecols + 1) * sizeof (PointInT);
     ptr += dy * imagecols + 1;
 
-    ret_val += C * int (*ptr);
+    ret_val += C * static_cast<int>(*ptr);
 
     //+ptr -= (dx + 1) * sizeof (PointInT);
     ptr -= dx + 1;
 
-    ret_val += D * int (*ptr);
+    ret_val += D * static_cast<int>(*ptr);
 
     // next the edges:
     //+int* ptr_integral;// = static_cast<int*> (integral.data) + x_left + integralcols * y_top + 1;
-    const int* ptr_integral = static_cast<const int*> (&integral_image[0]) + x_left + integralcols * y_top + 1;
+    const int* ptr_integral = static_cast<const int*> (integral_image.data()) + x_left + integralcols * y_top + 1;
 
     // find a simple path through the different surface corners
     const int tmp1 = (*ptr_integral);
@@ -374,10 +367,10 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
   // now the calculation:
 
   //const unsigned char* ptr = static_cast<const unsigned char*> (&image[0].r) + x_left + imagecols * y_top;
-  const unsigned char* ptr = static_cast<const unsigned char*>(&image[0]) + x_left + imagecols * y_top;
+  const unsigned char* ptr = static_cast<const unsigned char*>(image.data()) + x_left + imagecols * y_top;
 
   // first row:
-  ret_val = A * int (*ptr);
+  ret_val = A * static_cast<int>(*ptr);
 
   //+ptr += sizeof (PointInT);
   ptr++;
@@ -387,8 +380,8 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
 
   //+for (; ptr < end1; ptr += sizeof (PointInT))
   for (; ptr < end1; ptr++)
-    ret_val += r_y_1_i * int (*ptr);
-  ret_val += B * int (*ptr);
+    ret_val += r_y_1_i * static_cast<int>(*ptr);
+  ret_val += B * static_cast<int>(*ptr);
 
   // middle ones:
   //+ptr += (imagecols - dx - 1) * sizeof (PointInT);
@@ -400,7 +393,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
   //+for (; ptr < end_j; ptr += (imagecols - dx - 1) * sizeof (PointInT))
   for (; ptr < end_j; ptr += imagecols - dx - 1)
   {
-    ret_val += r_x_1_i * int (*ptr);
+    ret_val += r_x_1_i * static_cast<int>(*ptr);
 
     //+ptr += sizeof (PointInT);
     ptr++;
@@ -410,12 +403,12 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
 
     //+for (; ptr < end2; ptr += sizeof (PointInT))
     for (; ptr < end2; ptr++)
-      ret_val += int (*ptr) * scaling;
+      ret_val += static_cast<int>(*ptr) * scaling;
 
-    ret_val += r_x1_i * int (*ptr);
+    ret_val += r_x1_i * static_cast<int>(*ptr);
   }
   // last row:
-  ret_val += D * int (*ptr);
+  ret_val += D * static_cast<int>(*ptr);
 
   //+ptr += sizeof (PointInT);
   ptr++;
@@ -425,9 +418,9 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
 
   //+for (; ptr<end3; ptr += sizeof (PointInT))
   for (; ptr<end3; ptr++)
-    ret_val += r_y1_i * int (*ptr);
+    ret_val += r_y1_i * static_cast<int>(*ptr);
 
-  ret_val += C * int (*ptr);
+  ret_val += C * static_cast<int>(*ptr);
 
   return (ret_val + scaling2 / 2) / scaling2;
 }
@@ -477,14 +470,14 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
   unsigned int basicscale = 0;
 
   if (!scale_invariance_enabled_)
-    basicscale = std::max (static_cast<int> (float (scales_) / lb_scalerange * (std::log2 (1.45f * basic_size_ / (basic_size_06))) + 0.5f), 0);
+    basicscale = std::max (static_cast<int> (static_cast<float>(scales_) / lb_scalerange * (std::log2 (1.45f * basic_size_ / (basic_size_06))) + 0.5f), 0);
 
   for (std::size_t k = 0; k < ksize; k++)
   {
     unsigned int scale;
     if (scale_invariance_enabled_)
     {
-      scale = std::max (static_cast<int> (float (scales_) / lb_scalerange * (std::log2 ((*keypoints_)[k].size / (basic_size_06))) + 0.5f), 0);
+      scale = std::max (static_cast<int> (static_cast<float>(scales_) / lb_scalerange * (std::log2 ((*keypoints_)[k].size / (basic_size_06))) + 0.5f), 0);
       // saturate
       if (scale >= scales_) scale = scales_ - 1;
       kscales[k] = scale;
@@ -499,7 +492,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
     const int border_x = width - border;
     const int border_y = height - border;
 
-    if (RoiPredicate (float (border), float (border), float (border_x), float (border_y), (*keypoints_)[k]))
+    if (RoiPredicate (static_cast<float>(border), static_cast<float>(border), static_cast<float>(border_x), static_cast<float>(border_y), (*keypoints_)[k]))
     {
       //std::cerr << "remove keypoint" << std::endl;
       keypoints_->points.erase (beginning + k);
@@ -562,8 +555,9 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
     const int& scale = kscales[k];
     int shifter = 0;
     int* pvalues = values;
-    const float& x = float (kp.x);
-    const float& y = float (kp.y);
+    const float& x = (kp.x);
+    const float& y = (kp.y);
+    // NOLINTNEXTLINE(readability-simplify-boolean-expr)
     if (true) // kp.angle==-1
     {
       if (!rotation_invariance_enabled_)
@@ -592,11 +586,11 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
           direction0 += tmp0;
           direction1 += tmp1;
         }
-        kp.angle = std::atan2 (float (direction1), float (direction0)) / float (M_PI) * 180.0f;
-        theta = static_cast<int> ((float (n_rot_) * kp.angle) / (360.0f) + 0.5f);
+        kp.angle = std::atan2 (static_cast<float>(direction1), static_cast<float>(direction0)) / static_cast<float>(M_PI) * 180.0f;
+        theta = static_cast<int> ((static_cast<float>(n_rot_) * kp.angle) / (360.0f) + 0.5f);
         if (theta < 0)
           theta += n_rot_;
-        if (theta >= int (n_rot_))
+        if (theta >= static_cast<int>(n_rot_))
           theta -= n_rot_;
       }
     }
@@ -611,7 +605,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
         theta = static_cast<int> (n_rot_ * (kp.angle / (360.0)) + 0.5);
         if (theta < 0)
           theta += n_rot_;
-        if (theta >= int (n_rot_))
+        if (theta >= static_cast<int>(n_rot_))
           theta -= n_rot_;
       }
     }
index 9f17be2ffad7c9c13ce6206256135a4cfd9e95a1..f36826f5d193940fea739f080b6ca39ab33f9f3c 100644 (file)
@@ -66,18 +66,18 @@ pcl::ESFEstimation<PointInT, PointOutT>::computeESF (
   wt_d2.reserve (sample_size * 3);
   wt_d3.reserve (sample_size);
 
-  float h_in[binsize] = {0};
-  float h_out[binsize] = {0};
-  float h_mix[binsize] = {0};
-  float h_mix_ratio[binsize] = {0};
-
-  float h_a3_in[binsize] = {0};
-  float h_a3_out[binsize] = {0};
-  float h_a3_mix[binsize] = {0};
-
-  float h_d3_in[binsize] = {0};
-  float h_d3_out[binsize] = {0};
-  float h_d3_mix[binsize] = {0};
+  float h_in[binsize] = {0.0f};
+  float h_out[binsize] = {0.0f};
+  float h_mix[binsize] = {0.0f};
+  float h_mix_ratio[binsize] = {0.0f};
+
+  float h_a3_in[binsize] = {0.0f};
+  float h_a3_out[binsize] = {0.0f};
+  float h_a3_mix[binsize] = {0.0f};
+
+  float h_d3_in[binsize] = {0.0f};
+  float h_d3_out[binsize] = {0.0f};
+  float h_d3_mix[binsize] = {0.0f};
 
   float ratio=0.0;
   float pih = static_cast<float>(M_PI) / 2.0f;
index ba841a2ca6f5bac9b17b528f32057801ef8268d5..2f8d3c9577d5490255d7e9952d7d49b4a14bd8ab 100644 (file)
@@ -142,7 +142,7 @@ template<typename PointInT, typename PointNT, typename PointOutT, typename Signe
     //disambiguate Z axis with normal mean
     if (!pcl::flipNormalTowardsNormalsMean<PointNT> (*normals_, neighbours_indices, fitted_normal))
     {
-      //all normals in the neighbourood are invalid
+      //all normals in the neighbourhood are invalid
       //setting lrf to NaN
       lrf.setConstant (std::numeric_limits<float>::quiet_NaN ());
       return (std::numeric_limits<SignedDistanceT>::max ());
index 73074b63fbd3b7a18984f42b67baa504772ffbeb..47522c5763180f78adf73050fb53da5ebf5c9443 100644 (file)
@@ -76,11 +76,12 @@ pcl::GASDEstimation<PointInT, PointOutT>::computeAlignmentTransform ()
   Eigen::Vector4f centroid;
   Eigen::Matrix3f covariance_matrix;
 
-  // compute centroid of the object's partial view
-  pcl::compute3DCentroid (*surface_, *indices_, centroid);
-
-  // compute covariance matrix from points and centroid of the object's partial view
-  pcl::computeCovarianceMatrix (*surface_, *indices_, centroid, covariance_matrix);
+  // compute centroid of the object's partial view, then compute covariance matrix from points and centroid of the object's partial view
+  if (pcl::compute3DCentroid (*surface_, *indices_, centroid) == 0 ||
+      pcl::computeCovarianceMatrix (*surface_, *indices_, centroid, covariance_matrix) == 0) {
+    PCL_ERROR("[pcl::GASDEstimation::computeAlignmentTransform] Surface cloud or indices are empty!\n");
+    return;
+  }
 
   Eigen::Matrix3f eigenvectors;
   Eigen::Vector3f eigenvalues;
index 4fd45947b39cfca0b2326bc1e3fa74401362d1f3..88902cf6ddcbcc984ba85460bba8e88109995c81 100644 (file)
@@ -156,12 +156,12 @@ template <typename DataType, unsigned Dimension> void
 IntegralImage2D<DataType, Dimension>::computeIntegralImages (
     const DataType *data, unsigned row_stride, unsigned element_stride)
 {
-  ElementType* previous_row = &first_order_integral_image_[0];
+  ElementType* previous_row = first_order_integral_image_.data();
   ElementType* current_row  = previous_row + (width_ + 1);
   for (unsigned int i = 0; i < (width_ + 1); ++i)
     previous_row[i].setZero();
 
-  unsigned* count_previous_row = &finite_values_integral_image_[0];
+  unsigned* count_previous_row = finite_values_integral_image_.data();
   unsigned* count_current_row  = count_previous_row + (width_ + 1);
   std::fill_n(count_previous_row, width_ + 1, 0);
 
@@ -188,7 +188,7 @@ IntegralImage2D<DataType, Dimension>::computeIntegralImages (
   }
   else
   {
-    SecondOrderType* so_previous_row = &second_order_integral_image_[0];
+    SecondOrderType* so_previous_row = second_order_integral_image_.data();
     SecondOrderType* so_current_row  = so_previous_row + (width_ + 1);
     for (unsigned int i = 0; i < (width_ + 1); ++i)
       so_previous_row[i].setZero();
@@ -327,11 +327,11 @@ template <typename DataType> void
 IntegralImage2D<DataType, 1>::computeIntegralImages (
     const DataType *data, unsigned row_stride, unsigned element_stride)
 {
-  ElementType* previous_row = &first_order_integral_image_[0];
+  ElementType* previous_row = first_order_integral_image_.data();
   ElementType* current_row  = previous_row + (width_ + 1);
   std::fill_n(previous_row, width_ + 1, 0);
 
-  unsigned* count_previous_row = &finite_values_integral_image_[0];
+  unsigned* count_previous_row = finite_values_integral_image_.data();
   unsigned* count_current_row  = count_previous_row + (width_ + 1);
   std::fill_n(count_previous_row, width_ + 1, 0);
 
@@ -357,7 +357,7 @@ IntegralImage2D<DataType, 1>::computeIntegralImages (
   }
   else
   {
-    SecondOrderType* so_previous_row = &second_order_integral_image_[0];
+    SecondOrderType* so_previous_row = second_order_integral_image_.data();
     SecondOrderType* so_current_row  = so_previous_row + (width_ + 1);
     std::fill_n(so_previous_row, width_ + 1, 0);
 
index ea8aa26250ea7dc1278a7e98f7cf6a530780f152..f76765a1bcc69e739f904f67c526687787431684 100644 (file)
@@ -511,9 +511,9 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computePointNormalMirro
     auto cb_xyz_sosse = [this] (unsigned p1, unsigned p2, unsigned p3, unsigned p4) { return integral_image_XYZ_.getSecondOrderSumSE (p1, p2, p3, p4); };
     sumArea<typename IntegralImage2D<float, 3>::SecondOrderType>(start_x, start_y, end_x, end_y, width, height, cb_xyz_sosse, so_elements);
 
-    center[0] = float (tmp_center[0]);
-    center[1] = float (tmp_center[1]);
-    center[2] = float (tmp_center[2]);
+    center[0] = static_cast<float>(tmp_center[0]);
+    center[1] = static_cast<float>(tmp_center[1]);
+    center[2] = static_cast<float>(tmp_center[2]);
 
     covariance_matrix.coeffRef (0) = static_cast<float> (so_elements [0]);
     covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = static_cast<float> (so_elements [1]);
@@ -670,10 +670,10 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computePointNormalMirro
     sumArea<float>(start_x_U, start_y_U, end_x_U, end_y_U, width, height, cb_fosse, mean_U_z);
     sumArea<float>(start_x_D, start_y_D, end_x_D, end_y_D, width, height, cb_fosse, mean_D_z);
 
-    mean_L_z /= float (count_L_z);
-    mean_R_z /= float (count_R_z);
-    mean_U_z /= float (count_U_z);
-    mean_D_z /= float (count_D_z);
+    mean_L_z /= static_cast<float>(count_L_z);
+    mean_R_z /= static_cast<float>(count_R_z);
+    mean_U_z /= static_cast<float>(count_U_z);
+    mean_D_z /= static_cast<float>(count_D_z);
 
 
     PointInT pointL = (*input_)[point_index_L_y*width + point_index_L_x];
@@ -845,7 +845,7 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeatureFull (con
     // top and bottom borders
     // That sets the output density to false!
     output.is_dense = false;
-    unsigned border = int(normal_smoothing_size_);
+    const auto border = static_cast<unsigned>(normal_smoothing_size_);
     PointOutT* vec1 = &output [0];
     PointOutT* vec2 = vec1 + input_->width * (input_->height - border);
 
@@ -895,7 +895,13 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeatureFull (con
           if (smoothing > 2.0f)
           {
             setRectSize (static_cast<int> (smoothing), static_cast<int> (smoothing));
-            computePointNormal (ci, ri, index, output [index]);
+            // Since depth can be anything, we have no guarantee that the border is sufficient, so we need to check
+            if(ci>static_cast<unsigned>(rect_width_2_) && ri>static_cast<unsigned>(rect_height_2_) && (ci+rect_width_2_)<input_->width && (ri+rect_height_2_)<input_->height) {
+              computePointNormal (ci, ri, index, output [index]);
+            } else {
+              output[index].getNormalVector3fMap ().setConstant (bad_point);
+              output[index].curvature = bad_point;
+            }
           }
           else
           {
@@ -907,8 +913,6 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeatureFull (con
     }
     else
     {
-      float smoothing_constant = normal_smoothing_size_;
-
       index = border + input_->width * border;
       unsigned skip = (border << 1);
       for (unsigned ri = border; ri < input_->height - border; ++ri, index += skip)
@@ -924,7 +928,7 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeatureFull (con
             continue;
           }
 
-          float smoothing = (std::min)(distanceMap[index], smoothing_constant);
+          float smoothing = (std::min)(distanceMap[index], normal_smoothing_size_);
 
           if (smoothing > 2.0f)
           {
@@ -981,8 +985,6 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeatureFull (con
     }
     else
     {
-      float smoothing_constant = normal_smoothing_size_;
-
       //index = border + input_->width * border;
       //unsigned skip = (border << 1);
       //for (unsigned ri = border; ri < input_->height - border; ++ri, index += skip)
@@ -1000,7 +1002,7 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeatureFull (con
             continue;
           }
 
-          float smoothing = (std::min)(distanceMap[index], smoothing_constant);
+          float smoothing = (std::min)(distanceMap[index], normal_smoothing_size_);
 
           if (smoothing > 2.0f)
           {
@@ -1027,9 +1029,9 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeaturePart (con
   if (border_policy_ == BORDER_POLICY_IGNORE)
   {
     output.is_dense = false;
-    unsigned border = int(normal_smoothing_size_);
-    unsigned bottom = input_->height > border ? input_->height - border : 0;
-    unsigned right = input_->width > border ? input_->width - border : 0;
+    const auto border = static_cast<unsigned>(normal_smoothing_size_);
+    const unsigned bottom = input_->height > border ? input_->height - border : 0;
+    const unsigned right = input_->width > border ? input_->width - border : 0;
     if (use_depth_dependent_smoothing_)
     {
       // Iterating over the entire index vector
@@ -1075,7 +1077,6 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeaturePart (con
     }
     else
     {
-      float smoothing_constant = normal_smoothing_size_;
       // Iterating over the entire index vector
       for (std::size_t idx = 0; idx < indices_->size (); ++idx)
       {
@@ -1103,7 +1104,7 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeaturePart (con
           continue;
         }
 
-        float smoothing = (std::min)(distanceMap[pt_index], smoothing_constant);
+        float smoothing = (std::min)(distanceMap[pt_index], normal_smoothing_size_);
 
         if (smoothing > 2.0f)
         {
@@ -1154,7 +1155,6 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeaturePart (con
     }
     else
     {
-      float smoothing_constant = normal_smoothing_size_;
       for (std::size_t idx = 0; idx < indices_->size (); ++idx)
       {
         unsigned pt_index = (*indices_)[idx];
@@ -1168,7 +1168,7 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computeFeaturePart (con
           continue;
         }
 
-        float smoothing = (std::min)(distanceMap[pt_index], smoothing_constant);
+        float smoothing = (std::min)(distanceMap[pt_index], normal_smoothing_size_);
 
         if (smoothing > 2.0f)
         {
index cffb505622a4a6b56c2749d5b1dce6be9cf71c14..b7dd7ae4b4f55512122d9671d786da6fe724f9ed 100644 (file)
@@ -147,7 +147,7 @@ pcl::IntensitySpinEstimation<PointInT, PointOutT>::computeFeature (PointCloudOut
   for (std::size_t idx = 0; idx < indices_->size (); ++idx)
   {
     // Find neighbors within the search radius
-    // TODO: do we want to use searchForNeigbors instead?
+    // TODO: do we want to use searchForNeighbors instead?
     int k = tree_->radiusSearch ((*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr);
     if (k == 0)
     {
index 009443e666ba997879f42cd7e5c632afc1f775fe..51f7f9e098e44bdf5fb6da0bd86cb28742360bcf 100644 (file)
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
 pcl::MomentOfInertiaEstimation<PointT>::MomentOfInertiaEstimation () :
-  is_valid_ (false),
-  step_ (10.0f),
-  point_mass_ (0.0001f),
-  normalize_ (true),
+  
   mean_value_ (0.0f, 0.0f, 0.0f),
   major_axis_ (0.0f, 0.0f, 0.0f),
   middle_axis_ (0.0f, 0.0f, 0.0f),
   minor_axis_ (0.0f, 0.0f, 0.0f),
-  major_value_ (0.0f),
-  middle_value_ (0.0f),
-  minor_value_ (0.0f),
+  
   aabb_min_point_ (),
   aabb_max_point_ (),
   obb_min_point_ (),
index 932aad8d5e525855fe7f7d0ee6310147bd601cbd..5563efecbe502675e4bdada043ef5a292257927c 100644 (file)
@@ -45,8 +45,7 @@
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointSource, typename PointFeature>
 pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::MultiscaleFeaturePersistence () : 
-  alpha_ (0), 
-  distance_metric_ (L1),
+  
   feature_estimator_ (),
   features_at_scale_ (),
   feature_representation_ ()
@@ -91,10 +90,10 @@ pcl::MultiscaleFeaturePersistence<PointSource, PointFeature>::computeFeaturesAtA
   features_at_scale_.reserve (scale_values_.size ());
   features_at_scale_vectorized_.clear ();
   features_at_scale_vectorized_.reserve (scale_values_.size ());
-  for (std::size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i)
+  for (float & scale_value : scale_values_)
   {
     FeatureCloudPtr feature_cloud (new FeatureCloud ());
-    computeFeatureAtScale (scale_values_[scale_i], feature_cloud);
+    computeFeatureAtScale (scale_value, feature_cloud);
     features_at_scale_.push_back(feature_cloud);
 
     // Vectorize each feature and insert it into the vectorized feature storage
index b1a317598e62a6feb3cd42d3ecc074d1c590b88b..736b5c8d2fe82107b57614e8ea217de922883c56 100644 (file)
 template <typename PointInT, typename PointOutT> void
 pcl::NormalEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
 {
-  if (nr_threads == 0)
 #ifdef _OPENMP
+  if (nr_threads == 0)
     threads_ = omp_get_num_procs();
-#else
-    threads_ = 1;
-#endif
   else
     threads_ = nr_threads;
+  PCL_DEBUG ("[pcl::NormalEstimationOMP::setNumberOfThreads] Setting number of threads to %u.\n", threads_);
+#else
+  threads_ = 1;
+  if (nr_threads != 1)
+    PCL_WARN ("[pcl::NormalEstimationOMP::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n");
+#endif // _OPENMP
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////
@@ -74,7 +77,8 @@ pcl::NormalEstimationOMP<PointInT, PointOutT>::computeFeature (PointCloudOut &ou
   default(none) \
   shared(output) \
   firstprivate(nn_indices, nn_dists) \
-  num_threads(threads_)
+  num_threads(threads_) \
+  schedule(dynamic, chunk_size_)
     // Iterating over the entire index vector
     for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
     {
@@ -103,7 +107,8 @@ pcl::NormalEstimationOMP<PointInT, PointOutT>::computeFeature (PointCloudOut &ou
   default(none) \
   shared(output) \
   firstprivate(nn_indices, nn_dists) \
-  num_threads(threads_)
+  num_threads(threads_) \
+  schedule(dynamic, chunk_size_)
     // Iterating over the entire index vector
     for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
     {
index 65e68be56782af4b0e385ea04ad923692eaee740..90f87ee3f3ba7ba666f1f34f2b2815bd27e330c1 100644 (file)
@@ -52,7 +52,7 @@ template<typename PointT, typename PointLT> void
 pcl::OrganizedEdgeBase<PointT, PointLT>::compute (pcl::PointCloud<PointLT>& labels, std::vector<pcl::PointIndices>& label_indices) const
 {
   pcl::Label invalid_pt;
-  invalid_pt.label = unsigned (0);
+  invalid_pt.label = static_cast<unsigned>(0);
   labels.resize (input_->size (), invalid_pt);
   labels.width = input_->width;
   labels.height = input_->height;
@@ -66,7 +66,7 @@ pcl::OrganizedEdgeBase<PointT, PointLT>::compute (pcl::PointCloud<PointLT>& labe
 template<typename PointT, typename PointLT> void
 pcl::OrganizedEdgeBase<PointT, PointLT>::assignLabelIndices (pcl::PointCloud<PointLT>& labels, std::vector<pcl::PointIndices>& label_indices) const
 {
-  const auto invalid_label = unsigned (0);
+  const auto invalid_label = static_cast<unsigned>(0);
   label_indices.resize (num_of_edgetype_);
   for (std::size_t idx = 0; idx < input_->size (); idx++)
   {
@@ -98,11 +98,11 @@ pcl::OrganizedEdgeBase<PointT, PointLT>::extractEdges (pcl::PointCloud<PointLT>&
       Neighbor( 0,  1,  labels.width    ),
       Neighbor(-1,  1,  labels.width - 1)};
 
-    for (int row = 1; row < int(input_->height) - 1; row++)
+    for (int row = 1; row < static_cast<int>(input_->height) - 1; row++)
     {
-      for (int col = 1; col < int(input_->width) - 1; col++)
+      for (int col = 1; col < static_cast<int>(input_->width) - 1; col++)
       {
-        int curr_idx = row*int(input_->width) + col;
+        int curr_idx = row*static_cast<int>(input_->width) + col;
         if (!std::isfinite ((*input_)[curr_idx].z))
           continue;
 
@@ -179,12 +179,12 @@ pcl::OrganizedEdgeBase<PointT, PointLT>::extractEdges (pcl::PointCloud<PointLT>&
             int s_row = row + static_cast<int> (std::floor (f_dy*static_cast<float> (s_idx)));
             int s_col = col + static_cast<int> (std::floor (f_dx*static_cast<float> (s_idx)));
 
-            if (s_row < 0 || s_row >= int(input_->height) || s_col < 0 || s_col >= int(input_->width))
+            if (s_row < 0 || s_row >= static_cast<int>(input_->height) || s_col < 0 || s_col >= static_cast<int>(input_->width))
               break;
 
-            if (std::isfinite ((*input_)[s_row*int(input_->width)+s_col].z))
+            if (std::isfinite ((*input_)[s_row*static_cast<int>(input_->width)+s_col].z))
             {
-              corr_depth = std::abs ((*input_)[s_row*int(input_->width)+s_col].z);
+              corr_depth = std::abs ((*input_)[s_row*static_cast<int>(input_->width)+s_col].z);
               break;
             }
           }
@@ -226,7 +226,7 @@ template<typename PointT, typename PointLT> void
 pcl::OrganizedEdgeFromRGB<PointT, PointLT>::compute (pcl::PointCloud<PointLT>& labels, std::vector<pcl::PointIndices>& label_indices) const
 {
   pcl::Label invalid_pt;
-  invalid_pt.label = unsigned (0);
+  invalid_pt.label = static_cast<unsigned>(0);
   labels.resize (input_->size (), invalid_pt);
   labels.width = input_->width;
   labels.height = input_->height;
@@ -249,7 +249,7 @@ pcl::OrganizedEdgeFromRGB<PointT, PointLT>::extractEdges (pcl::PointCloud<PointL
     gray->resize (input_->height*input_->width);
 
     for (std::size_t i = 0; i < input_->size (); ++i)
-      (*gray)[i].intensity = float (((*input_)[i].r + (*input_)[i].g + (*input_)[i].b) / 3);
+      (*gray)[i].intensity = static_cast<float>(((*input_)[i].r + (*input_)[i].g + (*input_)[i].b) / 3);
 
     pcl::PointCloud<pcl::PointXYZIEdge> img_edge_rgb;
     pcl::Edge<PointXYZI, pcl::PointXYZIEdge> edge;
@@ -274,7 +274,7 @@ template<typename PointT, typename PointNT, typename PointLT> void
 pcl::OrganizedEdgeFromNormals<PointT, PointNT, PointLT>::compute (pcl::PointCloud<PointLT>& labels, std::vector<pcl::PointIndices>& label_indices) const
 {
   pcl::Label invalid_pt;
-  invalid_pt.label = unsigned (0);
+  invalid_pt.label = static_cast<unsigned>(0);
   labels.resize (input_->size (), invalid_pt);
   labels.width = input_->width;
   labels.height = input_->height;
@@ -332,7 +332,7 @@ template<typename PointT, typename PointNT, typename PointLT> void
 pcl::OrganizedEdgeFromRGBNormals<PointT, PointNT, PointLT>::compute (pcl::PointCloud<PointLT>& labels, std::vector<pcl::PointIndices>& label_indices) const
 {
   pcl::Label invalid_pt;
-  invalid_pt.label = unsigned (0);
+  invalid_pt.label = static_cast<unsigned>(0);
   labels.resize (input_->size (), invalid_pt);
   labels.width = input_->width;
   labels.height = input_->height;
index bfc8867c39cf9ba7ab6d488425e167a57101901d..092dbd3c09c87ff3cd4887bb0f623376c7ec8601 100644 (file)
@@ -334,10 +334,7 @@ bool RangeImageBorderExtractor::calculateMainPrincipalCurvature(int x, int y, in
         bool& beam_valid = beams_valid[beam_idx++];
         if (step==1)
         {
-          if (x2==x && y2==y)
-            beam_valid = false;
-          else
-            beam_valid = true;
+          beam_valid = !(x2==x && y2==y);
         }
         else
           if (!beam_valid)
index ef80b346e26ff6e607be4c780107955404ca84ba..510153637dfb4b26f8275d241131486059d0f599 100644 (file)
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointInT, typename PointOutT>
 pcl::ROPSEstimation <PointInT, PointOutT>::ROPSEstimation () :
-  number_of_bins_ (5),
-  number_of_rotations_ (3),
-  support_radius_ (1.0f),
-  sqr_support_radius_ (1.0f),
-  step_ (22.5f),
+  
   triangles_ (0),
   triangles_of_the_point_ (0)
 {
index 5a5f25eeb43b3291131eb3fe39f75045c7b91f00..7787eb885239fd401a09fa2652bb5a712f82c656 100644 (file)
@@ -124,8 +124,8 @@ pcl::computeRSD (const pcl::PointCloud<PointInT> &surface, const pcl::PointCloud
       Amaxt_d += p_max * f;
     }
   }
-  float min_radius = Amint_Amin == 0.0f ? float (plane_radius) : float (std::min (Amint_d/Amint_Amin, plane_radius));
-  float max_radius = Amaxt_Amax == 0.0f ? float (plane_radius) : float (std::min (Amaxt_d/Amaxt_Amax, plane_radius));
+  float min_radius = Amint_Amin == 0.0f ? static_cast<float>(plane_radius) : static_cast<float>(std::min (Amint_d/Amint_Amin, plane_radius));
+  float max_radius = Amaxt_Amax == 0.0f ? static_cast<float>(plane_radius) : static_cast<float>(std::min (Amaxt_d/Amaxt_Amax, plane_radius));
 
   // Small correction of the systematic error of the estimation (based on analysis with nr_subdiv_ = 5)
   min_radius *= 1.1f;
@@ -223,8 +223,8 @@ pcl::computeRSD (const pcl::PointCloud<PointNT> &normals,
       Amaxt_d += p_max * f;
     }
   }
-  float min_radius = Amint_Amin == 0.0f ? float (plane_radius) : float (std::min (Amint_d/Amint_Amin, plane_radius));
-  float max_radius = Amaxt_Amax == 0.0f ? float (plane_radius) : float (std::min (Amaxt_d/Amaxt_Amax, plane_radius));
+  float min_radius = Amint_Amin == 0.0f ? static_cast<float>(plane_radius) : static_cast<float>(std::min (Amint_d/Amint_Amin, plane_radius));
+  float max_radius = Amaxt_Amax == 0.0f ? static_cast<float>(plane_radius) : static_cast<float>(std::min (Amaxt_d/Amaxt_Amax, plane_radius));
 
   // Small correction of the systematic error of the estimation (based on analysis with nr_subdiv_ = 5)
   min_radius *= 1.1f;
index 9d6ec0aaba4d38494db6dd16a27743ba14afc87d..6b9f1944b72fd5dad2e7fa3c64b21783c71e074b 100644 (file)
@@ -114,9 +114,9 @@ pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::RGB2CIELAB (un
   float vy = y;
   float vz = z / 1.08883f;
 
-  vx = sXYZ_LUT[int(vx*4000)];
-  vy = sXYZ_LUT[int(vy*4000)];
-  vz = sXYZ_LUT[int(vz*4000)];
+  vx = sXYZ_LUT[static_cast<int>(vx*4000)];
+  vy = sXYZ_LUT[static_cast<int>(vy*4000)];
+  vz = sXYZ_LUT[static_cast<int>(vz*4000)];
 
   L = 116.0f * vy - 16.0f;
   if (L > 100)
index 319ea73eb4290e8b1636dc070d5ecd2ab4b919c9..0cc6671f8028cc02d6b9ba8b09545230ae043a09 100644 (file)
@@ -52,11 +52,13 @@ template <typename PointInT, typename PointNT, typename PointOutT>
 pcl::SpinImageEstimation<PointInT, PointNT, PointOutT>::SpinImageEstimation (
   unsigned int image_width, double support_angle_cos, unsigned int min_pts_neighb) :
   input_normals_ (), rotation_axes_cloud_ (), 
-  is_angular_ (false), rotation_axis_ (), use_custom_axis_(false), use_custom_axes_cloud_ (false), 
-  is_radial_ (false), image_width_ (image_width), support_angle_cos_ (support_angle_cos), 
+   rotation_axis_ (),  support_angle_cos_ (support_angle_cos),
   min_pts_neighb_ (min_pts_neighb)
 {
-  assert (support_angle_cos_ <= 1.0 && support_angle_cos_ >= 0.0); // may be permit negative cosine?
+  if (0.0 > support_angle_cos || support_angle_cos > 1.0) { // may be permit negative cosine?
+    throw PCLException ("Cosine of support angle should be between 0 and 1", "spin_image.hpp", "SpinImageEstimation");
+  }
+  setImageWidth(image_width);
 
   feature_name_ = "SpinImageEstimation";
 }
@@ -179,9 +181,9 @@ pcl::SpinImageEstimation<PointInT, PointNT, PointOutT>::computeSiForPoint (int i
 
     // bilinear interpolation
     double beta_bin_size = is_radial_ ? (M_PI / 2 / image_width_) : bin_size;
-    int beta_bin = int(std::floor (beta / beta_bin_size)) + int(image_width_);
+    int beta_bin = static_cast<int>(std::floor (beta / beta_bin_size)) + static_cast<int>(image_width_);
     assert (0 <= beta_bin && beta_bin < m_matrix.cols ());
-    int alpha_bin = int(std::floor (alpha / bin_size));
+    int alpha_bin = static_cast<int>(std::floor (alpha / bin_size));
     assert (0 <= alpha_bin && alpha_bin < m_matrix.rows ());
 
     if (alpha_bin == static_cast<int> (image_width_))  // border points
@@ -190,15 +192,15 @@ pcl::SpinImageEstimation<PointInT, PointNT, PointOutT>::computeSiForPoint (int i
       // HACK: to prevent a > 1
       alpha = bin_size * (alpha_bin + 1) - std::numeric_limits<double>::epsilon ();
     }
-    if (beta_bin == int(2*image_width_) )  // border points
+    if (beta_bin == static_cast<int>(2*image_width_) )  // border points
     {
       beta_bin--;
       // HACK: to prevent b > 1
-      beta = beta_bin_size * (beta_bin - int(image_width_) + 1) - std::numeric_limits<double>::epsilon ();
+      beta = beta_bin_size * (beta_bin - static_cast<int>(image_width_) + 1) - std::numeric_limits<double>::epsilon ();
     }
 
-    double a = alpha/bin_size - double(alpha_bin);
-    double b = beta/beta_bin_size - double(beta_bin-int(image_width_)); 
+    double a = alpha/bin_size - static_cast<double>(alpha_bin);
+    double b = beta/beta_bin_size - static_cast<double>(beta_bin-static_cast<int>(image_width_)); 
 
     assert (0 <= a && a <= 1);
     assert (0 <= b && b <= 1);
index 5d4e778494b01ef0b0e92d8329045119aaa2861d..92f0e53df05e35616d84f422879316145f4d96b8 100644 (file)
@@ -121,8 +121,7 @@ namespace pcl
       IntegralImage2D (bool compute_second_order_integral_images) :
         first_order_integral_image_ (),
         second_order_integral_image_ (),
-        width_ (1), 
-        height_ (1), 
+         
         compute_second_order_integral_images_ (compute_second_order_integral_images)
       {
       }
@@ -218,9 +217,9 @@ namespace pcl
       std::vector<unsigned> finite_values_integral_image_;
 
       /** \brief The width of the 2d input data array */
-      unsigned width_;
+      unsigned width_{1};
       /** \brief The height of the 2d input data array */
-      unsigned height_;
+      unsigned height_{1};
 
       /** \brief Indicates whether second order integral images are available **/
       bool compute_second_order_integral_images_;
@@ -247,7 +246,7 @@ namespace pcl
         first_order_integral_image_ (),
         second_order_integral_image_ (),
         
-        width_ (1), height_ (1), 
+         
         compute_second_order_integral_images_ (compute_second_order_integral_images)
       {
       }
@@ -337,9 +336,9 @@ namespace pcl
       std::vector<unsigned> finite_values_integral_image_;
 
       /** \brief The width of the 2d input data array */
-      unsigned width_;
+      unsigned width_{1};
       /** \brief The height of the 2d input data array */
-      unsigned height_;
+      unsigned height_{1};
 
       /** \brief Indicates whether second order integral images are available **/
       bool compute_second_order_integral_images_;
index b9bc0628422fb12b112b6179c7f1d60ccfebe599..8dc1249bd923dc66c71bcf3782aa8b65b3dcbd43 100644 (file)
@@ -107,28 +107,11 @@ namespace pcl
       IntegralImageNormalEstimation ()
         : normal_estimation_method_(AVERAGE_3D_GRADIENT)
         , border_policy_ (BORDER_POLICY_IGNORE)
-        , rect_width_ (0), rect_width_2_ (0), rect_width_4_ (0)
-        , rect_height_ (0), rect_height_2_ (0), rect_height_4_ (0)
-        , distance_threshold_ (0)
-        , integral_image_DX_ (false)
+        ,  integral_image_DX_ (false)
         , integral_image_DY_ (false)
         , integral_image_depth_ (false)
         , integral_image_XYZ_ (true)
-        , diff_x_ (nullptr)
-        , diff_y_ (nullptr)
-        , depth_data_ (nullptr)
-        , distance_map_ (nullptr)
-        , use_depth_dependent_smoothing_ (false)
         , max_depth_change_factor_ (20.0f*0.001f)
-        , normal_smoothing_size_ (10.0f)
-        , init_covariance_matrix_ (false)
-        , init_average_3d_gradient_ (false)
-        , init_simple_3d_gradient_ (false)
-        , init_depth_change_ (false)
-        , vpx_ (0.0f)
-        , vpy_ (0.0f)
-        , vpz_ (0.0f)
-        , use_sensor_origin_ (true)
       {
         feature_name_ = "IntegralImagesNormalEstimation";
         tree_.reset ();
@@ -189,9 +172,9 @@ namespace pcl
       void
       setNormalSmoothingSize (float normal_smoothing_size)
       {
-        if (normal_smoothing_size <= 0)
+        if (normal_smoothing_size < 2.0f)
         {
-          PCL_ERROR ("[pcl::%s::setNormalSmoothingSize] Invalid normal smoothing size given! (%f). Allowed ranges are: 0 < N. Defaulting to %f.\n", 
+          PCL_ERROR ("[pcl::%s::setNormalSmoothingSize] Invalid normal smoothing size given! (%g). Must be at least 2. Defaulting to %g.\n",
                       feature_name_.c_str (), normal_smoothing_size, normal_smoothing_size_);
           return;
         }
@@ -385,16 +368,16 @@ namespace pcl
       BorderPolicy border_policy_;
 
       /** The width of the neighborhood region used for computing the normal. */
-      int rect_width_;
-      int rect_width_2_;
-      int rect_width_4_;
+      int rect_width_{0};
+      int rect_width_2_{0};
+      int rect_width_4_{0};
       /** The height of the neighborhood region used for computing the normal. */
-      int rect_height_;
-      int rect_height_2_;
-      int rect_height_4_;
+      int rect_height_{0};
+      int rect_height_2_{0};
+      int rect_height_4_{0};
 
       /** the threshold used to detect depth discontinuities */
-      float distance_threshold_;
+      float distance_threshold_{0.0f};
 
       /** integral image in x-direction */
       IntegralImage2D<float, 3> integral_image_DX_;
@@ -406,43 +389,43 @@ namespace pcl
       IntegralImage2D<float, 3> integral_image_XYZ_;
 
       /** derivatives in x-direction */
-      float *diff_x_;
+      float *diff_x_{nullptr};
       /** derivatives in y-direction */
-      float *diff_y_;
+      float *diff_y_{nullptr};
 
       /** depth data */
-      float *depth_data_;
+      float *depth_data_{nullptr};
 
       /** distance map */
-      float *distance_map_;
+      float *distance_map_{nullptr};
 
       /** \brief Smooth data based on depth (true/false). */
-      bool use_depth_dependent_smoothing_;
+      bool use_depth_dependent_smoothing_{false};
 
       /** \brief Threshold for detecting depth discontinuities */
       float max_depth_change_factor_;
 
       /** \brief */
-      float normal_smoothing_size_;
+      float normal_smoothing_size_{10.0f};
 
       /** \brief True when a dataset has been received and the covariance_matrix data has been initialized. */
-      bool init_covariance_matrix_;
+      bool init_covariance_matrix_{false};
 
       /** \brief True when a dataset has been received and the average 3d gradient data has been initialized. */
-      bool init_average_3d_gradient_;
+      bool init_average_3d_gradient_{false};
 
       /** \brief True when a dataset has been received and the simple 3d gradient data has been initialized. */
-      bool init_simple_3d_gradient_;
+      bool init_simple_3d_gradient_{false};
 
       /** \brief True when a dataset has been received and the depth change data has been initialized. */
-      bool init_depth_change_;
+      bool init_depth_change_{false};
 
       /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit
         * from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */
-      float vpx_, vpy_, vpz_;
+      float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};
 
       /** whether the sensor origin of the input cloud or a user given viewpoint should be used.*/
-      bool use_sensor_origin_;
+      bool use_sensor_origin_{true};
       
       /** \brief This method should get called before starting the actual computation. */
       bool
index e8a2a1aaa5174181d355314b07a7f7a3cf8b4901..b0f2d75fdb995061990c28ffb6b5a5772cb6c895 100644 (file)
@@ -69,10 +69,10 @@ namespace pcl
       using PointCloudOut = typename Feature<PointInT, PointOutT>::PointCloudOut;
 
       /** \brief Empty constructor. */
-      IntensityGradientEstimation () : intensity_ (), threads_ (0)
+      IntensityGradientEstimation () : intensity_ ()
       {
         feature_name_ = "IntensityGradientEstimation";
-      };
+      }
 
       /** \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)
@@ -90,7 +90,7 @@ namespace pcl
 
       /** \brief Estimate the intensity gradient around a given point based on its spatial neighborhood of points
         * \param cloud a point cloud dataset containing XYZI coordinates (Cartesian coordinates + intensity)
-        * \param indices the indices of the neighoring points in the dataset
+        * \param indices the indices of the neighboring points in the dataset
         * \param point the 3D Cartesian coordinates of the point at which to estimate the gradient
         * \param mean_intensity
         * \param normal the 3D surface normal of the given point
@@ -108,7 +108,7 @@ namespace pcl
       ///intensity field accessor structure
       IntensitySelectorT intensity_;
       ///number of threads to be used, default 0 (auto)
-      unsigned int threads_;
+      unsigned int threads_{0};
   };
 }
 
index 6af285a1474583970e1b655512254340f21d4726..3872ec2f0bfdbe4829912e771e1633f6661a77ad 100644 (file)
@@ -74,10 +74,10 @@ namespace pcl
       using PointCloudOut = typename Feature<PointInT, PointOutT>::PointCloudOut;
 
       /** \brief Empty constructor. */
-      IntensitySpinEstimation () : nr_distance_bins_ (4), nr_intensity_bins_ (5), sigma_ (1.0)
+      IntensitySpinEstimation ()
       {
         feature_name_ = "IntensitySpinEstimation";
-      };
+      }
 
       /** \brief Estimate the intensity-domain spin image descriptor for a given point based on its spatial
         * neighborhood of 3D points and their intensities. 
@@ -135,13 +135,13 @@ namespace pcl
       computeFeature (PointCloudOut &output) override;
     
       /** \brief The number of distance bins in the descriptor. */
-      int nr_distance_bins_;
+      int nr_distance_bins_{4};
 
       /** \brief The number of intensity bins in the descriptor. */
-      int nr_intensity_bins_;
+      int nr_intensity_bins_{5};
 
       /** \brief The standard deviation of the Gaussian smoothing kernel used to construct the spin images. */
-      float sigma_;
+      float sigma_{1.0};
   };
 }
 
index bf2ce2e17946916e102ee75a8b8b826669cc9507..00f9a79eac6f4ce33375094d73c8cef69fb8cb07 100644 (file)
@@ -59,15 +59,12 @@ namespace pcl
       using Feature<PointInT, PointOutT>::k_;
 
       /** \brief Constructor */
-      LinearLeastSquaresNormalEstimation () :
-          use_depth_dependent_smoothing_(false),
-          max_depth_change_factor_(1.0f),
-          normal_smoothing_size_(9.0f)
+      LinearLeastSquaresNormalEstimation ()
       {
           feature_name_ = "LinearLeastSquaresNormalEstimation";
           tree_.reset ();
           k_ = 1;
-      };
+      }
 
       /** \brief Destructor */
       ~LinearLeastSquaresNormalEstimation () override;
@@ -131,13 +128,13 @@ namespace pcl
       //float distance_threshold_;
 
       /** \brief Smooth data based on depth (true/false). */
-      bool use_depth_dependent_smoothing_;
+      bool use_depth_dependent_smoothing_{false};
 
       /** \brief Threshold for detecting depth discontinuities */
-      float max_depth_change_factor_;
+      float max_depth_change_factor_{1.0f};
 
       /** \brief */
-      float normal_smoothing_size_;
+      float normal_smoothing_size_{9.0f};
   };
 }
 
index f827771151e412868036b9d66fa453e5e8cac34e..9d96d4071575a07e22500394b0bfccb129195451 100644 (file)
@@ -291,16 +291,16 @@ namespace pcl
 
       /** \brief Indicates if the stored values (eccentricity, moment of inertia, AABB etc.)
         * are valid when accessed with the get methods. */
-      bool is_valid_;
+      bool is_valid_{false};
 
       /** \brief Stores the angle step */
-      float step_;
+      float step_{10.0f};
 
       /** \brief Stores the mass of point in the cloud */
-      float point_mass_;
+      float point_mass_{0.0001f};
 
       /** \brief Stores the flag for mass normalization */
-      bool normalize_;
+      bool normalize_{true};
 
       /** \brief Stores the mean value (center of mass) of the cloud */
       Eigen::Vector3f mean_value_;
@@ -315,13 +315,13 @@ namespace pcl
       Eigen::Vector3f minor_axis_;
 
       /** \brief Major eigen value */
-      float major_value_;
+      float major_value_{0.0f};
 
       /** \brief Middle eigen value */
-      float middle_value_;
+      float middle_value_{0.0f};
 
       /** \brief Minor eigen value */
-      float minor_value_;
+      float minor_value_{0.0f};
 
       /** \brief Stores calculated moments of inertia */
       std::vector <float> moment_of_inertia_;
index 417d29e507ddae3b0ad43c7bd2e7fa9ed195871d..8a0ea5023cd1a128b6f32d1f6d1ed16905edf18d 100644 (file)
@@ -180,10 +180,10 @@ namespace pcl
       std::vector<float> scale_values_;
 
       /** \brief Parameter that determines if a feature is to be considered unique or not */
-      float alpha_;
+      float alpha_{0.0f};
 
       /** \brief Parameter that determines which distance metric is to be usedto calculate the difference between feature vectors */
-      NormType distance_metric_;
+      NormType distance_metric_{L1};
 
       /** \brief the feature estimator that will be used to determine the feature set at each scale level */
       FeatureEstimatorPtr feature_estimator_;
index 45dda48a9af788d5eeee0984e4232496a1d1a9f8..9a18d222d10765109b061b6258f8ec40511cc286 100644 (file)
@@ -277,12 +277,12 @@ namespace pcl
       // =====PROTECTED MEMBER VARIABLES=====
       Eigen::Vector3f position_;
       Eigen::Affine3f transformation_;
-      float* surface_patch_;
-      int surface_patch_pixel_size_;
-      float surface_patch_world_size_;
-      float surface_patch_rotation_;
-      float* descriptor_;
-      int descriptor_size_;
+      float* surface_patch_{nullptr};
+      int surface_patch_pixel_size_{0};
+      float surface_patch_world_size_{0.0f};
+      float surface_patch_rotation_{0.0f};
+      float* descriptor_{nullptr};
+      int descriptor_size_{0};
 
       // =====STATIC PROTECTED=====
       
index 9dc2e92660c86b1f01b9cf43ffe20774b56b9746..af46bb941f7c5b554984d16e187d56541fc80246 100644 (file)
@@ -63,9 +63,9 @@ namespace pcl
       // =====STRUCTS/CLASSES=====
       struct Parameters
       {
-        Parameters() : support_size(-1.0f), rotation_invariant(true) {}
-        float support_size;
-        bool rotation_invariant;
+        Parameters() = default;
+        float support_size{-1.0f};
+        bool rotation_invariant{true};
       };
       
       // =====CONSTRUCTOR & DESTRUCTOR=====
@@ -90,7 +90,7 @@ namespace pcl
       
     protected:
       // =====PROTECTED MEMBER VARIABLES=====
-      const RangeImage* range_image_;
+      const RangeImage* range_image_{};
       Parameters parameters_;
       
       // =====PROTECTED METHODS=====
index 44aecf6e3d4313389fd657dd023826d202569b6f..6a8b96fbd915c4d690ae44582ad54a525d226867 100644 (file)
@@ -258,11 +258,7 @@ namespace pcl
       using PointCloudConstPtr = typename Feature<PointInT, PointOutT>::PointCloudConstPtr;
       
       /** \brief Empty constructor. */
-      NormalEstimation () 
-      : vpx_ (0)
-      , vpy_ (0)
-      , vpz_ (0)
-      , use_sensor_origin_ (true)
+      NormalEstimation ()
       {
         feature_name_ = "NormalEstimation";
       };
@@ -403,7 +399,7 @@ namespace pcl
 
       /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit
         * from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */
-      float vpx_, vpy_, vpz_;
+      float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};
 
       /** \brief Placeholder for the 3x3 covariance matrix at each surface patch. */
       EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_;
@@ -412,7 +408,7 @@ namespace pcl
       Eigen::Vector4f xyz_centroid_;
       
       /** whether the sensor origin of the input cloud or a user given viewpoint should be used.*/
-      bool use_sensor_origin_;
+      bool use_sensor_origin_{true};
 
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
index a8ae45b0a37339d6e076e68fe93a726ab522b53b..ba10bb76d8d42de3cb17114c0aa5c8589bad8953 100644 (file)
@@ -72,8 +72,9 @@ namespace pcl
     public:
       /** \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)
+        * \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.
         */
-      NormalEstimationOMP (unsigned int nr_threads = 0)
+      NormalEstimationOMP (unsigned int nr_threads = 0, int chunk_size = 256): chunk_size_(chunk_size)
       {
         feature_name_ = "NormalEstimationOMP";
 
@@ -90,6 +91,8 @@ namespace pcl
       /** \brief The number of threads the scheduler should use. */
       unsigned int threads_;
 
+      /** \brief Chunk size for (dynamic) scheduling. */
+      int chunk_size_;
     private:
       /** \brief Estimate normals for all points given in <setInputCloud (), setIndices ()> using the surface in
         * setSearchSurface () and the spatial locator in setSearchMethod ()
index a3576b4460c4ef382d3c4eb696b03f674f1c9bad..9931ae2402dc37905cb73eb1813682982dbef33a 100644 (file)
@@ -75,12 +75,7 @@ namespace pcl
       /** \brief Empty constructor, initializes the internal parameters to the default values
         */
       NormalBasedSignatureEstimation ()
-        : FeatureFromNormals<PointT, PointNT, PointFeature> (),
-          scale_h_ (),
-          N_ (36),
-          M_ (8),
-          N_prime_ (4),
-          M_prime_ (3)
+        : FeatureFromNormals<PointT, PointNT, PointFeature> ()
       {
       }
 
@@ -152,8 +147,8 @@ namespace pcl
       computeFeature (FeatureCloud &output) override;
 
     private:
-      float scale_h_;
-      std::size_t N_, M_, N_prime_, M_prime_;
+      float scale_h_{};
+      std::size_t N_{36}, M_{8}, N_prime_{4}, M_prime_{3};
   };
 }
 
index ed5230f4ad3a8b59a16d6d6975e1af8be6562f98..fee39a76e15d325527289b82e59c1c9fa76f527d 100644 (file)
@@ -74,9 +74,8 @@ namespace pcl
 
       /** \brief Constructor for OrganizedEdgeBase */
       OrganizedEdgeBase ()
-        : th_depth_discon_ (0.02f)
-        , max_search_neighbors_ (50)
-        , detecting_edge_types_ (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED)
+        : 
+         detecting_edge_types_ (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED)
       {
       }
 
@@ -168,10 +167,10 @@ namespace pcl
       /** \brief The tolerance in meters for the relative difference in depth values between neighboring points
         * (The default value is set for .02 meters and is adapted with respect to depth value linearly.
         * e.g. If a point has a depth (z) value of 2.0 meters, a neighboring point is discontinuous if its depth differs by > 2.0 * th. */
-      float th_depth_discon_;
+      float th_depth_discon_{0.02f};
 
       /** \brief The max search distance for deciding occluding and occluded edges */
-      int max_search_neighbors_;
+      int max_search_neighbors_{50};
 
       /** \brief The bit encoded value that represents edge types to detect */
       int detecting_edge_types_;
@@ -202,8 +201,6 @@ namespace pcl
       /** \brief Constructor for OrganizedEdgeFromRGB */
       OrganizedEdgeFromRGB ()
         : OrganizedEdgeBase<PointT, PointLT> ()
-        , th_rgb_canny_low_ (40.0)
-        , th_rgb_canny_high_ (100.0)
       {
         this->setEdgeType (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED | EDGELABEL_RGB_CANNY);
       }
@@ -255,10 +252,10 @@ namespace pcl
       extractEdges (pcl::PointCloud<PointLT>& labels) const;
 
       /** \brief The low threshold value for RGB Canny edge detection (default: 40.0) */
-      float th_rgb_canny_low_;
+      float th_rgb_canny_low_{40.0};
 
       /** \brief The high threshold value for RGB Canny edge detection (default: 100.0) */
-      float th_rgb_canny_high_;
+      float th_rgb_canny_high_{100.0};
   };
 
   template <typename PointT, typename PointNT, typename PointLT>
@@ -291,9 +288,7 @@ namespace pcl
       OrganizedEdgeFromNormals ()
         : OrganizedEdgeBase<PointT, PointLT> ()
         , normals_ ()
-        , th_hc_canny_low_ (0.4f)
-        , th_hc_canny_high_ (1.1f)
-      {
+       {
         this->setEdgeType (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED | EDGELABEL_HIGH_CURVATURE);
       }
 
@@ -363,10 +358,10 @@ namespace pcl
       PointCloudNConstPtr normals_;
 
       /** \brief The low threshold value for high curvature Canny edge detection (default: 0.4) */
-      float th_hc_canny_low_;
+      float th_hc_canny_low_{0.4f};
 
       /** \brief The high threshold value for high curvature Canny edge detection (default: 1.1) */
-      float th_hc_canny_high_;
+      float th_hc_canny_high_{1.1f};
   };
 
   template <typename PointT, typename PointNT, typename PointLT>
index a40503fdb42056d4373eb0b38c2d378772ac6e53..969470622b7e3a3aff7ac80efaf1930eb5ec9b13 100644 (file)
@@ -74,8 +74,8 @@ namespace pcl
       using PointInTPtr = typename pcl::PointCloud<PointInT>::Ptr;
       /** \brief Empty constructor. */
       OURCVFHEstimation () :
-        vpx_ (0), vpy_ (0), vpz_ (0), leaf_size_ (0.005f), normalize_bins_ (false), curv_threshold_ (0.03f), cluster_tolerance_ (leaf_size_ * 3),
-            eps_angle_threshold_ (0.125f), min_points_ (50), radius_normals_ (leaf_size_ * 3)
+         cluster_tolerance_ (leaf_size_ * 3),
+             radius_normals_ (leaf_size_ * 3)
       {
         search_radius_ = 0;
         k_ = 1;
@@ -190,8 +190,8 @@ namespace pcl
       inline void
       getCentroidClusters (std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > & centroids)
       {
-        for (std::size_t i = 0; i < centroids_dominant_orientations_.size (); ++i)
-          centroids.push_back (centroids_dominant_orientations_[i]);
+        for (const auto & centroids_dominant_orientation : centroids_dominant_orientations_)
+          centroids.push_back (centroids_dominant_orientation);
       }
 
       /** \brief Get the normal centroids used to compute different CVFH descriptors
@@ -200,8 +200,8 @@ namespace pcl
       inline void
       getCentroidNormalClusters (std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > & centroids)
       {
-        for (std::size_t i = 0; i < dominant_normals_.size (); ++i)
-          centroids.push_back (dominant_normals_[i]);
+        for (const auto & dominant_normal : dominant_normals_)
+          centroids.push_back (dominant_normal);
       }
 
       /** \brief Sets max. Euclidean distance between points to be added to the cluster 
@@ -324,29 +324,29 @@ namespace pcl
       /** \brief Values describing the viewpoint ("pinhole" camera model assumed). 
        * By default, the viewpoint is set to 0,0,0.
        */
-      float vpx_, vpy_, vpz_;
+      float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};
 
       /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel 
        * size of the training data or the normalize_bins_ flag must be set to true.
        */
-      float leaf_size_;
+      float leaf_size_{0.005f};
 
       /** \brief Whether to normalize the signatures or not. Default: false. */
-      bool normalize_bins_;
+      bool normalize_bins_{false};
 
       /** \brief Curvature threshold for removing normals. */
-      float curv_threshold_;
+      float curv_threshold_{0.03f};
 
       /** \brief allowed Euclidean distance between points to be added to the cluster. */
       float cluster_tolerance_;
 
       /** \brief deviation of the normals between two points so they can be clustered together. */
-      float eps_angle_threshold_;
+      float eps_angle_threshold_{0.125f};
 
       /** \brief Minimum amount of points in a clustered region to be considered stable for CVFH
        * computation.
        */
-      std::size_t min_points_;
+      std::size_t min_points_{50};
 
       /** \brief Radius for the normals computation. */
       float radius_normals_;
index 30df460353b6c4328473551edf6502e2fe502eee..d8f3eecfef7ebf570a781f5c1ccfb11781c235d5 100644 (file)
@@ -98,16 +98,15 @@ namespace pcl
       /** \brief Empty constructor. 
         * Sets \a use_cache_ to false, \a nr_subdiv_ to 5, and the internal maximum cache size to 1GB.
         */
-      PFHEstimation () : 
-        nr_subdiv_ (5), 
+      PFHEstimation () :
+         
         d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI))), 
         key_list_ (),
         // Default 1GB memory size. Need to set it to something more conservative.
-        max_cache_size_ ((1ul*1024ul*1024ul*1024ul) / sizeof (std::pair<std::pair<int, int>, Eigen::Vector4f>)),
-        use_cache_ (false)
+        max_cache_size_ ((1ul*1024ul*1024ul*1024ul) / sizeof (std::pair<std::pair<int, int>, Eigen::Vector4f>))
       {
         feature_name_ = "PFHEstimation";
-      };
+      }
 
       /** \brief Set the maximum internal cache size. Defaults to 2GB worth of entries.
         * \param[in] cache_size maximum cache size 
@@ -189,7 +188,7 @@ namespace pcl
       computeFeature (PointCloudOut &output) override;
 
       /** \brief The number of subdivisions for each angular feature interval. */
-      int nr_subdiv_;
+      int nr_subdiv_{5};
 
       /** \brief Placeholder for a point's PFH signature. */
       Eigen::VectorXf pfh_histogram_;
@@ -213,7 +212,7 @@ namespace pcl
       unsigned int max_cache_size_;
 
       /** \brief Set to true to use the internal cache for removing redundant computations. */
-      bool use_cache_;
+      bool use_cache_{false};
   };
 }
 
index 60d702f7590b88e5171c5c9fa6c8b532b69c5e08..de87ce6bd94fa1478d1a35f9dc84d6129577c88a 100644 (file)
@@ -43,6 +43,9 @@
 
 namespace pcl
 {
+  /** \brief Similar to the Point Feature Histogram descriptor, but also takes color into account. See also \ref PFHEstimation
+    * \ingroup features
+    */
   template <typename PointInT, typename PointNT, typename PointOutT = pcl::PFHRGBSignature250>
   class PFHRGBEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
   {
@@ -59,7 +62,7 @@ namespace pcl
 
 
       PFHRGBEstimation ()
-        : nr_subdiv_ (5), d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI)))
+        :  d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI)))
       {
         feature_name_ = "PFHRGBEstimation";
       }
@@ -79,7 +82,7 @@ namespace pcl
 
     private:
       /** \brief The number of subdivisions for each angular feature interval. */
-      int nr_subdiv_;
+      int nr_subdiv_{5};
 
       /** \brief Placeholder for a point's PFHRGB signature. */
       Eigen::VectorXf pfhrgb_histogram_;
index 29ef75c0f3a300773ee633e526fd006a6b3d29fb..a24ea3d3e5af3762edfda8a0803bfae81bac6c56 100644 (file)
@@ -64,8 +64,7 @@ namespace pcl
       //! Stores some information extracted from the neighborhood of a point
       struct LocalSurface
       {
-        LocalSurface () : 
-           max_neighbor_distance_squared () {}
+        LocalSurface () = default;
 
         Eigen::Vector3f normal;
         Eigen::Vector3f neighborhood_mean;
@@ -73,27 +72,26 @@ namespace pcl
         Eigen::Vector3f normal_no_jumps;
         Eigen::Vector3f neighborhood_mean_no_jumps;
         Eigen::Vector3f eigen_values_no_jumps;
-        float max_neighbor_distance_squared;
+        float max_neighbor_distance_squared{};
       };
       
       //! Stores the indices of the shadow border corresponding to obstacle borders
       struct ShadowBorderIndices 
       {
-        ShadowBorderIndices () : left (-1), right (-1), top (-1), bottom (-1) {}
-        int left, right, top, bottom;
+        ShadowBorderIndices () = default;
+        int left{-1}, right{-1}, top{-1}, bottom{-1};
       };
 
       //! Parameters used in this class
       struct Parameters
       {
-        Parameters () : max_no_of_threads(1), pixel_radius_borders (3), pixel_radius_plane_extraction (2), pixel_radius_border_direction (2), 
-                       minimum_border_probability (0.8f), pixel_radius_principal_curvature (2) {}
-        int max_no_of_threads;
-        int pixel_radius_borders;
-        int pixel_radius_plane_extraction;
-        int pixel_radius_border_direction;
-        float minimum_border_probability;
-        int pixel_radius_principal_curvature;
+        Parameters () = default;
+        int max_no_of_threads{1};
+        int pixel_radius_borders{3};
+        int pixel_radius_plane_extraction{2};
+        int pixel_radius_border_direction{2};
+        float minimum_border_probability{0.8f};
+        int pixel_radius_principal_curvature{2};
       };
       
       // =====STATIC METHODS=====
@@ -181,16 +179,16 @@ namespace pcl
       // =====PROTECTED MEMBER VARIABLES=====
       Parameters parameters_;
       const RangeImage* range_image_;
-      int range_image_size_during_extraction_;
+      int range_image_size_during_extraction_{0};
       std::vector<float> border_scores_left_, border_scores_right_;
       std::vector<float> border_scores_top_, border_scores_bottom_;
-      LocalSurface** surface_structure_;
-      PointCloudOut* border_descriptions_;
-      ShadowBorderIndices** shadow_border_informations_;
-      Eigen::Vector3f** border_directions_;
+      LocalSurface** surface_structure_{nullptr};
+      PointCloudOut* border_descriptions_{nullptr};
+      ShadowBorderIndices** shadow_border_informations_{nullptr};
+      Eigen::Vector3f** border_directions_{nullptr};
       
-      float* surface_change_scores_;
-      Eigen::Vector3f* surface_change_directions_;
+      float* surface_change_scores_{nullptr};
+      Eigen::Vector3f* surface_change_directions_{nullptr};
       
       
       // =====PROTECTED METHODS=====
index 061b262eaeb4d6fccfc5acf7a445e9f474524dd1..7d47ba95000bc8deea5ba7922fba7178ba41db57 100644 (file)
@@ -80,10 +80,10 @@ namespace pcl
 
 
       /** \brief Empty constructor. */
-      RIFTEstimation () : gradient_ (), nr_distance_bins_ (4), nr_gradient_bins_ (8)
+      RIFTEstimation ()
       {
         feature_name_ = "RIFTEstimation";
-      };
+      }
 
       /** \brief Provide a pointer to the input gradient data
         * \param[in] gradient a pointer to the input gradient data
@@ -141,13 +141,13 @@ namespace pcl
       computeFeature (PointCloudOut &output) override;
 
       /** \brief The intensity gradient of the input point cloud data*/
-      PointCloudGradientConstPtr gradient_;
+      PointCloudGradientConstPtr gradient_{nullptr};
 
       /** \brief The number of distance bins in the descriptor. */
-      int nr_distance_bins_;
+      int nr_distance_bins_{4};
 
       /** \brief The number of gradient orientation bins in the descriptor. */
-      int nr_gradient_bins_;
+      int nr_gradient_bins_{8};
   };
 }
 
index 6d5cb34740545ca4eae53790255a4a51d5387aab..a34e09fc9417dfe529bc7370b3610ba0f8b0001b 100644 (file)
@@ -202,19 +202,19 @@ namespace pcl
     private:
 
       /** \brief Stores the number of partition bins that is used for distribution matrix calculation. */
-      unsigned int number_of_bins_;
+      unsigned int number_of_bins_{5};
 
       /** \brief Stores number of rotations. Central moments are calculated for every rotation. */
-      unsigned int number_of_rotations_;
+      unsigned int number_of_rotations_{3};
 
       /** \brief Support radius that is used to crop the local surface of the point. */
-      float support_radius_;
+      float support_radius_{1.0f};
 
       /** \brief Stores the squared support radius. Used to improve performance. */
-      float sqr_support_radius_;
+      float sqr_support_radius_{1.0f};
 
       /** \brief Stores the angle step. Step is calculated with respect to number of rotations. */
-      float step_;
+      float step_{22.5f};
 
       /** \brief Stores the set of triangles representing the mesh. */
       std::vector <pcl::Vertices> triangles_;
index 9eafe82b4d6625332740011096b8ce26d5a077e5..e5351daa544bfebeaa57be8bb921d41b858b55d6 100644 (file)
@@ -148,10 +148,10 @@ namespace pcl
 
 
       /** \brief Empty constructor. */
-      RSDEstimation () : nr_subdiv_ (5), plane_radius_ (0.2), save_histograms_ (false)
+      RSDEstimation ()
       {
         feature_name_ = "RadiusSurfaceDescriptor";
-      };
+      }
 
       /** \brief Set the number of subdivisions for the considered distance interval.
         * \param[in] nr_subdiv the number of subdivisions
@@ -220,13 +220,13 @@ namespace pcl
 
     private:
       /** \brief The number of subdivisions for the considered distance interval. */
-      int nr_subdiv_;
+      int nr_subdiv_{5};
 
       /** \brief The maximum radius, above which everything can be considered planar. */
-      double plane_radius_;
+      double plane_radius_{0.2};
 
       /** \brief Signals whether the full distance-angle histograms are being saved. */
-      bool save_histograms_;
+      bool save_histograms_{false};
 
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
index f4672bda483544c44ea1304adc51609b5ffb93b7..d278076b29fab5178ef2970ee24cc72ecdbdc29a 100644 (file)
@@ -91,15 +91,10 @@ namespace pcl
         * \param[in] nr_shape_bins the number of bins in the shape histogram
         */
       SHOTEstimationBase (int nr_shape_bins = 10) :
-        nr_shape_bins_ (nr_shape_bins),
-        lrf_radius_ (0),
-        sqradius_ (0), radius3_4_ (0), radius1_4_ (0), radius1_2_ (0),
-        nr_grid_sector_ (32),
-        maxAngularSectors_ (32),
-        descLength_ (0)
+        nr_shape_bins_ (nr_shape_bins)
       {
         feature_name_ = "SHOTEstimation";
-      };
+      }
 
     public:
 
@@ -170,28 +165,28 @@ namespace pcl
       int nr_shape_bins_;
 
       /** \brief The radius used for the LRF computation */
-      float lrf_radius_;
+      float lrf_radius_{0.0f};
 
       /** \brief The squared search radius. */
-      double sqradius_;
+      double sqradius_{0.0};
 
       /** \brief 3/4 of the search radius. */
-      double radius3_4_;
+      double radius3_4_{0.0};
 
       /** \brief 1/4 of the search radius. */
-      double radius1_4_;
+      double radius1_4_{0.0};
 
       /** \brief 1/2 of the search radius. */
-      double radius1_2_;
+      double radius1_2_{0.0};
 
       /** \brief Number of azimuthal sectors. */
-      const int nr_grid_sector_;
+      const int nr_grid_sector_{32};
 
       /** \brief ... */
-      const int maxAngularSectors_;
+      const int maxAngularSectors_{32};
 
       /** \brief One SHOT length. */
-      int descLength_;
+      int descLength_{0};
   };
 
   /** \brief SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for
@@ -326,11 +321,10 @@ namespace pcl
                            bool describe_color = true)
         : SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT> (10),
           b_describe_shape_ (describe_shape),
-          b_describe_color_ (describe_color),
-          nr_color_bins_ (30)
+          b_describe_color_ (describe_color)
       {
         feature_name_ = "SHOTColorEstimation";
-      };
+      }
       
       /** \brief Empty destructor */
       ~SHOTColorEstimation () override = default;
@@ -382,7 +376,7 @@ namespace pcl
       bool b_describe_color_;
 
       /** \brief The number of bins in each color histogram. */
-      int nr_color_bins_;
+      int nr_color_bins_{30};
 
     public:
       /** \brief Converts RGB triplets to CIELab space.
index 73a22356709526902c84e5c221ea0c3464b3e2b6..21fff6c0aabe41a8b9e4097ce3de2c5d816eea5d 100644 (file)
@@ -69,7 +69,9 @@ namespace pcl
     *
     * With the default parameters, pcl::Histogram<153> is a good choice for PointOutT.
     * Of course the dimension of this descriptor must change to match the number
-    * of bins set by the parameters.
+    * of bins set by the parameters. If you use SpinImageEstimation with something
+    * other than pcl::Histogram<153>, you may need to put `#define PCL_NO_PRECOMPILE 1`
+    * before including `pcl/features/spin_image.h`.
     *
     * For further information please see:
     *
@@ -131,7 +133,27 @@ namespace pcl
       void 
       setImageWidth (unsigned int bin_count)
       {
-        image_width_ = bin_count;
+        const unsigned int necessary_desc_size = (bin_count+1)*(2*bin_count+1);
+        if (necessary_desc_size > static_cast<unsigned int>(PointOutT::descriptorSize())) {
+          for(int i=0; ; ++i) { // Find the biggest possible image_width_
+            if(((i+1)*(2*i+1)) <= PointOutT::descriptorSize()) {
+              image_width_ = i;
+            } else {
+              break;
+            }
+          }
+          PCL_ERROR("[pcl::SpinImageEstimation] The chosen image width is too large, setting it to %u instead. "
+            "Consider using pcl::Histogram<%u> as output type of SpinImageEstimation "
+            "(possibly with `#define PCL_NO_PRECOMPILE 1`).\n", image_width_, ((bin_count+1)*(2*bin_count+1)));
+        } else if (necessary_desc_size < static_cast<unsigned int>(PointOutT::descriptorSize())) {
+          image_width_ = bin_count;
+          PCL_WARN("[pcl::SpinImageEstimation] The chosen image width is smaller than the output histogram allows. "
+            "This is not an error, but the last few histogram bins will not be set. "
+            "Consider using pcl::Histogram<%u> as output type of SpinImageEstimation "
+            "(possibly with `#define PCL_NO_PRECOMPILE 1`).\n", ((bin_count+1)*(2*bin_count+1)));
+        } else {
+          image_width_ = bin_count;
+        }
       }
 
       /** \brief Sets the maximum angle for the point normal to get to support region.
@@ -265,13 +287,13 @@ namespace pcl
       PointCloudNConstPtr input_normals_;
       PointCloudNConstPtr rotation_axes_cloud_;
       
-      bool is_angular_;
+      bool is_angular_{false};
 
       PointNT rotation_axis_;
-      bool use_custom_axis_;
-      bool use_custom_axes_cloud_;
+      bool use_custom_axis_{false};
+      bool use_custom_axes_cloud_{false};
 
-      bool is_radial_;
+      bool is_radial_{false};
 
       unsigned int image_width_;
       double support_angle_cos_;
index fed3fe8eb3a228c7864f411abc6753c3212eee22..0ad9cd2089c9acd9ae2de041f6eb25fcf035e264 100644 (file)
@@ -83,9 +83,7 @@ namespace pcl
 
       /** \brief Constructor. */
       UniqueShapeContext () :
-        radii_interval_(0), theta_divisions_(0), phi_divisions_(0), volume_lut_(0),
-        azimuth_bins_(14), elevation_bins_(14), radius_bins_(10),
-        min_radius_(0.1), point_density_radius_(0.1), descriptor_length_ (), local_radius_ (2.0)
+        radii_interval_(0), theta_divisions_(0), phi_divisions_(0), volume_lut_(0)
       {
         feature_name_ = "UniqueShapeContext";
         search_radius_ = 2.0;
@@ -167,25 +165,25 @@ namespace pcl
       std::vector<float> volume_lut_;
 
       /** \brief Bins along the azimuth dimension. */
-      std::size_t azimuth_bins_;
+      std::size_t azimuth_bins_{14};
 
       /** \brief Bins along the elevation dimension. */
-      std::size_t elevation_bins_;
+      std::size_t elevation_bins_{14};
 
       /** \brief Bins along the radius dimension. */
-      std::size_t radius_bins_;
+      std::size_t radius_bins_{10};
 
       /** \brief Minimal radius value. */
-      double min_radius_;
+      double min_radius_{0.1};
 
       /** \brief Point density radius. */
-      double point_density_radius_;
+      double point_density_radius_{0.1};
 
       /** \brief Descriptor length. */
-      std::size_t descriptor_length_;
+      std::size_t descriptor_length_{};
 
       /** \brief Radius to compute local RF. */
-      double local_radius_;
+      double local_radius_{2.0};
   };
 }
 
index d3dae27867477028c07e017eac5eabce275d7764..01379f334f09bd24c96fcabcbc73bb944f1f8312 100644 (file)
@@ -88,10 +88,7 @@ namespace pcl
 
       /** \brief Empty constructor. */
       VFHEstimation () :
-        nr_bins_f_ ({45, 45, 45, 45}), nr_bins_vp_ (128),
-        vpx_ (0), vpy_ (0), vpz_ (0),
-        use_given_normal_ (false), use_given_centroid_ (false),
-        normalize_bins_ (true), normalize_distances_ (false), size_component_ (false),
+        nr_bins_f_ ({45, 45, 45, 45}), 
         d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI)))
       {
         for (int i = 0; i < 4; ++i)
@@ -215,12 +212,12 @@ namespace pcl
 
       /** \brief The number of subdivisions for each feature interval. */
       std::array<int, 4> nr_bins_f_;
-      int nr_bins_vp_;
+      int nr_bins_vp_{128};
 
       /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit
         * from VFHEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0.
         */
-      float vpx_, vpy_, vpz_;
+      float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};
 
       /** \brief Estimate the Viewpoint Feature Histograms (VFH) descriptors at a set of points given by
         * <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in
@@ -248,15 +245,15 @@ namespace pcl
       // VFH configuration parameters because CVFH instantiates it. See constructor for default values.
 
       /** \brief Use the normal_to_use_ */
-      bool use_given_normal_;
+      bool use_given_normal_{false};
       /** \brief Use the centroid_to_use_ */
-      bool use_given_centroid_;
+      bool use_given_centroid_{false};
       /** \brief Normalize bins by the number the total number of points. */
-      bool normalize_bins_;
+      bool normalize_bins_{true};
       /** \brief Normalize the shape distribution component of VFH */
-      bool normalize_distances_;
+      bool normalize_distances_{false};
       /** \brief Activate or deactivate the size component of VFH */
-      bool size_component_;
+      bool size_component_{false};
 
     private:
       /** \brief Float constant = 1.0 / (2.0 * M_PI) */
index 059dd22ee9ce93c460d0457988dee182e4ba58dd..b391e3fcff5308408b96a16075b7c16a2d33746b 100644 (file)
@@ -55,10 +55,7 @@ namespace pcl
 int Narf::max_no_of_threads = 1;
 
 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-Narf::Narf() : 
-  surface_patch_ (nullptr), 
-  surface_patch_pixel_size_ (0), surface_patch_world_size_ (), 
-  surface_patch_rotation_ (), descriptor_ (nullptr), descriptor_size_ (0)
+Narf::Narf()
 {
   reset();
 }
@@ -70,10 +67,7 @@ Narf::~Narf()
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-Narf::Narf (const Narf& other) : 
-  surface_patch_ (nullptr), 
-  surface_patch_pixel_size_ (0), surface_patch_world_size_ (), 
-  surface_patch_rotation_ (), descriptor_ (nullptr), descriptor_size_ (0)
+Narf::Narf (const Narf& other)
 {
   deepCopy (other);
 }
@@ -136,7 +130,7 @@ Narf::extractDescriptor (int descriptor_size)
 {
   float weight_for_first_point = 2.0f; // The weight for the last point is always 1.0f
   int no_of_beam_points = getNoOfBeamPoints();
-  float weight_factor = -2.0f*(weight_for_first_point-1.0f) / ((weight_for_first_point+1.0f)*float(no_of_beam_points-1)),
+  float weight_factor = -2.0f*(weight_for_first_point-1.0f) / ((weight_for_first_point+1.0f)*static_cast<float>(no_of_beam_points-1)),
         weight_offset = 2.0f*weight_for_first_point / (weight_for_first_point+1.0f);
 
   if (descriptor_size != descriptor_size_)
@@ -148,7 +142,7 @@ Narf::extractDescriptor (int descriptor_size)
   float angle_step_size = deg2rad (360.0f) / static_cast<float> (descriptor_size_);
   //std::cout << PVARN(no_of_beam_points)<<PVARN(surface_patch_pixel_size_);
 
-  float cell_size = surface_patch_world_size_/float(surface_patch_pixel_size_),
+  float cell_size = surface_patch_world_size_/static_cast<float>(surface_patch_pixel_size_),
         cell_factor = 1.0f/cell_size,
         cell_offset = 0.5f*(surface_patch_world_size_ - cell_size),
         max_dist = 0.5f*surface_patch_world_size_,
@@ -188,7 +182,7 @@ Narf::extractDescriptor (int descriptor_size)
       float beam_value1=beam_values[beam_value_idx],
             beam_value2=beam_values[beam_value_idx+1];
 
-      float current_weight = weight_factor*float(beam_value_idx) + weight_offset;
+      float current_weight = weight_factor*static_cast<float>(beam_value_idx) + weight_offset;
       float diff = beam_value2-beam_value1;
       current_cell += current_weight * diff;
     }
@@ -273,7 +267,7 @@ Narf::extractFromRangeImageWithBestRotation (const RangeImage& range_image, cons
 float* 
 Narf::getBlurredSurfacePatch (int new_pixel_size, int blur_radius) const
 {
-  float new_to_old_factor = float(surface_patch_pixel_size_)/float(new_pixel_size);
+  float new_to_old_factor = static_cast<float>(surface_patch_pixel_size_)/static_cast<float>(new_pixel_size);
   int new_size = new_pixel_size*new_pixel_size;
   
   float* integral_image = new float[new_size];
@@ -376,6 +370,8 @@ Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud<
   schedule(dynamic, 10) \
   num_threads(max_no_of_threads)
   //!!! nizar 20110408 : for OpenMP sake on MSVC this must be kept signed
+  // Disable lint since this 'for' is part of the pragma
+  // NOLINTNEXTLINE(modernize-loop-convert)
   for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t>(interest_points.size ()); ++idx)
   {
     const auto& interest_point = interest_points[idx];
@@ -389,7 +385,7 @@ Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud<
     else {
       if (!rotation_invariant)
       {
-#       pragma omp critical
+#pragma omp critical
         {
           feature_list.push_back(feature);
         }
@@ -409,7 +405,7 @@ Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud<
               delete feature2;
               continue;
             }
-#           pragma omp critical
+#pragma omp critical
             {
               feature_list.push_back(feature2);
             }
@@ -602,8 +598,7 @@ Narf::loadBinary (const std::string& filename)
 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 /////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-NarfDescriptor::NarfDescriptor (const RangeImage* range_image, const pcl::Indices* indices) : 
-  range_image_ ()
+NarfDescriptor::NarfDescriptor (const RangeImage* range_image, const pcl::Indices* indices)
 {
   setRangeImage (range_image, indices);
 }
index ac6a6003247259ea1bc185aca4f75aec6a4ba0ee..6590b57aa459836aac228377e767f6035cc01613 100644 (file)
@@ -49,10 +49,7 @@ namespace pcl
 {
 
 ///////////////////////////////////////////////////////////////////////////////////////////////////////////////
-RangeImageBorderExtractor::RangeImageBorderExtractor(const RangeImage* range_image) :
-  range_image_(range_image), range_image_size_during_extraction_(0),
-  surface_structure_(nullptr), border_descriptions_(nullptr), shadow_border_informations_(nullptr), border_directions_(nullptr),
-  surface_change_scores_(nullptr), surface_change_directions_(nullptr)
+RangeImageBorderExtractor::RangeImageBorderExtractor(const RangeImage* range_image) : range_image_(range_image)
 {
 }
 
@@ -616,9 +613,9 @@ RangeImageBorderExtractor::blurSurfaceChanges ()
 
   auto* blurred_directions = new Eigen::Vector3f[range_image.width*range_image.height];
   float* blurred_scores = new float[range_image.width*range_image.height];
-  for (int y=0; y<int(range_image.height); ++y)
+  for (int y=0; y<static_cast<int>(range_image.height); ++y)
   {
-    for (int x=0; x<int(range_image.width); ++x)
+    for (int x=0; x<static_cast<int>(range_image.width); ++x)
     {
       int index = y*range_image.width + x;
       Eigen::Vector3f& new_point = blurred_directions[index];
index 5e9def6fd5beb276b7da993052f7ca8c63192ec2..f4541889fdf335b1bd5f039099d7c11042667aae 100644 (file)
@@ -4,7 +4,7 @@ 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})
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
index 916144c2ab573aecaa22f30c88847b2fbdb3a266..95e16a1d868ec5e26aca2b6aeabf6f48da73fd07 100644 (file)
@@ -49,8 +49,8 @@ namespace pcl
     
     xNdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointT &p2)
       : p1_ (p1),
-        p2_ (reinterpret_cast<Pod&>(p2)),
-        f_idx_ (0) { }
+        p2_ (reinterpret_cast<Pod&>(p2))
+        { }
 
     template<typename Key> inline void operator() ()
     {
@@ -63,7 +63,7 @@ namespace pcl
     private:
       const Eigen::VectorXf &p1_;
       Pod &p2_;
-      int f_idx_;
+      int f_idx_{0};
   };
 
   /** \brief Helper functor structure for copying data between an Eigen::VectorXf and a PointT. */
@@ -73,7 +73,7 @@ namespace pcl
     using Pod = typename traits::POD<PointT>::type;
     
     xNdCopyPointEigenFunctor (const PointT &p1, Eigen::VectorXf &p2)
-      : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
+      : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2) { }
 
     template<typename Key> inline void operator() ()
     {
@@ -86,11 +86,12 @@ namespace pcl
     private:
       const Pod &p1_;
       Eigen::VectorXf &p2_;
-      int f_idx_;
+      int f_idx_{0};
   };
 
   /** \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.
     * \author James Bowman, Radu B. Rusu
     * \ingroup filters
     */
@@ -109,9 +110,9 @@ namespace pcl
     private:
       struct he
       {
-        he () : ix (), iy (), iz (), count (0) {}
-        int ix, iy, iz;
-        int count;
+        he () = default;
+        int ix{0}, iy{0}, iz{0};
+        int count{0};
         Eigen::VectorXf centroid;
       };
 
@@ -126,7 +127,7 @@ namespace pcl
         pcl::Filter<PointT> (),
         leaf_size_ (Eigen::Vector3f::Ones ()),
         inverse_leaf_size_ (Eigen::Array3f::Ones ()),
-        downsample_all_data_ (true), histsize_ (512),
+        
         history_ (new he[histsize_])
       {
         filter_name_ = "ApproximateVoxelGrid";
@@ -218,10 +219,10 @@ namespace pcl
       Eigen::Array3f inverse_leaf_size_;
 
       /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */
-      bool downsample_all_data_;
+      bool downsample_all_data_{true};
 
       /** \brief history buffer size, power of 2 */
-      std::size_t histsize_;
+      std::size_t histsize_{512};
 
       /** \brief history buffer */
       struct he* history_;
index fc5353fdf80c426eac861fd95d58b020770f3654..06b0c59909d2b6cbb14b5cf674936fa658251769 100644 (file)
@@ -68,14 +68,12 @@ namespace pcl
       /** \brief Constructor. 
         * Sets sigma_s_ to 0 and sigma_r_ to MAXDBL
         */
-      BilateralFilter () : sigma_s_ (0), 
-                           sigma_r_ (std::numeric_limits<double>::max ()),
-                           tree_ ()
+      BilateralFilter () : tree_ ()
       {
       }
       /** \brief Compute the intensity average for a single point
         * \param[in] pid the point index to compute the weight for
-        * \param[in] indices the set of nearest neighor indices 
+        * \param[in] indices the set of nearest neighbor indices 
         * \param[in] distances the set of nearest neighbor distances
         * \return the intensity average at a given point index
         */
@@ -130,9 +128,9 @@ namespace pcl
       { return (std::exp (- (x*x)/(2*sigma*sigma))); }
 
       /** \brief The half size of the Gaussian bilateral filter window (e.g., spatial extents in Euclidean). */
-      double sigma_s_;
+      double sigma_s_{0.0};
       /** \brief The standard deviation of the bilateral filter (e.g., standard deviation in intensity). */
-      double sigma_r_;
+      double sigma_r_{std::numeric_limits<double>::max ()};
 
       /** \brief A pointer to the spatial search object. */
       KdTreePtr tree_;
index b2ebfa51f78b93e61e64ebe58b9bdc311bd71b2f..feade7de8600ed92ac88b7c5cfb9307e411e55f7 100644 (file)
@@ -46,7 +46,8 @@ namespace pcl
   /**
     * \author Suat Gedikli <gedikli@willowgarage.com>
     * \brief Implementation of a box clipper in 3D. Actually it allows affine transformations, thus any parallelepiped in general pose.
-    *        The affine transformation is used to transform the point before clipping it using the unit cube centered at origin and with an extend of -1 to +1 in each dimension
+    *        The affine transformation is used to transform the point before clipping it using a cube centered at origin and with an extend of -1 to +1 in each dimension
+    * \sa CropBox
     * \ingroup filters
     */
   template<typename PointT>
@@ -61,7 +62,7 @@ namespace pcl
       /**
         * \author Suat Gedikli <gedikli@willowgarage.com>
         * \brief Constructor taking an affine transformation matrix, which allows also shearing of the clipping area
-        * \param[in] transformation the 3x3 affine transformation matrix that is used to describe the unit cube
+        * \param[in] transformation the 3 dimensional affine transformation that is used to describe the cube ([-1; +1] in each dimension). The transformation is applied to the point(s)!
         */
       BoxClipper3D (const Eigen::Affine3f& transformation);
 
@@ -75,7 +76,7 @@ namespace pcl
 
       /**
         * \brief Set the affine transformation
-        * \param[in] transformation
+        * \param[in] transformation applied to the point(s)
         */
       void setTransformation (const Eigen::Affine3f& transformation);
 
@@ -115,7 +116,7 @@ namespace pcl
       void transformPoint (const PointT& pointIn, PointT& pointOut) const;
     private:
       /**
-        * \brief the affine transformation that is applied before clipping is done on the unit cube.
+        * \brief the affine transformation that is applied before clipping is done on the [-1; +1] cube.
         */
       Eigen::Affine3f transformation_;
 
index 350e8214ae377ca7e2686b1316ffa50653e3233b..d5e7b7ccaaa2d0d42a30a429503e5b14149fef76 100644 (file)
@@ -93,7 +93,7 @@ namespace pcl
       using ConstPtr = shared_ptr<const ComparisonBase<PointT> >;
 
       /** \brief Constructor. */
-      ComparisonBase () : capable_ (false), offset_ (), op_ () {}
+      ComparisonBase () = default;
 
       /** \brief Destructor. */
       virtual ~ComparisonBase () = default;
@@ -111,16 +111,16 @@ namespace pcl
 
     protected:
       /** \brief True if capable. */
-      bool capable_;
+      bool capable_{false};
 
       /** \brief Field name to compare data on. */
       std::string field_name_;
 
       /** \brief The data offset. */
-      std::uint32_t offset_;
+      std::uint32_t offset_{0};
 
       /** \brief The comparison operator type. */
-      ComparisonOps::CompareOp op_;
+      ComparisonOps::CompareOp op_{ComparisonOps::GT};
   };
 
   //////////////////////////////////////////////////////////////////////////////////////////
@@ -455,7 +455,7 @@ namespace pcl
       using ConstPtr = shared_ptr<const ConditionBase<PointT> >;
 
       /** \brief Constructor. */
-      ConditionBase () : capable_ (true), comparisons_ (), conditions_ ()
+      ConditionBase () :  comparisons_ (), conditions_ ()
       {
       }
 
@@ -489,7 +489,7 @@ namespace pcl
 
     protected:
       /** \brief True if capable. */
-      bool capable_;
+      bool capable_{true};
 
       /** \brief The collection of all comparisons that need to be verified. */
       std::vector<ComparisonBaseConstPtr> comparisons_;
@@ -617,7 +617,7 @@ namespace pcl
         * \param extract_removed_indices extract filtered indices from indices vector
         */
       ConditionalRemoval (int extract_removed_indices = false) :
-        Filter<PointT>::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (),
+        Filter<PointT>::Filter (extract_removed_indices),  condition_ (),
         user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
       {
         filter_name_ = "ConditionalRemoval";
@@ -671,12 +671,12 @@ namespace pcl
       applyFilter (PointCloud &output) override;
 
       /** \brief True if capable. */
-      bool capable_;
+      bool capable_{false};
 
       /** \brief Keep the structure of the data organized, by setting the
         * filtered points to the a user given value (NaN by default).
         */
-      bool keep_organized_;
+      bool keep_organized_{false};
 
       /** \brief The condition to use for filtering */
       ConditionBasePtr condition_;
index 85bc5826353b10e61599504ecb01c9a3e58cfc0f..3a817bbc087c9389d2f8e27efca7f72a4b5b4b97 100644 (file)
@@ -48,7 +48,7 @@ namespace pcl
     /** Convolution is a mathematical operation on two functions f and g,
       * producing a third function that is typically viewed as a modified
       * version of one of the original functions.
-      * see http://en.wikipedia.org/wiki/Convolution.
+      * see https://en.wikipedia.org/wiki/Convolution.
       *
       * The class provides rows, column and separate convolving operations
       * of a point cloud.
@@ -213,12 +213,12 @@ namespace pcl
         /// convolution kernel
         Eigen::ArrayXf kernel_;
         /// half kernel size
-        int half_width_;
+        int half_width_{};
         /// kernel size - 1
-        int kernel_width_;
+        int kernel_width_{};
       protected:
         /** \brief The number of threads the scheduler should use. */
-        unsigned int threads_;
+        unsigned int threads_{1};
 
         void
         makeInfinite (PointOut& p)
index 141dd6e0cc1a988ec5e5f55838cfb8da8f86a0b4..081c2f5d38e997a09fc006941d530244e1f362d5 100644 (file)
@@ -66,9 +66,7 @@ namespace pcl
 
       /** \brief Empty Constructor. */
       CropHull () :
-        hull_cloud_(),
-        dim_(3),
-        crop_outside_(true)
+        hull_cloud_()
       {
         filter_name_ = "CropHull";
       }
@@ -199,12 +197,12 @@ namespace pcl
       PointCloudPtr hull_cloud_;
 
       /** \brief The dimensionality of the hull to be used. */
-      int dim_;
+      int dim_{3};
 
       /** \brief If true, the filter will remove points outside the hull. If
        * false, those inside will be removed.
        */
-      bool crop_outside_;
+      bool crop_outside_{true};
   };
 
 } // namespace pcl
index 25e4f2e02c5fafe5f98390de5eafd85b92408d5d..683a9da62e964f6bdbc37fcd52fca37f6293e4ea 100644 (file)
@@ -65,11 +65,7 @@ namespace pcl
       using ConstPtr = shared_ptr<const FastBilateralFilter<PointT> >;
 
       /** \brief Empty constructor. */
-      FastBilateralFilter ()
-        : sigma_s_ (15.0f)
-        , sigma_r_ (0.05f)
-        , early_division_ (false)
-      { }
+      FastBilateralFilter () = default;
       
       /** \brief Empty destructor */
       ~FastBilateralFilter () override = default;
@@ -108,19 +104,19 @@ namespace pcl
       applyFilter (PointCloud &output) override;
 
     protected:
-      float sigma_s_;
-      float sigma_r_;
-      bool early_division_;
+      float sigma_s_{15.0f};
+      float sigma_r_{0.05f};
+      bool early_division_{false};
 
       class Array3D
       {
         public:
           Array3D (const std::size_t width, const std::size_t height, const std::size_t depth)
+            : v_({(width*height*depth), Eigen::Vector2f (0.0f, 0.0f), Eigen::aligned_allocator<Eigen::Vector2f>()})
           {
             x_dim_ = width;
             y_dim_ = height;
             z_dim_ = depth;
-            v_ = std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > (width*height*depth, Eigen::Vector2f (0.0f, 0.0f));
           }
 
           inline Eigen::Vector2f&
index a5bdfb75f418defa6d2bcb39267d934747025116..4fc612437170a58c6d79a24d7b1b432b09bf90b0 100644 (file)
@@ -86,8 +86,7 @@ namespace pcl
         */
       FilterIndices (bool extract_removed_indices = false) :
           Filter<PointT> (extract_removed_indices),
-          negative_ (false),
-          keep_organized_ (false),
+          
           user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
       {
       }
@@ -165,10 +164,10 @@ namespace pcl
       using Filter<PointT>::removed_indices_;
 
       /** \brief False = normal filter behavior (default), true = inverted behavior. */
-      bool negative_;
+      bool negative_{false};
 
       /** \brief False = remove points (default), true = redefine points, keep structure. */
-      bool keep_organized_;
+      bool keep_organized_{false};
 
       /** \brief The user given value that the filtered point dimensions should be set to (default = NaN). */
       float user_filter_value_;
@@ -203,8 +202,7 @@ namespace pcl
         */
       FilterIndices (bool extract_removed_indices = false) :
           Filter<PCLPointCloud2> (extract_removed_indices),
-          negative_ (false), 
-          keep_organized_ (false), 
+           
           user_filter_value_ (std::numeric_limits<float>::quiet_NaN ())
       {
       }
@@ -268,10 +266,10 @@ namespace pcl
     protected:
 
       /** \brief False = normal filter behavior (default), true = inverted behavior. */
-      bool negative_;
+      bool negative_{false};
 
       /** \brief False = remove points (default), true = redefine points, keep structure. */
-      bool keep_organized_;
+      bool keep_organized_{false};
 
       /** \brief The user given value that the filtered point dimensions should be set to (default = NaN). */
       float user_filter_value_;
index 13c11aabe587a9a70c23213cafd710e776aa2bf6..707b849342f39ac19e925f3712d383cd81a5be6f 100644 (file)
@@ -90,16 +90,6 @@ namespace pcl
       FrustumCulling (bool extract_removed_indices = false) 
         : FilterIndices<PointT> (extract_removed_indices)
         , camera_pose_ (Eigen::Matrix4f::Identity ())
-        , fov_left_bound_ (-30.0f)
-        , fov_right_bound_ (30.0f)
-        , fov_lower_bound_ (-30.0f)
-        , fov_upper_bound_ (30.0f)
-        , np_dist_ (0.1f)
-        , fp_dist_ (5.0f)
-        , roi_x_ (0.5f)
-        , roi_y_ (0.5f)
-        , roi_w_ (1.0f)
-        , roi_h_ (1.0f)
       {
         filter_name_ = "FrustumCulling";
       }
@@ -363,25 +353,25 @@ namespace pcl
       /** \brief The camera pose */
       Eigen::Matrix4f camera_pose_;
       /** \brief The left bound of horizontal field of view */
-      float fov_left_bound_;
+      float fov_left_bound_{-30.0f};
       /** \brief The right bound of horizontal field of view */
-      float fov_right_bound_;
+      float fov_right_bound_{30.0f};
       /** \brief The lower bound of vertical field of view */
-      float fov_lower_bound_;
+      float fov_lower_bound_{-30.0f};
       /** \brief The upper bound of vertical field of view */
-      float fov_upper_bound_;
+      float fov_upper_bound_{30.0f};
       /** \brief Near plane distance */
-      float np_dist_;
+      float np_dist_{0.1f};
       /** \brief Far plane distance */
-      float fp_dist_;
+      float fp_dist_{5.0f};
       /** \brief Region of interest x center position (normalized)*/
-      float roi_x_;
+      float roi_x_{0.5f};
       /** \brief Region of interest y center position (normalized)*/
-      float roi_y_;
+      float roi_y_{0.5f};
       /** \brief Region of interest width (normalized)*/
-      float roi_w_;
+      float roi_w_{1.0f};
       /** \brief Region of interest height (normalized)*/
-      float roi_h_;
+      float roi_h_{1.0f};
 
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
index 9ef530eed72759cb75bd5f80a25c79328521efa6..923a3024a43a291ad26eefb17148eeb9ef528357 100644 (file)
@@ -41,7 +41,6 @@ template<typename PointT>
 pcl::BoxClipper3D<PointT>::BoxClipper3D (const Eigen::Affine3f& transformation)
 : transformation_ (transformation)
 {
-  //inverse_transformation_ = transformation_.inverse ();
 }
 
 ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -61,15 +60,13 @@ template<typename PointT> void
 pcl::BoxClipper3D<PointT>::setTransformation (const Eigen::Affine3f& transformation)
 {
   transformation_ = transformation;
-  //inverse_transformation_ = transformation_.inverse ();
 }
 
 ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template<typename PointT> void
 pcl::BoxClipper3D<PointT>::setTransformation (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size)
 {
-  transformation_ = Eigen::Translation3f (translation) * Eigen::AngleAxisf(rodrigues.norm (), rodrigues.normalized ()) * Eigen::Scaling (box_size);
-  //inverse_transformation_ = transformation_.inverse ();
+  transformation_ = (Eigen::Translation3f (translation) * Eigen::AngleAxisf(rodrigues.norm (), rodrigues.normalized ()) * Eigen::Scaling (0.5f * box_size)).inverse ();
 }
 
 ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
index 560aca39e618d88b573a1e8ec54350ab22dae3f0..99cc9295b58899f5873765d077a733fc4ad49336 100644 (file)
@@ -310,7 +310,7 @@ pcl::PackedHSIComparison<PointT>::evaluate (const PointT &point) const
     g_ = static_cast <std::uint8_t> (rgb_val_ >> 8);
     b_ = static_cast <std::uint8_t> (rgb_val_);
 
-    // definitions taken from http://en.wikipedia.org/wiki/HSL_and_HSI
+    // definitions taken from https://en.wikipedia.org/wiki/HSL_and_HSI
     float hx = (2.0f * r_ - g_ - b_) / 4.0f;  // hue x component -127 to 127
     float hy = static_cast<float> (g_ - b_) * 111.0f / 255.0f; // hue y component -111 to 111
     h_ = static_cast<std::int8_t> (std::atan2(hy, hx) * 128.0f / M_PI);
@@ -624,7 +624,7 @@ pcl::ConditionalRemoval<PointT>::setCondition (ConditionBasePtr condition)
 template <typename PointT> void
 pcl::ConditionalRemoval<PointT>::applyFilter (PointCloud &output)
 {
-  if (capable_ == false)
+  if (!capable_)
   {
     PCL_WARN ("[pcl::%s::applyFilter] not capable!\n", getClassName ().c_str ());
     return;
index 3ee170e5ae64026a371504e9ea227c54dc596319..087fa9001f0132c44e1793637532b2ca3c136e76 100644 (file)
@@ -55,9 +55,6 @@ Convolution<PointIn, PointOut>::Convolution ()
   : borders_policy_ (BORDERS_POLICY_IGNORE)
   , distance_threshold_ (std::numeric_limits<float>::infinity ())
   , input_ ()
-  , half_width_ ()
-  , kernel_width_ ()
-  , threads_ (1)
 {}
 
 template <typename PointIn, typename PointOut> void
index 0e229710a9219faa44e122308ee575f1c6c6f7db..99d8da8f55086889d12cd34b85b850968ef3aaf2 100644 (file)
@@ -64,7 +64,7 @@ pcl::CovarianceSampling<PointT, PointNT>::initCompute ()
   Eigen::Vector3f centroid (0.f, 0.f, 0.f);
   for (std::size_t p_i = 0; p_i < indices_->size (); ++p_i)
     centroid += (*input_)[(*indices_)[p_i]].getVector3fMap ();
-  centroid /= float (indices_->size ());
+  centroid /= static_cast<float>(indices_->size ());
 
   scaled_points_.resize (indices_->size ());
   double average_norm = 0.0;
@@ -74,9 +74,9 @@ pcl::CovarianceSampling<PointT, PointNT>::initCompute ()
     average_norm += scaled_points_[p_i].norm ();
   }
 
-  average_norm /= double (scaled_points_.size ());
-  for (std::size_t p_i = 0; p_i < scaled_points_.size (); ++p_i)
-    scaled_points_[p_i] /= float (average_norm);
+  average_norm /= static_cast<double>(scaled_points_.size ());
+  for (auto & scaled_point : scaled_points_)
+    scaled_point /= static_cast<float>(average_norm);
 
   return (true);
 }
index ef34a021bd4851d14e14946f9b25bef332e688eb..dbe8f5d07bccd0577c5eb45cfa4b4bab82224d61 100644 (file)
@@ -153,10 +153,10 @@ pcl::CropHull<PointT>::applyFilter3D (Indices &indices)
       Eigen::Vector3f(0.856514f,  0.508771f, 0.0868081f)
     };
 
-    for (std::size_t poly = 0; poly < hull_polygons_.size (); poly++)
+    for (const auto & hull_polygon : hull_polygons_)
       for (std::size_t ray = 0; ray < 3; ray++)
         crossings[ray] += rayTriangleIntersect
-          ((*input_)[(*indices_)[index]], rays[ray], hull_polygons_[poly], *hull_cloud_);
+          ((*input_)[(*indices_)[index]], rays[ray], hull_polygon, *hull_cloud_);
 
     bool crosses = (crossings[0]&1) + (crossings[1]&1) + (crossings[2]&1) > 1;
     if ((crop_outside_ && crosses) || (!crop_outside_ && !crosses))
index f7550e8ee8c8e7fe57ee062c5fd989324c551992..27a0a859db7860404126aa7210c5e4727623a3e0 100644 (file)
@@ -58,7 +58,7 @@ pcl::ExtractIndices<PointT>::filterDirectly (PointCloudPtr &cloud)
   pcl::for_each_type<FieldList> (pcl::detail::FieldAdder<PointT> (fields));
   for (const auto& rii : (*removed_indices_)) // rii = removed indices iterator
   {
-    auto pt_index = (uindex_t) rii;
+    auto pt_index = static_cast<uindex_t>(rii);
     if (pt_index >= input_->size ())
     {
       PCL_ERROR ("[pcl::%s::filterDirectly] The index exceeds the size of the input. Do nothing.\n",
@@ -91,7 +91,7 @@ pcl::ExtractIndices<PointT>::applyFilter (PointCloud &output)
     pcl::for_each_type<FieldList> (pcl::detail::FieldAdder<PointT> (fields));
     for (const auto ri : *removed_indices_)  // ri = removed index
     {
-      auto pt_index = (std::size_t)ri;
+      auto pt_index = static_cast<std::size_t>(ri);
       if (pt_index >= input_->size ())
       {
         PCL_ERROR ("[pcl::%s::applyFilter] The index exceeds the size of the input. Do nothing.\n",
index 3a23feea3f5441a4ff4a3e999bcad305953e13ff..1aba5722c10365130a0190796c6746d3fe802679 100644 (file)
@@ -63,25 +63,25 @@ pcl::FrustumCulling<PointT>::applyFilter (Indices &indices)
   Eigen::Vector3f T = camera_pose_.block<3, 1> (0, 3);       // The (X, Y, Z) position of the camera w.r.t origin
 
 
-  float fov_lower_bound_rad = float (fov_lower_bound_ * M_PI / 180);  // degrees to radians
-  float fov_upper_bound_rad = float (fov_upper_bound_ * M_PI / 180);  // degrees to radians
-  float fov_left_bound_rad = float (fov_left_bound_ * M_PI / 180);    // degrees to radians
-  float fov_right_bound_rad = float (fov_right_bound_ * M_PI / 180);  // degrees to radians
+  float fov_lower_bound_rad = static_cast<float>(fov_lower_bound_ * M_PI / 180);  // degrees to radians
+  float fov_upper_bound_rad = static_cast<float>(fov_upper_bound_ * M_PI / 180);  // degrees to radians
+  float fov_left_bound_rad = static_cast<float>(fov_left_bound_ * M_PI / 180);    // degrees to radians
+  float fov_right_bound_rad = static_cast<float>(fov_right_bound_ * M_PI / 180);  // degrees to radians
 
   float roi_xmax = roi_x_ + (roi_w_ / 2);  // roi max x
   float roi_xmin = roi_x_ - (roi_w_ / 2);  // roi min x
   float roi_ymax = roi_y_ + (roi_h_ / 2);  // roi max y
   float roi_ymin = roi_y_ - (roi_h_ / 2);  // roi min y
   
-  float np_h_u = float(2 * std::tan(fov_lower_bound_rad) * np_dist_ * (roi_ymin - 0.5));  // near plane upper height
-  float np_h_d = float(2 * std::tan(fov_upper_bound_rad) * np_dist_ * (roi_ymax - 0.5));  // near plane lower height
-  float np_w_l = float(2 * std::tan(fov_left_bound_rad) * np_dist_ * (roi_xmin - 0.5));   // near plane left width
-  float np_w_r = float(2 * std::tan(fov_right_bound_rad) * np_dist_ * (roi_xmax - 0.5));  // near plane right width
-
-  float fp_h_u = float(2 * std::tan(fov_lower_bound_rad) * fp_dist_ * (roi_ymin - 0.5));  // far plane upper height
-  float fp_h_d = float(2 * std::tan(fov_upper_bound_rad) * fp_dist_ * (roi_ymax - 0.5));  // far plane lower height
-  float fp_w_l = float(2 * std::tan(fov_left_bound_rad) * fp_dist_ * (roi_xmin - 0.5));   // far plane left width
-  float fp_w_r = float(2 * std::tan(fov_right_bound_rad) * fp_dist_ * (roi_xmax - 0.5));  // far plane right width
+  float np_h_u = static_cast<float>(2 * std::tan(fov_lower_bound_rad) * np_dist_ * (roi_ymin - 0.5));  // near plane upper height
+  float np_h_d = static_cast<float>(2 * std::tan(fov_upper_bound_rad) * np_dist_ * (roi_ymax - 0.5));  // near plane lower height
+  float np_w_l = static_cast<float>(2 * std::tan(fov_left_bound_rad) * np_dist_ * (roi_xmin - 0.5));   // near plane left width
+  float np_w_r = static_cast<float>(2 * std::tan(fov_right_bound_rad) * np_dist_ * (roi_xmax - 0.5));  // near plane right width
+
+  float fp_h_u = static_cast<float>(2 * std::tan(fov_lower_bound_rad) * fp_dist_ * (roi_ymin - 0.5));  // far plane upper height
+  float fp_h_d = static_cast<float>(2 * std::tan(fov_upper_bound_rad) * fp_dist_ * (roi_ymax - 0.5));  // far plane lower height
+  float fp_w_l = static_cast<float>(2 * std::tan(fov_left_bound_rad) * fp_dist_ * (roi_xmin - 0.5));   // far plane left width
+  float fp_w_r = static_cast<float>(2 * std::tan(fov_right_bound_rad) * fp_dist_ * (roi_xmax - 0.5));  // far plane right width
 
   Eigen::Vector3f fp_c (T + view * fp_dist_);                           // far plane center
   Eigen::Vector3f fp_tl (fp_c + (up * fp_h_u) - (right * fp_w_l));  // Top left corner of the far plane
index 7b0b1915c712bae03c76f2013e0f92dab030bbaa..fdb515d7b64dea02cfaa5abafad07a9c85aa19c9 100644 (file)
@@ -135,7 +135,7 @@ pcl::GridMinimum<PointT>::applyFilterIndices (Indices &indices)
   
   // 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
-  std::sort (index_vector.begin (), index_vector.end (), std::less<point_index_idx> ());
+  std::sort (index_vector.begin (), index_vector.end (), std::less<> ());
 
   // Third pass: count output cells
   // we need to skip all the same, adjacenent idx values
index da5e960a0246b49af0251e0bc5f19574255e93e1..e2ab6c0232b529f2220c3aab68ed46cc4f3cbc45 100644 (file)
@@ -97,7 +97,13 @@ pcl::LocalMaximum<PointT>::applyFilterIndices (Indices &indices)
     else
       searcher_.reset (new pcl::search::KdTree<PointT> (false));
   }
-  searcher_->setInputCloud (cloud_projected);
+  if (!searcher_->setInputCloud (cloud_projected))
+  {
+    PCL_ERROR ("[pcl::%s::applyFilter] Error when initializing search method!\n", getClassName ().c_str ());
+    indices.clear ();
+    removed_indices_->clear ();
+    return;
+  }
 
   // The arrays to be used
   indices.resize (indices_->size ());
@@ -121,6 +127,14 @@ pcl::LocalMaximum<PointT>::applyFilterIndices (Indices &indices)
     // not be maximal in their own neighborhood
     if (point_is_visited[iii] && !point_is_max[iii])
     {
+      if (negative_) {
+        if (extract_removed_indices_) {
+          (*removed_indices_)[rii++] = iii;
+        }
+      }
+      else {
+        indices[oii++] = iii;
+      }
       continue;
     }
 
@@ -146,9 +160,9 @@ pcl::LocalMaximum<PointT>::applyFilterIndices (Indices &indices)
 
     // Check to see if a neighbor is higher than the query point
     float query_z = (*input_)[iii].z;
-    for (std::size_t k = 1; k < radius_indices.size (); ++k)  // k = 1 is the first neighbor
+    for (const auto& radius_index : radius_indices) // the query point itself is in the (unsorted) radius_indices, but that is okay since we compare with ">"
     {
-      if ((*input_)[radius_indices[k]].z > query_z)
+      if ((*input_)[radius_index].z > query_z)
       {
         // Query point is not the local max, no need to check others
         point_is_max[iii] = false;
@@ -160,9 +174,9 @@ pcl::LocalMaximum<PointT>::applyFilterIndices (Indices &indices)
     // visited, excluding them from future consideration as local maxima
     if (point_is_max[iii])
     {
-      for (std::size_t k = 1; k < radius_indices.size (); ++k)  // k = 1 is the first neighbor
+      for (const auto& radius_index : radius_indices) // the query point itself is in the (unsorted) radius_indices, but it must also be marked as visited
       {
-        point_is_visited[radius_indices[k]] = true;
+        point_is_visited[radius_index] = true;
       }
     }
 
index 15926d8f2e126f5af2b98f295483a1ee4070e29e..8e13ec06824a9b0e70ad059c5a4f37178699df0b 100644 (file)
@@ -64,7 +64,13 @@ pcl::RadiusOutlierRemoval<PointT>::applyFilterIndices (Indices &indices)
     else
       searcher_.reset (new pcl::search::KdTree<PointT> (false));
   }
-  searcher_->setInputCloud (input_);
+  if (!searcher_->setInputCloud (input_))
+  {
+    PCL_ERROR ("[pcl::%s::applyFilter] Error when initializing search method!\n", getClassName ().c_str ());
+    indices.clear ();
+    removed_indices_->clear ();
+    return;
+  }
 
   // The arrays to be used
   Indices nn_indices (indices_->size ());
@@ -109,10 +115,7 @@ pcl::RadiusOutlierRemoval<PointT>::applyFilterIndices (Indices &indices)
       }
       else
       {
-        if (negative_)
-          chk_neighbors = true;
-        else
-          chk_neighbors = false;
+        chk_neighbors = negative_;
       }
 
       // Points having too few neighbors are outliers and are passed to removed indices
index fd3f221e18ce11dd824986c7d2b1effa34e390a7..a711bf8cba049a7e902aaecff948a898d4ee8067 100644 (file)
@@ -148,7 +148,7 @@ pcl::SamplingSurfaceNormal<PointT>::samplePartition (
   for (const auto& point: cloud)
   {
     // TODO: change to Boost random number generators!
-    const float r = float (std::rand ()) / float (RAND_MAX);
+    const float r = static_cast<float>(std::rand ()) / static_cast<float>(RAND_MAX);
 
     if (r < ratio_)
     {
index e6c3182292f00111dae877ba553a1f6fd90b75ab..0e9359f0bad18ee145ab16ef04b9eec6b9a2e3f7 100644 (file)
@@ -56,7 +56,13 @@ pcl::StatisticalOutlierRemoval<PointT>::applyFilterIndices (Indices &indices)
     else
       searcher_.reset (new pcl::search::KdTree<PointT> (false));
   }
-  searcher_->setInputCloud (input_);
+  if (!searcher_->setInputCloud (input_))
+  {
+    PCL_ERROR ("[pcl::%s::applyFilter] Error when initializing search method!\n", getClassName ().c_str ());
+    indices.clear ();
+    removed_indices_->clear ();
+    return;
+  }
 
   // The arrays to be used
   const int searcher_k = mean_k_ + 1;  // Find one more, since results include the query point.
index b67351dcdfc09da98f6866026283f400004bbf13..0c4c458bac4683a97c6a96fd15bb8a4ae8ae05a9 100644 (file)
@@ -267,7 +267,7 @@ pcl::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
   if (save_leaf_layout_)
     leaf_layout_.resize (div_b_[0] * div_b_[1] * div_b_[2], -1);
 
-  // Eigen values and vectors calculated to prevent near singluar matrices
+  // Eigen values and vectors calculated to prevent near singular matrices
   Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eigensolver;
   Eigen::Matrix3d eigen_val;
   Eigen::Vector3d pt_sum;
@@ -289,7 +289,7 @@ pcl::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
     leaf.mean_ /= leaf.nr_points;
 
     // If the voxel contains sufficient points, its covariance is calculated and is added to the voxel centroids and output clouds.
-    // Points with less than the minimum points will have a can not be accuratly approximated using a normal distribution.
+    // Points with less than the minimum points will have a can not be accurately approximated using a normal distribution.
     if (leaf.nr_points >= min_points_per_voxel_)
     {
       if (save_leaf_layout_)
index 5a6d397401493aa89091221c51db9a2eff45f875..63fac68a2676506c4c94af8102523aa4b0a08ebb 100644 (file)
@@ -62,6 +62,13 @@ pcl::VoxelGridOcclusionEstimation<PointT>::initializeVoxelGrid ()
   // set the sensor origin and sensor orientation
   sensor_origin_ = filtered_cloud_.sensor_origin_;
   sensor_orientation_ = filtered_cloud_.sensor_orientation_;
+
+  Eigen::Vector3i ijk = this->getGridCoordinates(sensor_origin_.x(), sensor_origin_.y(), sensor_origin_.z());
+  // first check whether the sensor origin is within the voxel grid bounding box, then whether it is occupied
+  if((ijk[0]>=min_b_[0] && ijk[1]>=min_b_[1] && ijk[2]>=min_b_[2] && ijk[0]<=max_b_[0] && ijk[1]<=max_b_[1] && ijk[2]<=max_b_[2]) && this->getCentroidIndexAt (ijk) != -1) {
+    PCL_WARN ("[VoxelGridOcclusionEstimation::initializeVoxelGrid] The voxel containing the sensor origin (%g, %g, %g) is marked as occupied. We will instead assume that it is free, to be able to perform the occlusion estimation.\n", sensor_origin_.x(), sensor_origin_.y(), sensor_origin_.z());
+    this->leaf_layout_[((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (this->divb_mul_)] = -1;
+  }
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -233,8 +240,7 @@ pcl::VoxelGridOcclusionEstimation<PointT>::rayBoxIntersection (const Eigen::Vect
     tmin = tzmin;
   if (tzmax < tmax)
     tmax = tzmax;
-
-  return tmin;
+  return std::max<float>(tmin, 0.0f); // We only want to go in "positive" direction here, not in negative. This is relevant if the origin is inside the bounding box
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
index 741bf3b87bcc933662f5aa080138586ce54cc3ff..cd65455f58d85c355b9f9e187a31d604918ce555 100644 (file)
@@ -67,8 +67,7 @@ namespace pcl
       /** \brief Empty constructor. */
       LocalMaximum (bool extract_removed_indices = false) :
         FilterIndices<PointT>::FilterIndices (extract_removed_indices),
-        searcher_ (),
-        radius_ (1)
+        searcher_ ()
       {
         filter_name_ = "LocalMaximum";
       }
@@ -85,6 +84,12 @@ namespace pcl
       inline float
       getRadius () const { return (radius_); }
 
+      /** \brief Provide a pointer to the search object.
+        * Calling this is optional. If not called, the search method will be chosen automatically.
+        * \param[in] searcher a pointer to the spatial search object.
+        */
+      inline void
+      setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; }
     protected:
       using PCLBase<PointT>::input_;
       using PCLBase<PointT>::indices_;
@@ -120,7 +125,7 @@ namespace pcl
       SearcherPtr searcher_;
 
       /** \brief The radius to use to determine if a point is the local max. */
-      float radius_;
+      float radius_{1.0f};
   };
 }
 
index 8e08e508096813b8991d1ae33443f54c3157311a..614b34ea6103f311a7bdd186503cdfa1609aca87 100644 (file)
@@ -64,10 +64,7 @@ namespace pcl
 
     public:
       /** \brief Empty constructor. */
-      MedianFilter ()
-        : window_size_ (5)
-        , max_allowed_movement_ (std::numeric_limits<float>::max ())
-      { }
+      MedianFilter () = default;
 
       /** \brief Set the window size of the filter.
         * \param[in] window_size the new window size
@@ -104,8 +101,8 @@ namespace pcl
       applyFilter (PointCloud &output) override;
 
     protected:
-      int window_size_;
-      float max_allowed_movement_;
+      int window_size_{5};
+      float max_allowed_movement_{std::numeric_limits<float>::max ()};
   };
 }
 
index 73963449d6eaa685c2eee916fb6f34a95e262f9d..8fbe3dce188bd3da24690b2760f551405ce1b901 100644 (file)
@@ -48,20 +48,24 @@ namespace pcl
 {
   /** \brief @b ModelOutlierRemoval filters points in a cloud based on the distance between model and point.
    * \details Iterates through the entire input once, automatically filtering non-finite points and the points outside
-   * the model specified by setSampleConsensusModelPointer() and the threshold specified by setThreholdFunctionPointer().
    * <br><br>
    * Usage example:
    * \code
+   * 
    * pcl::ModelCoefficients model_coeff;
    * model_coeff.values.resize(4);
-   * model_coeff.values[0] = 0; model_coeff.values[1] = 0; model_coeff.values[2] = 1.5; model_coeff.values[3] = 0.5;
+   * model_coeff.values[0] = 0; 
+   * model_coeff.values[1] = 0; 
+   * model_coeff.values[2] = 1; 
+   * model_coeff.values[3] = 0.5;
    * pcl::ModelOutlierRemoval<pcl::PointXYZ> filter;
    * filter.setModelCoefficients (model_coeff);
    * filter.setThreshold (0.1);
    * filter.setModelType (pcl::SACMODEL_PLANE);
    * filter.setInputCloud (*cloud_in);
-   * filter.setFilterLimitsNegative (false);
+   * filter.setNegative (false);
    * filter.filter (*cloud_out);
+
    * \endcode
    */
   template <typename PointT>
index 144ec0ad9cae9ef162c2c4c58eebdf229a0fc3dc..7de5be0300c5fbbcc595d58642d1781d0f5bf8f1 100644 (file)
@@ -64,7 +64,11 @@ namespace pcl
       PCL_ERROR("[pcl::assignNormalWeights] inequal size of neighbor indices and distances!\n");
     
     // TODO: For now we use uniform weights
-    return (std::vector<float> (k_indices.size (), 1.0f));
+    // Disable check for braced-initialization,
+    // since the compiler doesn't seem to recognize that
+    // {k_indices.size (), 1.0f} is selecting the vector(size_type count, const T&) constructor
+    // NOLINTNEXTLINE(modernize-return-braced-init-list)
+    return std::vector<float> (k_indices.size (), 1.0f);
   }
   
   /** \brief Refine an indexed point based on its neighbors, this function only writes to the normal_* fields
index 7edc84bfbc06b71bfb58159ec05b16223282f3ef..644b9d4ea9dcbd655be88905550509f4259db027 100644 (file)
@@ -97,7 +97,7 @@ namespace pcl
         */
       PassThrough (bool extract_removed_indices = false) :
         FilterIndices<PointT> (extract_removed_indices),
-        filter_field_name_ (""),
+        
         filter_limit_min_ (std::numeric_limits<float>::lowest()),
         filter_limit_max_ (std::numeric_limits<float>::max())
       {
@@ -212,8 +212,8 @@ namespace pcl
     public:
       /** \brief Constructor. */
       PassThrough (bool extract_removed_indices = false) :
-        FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices), filter_field_name_("")
-      , filter_limit_min_(std::numeric_limits<float>::lowest())
+        FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices), 
+       filter_limit_min_(std::numeric_limits<float>::lowest())
       , filter_limit_max_(std::numeric_limits<float>::max())
       {
         filter_name_ = "PassThrough";
index 507685bcffbe1419bd2d27acb9416b59cd8682c0..a886f3bcef99da22b47b98b23e27bb560f839f78 100644 (file)
@@ -54,7 +54,7 @@ namespace pcl
       using Ptr = shared_ptr< PlaneClipper3D<PointT> >;
       using ConstPtr = shared_ptr< const PlaneClipper3D<PointT> >;
 
-      PCL_MAKE_ALIGNED_OPERATOR_NEW;
+      PCL_MAKE_ALIGNED_OPERATOR_NEW
 
       /**
        * @author Suat Gedikli <gedikli@willowgarage.com>
index 6a7c36f6ad38a869ce8183aedc2b862cb00cde78..cc02be447fa48596d1b8b97a52eca102668f7e66 100644 (file)
@@ -71,7 +71,7 @@ namespace pcl
 
 
       /** \brief Empty constructor. */
-      ProjectInliers () : sacmodel_ (), model_type_ (), copy_all_data_ (false)
+      ProjectInliers () : sacmodel_ ()
       {
         filter_name_ = "ProjectInliers";
       }
@@ -142,10 +142,10 @@ namespace pcl
       SampleConsensusModelPtr sacmodel_;
 
       /** \brief The type of model to use (user given parameter). */
-      int model_type_;
+      int model_type_{0};
 
       /** \brief True if all data will be returned, false if only the projected inliers. Default: false. */
-      bool copy_all_data_;
+      bool copy_all_data_{false};
 
       /** \brief Initialize the Sample Consensus model and set its parameters.
         * \param model_type the type of SAC model that is to be used
@@ -174,7 +174,7 @@ namespace pcl
 
     public:
       /** \brief Empty constructor. */
-      ProjectInliers () : model_type_ (), copy_all_data_ (false), copy_all_fields_ (true)
+      ProjectInliers ()
       {
         filter_name_ = "ProjectInliers";
       }
@@ -247,13 +247,13 @@ namespace pcl
       }
     protected:
       /** \brief The type of model to use (user given parameter). */
-      int model_type_;
+      int model_type_{0};
 
       /** \brief True if all data will be returned, false if only the projected inliers. Default: false. */
-      bool copy_all_data_;
+      bool copy_all_data_{false};
 
       /** \brief True if all fields will be returned, false if only XYZ. Default: true. */
-      bool copy_all_fields_;
+      bool copy_all_fields_{true};
 
       /** \brief A pointer to the vector of model coefficients. */
       ModelCoefficientsConstPtr model_;
index 8077eac8a348c0f9cdea3c4bcb1b014a2302284c..107c83000c482774ed50cf79932a31fb8cfac520 100644 (file)
@@ -69,10 +69,7 @@ namespace pcl
  
         Pyramid (int levels = 4)
           : levels_ (levels)
-          , large_ (false)
           , name_ ("Pyramid")
-          , threshold_ (0.01)
-          , threads_ (0)
         {
         }
       
@@ -148,17 +145,17 @@ namespace pcl
         /// \brief The input point cloud dataset.
         PointCloudConstPtr input_;
         /// \brief number of pyramid levels
-        int levels_;
+        int levels_{4};
         /// \brief use large smoothing kernel
-        bool large_;
+        bool large_{false};
         /// \brief filter name
         std::string name_;
         /// \brief smoothing kernel
         Eigen::MatrixXf kernel_;
         /// Threshold distance between adjacent points
-        float threshold_;
+        float threshold_{0.01f};
         /// \brief number of threads
-        unsigned int threads_;
+        unsigned int threads_{0};
 
       public:
         PCL_MAKE_ALIGNED_OPERATOR_NEW
index 62a65031f1dbc2a8c42bb7475ea59fe7ede2741f..23f1d48317d96d72e05fca04981cfa39a4eed772 100644 (file)
@@ -87,9 +87,7 @@ namespace pcl
         */
       RadiusOutlierRemoval (bool extract_removed_indices = false) :
         FilterIndices<PointT> (extract_removed_indices),
-        searcher_ (),
-        search_radius_ (0.0),
-        min_pts_radius_ (1)
+        searcher_ ()
       {
         filter_name_ = "RadiusOutlierRemoval";
       }
@@ -138,6 +136,12 @@ namespace pcl
         return (min_pts_radius_);
       }
 
+      /** \brief Provide a pointer to the search object.
+        * Calling this is optional. If not called, the search method will be chosen automatically.
+        * \param[in] searcher a pointer to the spatial search object.
+        */
+      inline void
+      setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; }
     protected:
       using PCLBase<PointT>::input_;
       using PCLBase<PointT>::indices_;
@@ -169,10 +173,10 @@ namespace pcl
       SearcherPtr searcher_;
 
       /** \brief The nearest neighbors search radius for each point. */
-      double search_radius_;
+      double search_radius_{0.0};
 
       /** \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_;
+      int min_pts_radius_{1};
   };
 
   //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -200,8 +204,7 @@ namespace pcl
     public:
       /** \brief Empty constructor. */
       RadiusOutlierRemoval (bool extract_removed_indices = false) :
-        FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices),
-        search_radius_ (0.0), min_pts_radius_ (1)
+        FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices)
       {
         filter_name_ = "RadiusOutlierRemoval";
       }
@@ -243,12 +246,12 @@ namespace pcl
 
     protected:
       /** \brief The nearest neighbors search radius for each point. */
-      double search_radius_;
+      double search_radius_{0.0};
 
       /** \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_;
+      int min_pts_radius_{1};
 
       /** \brief A pointer to the spatial search object. */
       KdTreePtr searcher_;
index 44cd2543e0afc9b09e44062c47d19836d812de66..672fd68d24113635f299ce48a21902f23fb54210 100644 (file)
@@ -135,7 +135,7 @@ namespace pcl
       inline float
       unifRand ()
       {
-        return (static_cast<float>(rand () / double (RAND_MAX)));
+        return (static_cast<float>(rand () / static_cast<double>(RAND_MAX)));
         //return (((214013 * seed_ + 2531011) >> 16) & 0x7FFF);
       }
   };
@@ -226,7 +226,7 @@ namespace pcl
       inline float
       unifRand ()
       {
-        return (static_cast<float> (rand () / double (RAND_MAX)));
+        return (static_cast<float> (rand () / static_cast<double>(RAND_MAX)));
       }
    };
 }
index ea0a68bc41734724b24f4bc08d68a754c7f53c5d..3c2e8397404aa717f523206a956628bdc8924068 100644 (file)
@@ -69,8 +69,7 @@ namespace pcl
       using ConstPtr = shared_ptr<const SamplingSurfaceNormal<PointT> >;
 
       /** \brief Empty constructor. */
-      SamplingSurfaceNormal () : 
-        sample_ (10), seed_ (static_cast<unsigned int> (time (nullptr))), ratio_ ()
+      SamplingSurfaceNormal ()
       {
         filter_name_ = "SamplingSurfaceNormal";
         srand (seed_);
@@ -128,11 +127,11 @@ namespace pcl
     protected:
 
       /** \brief Maximum number of samples in each grid. */
-      unsigned int sample_;
+      unsigned int sample_{10};
       /** \brief Random number seed. */
-      unsigned int seed_;
+      unsigned int seed_{static_cast<unsigned int> (time (nullptr))};
       /** \brief Ratio of points to be sampled in each grid */
-      float ratio_;
+      float ratio_{0.0f};
 
       /** \brief Sample of point indices into a separate PointCloud
         * \param[out] output the resultant point cloud
index 5e2fe6ad6a4f27a1c2b03cbb166631774e9a49ff..af926bd1a5d202749eac3e64a21bfdd847709266 100644 (file)
@@ -72,8 +72,7 @@ namespace pcl
       /** \brief Empty constructor. */
       ShadowPoints (bool extract_removed_indices = false) : 
         FilterIndices<PointT> (extract_removed_indices),
-        input_normals_ (), 
-        threshold_ (0.1f) 
+        input_normals_ ()
       {
         filter_name_ = "ShadowPoints";
       }
@@ -119,7 +118,7 @@ namespace pcl
 
       /** \brief Threshold for shadow point rejection
         */
-      float threshold_;
+      float threshold_{0.1f};
   };
 }
 
index 70b450dea12d96b895d3a25b02599e7b66fdf0eb..4abfd12316ee0d200b53dc6535ede505a89ce9f4 100644 (file)
@@ -96,9 +96,7 @@ namespace pcl
         */
       StatisticalOutlierRemoval (bool extract_removed_indices = false) :
         FilterIndices<PointT> (extract_removed_indices),
-        searcher_ (),
-        mean_k_ (1),
-        std_mul_ (0.0)
+        searcher_ ()
       {
         filter_name_ = "StatisticalOutlierRemoval";
       }
@@ -142,6 +140,12 @@ namespace pcl
         return (std_mul_);
       }
 
+      /** \brief Provide a pointer to the search object.
+        * Calling this is optional. If not called, the search method will be chosen automatically.
+        * \param[in] searcher a pointer to the spatial search object.
+        */
+      inline void
+      setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; }
     protected:
       using PCLBase<PointT>::input_;
       using PCLBase<PointT>::indices_;
@@ -173,11 +177,11 @@ namespace pcl
       SearcherPtr searcher_;
 
       /** \brief The number of points to use for mean distance estimation. */
-      int mean_k_;
+      int mean_k_{1};
 
       /** \brief Standard deviations threshold (i.e., points outside of 
         * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */
-      double std_mul_;
+      double std_mul_{0.0};
   };
 
   /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more
@@ -208,8 +212,7 @@ namespace pcl
     public:
       /** \brief Empty constructor. */
       StatisticalOutlierRemoval (bool extract_removed_indices = false) :
-        FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices), mean_k_ (2),
-        std_mul_ (0.0)
+        FilterIndices<pcl::PCLPointCloud2>::FilterIndices (extract_removed_indices)
       {
         filter_name_ = "StatisticalOutlierRemoval";
       }
@@ -251,12 +254,12 @@ namespace pcl
 
     protected:
       /** \brief The number of points to use for mean distance estimation. */
-      int mean_k_;
+      int mean_k_{2};
 
       /** \brief Standard deviations threshold (i.e., points outside of 
         * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). 
         */
-      double std_mul_;
+      double std_mul_{0.0};
 
       /** \brief A pointer to the spatial search object. */
       KdTreePtr tree_;
index 18d0f046314f6b7df6b69d65022d6eb7d5960ac0..39d0815d32a77bf3a4e6e99b8c525225eaeeea52 100644 (file)
@@ -71,7 +71,7 @@ namespace pcl
       using Ptr = shared_ptr<UniformSampling<PointT> >;
       using ConstPtr = shared_ptr<const UniformSampling<PointT> >;
 
-      PCL_MAKE_ALIGNED_OPERATOR_NEW;
+      PCL_MAKE_ALIGNED_OPERATOR_NEW
 
       /** \brief Empty constructor. */
       UniformSampling (bool extract_removed_indices = false) :
@@ -82,8 +82,7 @@ namespace pcl
         min_b_ (Eigen::Vector4i::Zero ()),
         max_b_ (Eigen::Vector4i::Zero ()),
         div_b_ (Eigen::Vector4i::Zero ()),
-        divb_mul_ (Eigen::Vector4i::Zero ()),
-        search_radius_ (0)
+        divb_mul_ (Eigen::Vector4i::Zero ())
       {
         filter_name_ = "UniformSampling";
       }
@@ -113,8 +112,8 @@ namespace pcl
       /** \brief Simple structure to hold an nD centroid and the number of points in a leaf. */
       struct Leaf
       {
-        Leaf () : idx (-1) { }
-        int idx;
+        Leaf () = default;
+        int idx{-1};
       };
 
       /** \brief The 3D grid leaves. */
@@ -130,7 +129,7 @@ namespace pcl
       Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
 
       /** \brief The nearest neighbors search radius for each point. */
-      double search_radius_;
+      double search_radius_{0.0};
 
       /** \brief Downsample a Point Cloud using a voxelized grid approach
         * \param[out] output the resultant point cloud message
index cde68c0a1326b0365e668653eccf80568762d844..24615c43e7ffc0b561e26fa1b4223522a938468b 100644 (file)
@@ -190,23 +190,16 @@ namespace pcl
       using Ptr = shared_ptr<VoxelGrid<PointT> >;
       using ConstPtr = shared_ptr<const VoxelGrid<PointT> >;
 
-      PCL_MAKE_ALIGNED_OPERATOR_NEW;
+      PCL_MAKE_ALIGNED_OPERATOR_NEW
 
       /** \brief Empty constructor. */
       VoxelGrid () :
         leaf_size_ (Eigen::Vector4f::Zero ()),
         inverse_leaf_size_ (Eigen::Array4f::Zero ()),
-        downsample_all_data_ (true),
-        save_leaf_layout_ (false),
         min_b_ (Eigen::Vector4i::Zero ()),
         max_b_ (Eigen::Vector4i::Zero ()),
         div_b_ (Eigen::Vector4i::Zero ()),
-        divb_mul_ (Eigen::Vector4i::Zero ()),
-        filter_field_name_ (""),
-        filter_limit_min_ (std::numeric_limits<float>::lowest()),
-        filter_limit_max_ (std::numeric_limits<float>::max()),
-        filter_limit_negative_ (false),
-        min_points_per_voxel_ (0)
+        divb_mul_ (Eigen::Vector4i::Zero ())
       {
         filter_name_ = "VoxelGrid";
       }
@@ -362,9 +355,9 @@ namespace pcl
       inline Eigen::Vector3i
       getGridCoordinates (float x, float y, float z) const
       {
-        return (Eigen::Vector3i (static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
+        return {static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
                                  static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
-                                 static_cast<int> (std::floor (z * inverse_leaf_size_[2]))));
+                                 static_cast<int> (std::floor (z * inverse_leaf_size_[2]))};
       }
 
       /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates.
@@ -460,10 +453,10 @@ namespace pcl
       Eigen::Array4f inverse_leaf_size_;
 
       /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */
-      bool downsample_all_data_;
+      bool downsample_all_data_{true};
 
       /** \brief Set to true if leaf layout information needs to be saved in \a leaf_layout_. */
-      bool save_leaf_layout_;
+      bool save_leaf_layout_{false};
 
       /** \brief The leaf layout information for fast access to cells relative to current position **/
       std::vector<int> leaf_layout_;
@@ -475,16 +468,16 @@ namespace pcl
       std::string filter_field_name_;
 
       /** \brief The minimum allowed filter value a point will be considered from. */
-      double filter_limit_min_;
+      double filter_limit_min_{std::numeric_limits<float>::lowest()};
 
       /** \brief The maximum allowed filter value a point will be considered from. */
-      double filter_limit_max_;
+      double filter_limit_max_{std::numeric_limits<float>::max()};
 
       /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */
-      bool filter_limit_negative_;
+      bool filter_limit_negative_{false};
 
       /** \brief Minimum number of points per voxel for the centroid to be computed */
-      unsigned int min_points_per_voxel_;
+      unsigned int min_points_per_voxel_{0};
 
       using FieldList = typename pcl::traits::fieldList<PointT>::type;
 
@@ -522,17 +515,11 @@ namespace pcl
       VoxelGrid () :
         leaf_size_ (Eigen::Vector4f::Zero ()),
         inverse_leaf_size_ (Eigen::Array4f::Zero ()),
-        downsample_all_data_ (true),
-        save_leaf_layout_ (false),
+        
         min_b_ (Eigen::Vector4i::Zero ()),
         max_b_ (Eigen::Vector4i::Zero ()),
         div_b_ (Eigen::Vector4i::Zero ()),
-        divb_mul_ (Eigen::Vector4i::Zero ()),
-        filter_field_name_ (""),
-        filter_limit_min_ (std::numeric_limits<float>::lowest()),
-        filter_limit_max_ (std::numeric_limits<float>::max()),
-        filter_limit_negative_ (false),
-        min_points_per_voxel_ (0)
+        divb_mul_ (Eigen::Vector4i::Zero ())
       {
         filter_name_ = "VoxelGrid";
       }
@@ -710,9 +697,9 @@ namespace pcl
       inline Eigen::Vector3i
       getGridCoordinates (float x, float y, float z) const
       {
-        return (Eigen::Vector3i (static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
+        return {static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
                                  static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
-                                 static_cast<int> (std::floor (z * inverse_leaf_size_[2]))));
+                                 static_cast<int> (std::floor (z * inverse_leaf_size_[2]))};
       }
 
       /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates.
@@ -808,12 +795,12 @@ namespace pcl
       Eigen::Array4f inverse_leaf_size_;
 
       /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */
-      bool downsample_all_data_;
+      bool downsample_all_data_{true};
 
       /** \brief Set to true if leaf layout information needs to be saved in \a
         * leaf_layout.
         */
-      bool save_leaf_layout_;
+      bool save_leaf_layout_{false};
 
       /** \brief The leaf layout information for fast access to cells relative
         * to current position
@@ -829,16 +816,16 @@ namespace pcl
       std::string filter_field_name_;
 
       /** \brief The minimum allowed filter value a point will be considered from. */
-      double filter_limit_min_;
+      double filter_limit_min_{std::numeric_limits<float>::lowest()};
 
       /** \brief The maximum allowed filter value a point will be considered from. */
-      double filter_limit_max_;
+      double filter_limit_max_{std::numeric_limits<float>::max()};
 
       /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */
-      bool filter_limit_negative_;
+      bool filter_limit_negative_{false};
 
       /** \brief Minimum number of points per voxel for the centroid to be computed */
-      unsigned int min_points_per_voxel_;
+      unsigned int min_points_per_voxel_{0};
 
       /** \brief Downsample a Point Cloud using a voxelized grid approach
         * \param[out] output the resultant point cloud
index 67b9fe2f7f873030545aebd414c927e3748c8602..d2f69e788a00ef61e3391579822a0387b1eab6a5 100644 (file)
@@ -44,7 +44,7 @@
 
 namespace pcl
 {
-  /** \brief A searchable voxel strucure containing the mean and covariance of the data.
+  /** \brief A searchable voxel structure containing the mean and covariance of the data.
     * \note For more information please see
     * <b>Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform —
     * an Efficient Representation for Registration, Surface Analysis, and Loop Detection.
@@ -94,7 +94,6 @@ namespace pcl
          * Sets \ref nr_points, \ref cov_, \ref icov_, \ref mean_ and \ref evals_ to 0 and \ref evecs_ to the identity matrix
          */
         Leaf () :
-          nr_points (0),
           mean_ (Eigen::Vector3d::Zero ()),
           cov_ (Eigen::Matrix3d::Zero ()),
           icov_ (Eigen::Matrix3d::Zero ()),
@@ -160,7 +159,7 @@ namespace pcl
         }
 
         /** \brief Number of points contained by voxel */
-        int nr_points;
+        int nr_points{0};
 
         /** \brief 3D voxel centroid */
         Eigen::Vector3d mean_;
@@ -196,9 +195,6 @@ namespace pcl
        * Sets \ref leaf_size_ to 0 and \ref searchable_ to false.
        */
       VoxelGridCovariance () :
-        searchable_ (true),
-        min_points_per_voxel_ (6),
-        min_covar_eigvalue_mult_ (0.01),
         leaves_ (),
         voxel_centroids_ (),
         kdtree_ ()
@@ -464,7 +460,7 @@ namespace pcl
         }
 
         // Find k-nearest neighbors in the occupied voxel centroid cloud
-        Indices k_indices;
+        Indices k_indices (k);
         k = kdtree_.nearestKSearch (point, k, k_indices, k_sqr_distances);
 
         // Find leaves corresponding to neighbors
@@ -568,13 +564,13 @@ namespace pcl
       void applyFilter (PointCloud &output) override;
 
       /** \brief Flag to determine if voxel structure is searchable. */
-      bool searchable_;
+      bool searchable_{true};
 
       /** \brief Minimum points contained with in a voxel to allow it to be usable. */
-      int min_points_per_voxel_;
+      int min_points_per_voxel_{6};
 
       /** \brief Minimum allowable ratio between eigenvalues to prevent singular covariance matrices. */
-      double min_covar_eigvalue_mult_;
+      double min_covar_eigvalue_mult_{0.01};
 
       /** \brief Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points). */
       std::map<std::size_t, Leaf> leaves_;
@@ -582,7 +578,7 @@ namespace pcl
       /** \brief Point cloud containing centroids of voxels containing atleast minimum number of points. */
       PointCloudPtr voxel_centroids_;
 
-      /** \brief Indices of leaf structurs associated with each point in \ref voxel_centroids_ (used for searching). */
+      /** \brief Indices of leaf structures associated with each point in \ref voxel_centroids_ (used for searching). */
       std::vector<int> voxel_centroids_leaf_indices_;
 
       /** \brief KdTree generated using \ref voxel_centroids_ (used for searching). */
index b148e2bd2822f545cda2d449428f0d56f38f10b0..a55b84b3f30777606f45a46911e9b2cbd629b6da 100644 (file)
@@ -47,7 +47,15 @@ namespace pcl
   /** \brief VoxelGrid to estimate occluded space in the scene.
     * The ray traversal algorithm is implemented by the work of 
     * 'John Amanatides and Andrew Woo, A Fast Voxel Traversal Algorithm for Ray Tracing'
-    *
+    * Example code:
+    * \code
+    * pcl::VoxelGridOcclusionEstimation<pcl::PointXYZ> vg;
+    * vg.setInputCloud (input_cloud);
+    * vg.setLeafSize (leaf_x, leaf_y, leaf_z);
+    * vg.initializeVoxelGrid ();
+    * std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> > occluded_voxels;
+    * vg.occlusionEstimationAll (occluded_voxels);
+    * \endcode
     * \author Christian Potthast
     * \ingroup filters
     */
@@ -67,7 +75,7 @@ namespace pcl
 
     public:
 
-      PCL_MAKE_ALIGNED_OPERATOR_NEW;
+      PCL_MAKE_ALIGNED_OPERATOR_NEW
 
       /** \brief Empty constructor. */
       VoxelGridOcclusionEstimation ()
@@ -179,7 +187,7 @@ namespace pcl
                           const Eigen::Vector4f& direction);
 
       /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied)
-        * unsing a ray traversal algorithm.
+        * using a ray traversal algorithm.
         * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k).
         * \param[in] origin The sensor origin.
         * \param[in] direction The sensor orientation
@@ -193,7 +201,7 @@ namespace pcl
                     const float t_min);
 
       /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied) and
-        * the voxels penetrated by the ray unsing a ray traversal algorithm.
+        * the voxels penetrated by the ray using a ray traversal algorithm.
         * \param[out] out_ray The voxels penetrated by the ray in (i, j, k) coordinates
         * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k).
         * \param[in] origin The sensor origin.
@@ -227,9 +235,9 @@ namespace pcl
       inline Eigen::Vector3i
       getGridCoordinatesRound (float x, float y, float z) 
       {
-        return Eigen::Vector3i (static_cast<int> (round (x * inverse_leaf_size_[0])), 
-                                static_cast<int> (round (y * inverse_leaf_size_[1])), 
-                                static_cast<int> (round (z * inverse_leaf_size_[2])));
+        return {static_cast<int> (round (x * inverse_leaf_size_[0])),
+                                static_cast<int> (round (y * inverse_leaf_size_[1])),
+                                static_cast<int> (round (z * inverse_leaf_size_[2]))};
       }
 
       // initialization flag
index 6ac3544d89582b4eacd077482b4f632aaa6b7b3c..14d04e13af24ae0ede99488a467c1803d5257fd7 100644 (file)
@@ -65,7 +65,7 @@ pcl::ExtractIndices<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
       Indices indices = *indices_;
       std::sort (indices.begin (), indices.end ());
 
-      // Get the diference
+      // Get the difference
       Indices remaining_indices;
       set_difference (all_indices.begin (), all_indices.end (), indices.begin (), indices.end (),
                       inserter (remaining_indices, remaining_indices.begin ()));
@@ -120,7 +120,7 @@ pcl::ExtractIndices<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     Indices indices = *indices_;
     std::sort (indices.begin (), indices.end ());
 
-    // Get the diference
+    // Get the difference
     Indices remaining_indices;
     set_difference (all_indices.begin (), all_indices.end (), indices.begin (), indices.end (),
                     inserter (remaining_indices, remaining_indices.begin ()));
index c8fdd255e0f69f3709a2ab7c7743709453d7852e..c56a285a0f51859582adcd7c2dd4acaeebc39e1d 100644 (file)
@@ -217,7 +217,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
         }
 
         // Unoptimized memcpys: assume fields x, y, z are in random order
-        memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float));
+        memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer)
         memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
         memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));
 
@@ -245,7 +245,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     for (int 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));
+      memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer)
       memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
       memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));
 
index baaf90b9efca8a8ac1203f464a18113714748cf7..3690d86c3fa64e19eb16a53491b4920336460bbf 100644 (file)
@@ -56,7 +56,7 @@ pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2
 
   if (std_mul_ == 0.0)
   {
-    PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multipler not set!\n", getClassName ().c_str ());
+    PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multiplier not set!\n", getClassName ().c_str ());
     output.width = output.height = 0;
     output.data.clear ();
     return;
@@ -147,7 +147,7 @@ pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2>::applyFilter (Indices& indic
 
   if (std_mul_ == 0.0)
   {
-    PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multipler not set!\n", getClassName ().c_str ());
+    PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multiplier not set!\n", getClassName ().c_str ());
     indices.clear();
     return;
   }
index 4c1566da57058de84480d503e5a56962ee502a4c..2a3ab968bfd42e114126aeba6def62887b8b65fa 100644 (file)
@@ -45,7 +45,7 @@
 #include <array>
 
 using Array4size_t = Eigen::Array<std::size_t, 4, 1>;
-
+// NOLINTBEGIN(readability-container-data-pointer)
 ///////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
@@ -406,7 +406,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
   }
 
   // Fourth pass: compute centroids, insert them into their final position
-  output.width = std::uint32_t (total);
+  output.width = static_cast<std::uint32_t>(total);
   output.row_step = output.point_step * output.width;
   output.data.resize (output.width * output.point_step);
 
@@ -525,7 +525,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
     ++index;
   }
 }
-
+// NOLINTEND(readability-container-data-pointer)
 #ifndef PCL_NO_PRECOMPILE
 #include <pcl/impl/instantiate.hpp>
 #include <pcl/point_types.h>
index a7f3f08c3ce94339a07ea75d33603afca9d47959..13dd7cdfdb49e4fcfc487b9ae2f423e7630246b8 100644 (file)
@@ -189,7 +189,7 @@ pcl::VoxelGridLabel::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
-  std::sort (index_vector.begin (), index_vector.end (), std::less<cloud_point_index_idx> ());
+  std::sort (index_vector.begin (), index_vector.end (), std::less<> ());
 
   // Third pass: count output cells
   // we need to skip all the same, adjacenent idx values
index 4928236aab3907f9895e86fad12d677d257c637b..f0437d2d5d35e59ec377f38e454a12031b21f9a8 100644 (file)
@@ -48,6 +48,7 @@
 #include <pcl/pcl_macros.h>
 #include <pcl/point_cloud.h>
 
+#include <cassert>
 #include <type_traits>
 #include <vector>
 
@@ -183,7 +184,7 @@ public:
   {
     vertices_.push_back(Vertex());
     this->addData(vertex_data_cloud_, vertex_data, HasVertexData());
-    return (VertexIndex(static_cast<int>(this->sizeVertices() - 1)));
+    return (static_cast<VertexIndex>(this->sizeVertices() - 1));
   }
 
   /**
@@ -323,25 +324,28 @@ public:
     }
 
     // Adjust the indices
-    for (auto it = vertices_.begin(); it != vertices_.end(); ++it) {
-      if (it->idx_outgoing_half_edge_.isValid()) {
-        it->idx_outgoing_half_edge_ =
-            new_half_edge_indices[it->idx_outgoing_half_edge_.get()];
+    for (auto& vertex : vertices_) {
+      if (vertex.idx_outgoing_half_edge_.isValid()) {
+        vertex.idx_outgoing_half_edge_ =
+            new_half_edge_indices[vertex.idx_outgoing_half_edge_.get()];
       }
     }
 
-    for (auto it = half_edges_.begin(); it != half_edges_.end(); ++it) {
-      it->idx_terminating_vertex_ =
-          new_vertex_indices[it->idx_terminating_vertex_.get()];
-      it->idx_next_half_edge_ = new_half_edge_indices[it->idx_next_half_edge_.get()];
-      it->idx_prev_half_edge_ = new_half_edge_indices[it->idx_prev_half_edge_.get()];
-      if (it->idx_face_.isValid()) {
-        it->idx_face_ = new_face_indices[it->idx_face_.get()];
+    for (auto& half_edge : half_edges_) {
+      half_edge.idx_terminating_vertex_ =
+          new_vertex_indices[half_edge.idx_terminating_vertex_.get()];
+      half_edge.idx_next_half_edge_ =
+          new_half_edge_indices[half_edge.idx_next_half_edge_.get()];
+      half_edge.idx_prev_half_edge_ =
+          new_half_edge_indices[half_edge.idx_prev_half_edge_.get()];
+      if (half_edge.idx_face_.isValid()) {
+        half_edge.idx_face_ = new_face_indices[half_edge.idx_face_.get()];
       }
     }
 
-    for (auto it = faces_.begin(); it != faces_.end(); ++it) {
-      it->idx_inner_half_edge_ = new_half_edge_indices[it->idx_inner_half_edge_.get()];
+    for (auto& face : faces_) {
+      face.idx_inner_half_edge_ =
+          new_half_edge_indices[face.idx_inner_half_edge_.get()];
     }
   }
 
@@ -637,29 +641,32 @@ public:
   inline bool
   isValid(const VertexIndex& idx_vertex) const
   {
-    return (idx_vertex >= VertexIndex(0) &&
-            idx_vertex < VertexIndex(int(vertices_.size())));
+    return (idx_vertex >= static_cast<VertexIndex>(0) &&
+            idx_vertex < static_cast<VertexIndex>(vertices_.size()));
   }
 
   /** \brief Check if the given half-edge index is a valid index into the mesh.  */
   inline bool
   isValid(const HalfEdgeIndex& idx_he) const
   {
-    return (idx_he >= HalfEdgeIndex(0) && idx_he < HalfEdgeIndex(half_edges_.size()));
+    return (idx_he >= static_cast<HalfEdgeIndex>(0) &&
+            idx_he < static_cast<HalfEdgeIndex>(half_edges_.size()));
   }
 
   /** \brief Check if the given edge index is a valid index into the mesh. */
   inline bool
   isValid(const EdgeIndex& idx_edge) const
   {
-    return (idx_edge >= EdgeIndex(0) && idx_edge < EdgeIndex(half_edges_.size() / 2));
+    return (idx_edge >= static_cast<EdgeIndex>(0) &&
+            idx_edge < static_cast<EdgeIndex>(half_edges_.size() / 2));
   }
 
   /** \brief Check if the given face index is a valid index into the mesh.  */
   inline bool
   isValid(const FaceIndex& idx_face) const
   {
-    return (idx_face >= FaceIndex(0) && idx_face < FaceIndex(faces_.size()));
+    return (idx_face >= static_cast<FaceIndex>(0) &&
+            idx_face < static_cast<FaceIndex>(faces_.size()));
   }
 
   ////////////////////////////////////////////////////////////////////////
@@ -727,7 +734,7 @@ public:
     return (this->isBoundary(this->getOutgoingHalfEdgeIndex(idx_vertex)));
   }
 
-  /** \brief Check if the given half-edge lies on the bounddary. */
+  /** \brief Check if the given half-edge lies on the boundary. */
   inline bool
   isBoundary(const HalfEdgeIndex& idx_he) const
   {
@@ -1088,7 +1095,7 @@ public:
              &vertex_data <= &vertex_data_cloud_.back());
       return (VertexIndex(std::distance(&vertex_data_cloud_.front(), &vertex_data)));
     }
-    return (VertexIndex());
+    return {};
   }
 
   /** \brief Get the index associated to the given half-edge data. */
@@ -1101,7 +1108,7 @@ public:
       return (HalfEdgeIndex(
           std::distance(&half_edge_data_cloud_.front(), &half_edge_data)));
     }
-    return (HalfEdgeIndex());
+    return {};
   }
 
   /** \brief Get the index associated to the given edge data. */
@@ -1113,7 +1120,7 @@ public:
              &edge_data <= &edge_data_cloud_.back());
       return (EdgeIndex(std::distance(&edge_data_cloud_.front(), &edge_data)));
     }
-    return (EdgeIndex());
+    return {};
   }
 
   /** \brief Get the index associated to the given face data. */
@@ -1125,7 +1132,7 @@ public:
              &face_data <= &face_data_cloud_.back());
       return (FaceIndex(std::distance(&face_data_cloud_.front(), &face_data)));
     }
-    return (FaceIndex());
+    return {};
   }
 
 protected:
@@ -1159,7 +1166,7 @@ protected:
   {
     const int n = static_cast<int>(vertices.size());
     if (n < 3)
-      return (FaceIndex());
+      return {};
 
     // Check for topological errors
     inner_he_.resize(n);
@@ -1172,7 +1179,7 @@ protected:
                                 inner_he_[i],
                                 is_new_[i],
                                 IsManifold())) {
-        return (FaceIndex());
+        return {};
       }
     }
     for (int i = 0; i < n; ++i) {
@@ -1185,7 +1192,7 @@ protected:
                                 make_adjacent_[i],
                                 free_he_[i],
                                 IsManifold())) {
-        return (FaceIndex());
+        return {};
       }
     }
 
@@ -1248,7 +1255,7 @@ protected:
     this->addData(half_edge_data_cloud_, he_data, HasHalfEdgeData());
     this->addData(edge_data_cloud_, edge_data, HasEdgeData());
 
-    return (HalfEdgeIndex(static_cast<int>(half_edges_.size() - 2)));
+    return (static_cast<HalfEdgeIndex>(half_edges_.size() - 2));
   }
 
   ////////////////////////////////////////////////////////////////////////
@@ -2167,7 +2174,7 @@ private:
   /** \brief Connectivity information for the faces. */
   Faces faces_;
 
-  // NOTE: It is MUCH faster to store these variables permamently.
+  // NOTE: It is MUCH faster to store these variables permanently.
 
   /** \brief Storage for addFaceImplBase and deleteFace. */
   HalfEdgeIndices inner_he_;
index 68125dad5a54fe33dfe2b495b70bdfea281e472c..227447afa53b14a6bd0098f6f6284f032dece1e2 100644 (file)
@@ -40,8 +40,8 @@
 
 #pragma once
 
-#include <pcl/PolygonMesh.h>
 #include <pcl/conversions.h>
+#include <pcl/PolygonMesh.h>
 
 namespace pcl {
 namespace geometry {
index e887e997b7f9a2af67889e0f82be19f00b602667..967bff362dde86743cf6fe216157ffd16b2c8b47 100644 (file)
@@ -101,7 +101,7 @@ protected:
   unsigned width_;
 
   /** \brief the index of the current pixel/point*/
-  unsigned index_;
+  unsigned index_{0};
 };
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -109,9 +109,7 @@ protected:
 ////////////////////////////////////////////////////////////////////////////////
 
 ////////////////////////////////////////////////////////////////////////////////
-inline OrganizedIndexIterator::OrganizedIndexIterator(unsigned width)
-: width_(width), index_(0)
-{}
+inline OrganizedIndexIterator::OrganizedIndexIterator(unsigned width) : width_(width) {}
 
 ////////////////////////////////////////////////////////////////////////////////
 inline OrganizedIndexIterator::~OrganizedIndexIterator() = default;
index fe3e9eb2ca52e0a21935df05a1f0a5651d8ab4ca..72728adaf55b8d55f87806dfbc64e3280b945480 100644 (file)
@@ -39,8 +39,8 @@
 
 #pragma once
 
-#include <pcl/ModelCoefficients.h>
 #include <pcl/memory.h>
+#include <pcl/ModelCoefficients.h>
 #include <pcl/pcl_macros.h>
 #include <pcl/point_cloud.h>
 
index 74384d5b5794031fe92f094b35fca1b2b75533df..f25120bafc03d2f49bff7b2b25510df67d2214c9 100644 (file)
@@ -25,6 +25,7 @@ get_filename_component(UTILS_INC "${CMAKE_CURRENT_SOURCE_DIR}/../utils/include"
 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)
 
 #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)
index 74dfcbe8a7033d87f1d09e0e4b6f0690476175aa..2930172ee9addcf9fef9459d64467207980c3749 100644 (file)
@@ -100,7 +100,7 @@ public:
   copyTo(DeviceArray& other) const;
 
   /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to
-   * ensure that intenal buffer size is enough.
+   * ensure that internal buffer size is enough.
    * \param host_ptr pointer to buffer to upload
    * \param size elements number
    * */
@@ -136,7 +136,7 @@ public:
            std::size_t num_elements) const;
 
   /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to
-   * ensure that intenal buffer size is enough.
+   * ensure that internal buffer size is enough.
    * \param data host vector to upload from
    * */
   template <class A>
@@ -238,7 +238,7 @@ public:
   copyTo(DeviceArray2D& other) const;
 
   /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to
-   * ensure that intenal buffer size is enough.
+   * ensure that internal buffer size is enough.
    * \param host_ptr pointer to host buffer to upload
    * \param host_step stride between two consecutive rows in bytes for host buffer
    * \param rows number of rows to upload
@@ -262,7 +262,7 @@ public:
   swap(DeviceArray2D& other_arg);
 
   /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to
-   * ensure that intenal buffer size is enough.
+   * ensure that internal buffer size is enough.
    * \param data host vector to upload from
    * \param cols stride in elements between two consecutive rows for host buffer
    * */
index 40f120024ed5c05545b524b4f0df7a6b0ea97ebc..5b23a652de40fe06a760d589603642cf286748c2 100644 (file)
@@ -97,7 +97,7 @@ public:
   copyTo(DeviceMemory& other) const;
 
   /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to
-   * ensure that intenal buffer size is enough.
+   * ensure that internal buffer size is enough.
    * \param host_ptr_arg pointer to buffer to upload
    * \param sizeBytes_arg buffer size
    * */
@@ -230,7 +230,7 @@ public:
   copyTo(DeviceMemory2D& other) const;
 
   /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to
-   * ensure that intenal buffer size is enough.
+   * ensure that internal buffer size is enough.
    * \param host_ptr_arg pointer to host buffer to upload
    * \param host_step_arg stride between two consecutive rows in bytes for host buffer
    * \param rows_arg number of rows to upload
index 348e27c12c11327617bd319b641cc8850bcd44ff..923b2326057afc557377f81ee4c1e761f0af089e 100644 (file)
@@ -26,6 +26,8 @@ main (int argc, char** argv)
   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>);
   pcl::PCDWriter writer;
   reader.read (argv[1], *cloud_filtered);
+  pcl::Indices unused;
+  pcl::removeNaNFromPointCloud(*cloud_filtered, *cloud_filtered, unused);
 
 /////////////////////////////////////////////
 /// CPU VERSION
@@ -81,7 +83,7 @@ main (int argc, char** argv)
   octree_device->build();
 
   std::vector<pcl::PointIndices> cluster_indices_gpu;
-  pcl::gpu::EuclideanClusterExtraction gec;
+  pcl::gpu::EuclideanClusterExtraction<pcl::PointXYZ> gec;
   gec.setClusterTolerance (0.02); // 2cm
   gec.setMinClusterSize (100);
   gec.setMaxClusterSize (25000);
index cefd88b6916bea124c3150ad01a66ba35642590d..5f356ef94dff12e7b9ca7802468cc1769501fbb5 100644 (file)
@@ -41,6 +41,8 @@
 #include <pcl/exceptions.h>
 #include <pcl/console/print.h>
 
+#include <cassert>
+
 using namespace pcl::device;
 
 /////////////////////////////////////////////////////////////////////////
@@ -101,6 +103,10 @@ void pcl::gpu::NormalEstimation::getViewPoint (float &vpx, float &vpy, float &vp
 void pcl::gpu::NormalEstimation::compute(Normals& normals)
 {
     assert(!cloud_.empty());
+    if (radius_ <= 0.0f || max_results_ <= 0) {
+        pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+        return;
+    }
 
     PointCloud& surface = surface_.empty() ? cloud_ : surface_;
 
@@ -143,6 +149,10 @@ void pcl::gpu::PFHEstimation::compute(const PointCloud& cloud, const Normals& no
 
 void pcl::gpu::PFHEstimation::compute(DeviceArray2D<PFHSignature125>& features)
 {
+    if (radius_ <= 0.0f || max_results_ <= 0) {
+        pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+        return;
+    }
     PointCloud& surface = surface_.empty() ? cloud_ : surface_;
 
     octree_.setCloud(surface);
@@ -181,6 +191,10 @@ void pcl::gpu::PFHRGBEstimation::compute(const PointCloud& cloud, const Normals&
 
 void pcl::gpu::PFHRGBEstimation::compute(DeviceArray2D<PFHRGBSignature250>& features)
 {
+    if (radius_ <= 0.0f || max_results_ <= 0) {
+        pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+        return;
+    }
     PointCloud& surface = surface_.empty() ? cloud_ : surface_;
 
     octree_.setCloud(surface);
@@ -229,6 +243,10 @@ void pcl::gpu::FPFHEstimation::compute(const PointCloud& cloud, const Normals& n
 
 void pcl::gpu::FPFHEstimation::compute(DeviceArray2D<FPFHSignature33>& features)
 {   
+    if (radius_ <= 0.0f || max_results_ <= 0) {
+        pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+        return;
+    }
     bool hasInds = !indices_.empty() && indices_.size() != cloud_.size();
     bool hasSurf = !surface_.empty();
 
@@ -312,6 +330,10 @@ void pcl::gpu::PPFRGBEstimation::compute(DeviceArray<PPFRGBSignature>& features)
 
 void pcl::gpu::PPFRGBRegionEstimation::compute(DeviceArray<PPFRGBSignature>& features)
 {
+    if (radius_ <= 0.0f || max_results_ <= 0) {
+        pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__);
+        return;
+    }
     static_assert(sizeof(PPFRGBRegionEstimation:: PointType) == sizeof(device:: PointType), "Point sizes do not match");
     static_assert(sizeof(PPFRGBRegionEstimation::NormalType) == sizeof(device::NormalType), "Normal sizes do not match");
 
index 29cb73e955ac45060e7d24a67ee5420f8bea502f..fbbd294fdbc2317002aa0ecba3e770d146ed84ee 100644 (file)
@@ -2,7 +2,12 @@ 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(DEFAULT TRUE)
+if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0")
+  set(DEFAULT FALSE)
+  set(REASON "Kinfu 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})
index 7e24a9acf1499685774185c092bfc76ffdd0f52b..8723245f3510ed6947e59a147eeaa8f254d566c8 100644 (file)
@@ -121,7 +121,7 @@ namespace pcl
         void
         setIcpCorespFilteringParams (float distThreshold, float sineOfAngle);
         
-        /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceedes the threshold value. 
+        /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceeds the threshold value. 
           * The metric represents the following: M = (rodrigues(Rotation).norm() + alpha*translation.norm())/2, where alpha = 1.f (hardcoded constant)
           * \param[in] threshold a value to compare with the metric. Suitable values are ~0.001          
           */
@@ -278,7 +278,7 @@ namespace pcl
         /** \brief Array of camera translations for each moment of time. */
         std::vector<Vector3f> tvecs_;
 
-        /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceedes some value. */
+        /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceeds some value. */
         float integration_metric_threshold_;
 
         /** \brief ICP step is completely disabled. Only integration now. */
index 7610bf89dd45fe4062c6389bdca4f49f4b32d1cc..9f4e31955242fb32732c306a313def2de19addc5 100644 (file)
@@ -86,14 +86,9 @@ namespace pcl
         int x = threadIdx.x + blockIdx.x * CTA_SIZE_X;
         int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y;
        
-#if CUDART_VERSION >= 9000
         if (__all_sync (__activemask (), x >= VOLUME_X)
             || __all_sync (__activemask (), y >= VOLUME_Y))
           return;
-#else 
-        if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y))
-          return;
-#endif
 
         float3 V;
         V.x = (x + 0.5f) * cell_size.x;
@@ -183,14 +178,9 @@ namespace pcl
             }              /* if (W != 0 && F != 1.f) */
           }            /* if (x < VOLUME_X && y < VOLUME_Y) */
 
-#if CUDART_VERSION >= 9000
           int total_warp = __popc (__ballot_sync (__activemask (), local_count > 0))
                          + __popc (__ballot_sync (__activemask (), local_count > 1))
                          + __popc (__ballot_sync (__activemask (), local_count > 2));
-#else
-          ///not we fulfilled points array at current iteration
-          int total_warp = __popc (__ballot (local_count > 0)) + __popc (__ballot (local_count > 1)) + __popc (__ballot (local_count > 2));
-#endif
 
           if (total_warp > 0)
           {
index ca4d10225d9efb26627d2d78c715bde01bdefc62..127f0509e284f6c2a2ff16698d5d231be8bde8a7 100644 (file)
@@ -138,14 +138,9 @@ namespace pcl
         int x = threadIdx.x + blockIdx.x * CTA_SIZE_X;
         int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y;
 
-#if CUDART_VERSION >= 9000
         if (__all_sync (__activemask (), x >= VOLUME_X)
             || __all_sync (__activemask (), y >= VOLUME_Y))
           return;
-#else
-        if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y))
-          return;
-#endif
 
         int ftid = Block::flattenedThreadId ();
                int warp_id = Warp::id();
@@ -164,11 +159,8 @@ namespace pcl
             // read number of vertices from texture
             numVerts = (cubeindex == 0 || cubeindex == 255) ? 0 : tex1Dfetch (numVertsTex, cubeindex);
           }
-#if CUDART_VERSION >= 9000
+
           int total = __popc (__ballot_sync (__activemask (), numVerts > 0));
-#else
-          int total = __popc (__ballot (numVerts > 0));
-#endif
                  if (total == 0)
                        continue;
 
@@ -179,11 +171,7 @@ namespace pcl
           }
           int old_global_voxels_count = warps_buffer[warp_id];
 
-#if CUDART_VERSION >= 9000
           int offs = Warp::binaryExclScan (__ballot_sync (__activemask (), numVerts > 0));
-#else
-          int offs = Warp::binaryExclScan (__ballot (numVerts > 0));
-#endif
 
           if (old_global_voxels_count + offs < max_size && numVerts > 0)
           {
index daf34652c516f185f1b84e90073bff8a507ef18f..535689f927bb448c4a1ed13bdf3b9ca0ff59f9be 100644 (file)
@@ -251,7 +251,7 @@ namespace pcl
     integrateTsdfVolume (const PtrStepSz<ushort>& depth_raw, const Intr& intr, const float3& volume_size, 
                          const Mat33& Rcurr_inv, const float3& tcurr, float tranc_dist, PtrStep<short2> volume, DeviceArray2D<float>& depthRawScaled);
     
-    /** \brief Initialzied color volume
+    /** \brief Initialized color volume
       * \param[out] color_volume color volume for initialization
       */
 
@@ -352,7 +352,7 @@ namespace pcl
     void 
     extractNormals (const PtrStep<short2>& volume, const float3& volume_size, const PtrSz<PointType>& input, NormalType* output);
 
-    /** \brief Performs colors exctraction from color volume
+    /** \brief Performs colors extraction from color volume
       * \param[in] color_volume color volume
       * \param[in] volume_size volume size
       * \param[in] points points for which color are computed
index 552a1f588f404678c84825b7114287ffda068c95..5af84fb5b65f87bbd9b6a43ae3a924cd3bde0af1 100644 (file)
@@ -72,7 +72,7 @@ public:
   bool grab (double stamp, pcl::gpu::PtrStepSz<const unsigned short>& depth);
 
   /** \brief Reads depth & rgb frame from the folder. Before calling this folder please call 'setMatchFile', or an error will be returned otherwise.
-    * \param stamp index of accociated frame pair (stamps are not implemented)
+    * \param stamp index of associated frame pair (stamps are not implemented)
     * \param depth
     * \param rgb24
     */
index 84d05ed2cc470eba6106576b6425dad74c890224..ffdb154ffaa336f59c3a36d27b94d41e675082d0 100644 (file)
@@ -44,7 +44,6 @@
 #include <pcl/console/parse.h>
 
 #include <boost/filesystem.hpp>
-#include <boost/date_time/posix_time/posix_time.hpp> // for microsec_clock::local_time
 
 #include <pcl/gpu/kinfu/kinfu.h>
 #include <pcl/gpu/kinfu/raycaster.h>
@@ -187,7 +186,7 @@ std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 
   for(; pos != end ; ++pos)
     if (fs::is_regular_file(pos->status()) )
-      if (fs::extension(*pos) == ".pcd")
+      if (pos->path().extension().string() == ".pcd")
       {
         result.push_back (pos->path ().string ());
         std::cout << "added: " << result.back() << std::endl;
@@ -201,24 +200,24 @@ std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 struct SampledScopeTime : public StopWatch
 {          
   enum { EACH = 33 };
-  SampledScopeTime(int& time_ms) : time_ms_(time_ms) {}
+  SampledScopeTime(double& time_s) : time_s_(time_s) {}
   ~SampledScopeTime()
   {
     static int i_ = 0;
-    static boost::posix_time::ptime starttime_ = boost::posix_time::microsec_clock::local_time();
-    time_ms_ += getTime ();
+    static double starttime_ = pcl::getTime();
+    time_s_ += getTime ();
     if (i_ % EACH == 0 && i_)
     {
-      boost::posix_time::ptime endtime_ = boost::posix_time::microsec_clock::local_time();
-      std::cout << "Average frame time = " << time_ms_ / EACH << "ms ( " << 1000.f * EACH / time_ms_ << "fps )"
-           << "( real: " << 1000.f * EACH / (endtime_-starttime_).total_milliseconds() << "fps )"  << std::endl;
-      time_ms_ = 0;
+      const auto endtime_ = pcl::getTime();
+      std::cout << "Average frame time = " << time_s_ / EACH << "ms ( " << EACH / time_s_ << "fps )"
+           << "( real: " <<EACH / (endtime_-starttime_) << "fps )"  << std::endl;
+      time_s_ = 0;
       starttime_ = endtime_;
     }
     ++i_;
   }
 private:    
-  int& time_ms_;
+  double& time_s_;
 };
 
 ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -567,9 +566,9 @@ struct SceneCloudView
 
     switch (extraction_mode_)
     {
-    case 0: std::cout << "Cloud exctraction mode: GPU, Connected-6" << std::endl; break;
-    case 1: std::cout << "Cloud exctraction mode: CPU, Connected-6    (requires a lot of memory)" << std::endl; break;
-    case 2: std::cout << "Cloud exctraction mode: CPU, Connected-26   (requires a lot of memory)" << std::endl; break;
+    case 0: std::cout << "Cloud extraction mode: GPU, Connected-6" << std::endl; break;
+    case 1: std::cout << "Cloud extraction mode: CPU, Connected-6    (requires a lot of memory)" << std::endl; break;
+    case 2: std::cout << "Cloud extraction mode: CPU, Connected-26   (requires a lot of memory)" << std::endl; break;
     }
     ;
   }
@@ -651,7 +650,7 @@ struct KinFuApp
   enum { PCD_BIN = 1, PCD_ASCII = 2, PLY = 3, MESH_PLY = 7, MESH_VTK = 8 };
   
   KinFuApp(pcl::Grabber& source, float vsz, int icp, int viz, CameraPoseProcessor::Ptr pose_processor=CameraPoseProcessor::Ptr () ) : exit_ (false), scan_ (false), scan_mesh_(false), scan_volume_ (false), independent_camera_ (false),
-      registration_ (false), integrate_colors_ (false), pcd_source_ (false), focal_length_(-1.f), capture_ (source), scene_cloud_view_(viz), image_view_(viz), time_ms_(0), icp_(icp), viz_(viz), pose_processor_ (pose_processor)
+      registration_ (false), integrate_colors_ (false), pcd_source_ (false), focal_length_(-1.f), capture_ (source), scene_cloud_view_(viz), image_view_(viz), time_s_(0), icp_(icp), viz_(viz), pose_processor_ (pose_processor)
   {    
     //Init Kinfu Tracker
     Eigen::Vector3f volume_size = Vector3f::Constant (vsz/*meters*/);    
@@ -732,7 +731,7 @@ struct KinFuApp
   {
     if(registration_)
     {
-      const int max_color_integration_weight = 2;
+      constexpr int max_color_integration_weight = 2;
       kinfu_.initColorIntegration(max_color_integration_weight);
       integrate_colors_ = true;      
     }    
@@ -775,7 +774,7 @@ struct KinFuApp
           image_view_.colors_device_.upload (rgb24.data, rgb24.step, rgb24.rows, rgb24.cols);
     
       {
-        SampledScopeTime fps(time_ms_);
+        SampledScopeTime fps(time_s_);
     
         //run kinfu algorithm
         if (integrate_colors_)
@@ -1073,8 +1072,8 @@ struct KinFuApp
     std::cout << "   Esc   : exit" << std::endl;
     std::cout << "    T    : take cloud" << std::endl;
     std::cout << "    A    : take mesh" << std::endl;
-    std::cout << "    M    : toggle cloud exctraction mode" << std::endl;
-    std::cout << "    N    : toggle normals exctraction" << std::endl;
+    std::cout << "    M    : toggle cloud extraction mode" << std::endl;
+    std::cout << "    N    : toggle normals extraction" << std::endl;
     std::cout << "    I    : toggle independent camera mode" << std::endl;
     std::cout << "    B    : toggle volume bounds" << std::endl;
     std::cout << "    *    : toggle scene view painting ( requires registration mode )" << std::endl;
@@ -1119,7 +1118,7 @@ struct KinFuApp
   PtrStepSz<const unsigned short> depth_;
   PtrStepSz<const KinfuTracker::PixelRGB> rgb24_;
 
-  int time_ms_;
+  double time_s_;
   int icp_, viz_;
 
   CameraPoseProcessor::Ptr pose_processor_;
index 1591c199846ec0311d83389bd120d4e656a75071..383ecb83758ca19608127fcbf6a774b9243ab43b 100644 (file)
@@ -807,9 +807,9 @@ struct SceneCloudView
 
     switch (extraction_mode_)
     {
-    case 0: std::cout << "Cloud exctraction mode: GPU, Connected-6" << std::endl; break;
-    case 1: std::cout << "Cloud exctraction mode: CPU, Connected-6    (requires a lot of memory)" << std::endl; break;
-    case 2: std::cout << "Cloud exctraction mode: CPU, Connected-26   (requires a lot of memory)" << std::endl; break;
+    case 0: std::cout << "Cloud extraction mode: GPU, Connected-6" << std::endl; break;
+    case 1: std::cout << "Cloud extraction mode: CPU, Connected-6    (requires a lot of memory)" << std::endl; break;
+    case 2: std::cout << "Cloud extraction mode: CPU, Connected-26   (requires a lot of memory)" << std::endl; break;
     }
     ;
   }
@@ -1217,8 +1217,8 @@ struct KinFuApp
     std::cout << "   Esc   : exit" << std::endl;
     std::cout << "    T    : take cloud" << std::endl;
     std::cout << "    A    : take mesh" << std::endl;
-    std::cout << "    M    : toggle cloud exctraction mode" << std::endl;
-    std::cout << "    N    : toggle normals exctraction" << std::endl;
+    std::cout << "    M    : toggle cloud extraction mode" << std::endl;
+    std::cout << "    N    : toggle normals extraction" << std::endl;
     std::cout << "    I    : toggle independent camera mode" << std::endl;
     std::cout << "    B    : toggle volume bounds" << std::endl;
     std::cout << "    *    : toggle scene view painting ( requires registration mode )" << std::endl;
index 4df0dce1a235d17a17385e7ae0025ba8b35bc9fa..213dd8d2d496f4826a1fd25cd1e19988ef1781d9 100644 (file)
@@ -68,7 +68,7 @@ end
 end
 
 function R=q2rot(q)
-% conversion code from http://en.wikipedia.org/wiki/Rotation_matrix%Quaternion 
+% conversion code from https://en.wikipedia.org/wiki/Rotation_matrix%Quaternion        
 Nq = q(1)^2 + q(2)^2 + q(3)^2 + q(4)^2;
 if Nq>0; s=2/Nq; else s=0; end
 X = q(2)*s; Y = q(3)*s; Z = q(4)*s;
index 07878994a8b514e98ce82bef1711ba3babc48e46..873111eb2aca6e72d46027472271fede4a798aed 100644 (file)
@@ -97,7 +97,7 @@ public:
 
   /** \brief Creates the TSDF volume on the GPU
    * param[in] depth depth readings from the sensor
-   * param[in] intr camaera intrinsics
+   * param[in] intr camera intrinsics
    */
   void
   createFromDepth (const pcl::device::PtrStepSz<const unsigned short> &depth, const pcl::device::Intr &intr);
@@ -138,8 +138,8 @@ DeviceVolume::createFromDepth (const pcl::device::PtrStepSz<const unsigned short
 
   using Matrix3frm = Eigen::Matrix<float, 3, 3, Eigen::RowMajor>;
 
-  const int rows = 480;
-  const int cols = 640;
+  constexpr int rows = 480;
+  constexpr int cols = 640;
 
   // scale depth values
   gpu::DeviceArray2D<float> device_depth_scaled;
@@ -197,7 +197,7 @@ DeviceVolume::getVolume (pcl::TSDFVolume<VoxelT, WeightT>::Ptr &volume)
 bool
 DeviceVolume::getCloud (pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud)
 {
-  const int DEFAULT_VOLUME_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000;
+  constexpr int DEFAULT_VOLUME_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000;
 
   // point buffer on the device
   pcl::gpu::DeviceArray<pcl::PointXYZ> device_cloud_buffer (DEFAULT_VOLUME_CLOUD_BUFFER_SIZE);
index 5b700d6e6573e8e1656898adfad87eb01d8429d9..6820749b7d3224d0b0eee83a24f2339c5edf7f1b 100644 (file)
@@ -237,7 +237,7 @@ public:
   //  void
   //  convertToCloud (pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud) const;
 
-    /** \brief Crate Volume from Point Cloud */
+    /** \brief Create Volume from Point Cloud */
   //   template <typename PointT> void
   //   createFromCloud (const typename pcl::PointCloud<PointT>::ConstPtr &cloud, const Intr &intr);
 
index d7efc4ad5aaef6f6e806471e3900643898b9481f..0488fcb46aaf1ca23fa447139dc467f974f37924 100644 (file)
@@ -2,7 +2,12 @@ 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(DEFAULT TRUE)
+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")
+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})
index 6c8f1f359f5bf63e8f55eca6da4723b57d9b40e8..dd114fd47f7c28fb2c2df196370eee275050fe5c 100644 (file)
@@ -125,7 +125,7 @@ namespace pcl
           void
           setIcpCorespFilteringParams (float distThreshold, float sineOfAngle);
           
-          /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceedes the threshold value. 
+          /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceeds the threshold value. 
             * The metric represents the following: M = (rodrigues(Rotation).norm() + alpha*translation.norm())/2, where alpha = 1.f (hardcoded constant)
             * \param[in] threshold a value to compare with the metric. Suitable values are ~0.001          
             */
@@ -421,7 +421,7 @@ namespace pcl
           /** \brief Array of camera translations for each moment of time. */
           std::vector<Vector3f> tvecs_;
 
-          /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceedes some value. */
+          /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceeds some value. */
           float integration_metric_threshold_;          
                   
           /** \brief When set to true, KinFu will extract the whole world and mesh it. */
index 97e1f6098a0ef77bc2c4eba6f0f6731a732beef9..6880239de8927584665e4332db98eefeeb5bfc3f 100644 (file)
@@ -47,7 +47,7 @@
 struct EIGEN_ALIGN16 PointIntensity
 {
 
-  PCL_MAKE_ALIGNED_OPERATOR_NEW;
+  PCL_MAKE_ALIGNED_OPERATOR_NEW
   union
   {
     struct
index 4707dd897b72a4e80d2dc97d7fc5628e2af87aa9..d7db4bedeeb2283a26a9865bcd706404c1d8a6fb 100644 (file)
@@ -104,14 +104,9 @@ namespace pcl
           int x = threadIdx.x + blockIdx.x * CTA_SIZE_X;
           int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y;
 
-  #if CUDART_VERSION >= 9000
           if (__all_sync (__activemask (), x >= VOLUME_X)
               || __all_sync (__activemask (), y >= VOLUME_Y))
             return;
-  #else
-          if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y))
-            return;
-  #endif
 
           float3 V;
           V.x = (x + 0.5f) * cell_size.x;
@@ -201,15 +196,9 @@ namespace pcl
               }/* if (W != 0 && F != 1.f) */
             }/* if (x < VOLUME_X && y < VOLUME_Y) */
 
-
-  #if CUDART_VERSION >= 9000
             int total_warp = __popc (__ballot_sync (__activemask (), local_count > 0))
                            + __popc (__ballot_sync (__activemask (), local_count > 1))
                            + __popc (__ballot_sync (__activemask (), local_count > 2));
-  #else
-            //not we fulfilled points array at current iteration
-            int total_warp = __popc (__ballot (local_count > 0)) + __popc (__ballot (local_count > 1)) + __popc (__ballot (local_count > 2));
-  #endif
 
             if (total_warp > 0)
             {
@@ -312,15 +301,9 @@ namespace pcl
 
             // local_count counts the number of zero crossing for the current thread. Now we need to merge this knowledge with the other threads
             // not we fulfilled points array at current iteration
-          #if CUDART_VERSION >= 9000
             int total_warp = __popc (__ballot_sync (__activemask (), local_count > 0))
                            + __popc (__ballot_sync (__activemask (), local_count > 1))
                            + __popc (__ballot_sync (__activemask (), local_count > 2));
-          #else
-            int total_warp = __popc (__ballot (local_count > 0))
-                           + __popc (__ballot (local_count > 1))
-                           + __popc (__ballot (local_count > 2));
-          #endif
 
             if (total_warp > 0)  ///more than 0 zero-crossings
             {
index 3e89b4e03e049b9ea51e052a9beba7377bdefdbf..b1c12de5c3c5072673bc880f2a51fa839de23105 100644 (file)
@@ -146,14 +146,9 @@ namespace pcl
           int x = threadIdx.x + blockIdx.x * CTA_SIZE_X;
           int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y;
 
-        #if CUDART_VERSION >= 9000
           if (__all_sync (__activemask (), x >= VOLUME_X)
               || __all_sync (__activemask (), y >= VOLUME_Y))
             return;
-        #else
-          if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y))
-            return;
-        #endif
 
           int ftid = Block::flattenedThreadId ();
                   int warp_id = Warp::id();
@@ -173,11 +168,7 @@ namespace pcl
               numVerts = (cubeindex == 0 || cubeindex == 255) ? 0 : tex1Dfetch (numVertsTex, cubeindex);
             }
 
-          #if CUDART_VERSION >= 9000
             int total = __popc (__ballot_sync (__activemask (), numVerts > 0));
-          #else
-            int total = __popc (__ballot (numVerts > 0));
-          #endif
                     if (total == 0)
                           continue;
 
@@ -187,12 +178,7 @@ namespace pcl
               warps_buffer[warp_id] = old;
             }
             int old_global_voxels_count = warps_buffer[warp_id];
-
-          #if CUDART_VERSION >= 9000
             int offs = Warp::binaryExclScan (__ballot_sync (__activemask (), numVerts > 0));
-          #else
-            int offs = Warp::binaryExclScan (__ballot (numVerts > 0));
-          #endif
 
             if (old_global_voxels_count + offs < max_size && numVerts > 0)
             {
index 745eb56cfc8bb3ab11888b066f8e9e3f969d0d2f..7d1accb5bb8654be249c8d027bf128f21b9d3b8b 100644 (file)
@@ -108,7 +108,7 @@ pcl::gpu::kinfuLS::CyclicalBuffer::performShift (const TsdfVolume::Ptr volume, c
 
   // Retrieving intensities
   // TODO change this mechanism by using PointIntensity directly (in spite of float)
-  // when tried, this lead to wrong intenisty values being extracted by fetchSliceAsCloud () (padding pbls?)
+  // when tried, this lead to wrong intensity values being extracted by fetchSliceAsCloud () (padding pbls?)
   std::vector<float , Eigen::aligned_allocator<float> > intensities_vector;
   intensities.download (intensities_vector);
   current_slice_intensities->resize (current_slice_xyz->size ());
index b5e5673a59fe976a40ab303215e0680ef8b7523d..c46ffa1c0eafe175919070072ce0ef8f2bd0e95c 100644 (file)
@@ -240,7 +240,7 @@ namespace pcl
       PCL_EXPORTS void 
       clearTSDFSlice (PtrStep<short2> volume, pcl::gpu::kinfuLS::tsdf_buffer* buffer, int shiftX, int shiftY, int shiftZ);
       
-      /** \brief Initialzied color volume
+      /** \brief Initialized color volume
         * \param[out] color_volume color volume for initialization
         */
       void 
@@ -366,7 +366,7 @@ namespace pcl
       void 
       extractNormals (const PtrStep<short2>& volume, const float3& volume_size, const PtrSz<PointType>& input, NormalType* output);
 
-      /** \brief Performs colors exctraction from color volume
+      /** \brief Performs colors extraction from color volume
         * \param[in] color_volume color volume
         * \param[in] volume_size volume size
         * \param[in] points points for which color are computed
index b4fa69a270303d39fa881db11773348220dea41e..8b2252a2ccfe3d0133099ee762df2b7dc5566e32 100644 (file)
@@ -72,7 +72,7 @@ public:
   bool grab (double stamp, pcl::gpu::PtrStepSz<const unsigned short>& depth);
 
   /** \brief Reads depth & rgb frame from the folder. Before calling this folder please call 'setMatchFile', or an error will be returned otherwise.
-    * \param stamp index of accociated frame pair (stamps are not implemented)
+    * \param stamp index of associated frame pair (stamps are not implemented)
     * \param depth
     * \param rgb24
     */
index d96b6171de3138c5d4bc70faee0a5dac0694e01b..28278195e422ddeffaebf7aa9033dd1316da9b97 100644 (file)
@@ -56,7 +56,6 @@ Work in progress: patch by Marco (AUG,19th 2012)
 #include <pcl/console/parse.h>
 
 #include <boost/filesystem.hpp>
-#include <boost/date_time/posix_time/posix_time.hpp> // for microsec_clock::local_time
 
 #include <pcl/gpu/kinfu_large_scale/kinfu.h>
 #include <pcl/gpu/kinfu_large_scale/raycaster.h>
@@ -137,7 +136,7 @@ std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 
   for(; pos != end ; ++pos)
     if (fs::is_regular_file(pos->status()) )
-      if (fs::extension(*pos) == ".pcd")
+      if (pos->path().extension().string() == ".pcd")
       {
         result.push_back (pos->path ().string ());
         std::cout << "added: " << result.back() << std::endl;
@@ -151,24 +150,24 @@ std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 struct SampledScopeTime : public StopWatch
 {          
   enum { EACH = 33 };
-  SampledScopeTime(int& time_ms) : time_ms_(time_ms) {}
+  SampledScopeTime(double& time_s) : time_s_(time_s) {}
   ~SampledScopeTime()
   {
     static int i_ = 0;
-    static boost::posix_time::ptime starttime_ = boost::posix_time::microsec_clock::local_time();
-    time_ms_ += getTime ();
+    static double starttime_ = pcl::getTime();
+    time_s_ += getTime ();
     if (i_ % EACH == 0 && i_)
     {
-      boost::posix_time::ptime endtime_ = boost::posix_time::microsec_clock::local_time();
-      std::cout << "Average frame time = " << time_ms_ / EACH << "ms ( " << 1000.f * EACH / time_ms_ << "fps )"
-           << "( real: " << 1000.f * EACH / (endtime_-starttime_).total_milliseconds() << "fps )"  << std::endl;
-      time_ms_ = 0;
+      const auto endtime_ = pcl::getTime();
+      std::cout << "Average frame time = " << time_s_ / EACH << "ms ( " << EACH / time_s_ << "fps )"
+           << "( real: " << EACH / (endtime_-starttime_) << "fps )"  << std::endl;
+      time_s_ = 0;
       starttime_ = endtime_;
     }
     ++i_;
   }
 private:    
-  int& time_ms_;    
+  double& time_s_;    
 };
 
 ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -701,7 +700,7 @@ struct KinFuLSApp
   enum { PCD_BIN = 1, PCD_ASCII = 2, PLY = 3, MESH_PLY = 7, MESH_VTK = 8 };
 
   KinFuLSApp(pcl::Grabber& source, float vsz, float shiftDistance, int snapshotRate) : exit_ (false), scan_ (false), scan_mesh_(false), scan_volume_ (false), independent_camera_ (false),
-          registration_ (false), integrate_colors_ (false), pcd_source_ (false), focal_length_(-1.f), capture_ (source), was_lost_(false), time_ms_ (0)
+          registration_ (false), integrate_colors_ (false), pcd_source_ (false), focal_length_(-1.f), capture_ (source), was_lost_(false), time_s_ (0)
   {    
     //Init Kinfu Tracker
     Eigen::Vector3f volume_size = Vector3f::Constant (vsz/*meters*/);    
@@ -790,7 +789,7 @@ struct KinFuLSApp
   {
     if(registration_)
     {
-      const int max_color_integration_weight = 2;
+      constexpr int max_color_integration_weight = 2;
       kinfu_->initColorIntegration(max_color_integration_weight);
       integrate_colors_ = true;      
     }    
@@ -829,7 +828,7 @@ struct KinFuLSApp
         image_view_.colors_device_.upload (rgb24.data, rgb24.step, rgb24.rows, rgb24.cols);
 
       {
-        SampledScopeTime fps(time_ms_);
+        SampledScopeTime fps(time_s_);
 
         //run kinfu algorithm
         if (integrate_colors_)
@@ -1143,8 +1142,8 @@ struct KinFuLSApp
     std::cout << "   Esc   : exit" << std::endl;
     std::cout << "    T    : take cloud" << std::endl;
     std::cout << "    A    : take mesh" << std::endl;
-    std::cout << "    M    : toggle cloud exctraction mode" << std::endl;
-    std::cout << "    N    : toggle normals exctraction" << std::endl;
+    std::cout << "    M    : toggle cloud extraction mode" << std::endl;
+    std::cout << "    N    : toggle normals extraction" << std::endl;
     std::cout << "    I    : toggle independent camera mode" << std::endl;
     std::cout << "    B    : toggle volume bounds" << std::endl;
     std::cout << "    *    : toggle scene view painting ( requires registration mode )" << std::endl;
@@ -1198,7 +1197,7 @@ struct KinFuLSApp
   
   bool was_lost_;
 
-  int time_ms_;
+  double time_s_;
 
   /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
   static void
index c333b26994196d59285c28050ed7eb5dcf92cdc8..b1ff4f56b9911d3bafa8209f0e7e09d20b1ad352 100644 (file)
@@ -801,9 +801,9 @@ struct SceneCloudView
 
     switch (extraction_mode_)
     {
-    case 0: std::cout << "Cloud exctraction mode: GPU, Connected-6" << std::endl; break;
-    case 1: std::cout << "Cloud exctraction mode: CPU, Connected-6    (requires a lot of memory)" << std::endl; break;
-    case 2: std::cout << "Cloud exctraction mode: CPU, Connected-26   (requires a lot of memory)" << std::endl; break;
+    case 0: std::cout << "Cloud extraction mode: GPU, Connected-6" << std::endl; break;
+    case 1: std::cout << "Cloud extraction mode: CPU, Connected-6    (requires a lot of memory)" << std::endl; break;
+    case 2: std::cout << "Cloud extraction mode: CPU, Connected-26   (requires a lot of memory)" << std::endl; break;
     }
     ;
   }
@@ -1240,8 +1240,8 @@ struct KinFuApp
     std::cout << "   Esc   : exit" << std::endl;
     std::cout << "    T    : take cloud" << std::endl;
     std::cout << "    A    : take mesh" << std::endl;
-    std::cout << "    M    : toggle cloud exctraction mode" << std::endl;
-    std::cout << "    N    : toggle normals exctraction" << std::endl;
+    std::cout << "    M    : toggle cloud extraction mode" << std::endl;
+    std::cout << "    N    : toggle normals extraction" << std::endl;
     std::cout << "    I    : toggle independent camera mode" << std::endl;
     std::cout << "    B    : toggle volume bounds" << std::endl;
     std::cout << "    *    : toggle scene view painting ( requires registration mode )" << std::endl;
index 0620a84ca7f2221c92a07fc985da9a3955efc86f..ec9263cc0fdc2baee3b6662d46aaf26bc17510cc 100644 (file)
@@ -90,7 +90,7 @@ main (int argc, char** argv)
     std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > transforms;
   
     //Get world as a vector of cubes 
-    wm.getWorldAsCubes (pcl::device::kinfuLS::VOLUME_X, clouds, transforms, 0.025); // 2.5% overlapp (12 cells with a 512-wide cube)
+    wm.getWorldAsCubes (pcl::device::kinfuLS::VOLUME_X, clouds, transforms, 0.025); // 2.5% overlap (12 cells with a 512-wide cube)
 
     //Creating the standalone marching cubes instance
     float volume_size = pcl::device::kinfuLS::VOLUME_SIZE;
index 483c38c91958a8745cfc4addb6804aba03681e2c..60addb9839c77b7f00cf26333050249b4d7f376f 100644 (file)
@@ -71,7 +71,7 @@ do \
 bool is_done = false;
 std::mutex io_mutex;
 
-const int BUFFER_SIZE = 1000;
+constexpr int BUFFER_SIZE = 1000;
 static int counter = 1;
 //////////////////////////////////////////////////////////////////////////////////////////
 class MapsBuffer
@@ -254,7 +254,7 @@ grabberMapsCallBack(const openni_wrapper::Image::Ptr& image_wrapper, const openn
 
 
 //////////////////////////////////////////////////////////////////////////////////////////
-// Procuder thread function
+// Producer thread function
 void 
 grabAndSend ()
 {
index b88550a8551c2048044b82f18a657935d8a7b466..575108a4ebd2dc6a5be4141b00d86b3e11fea543 100644 (file)
@@ -95,7 +95,7 @@ public:
 
   /** \brief Creates the TSDF volume on the GPU
    * param[in] depth depth readings from the sensor
-   * param[in] intr camaera intrinsics
+   * param[in] intr camera intrinsics
    */
   void
   createFromDepth (const pcl::device::PtrStepSz<const unsigned short> &depth, const pcl::device::Intr &intr);
index 657927043c15adfa403d17038f6d85c14e1401ef..6803bba3e3db0947dc324ea8d3dcd4612bfa438f 100644 (file)
@@ -48,6 +48,7 @@
 #include <pcl/visualization/pcl_visualizer.h>
 #include <pcl/surface/texture_mapping.h>
 #include <pcl/io/vtk_lib_io.h>
+#include <pcl/io/ply_io.h>
 
 using namespace pcl;
 
@@ -405,7 +406,7 @@ main (int argc, char** argv)
   // read mesh from plyfile
   PCL_INFO ("\nLoading mesh from file %s...\n", argv[1]);
   pcl::PolygonMesh triangles;
-  pcl::io::loadPolygonFilePLY(argv[1], triangles);
+  pcl::io::loadPLYFile(argv[1], triangles);
 
   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
   pcl::fromPCLPointCloud2(triangles.cloud, *cloud);
@@ -435,11 +436,11 @@ main (int argc, char** argv)
   std::string extension (".txt");
   for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it)
   {
-    if(boost::filesystem::is_regular_file (it->status ()) && boost::filesystem::extension (it->path ()) == extension)
+    if(boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension)
     {
       pcl::TextureMapping<pcl::PointXYZ>::Camera cam;
       readCamPoseFile(it->path ().string (), cam);
-      cam.texture_file = boost::filesystem::basename (it->path ()) + ".png";
+      cam.texture_file = it->path ().stem ().string () + ".png";
       my_cams.push_back (cam);
     }
   }
index 9f645f348e8be8dd7464d6461c66e83b80b93951..5e222a5c38ce3fb4a7d9f0eeb167a8a2a7580bd9 100644 (file)
@@ -51,7 +51,7 @@ namespace pcl
     namespace gpu
     {   
         /**
-         * \brief   Octree implementation on GPU. It suppors parallel building and parallel batch search as well .       
+         * \brief   Octree implementation on GPU. It supports parallel building and parallel batch search as well .       
          * \author  Anaoly Baksheev, Itseez, myname.mysurname@mycompany.com
          */
 
@@ -142,13 +142,6 @@ namespace pcl
               */
             void radiusSearch(const Queries& centers, const Indices& indices, float radius, int max_results, NeighborIndices& result) const;
 
-            /** \brief Batch approximate nearest search on GPU
-              * \param[in] queries array of centers
-              * \param[out] result array of results ( one index for each query ) 
-              */
-            PCL_DEPRECATED(1, 14, "use approxNearestSearch() which returns square distances instead")
-            void approxNearestSearch(const Queries& queries, NeighborIndices& result) const;
-
             /** \brief Batch approximate nearest search on GPU
               * \param[in] queries array of centers
               * \param[out] result array of results ( one index for each query )
index 4537179fbd49a1d1c87d3dab03a6a34b4031c0c4..63a7e7383608a15a759ccc2314b5bf0364710931 100644 (file)
@@ -168,12 +168,6 @@ void pcl::gpu::Octree::radiusSearch(const Queries& queries, const Indices& indic
     static_cast<OctreeImpl*>(impl)->radiusSearch(q, indices, radius, results);
 }
 
-void pcl::gpu::Octree::approxNearestSearch(const Queries& queries, NeighborIndices& results) const
-{
-    ResultSqrDists sqr_distance;
-    approxNearestSearch(queries, results, sqr_distance);
-}
-
 void pcl::gpu::Octree::approxNearestSearch(const Queries& queries, NeighborIndices& results, ResultSqrDists& sqr_distance) const
 {
     assert(queries.size() > 0);    
index de0858948b1fdeab415a9d892310c64d28df2674..9aef9a67039fb17eb2a2a5095e5fc8dc91d08e27 100644 (file)
@@ -53,7 +53,7 @@ namespace pcl
       namespace trees
       {
         // this has nothing to do here...
-        static const double focal = 1000.;
+        constexpr double focal = 1000.;
 
         // ###############################################
         // compile type values
index 8d0eb888b147f947c034868c371f1fabd550be5c..3cf271bcbbdceafe85c2f2708ec6e7db9e0557ea 100644 (file)
@@ -188,7 +188,7 @@ pcl::gpu::people::RDFBodyPartsDetector::process (const pcl::device::Depth& depth
     labels_smoothed_.download(lmap_host_, c);
     //async_labels_download.download(labels_smoothed_);
 
-    // cc = generalized floodfill = approximation of euclidian clusterisation
+    // cc = generalized floodfill = approximation of euclidean clusterisation
     device::ConnectedComponents::computeEdges(labels_smoothed_, depth, NUM_PARTS, cluster_tolerance_ * cluster_tolerance_, edges_);
     device::ConnectedComponents::labelComponents(edges_, comps_);
 
@@ -283,7 +283,7 @@ pcl::gpu::people::RDFBodyPartsDetector::processSmooth (const pcl::device::Depth&
   labels_smoothed_.download(lmap_host_, c);
   //async_labels_download.download(labels_smoothed_);
 
-  // cc = generalized floodfill = approximation of euclidian clusterisation
+  // cc = generalized floodfill = approximation of euclidean clusterisation
   device::ConnectedComponents::computeEdges(labels_smoothed_, depth, NUM_PARTS, cluster_tolerance_ * cluster_tolerance_, edges_);
   device::ConnectedComponents::labelComponents(edges_, comps_);
 
index e11beb8f5b58c9869e8774be4e28972dc42ca24b..0cacdf9f0e15d84b0646a6051b68c0a5ac5a8695 100644 (file)
@@ -294,7 +294,7 @@ namespace pcl
             int old_label = old_labels[i][j];
             int new_label = new_labels[i][j];
 
-            //if there is a neigboring element with a smaller label, update the equivalence tree of the processed element
+            //if there is a neighboring element with a smaller label, update the equivalence tree of the processed element
                    //(the tree is always flattened in this stage so there is no need to use findRoot to find the root)
             if (new_label < old_label)
             {
index 039cac5fe4acb9e85ddb86ee0366831f37872445..08cab2752be7cc80dab97e827bc6d45662c17f87 100644 (file)
@@ -212,8 +212,8 @@ NCV_CT_ASSERT(sizeof(NcvPoint2D32u) == 2 * sizeof(Ncv32u));
 //
 //==============================================================================
 
-const Ncv32u K_WARP_SIZE = 32;
-const Ncv32u K_LOG2_WARP_SIZE = 5;
+constexpr Ncv32u K_WARP_SIZE = 32;
+constexpr Ncv32u K_LOG2_WARP_SIZE = 5;
 
 //==============================================================================
 //
index 37807be328f784ad1c7ec8b592bd5a7854bea4bb..8b396a835a38d70b906aa0cee645b12698656331 100644 (file)
@@ -120,8 +120,6 @@ pcl::gpu::people::FaceDetector::loadFromXML2(const std::string
   haar.bHasStumpsOnly = true;
   haar.bNeedsTiltedII = false;
 
-  Ncv32u cur_max_tree_depth;
-
   std::vector<HaarClassifierNode128> host_temp_classifier_not_root_nodes;
   haar_stages.resize(0);
   haarClassifierNodes.resize(0);
@@ -258,7 +256,6 @@ pcl::gpu::people::FaceDetector::loadFromXML2(const std::string
                     {
                         //root node
                         haarClassifierNodes.push_back(current_node);
-                        cur_max_tree_depth = 1;
                     }
                     else
                     {
@@ -266,7 +263,6 @@ pcl::gpu::people::FaceDetector::loadFromXML2(const std::string
                         host_temp_classifier_not_root_nodes.push_back(current_node);
                         // TODO replace with PCL_DEBUG in the future
                         PCL_INFO("[pcl::gpu::people::FaceDetector::loadFromXML2] : (I) : Found non root node number %d", host_temp_classifier_not_root_nodes.size());
-                        cur_max_tree_depth++;
                     }
                     node_identifier++;
                   }
index acf452edd024fdda7e3c4c5f9d66939da049ed58..91308e4e26366693d20e0efc54ae093753e75844 100644 (file)
@@ -78,7 +78,7 @@ std::vector<std::string> getPcdFilesInDir(const std::string& directory)
 
   for(; pos != end ; ++pos)
     if (fs::is_regular_file(pos->status()) )
-      if (fs::extension(*pos) == ".pcd")
+      if (pos->path().extension().string() == ".pcd")
         result.push_back(pos->path().string());
     
   return result;  
@@ -373,7 +373,7 @@ int main(int argc, char** argv)
   if(pc::find_switch (argc, argv, "--help") || pc::find_switch (argc, argv, "-h"))
     return print_help(), 0;
   
-  // selecting GPU and prining info
+  // selecting GPU and printing info
   int device = 0;
   pc::parse_argument (argc, argv, "-gpu", device);
   pcl::gpu::setDevice (device);
index 9f61338dc6ed74aa5e633f2ac0b1f60bad0232ba..18aea6e768280125292226113bb7aa27f1893d5e 100644 (file)
 
 #include <pcl/gpu/containers/device_array.h>
 #include <pcl/gpu/octree/octree.hpp>
-#include <pcl/PointIndices.h>
 #include <pcl/pcl_macros.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
+#include <pcl/PointIndices.h>
 
 namespace pcl {
 namespace gpu {
@@ -191,7 +191,7 @@ protected:
   GPUTreePtr tree_;
 
   /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
-  double cluster_tolerance_{0};
+  double cluster_tolerance_{0.0};
 
   /** \brief The minimum number of points that a cluster needs to contain in order to be
    * considered valid (default = 1). */
index c262e50dcc764e4ee3a5958f6b361c5eb270931d..e1f883579eea27d1871fe40ab7013e0df70d4ae8 100644 (file)
 #pragma once
 
 #include <pcl/gpu/octree/octree.hpp>
-#include <pcl/PointIndices.h>
 #include <pcl/pcl_macros.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
+#include <pcl/PointIndices.h>
 
 namespace pcl {
 namespace gpu {
@@ -185,7 +185,7 @@ protected:
   GPUTreePtr tree_;
 
   /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
-  double cluster_tolerance_{0};
+  double cluster_tolerance_{0.0};
 
   /** \brief The minimum number of points that a cluster needs to contain in order to be
    * considered valid (default = 1). */
index afa34b2363f671fcbb2417f26ed48a811b76fa0c..b5e7f97abbaef13d853629b4b6aa33cceeab18e3 100644 (file)
 
 #pragma once
 
-#include <pcl/PointIndices.h>
 #include <pcl/pcl_macros.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
+#include <pcl/PointIndices.h>
 
 namespace pcl {
 namespace gpu {
@@ -121,7 +121,7 @@ public:
     host_cloud_ = host_cloud;
   }
 
-  /** \brief Set the tollerance on the hue
+  /** \brief Set the tolerance on the hue
    * \param[in] delta_hue the new delta hue
    */
   inline void
@@ -155,7 +155,7 @@ protected:
   GPUTreePtr tree_;
 
   /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
-  double cluster_tolerance_{0};
+  double cluster_tolerance_{0.0};
 
   /** \brief The allowed difference on the hue*/
   float delta_hue_{0.0};
index d5c0371aac9633031ed1d1991818fda421d7fb56..2e2be0de375d74918b3e595dbb4a39cbdd13be0a 100644 (file)
@@ -152,7 +152,7 @@ pcl::gpu::extractEuclideanClusters(
         continue;
 
       // Process the results
-      for (auto idx : data) {
+      for (const auto& idx : data) {
         if (processed[idx])
           continue;
         processed[idx] = true;
index 0e5eac3dcd1264b5579f6ff186af3281dfa46da9..3910551c62465f3bd05794a6536672b96d69f335 100644 (file)
@@ -46,7 +46,7 @@ PCL_INSTANTIATE(EuclideanClusterExtraction, PCL_XYZ_POINT_TYPES);
 PCL_INSTANTIATE(extractLabeledEuclideanClusters, PCL_XYZL_POINT_TYPES);
 PCL_INSTANTIATE(EuclideanLabeledClusterExtraction, PCL_XYZL_POINT_TYPES);
 
-void
+void PCL_EXPORTS
 pcl::detail::economical_download(const pcl::gpu::NeighborIndices& source_indices,
                                  const pcl::Indices& buffer_indices,
                                  std::size_t buffer_size,
index e4224f735646a80815d5d143176246d2b867b363..c1f20234ebaa83f2710f944fa8848e5611111ac0 100644 (file)
@@ -460,13 +460,8 @@ namespace pcl
                {
                        int idx = threadIdx.x + blockIdx.x * blockDim.x;
 
-#if CUDART_VERSION >= 9000
       if (__all_sync (__activemask (), idx >= facet_count))
         return;
-#else
-                       if (__all (idx >= facet_count))
-                               return;
-#endif
 
                        int empty = 0;
 
@@ -490,18 +485,11 @@ namespace pcl
                                  empty = 1;                
                        }
 
-#if CUDART_VERSION >= 9000
       int total = __popc (__ballot_sync (__activemask (), empty));
-#else
-                       int total = __popc (__ballot (empty));
-#endif
+
                        if (total > 0)
                        {
-#if CUDART_VERSION >= 9000
         int offset = Warp::binaryExclScan (__ballot_sync (__activemask (), empty));
-#else
-                               int offset = Warp::binaryExclScan (__ballot (empty));
-#endif
 
                                volatile __shared__ int wapr_buffer[WARPS];
 
index 9040f438a2bd7e701bbc27a929d1cdb647555a07..7fc86b26e641df166a6e0e6d52df3085f4715c09 100644 (file)
@@ -1,14 +1,14 @@
 set(SUBSYS_NAME io)
 set(SUBSYS_DESC "Point cloud IO library")
 set(SUBSYS_DEPS common octree)
-set(SUBSYS_EXT_DEPS boost eigen)
+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 EXT_DEPS ${SUBSYS_EXT_DEPS})
+  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})
 else()
-  PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk pcap png vtk libusb EXT_DEPS ${SUBSYS_EXT_DEPS})
+  PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk pcap png vtk libusb OpenMP EXT_DEPS ${SUBSYS_EXT_DEPS})
 endif()
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
@@ -211,7 +211,7 @@ if(MINGW)
 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 Boost::boost)
+target_link_libraries(pcl_io_ply pcl_common Boost::boost)
 
 set(srcs
   src/debayer.cpp
@@ -269,6 +269,7 @@ set(incs
   "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"
   "include/pcl/${SUBSYS_NAME}/pcd_grabber.h"
   "include/pcl/${SUBSYS_NAME}/pcd_io.h"
   "include/pcl/${SUBSYS_NAME}/vtk_io.h"
@@ -347,6 +348,7 @@ target_link_libraries("${LIB_NAME}" Boost::boost Boost::filesystem Boost::iostre
 if(VTK_FOUND)
   if(${VTK_VERSION} VERSION_GREATER_EQUAL 9.0)
     target_link_libraries("${LIB_NAME}" 
+                          VTK::FiltersGeneral
                           VTK::IOImage
                           VTK::IOGeometry
                           VTK::IOPLY)
@@ -438,7 +440,3 @@ PCL_ADD_INCLUDES("${SUBSYS_NAME}" compression ${compression_incs})
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/openni_camera" ${OPENNI_INCLUDES})
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/openni2" ${OPENNI2_INCLUDES})
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs})
-
-if(BUILD_tools)
-  add_subdirectory(tools)
-endif()
index 67cd089b58f65d7e2eef36f5b5855fa79f405265..8b26fad35ec933c00da93a3278e9a92477a0736e 100644 (file)
@@ -64,10 +64,7 @@ public:
   /** \brief Constructor.
    *
    * */
-  ColorCoding () :
-    output_ (), colorBitReduction_ (0)
-  {
-  }
+  ColorCoding () = default;
 
   /** \brief Empty class constructor. */
   virtual
@@ -353,7 +350,7 @@ public:
 
 protected:
   /** \brief Pointer to output point cloud dataset. */
-  PointCloudPtr output_;
+  PointCloudPtr output_{nullptr};
 
   /** \brief Vector for storing average color information  */
   std::vector<char> pointAvgColorDataVector_;
@@ -368,7 +365,7 @@ protected:
   std::vector<char>::const_iterator pointDiffColorDataVector_Iterator_;
 
   /** \brief Amount of bits to be removed from color components before encoding */
-  unsigned char colorBitReduction_;
+  unsigned char colorBitReduction_{0};
 
   // frame header identifier
   static const int defaultColor_;
index 83218ead9268165e96c794e0d1f9177d478f0e6d..8300722e0fe30616b80a0d7a97e64a438cc738be 100644 (file)
@@ -54,9 +54,9 @@ pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector<char>& inpu
   DWord freq[257];
 
   // define limits
-  const DWord top = static_cast<DWord> (1) << 24;
-  const DWord bottom = static_cast<DWord> (1) << 16;
-  const DWord maxRange = static_cast<DWord> (1) << 16;
+  constexpr DWord top = static_cast<DWord>(1) << 24;
+  constexpr DWord bottom = static_cast<DWord>(1) << 16;
+  constexpr DWord maxRange = static_cast<DWord>(1) << 16;
 
   auto input_size = static_cast<unsigned> (inputByteVector_arg.size ());
 
@@ -84,7 +84,7 @@ pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector<char>& inpu
     range *= freq[ch + 1] - freq[ch];
 
     // check range limits
-    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1)))
+    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast<int>(low) & (bottom - 1)), 1)))
     {
       char out = static_cast<char> (low >> 24);
       range <<= 8;
@@ -119,7 +119,7 @@ pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector<char>& inpu
   }
 
   // write to stream
-  outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ());
+  outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ());
 
   return (static_cast<unsigned long> (outputCharVector_.size ()));
 }
@@ -132,9 +132,9 @@ pcl::AdaptiveRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream
   DWord freq[257];
 
   // define limits
-  const DWord top = static_cast<DWord> (1) << 24;
-  const DWord bottom = static_cast<DWord> (1) << 16;
-  const DWord maxRange = static_cast<DWord> (1) << 16;
+  constexpr DWord top = static_cast<DWord>(1) << 24;
+  constexpr DWord bottom = static_cast<DWord>(1) << 16;
+  constexpr DWord maxRange = static_cast<DWord>(1) << 16;
 
   auto output_size = static_cast<unsigned> (outputByteVector_arg.size ());
 
@@ -186,7 +186,7 @@ pcl::AdaptiveRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream
     range *= freq[symbol + 1] - freq[symbol];
 
     // decode range limits
-    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1)))
+    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast<int>(low) & (bottom - 1)), 1)))
     {
       std::uint8_t ch;
       inputByteStream_arg.read (reinterpret_cast<char*> (&ch), sizeof(char));
@@ -222,9 +222,9 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector<unsigned int>& input
                                                 std::ostream& outputByteStream_arg)
 {
   // define numerical limits
-  const std::uint64_t top = static_cast<std::uint64_t> (1) << 56;
-  const std::uint64_t bottom = static_cast<std::uint64_t> (1) << 48;
-  const std::uint64_t maxRange = static_cast<std::uint64_t> (1) << 48;
+  constexpr std::uint64_t top = static_cast<std::uint64_t>(1) << 56;
+  constexpr std::uint64_t bottom = static_cast<std::uint64_t>(1) << 48;
+  constexpr std::uint64_t maxRange = static_cast<std::uint64_t>(1) << 48;
 
   auto input_size = static_cast<unsigned long> (inputIntVector_arg.size ());
 
@@ -313,7 +313,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector<unsigned int>& input
   while (readPos < input_size)
   {
 
-    // read symol
+    // read symbol
     unsigned int inputsymbol = inputIntVector_arg[readPos++];
 
     // map to range
@@ -340,7 +340,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector<unsigned int>& input
   }
 
   // write encoded data to stream
-  outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ());
+  outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ());
 
   streamByteCount += static_cast<unsigned long> (outputCharVector_.size ());
 
@@ -353,8 +353,8 @@ pcl::StaticRangeCoder::decodeStreamToIntVector (std::istream& inputByteStream_ar
                                                 std::vector<unsigned int>& outputIntVector_arg)
 {
   // define range limits
-  const std::uint64_t top = static_cast<std::uint64_t> (1) << 56;
-  const std::uint64_t bottom = static_cast<std::uint64_t> (1) << 48;
+  constexpr std::uint64_t top = static_cast<std::uint64_t>(1) << 56;
+  constexpr std::uint64_t bottom = static_cast<std::uint64_t>(1) << 48;
 
   std::uint64_t frequencyTableSize;
   unsigned char frequencyTableByteSize;
@@ -445,9 +445,9 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector<char>& inputB
   DWord freq[257];
 
   // define numerical limits
-  const DWord top = static_cast<DWord> (1) << 24;
-  const DWord bottom = static_cast<DWord> (1) << 16;
-  const DWord maxRange = static_cast<DWord> (1) << 16;
+  constexpr DWord top = static_cast<DWord>(1) << 24;
+  constexpr DWord bottom = static_cast<DWord>(1) << 16;
+  constexpr DWord maxRange = static_cast<DWord>(1) << 16;
 
   DWord low, range;
 
@@ -501,7 +501,7 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector<char>& inputB
   // start encoding
   while (readPos < input_size)
   {
-    // read symol
+    // read symbol
     std::uint8_t ch = inputByteVector_arg[readPos++];
 
     // map to range
@@ -509,7 +509,7 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector<char>& inputB
     range *= freq[ch + 1] - freq[ch];
 
     // check range limits
-    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1)))
+    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast<int>(low) & (bottom - 1)), 1)))
     {
       char out = static_cast<char> (low >> 24);
       range <<= 8;
@@ -528,7 +528,7 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector<char>& inputB
   }
 
   // write encoded data to stream
-  outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ());
+  outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ());
 
   streamByteCount += static_cast<unsigned long> (outputCharVector_.size ());
 
@@ -543,8 +543,8 @@ pcl::StaticRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream_a
   DWord freq[257];
 
   // define range limits
-  const DWord top = static_cast<DWord> (1) << 24;
-  const DWord bottom = static_cast<DWord> (1) << 16;
+  constexpr DWord top = static_cast<DWord>(1) << 24;
+  constexpr DWord bottom = static_cast<DWord>(1) << 16;
 
   DWord low, range;
   DWord code;
@@ -602,7 +602,7 @@ pcl::StaticRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream_a
     range *= freq[symbol + 1] - freq[symbol];
 
     // check range limits
-    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1)))
+    while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast<int>(low) & (bottom - 1)), 1)))
     {
       std::uint8_t ch;
       inputByteStream_arg.read (reinterpret_cast<char*> (&ch), sizeof(char));
index 12072da075af8f7391db0c504d06795da445ce83..4072e574012b8645c620b2265f44024fa854c044 100644 (file)
@@ -109,7 +109,7 @@ namespace pcl
       // Encode size of compressed disparity image data
       compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparitySize), sizeof (compressedDisparitySize));
       // Output compressed disparity to ostream
-      compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparity[0]), compressedDisparity.size () * sizeof(std::uint8_t));
+      compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedDisparity.data()), compressedDisparity.size () * sizeof(std::uint8_t));
 
       // Compress color information
       if (CompressionPointTraits<PointT>::hasColor && doColorEncoding)
@@ -127,7 +127,7 @@ namespace pcl
       // Encode size of compressed Color image data
       compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColorSize), sizeof (compressedColorSize));
       // Output compressed disparity to ostream
-      compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColor[0]), compressedColor.size () * sizeof(std::uint8_t));
+      compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedColor.data()), compressedColor.size () * sizeof(std::uint8_t));
 
       if (bShowStatistics_arg)
       {
@@ -194,8 +194,8 @@ namespace pcl
        std::uint32_t compressedColorSize = 0;
 
        // Remove color information of invalid points
-       std::uint16_t* depth_ptr = &disparityMap_arg[0];
-       std::uint8_t* color_ptr = &colorImage_arg[0];
+       std::uint16_t* depth_ptr = disparityMap_arg.data();
+       std::uint8_t* color_ptr = colorImage_arg.data();
 
        for (std::size_t i = 0; i < cloud_size; ++i, ++depth_ptr, color_ptr += sizeof(std::uint8_t) * 3)
        {
@@ -211,7 +211,7 @@ namespace pcl
        // Encode size of compressed disparity image data
        compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparitySize), sizeof (compressedDisparitySize));
        // Output compressed disparity to ostream
-       compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparity[0]), compressedDisparity.size () * sizeof(std::uint8_t));
+       compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedDisparity.data()), compressedDisparity.size () * sizeof(std::uint8_t));
 
        // Compress color information
        if (!colorImage_arg.empty () && doColorEncoding)
@@ -244,7 +244,7 @@ namespace pcl
        // Encode size of compressed Color image data
        compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColorSize), sizeof (compressedColorSize));
        // Output compressed disparity to ostream
-       compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColor[0]), compressedColor.size () * sizeof(std::uint8_t));
+       compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedColor.data()), compressedColor.size () * sizeof(std::uint8_t));
 
        if (bShowStatistics_arg)
        {
@@ -320,12 +320,12 @@ namespace pcl
         // reading compressed disparity data
         compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedDisparitySize), sizeof (compressedDisparitySize));
         compressedDisparity.resize (compressedDisparitySize);
-        compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedDisparity[0]), compressedDisparitySize * sizeof(std::uint8_t));
+        compressedDataIn_arg.read (reinterpret_cast<char*> (compressedDisparity.data()), compressedDisparitySize * sizeof(std::uint8_t));
 
         // reading compressed rgb data
         compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedColorSize), sizeof (compressedColorSize));
         compressedColor.resize (compressedColorSize);
-        compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedColor[0]), compressedColorSize * sizeof(std::uint8_t));
+        compressedDataIn_arg.read (reinterpret_cast<char*> (compressedColor.data()), compressedColorSize * sizeof(std::uint8_t));
 
         std::size_t png_width = 0;
         std::size_t png_height = 0;
@@ -335,6 +335,9 @@ namespace pcl
 
         // decode PNG compressed rgb data
         decodePNGToImage (compressedColor, colorData, png_width, png_height, png_channels);
+      } else {
+        PCL_ERROR("[OrganizedPointCloudCompression::decodePointCloud] Unable to find an encoded point cloud in the input stream!\n");
+        return false;
       }
 
       if (disparityShift==0.0f)
index 40c85c9e5779b9ee4bb1d2426db6ee11c901b3e1..d2eae276364b43168887635acb8192c110d77e7c 100644 (file)
@@ -106,13 +106,11 @@ namespace pcl
           color_coder_ (),
           point_coder_ (),
           do_voxel_grid_enDecoding_ (doVoxelGridDownDownSampling_arg), i_frame_rate_ (iFrameRate_arg),
-          i_frame_counter_ (0), frame_ID_ (0), point_count_ (0), i_frame_ (true),
-          do_color_encoding_ (doColorEncoding_arg), cloud_with_color_ (false), data_with_color_ (false),
-          point_color_offset_ (0), b_show_statistics_ (showStatistics_arg), 
-          compressed_point_data_len_ (), compressed_color_data_len_ (), selected_profile_(compressionProfile_arg),
+          
+          do_color_encoding_ (doColorEncoding_arg),  b_show_statistics_ (showStatistics_arg), 
+           selected_profile_(compressionProfile_arg),
           point_resolution_(pointResolution_arg), octree_resolution_(octreeResolution_arg),
-          color_bit_resolution_(colorBitResolution_arg),
-          object_count_(0)
+          color_bit_resolution_(colorBitResolution_arg)
         {
           initialization();
         }
@@ -266,22 +264,22 @@ namespace pcl
         /** \brief Static range coder instance */
         StaticRangeCoder entropy_coder_;
 
-        bool do_voxel_grid_enDecoding_;
-        std::uint32_t i_frame_rate_;
-        std::uint32_t i_frame_counter_;
-        std::uint32_t frame_ID_;
-        std::uint64_t point_count_;
-        bool i_frame_;
+        bool do_voxel_grid_enDecoding_{false};
+        std::uint32_t i_frame_rate_{0};
+        std::uint32_t i_frame_counter_{0};
+        std::uint32_t frame_ID_{0};
+        std::uint64_t point_count_{0};
+        bool i_frame_{true};
 
-        bool do_color_encoding_;
-        bool cloud_with_color_;
-        bool data_with_color_;
-        unsigned char point_color_offset_;
+        bool do_color_encoding_{false};
+        bool cloud_with_color_{false};
+        bool data_with_color_{false};
+        unsigned char point_color_offset_{0};
 
         //bool activating statistics
-        bool b_show_statistics_;
-        std::uint64_t compressed_point_data_len_;
-        std::uint64_t compressed_color_data_len_;
+        bool b_show_statistics_{false};
+        std::uint64_t compressed_point_data_len_{0};
+        std::uint64_t compressed_color_data_len_{0};
 
         // frame header identifier
         static const char* frame_header_identifier_;
@@ -291,7 +289,7 @@ namespace pcl
         const double octree_resolution_;
         const unsigned char color_bit_resolution_;
 
-        std::size_t object_count_;
+        std::size_t object_count_{0};
 
       };
 
index 168d2f31f7096b0208da6e9d29941e98093a38e5..b365c18900cc58ce7ef38ae81d8011b58c22b66c 100644 (file)
@@ -60,11 +60,7 @@ class PointCoding
 
   public:
     /** \brief Constructor. */
-    PointCoding () :
-      output_ (),
-      pointCompressionResolution_ (0.001f) // 1mm
-    {
-    }
+    PointCoding () = default;
 
     /** \brief Empty class constructor. */
     virtual
@@ -181,7 +177,7 @@ class PointCoding
 
   protected:
     /** \brief Pointer to output point cloud dataset. */
-    PointCloudPtr output_;
+    PointCloudPtr output_{nullptr};
 
     /** \brief Vector for storing differential point information  */
     std::vector<char> pointDiffDataVector_;
@@ -190,7 +186,7 @@ class PointCoding
     std::vector<char>::const_iterator pointDiffDataVectorIterator_;
 
     /** \brief Precision of point coding*/
-    float pointCompressionResolution_;
+    float pointCompressionResolution_{0.001f};
 };
 
 } // namespace octree
index be19192f2f6440c3734a692afe80d36b4c90b8d4..a0867796df8d28574f4733f23bb74dcbf139bb1c 100644 (file)
@@ -52,7 +52,6 @@ PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly."
 #include <boost/mpl/joint_view.hpp>
 #include <boost/mpl/transform.hpp>
 #include <boost/mpl/vector.hpp>
-#include <boost/date_time/posix_time/posix_time.hpp>
 #include <boost/tokenizer.hpp>
 #include <boost/foreach.hpp>
 #include <boost/shared_array.hpp>
index 67cbdd9a9d97fb9e71ca9635bc5b0e5373ecc090..2bec889910ac23b60218db6c5e39dfab69d9cf4e 100644 (file)
@@ -81,7 +81,7 @@ namespace pcl
         */
       std::string
       getName () const override
-      { return (std::string ("DinastGrabber")); }
+      { return {"DinastGrabber"}; }
       
       /** \brief Start the data acquisition process.
         */
@@ -163,51 +163,51 @@ namespace pcl
       captureThreadFunction ();
       
       /** \brief Width of image */
-      int image_width_;
+      int image_width_{320};
       
       /** \brief Height of image */
-      int image_height_;
+      int image_height_{240};
       
       /** \brief Total size of image */
-      int image_size_;
+      int image_size_{image_width_ * image_height_};
       
       /** \brief Length of a sync packet */
-      int sync_packet_size_;
+      int sync_packet_size_{512};
       
-      double dist_max_2d_;
+      double dist_max_2d_{1. / (image_width_ / 2.)};
       
       /** \brief diagonal Field of View*/
-      double fov_;
+      double fov_{64. * M_PI / 180.};
       
       /** \brief Size of pixel */
       enum pixel_size { RAW8=1, RGB16=2, RGB24=3, RGB32=4 };
       
       /** \brief The libusb context*/
-      libusb_context *context_;
+      libusb_context *context_{nullptr};
       
       /** \brief the actual device_handle for the camera */
-      struct libusb_device_handle *device_handle_;
+      struct libusb_device_handle *device_handle_{nullptr};
       
       /** \brief Temporary USB read buffer, since we read two RGB16 images at a time size is the double of two images
         * plus a sync packet.
         */
-      unsigned char *raw_buffer_ ;
+      unsigned char *raw_buffer_{nullptr} ;
 
       /** \brief Global circular buffer */
       boost::circular_buffer<unsigned char> g_buffer_;
 
       /** \brief Bulk endpoint address value */
-      unsigned char bulk_ep_;
+      unsigned char bulk_ep_{std::numeric_limits<unsigned char>::max ()};
       
       /** \brief Device command values */
       enum { CMD_READ_START=0xC7, CMD_READ_STOP=0xC8, CMD_GET_VERSION=0xDC, CMD_SEND_DATA=0xDE };
 
-      unsigned char *image_;
+      unsigned char *image_{nullptr};
       
       /** \brief Since there is no header after the first image, we need to save the state */
-      bool second_image_;
+      bool second_image_{false};
       
-      bool running_;
+      bool running_{false};
       
       std::thread capture_thread_;
       
index 6fdf84c8b948b59196b3e7aeb3689cf396739426..213aff53ebf7949fe6f84fbe02c0346ab00207ab 100644 (file)
@@ -443,13 +443,13 @@ namespace pcl
       boost::signals2::signal<sig_cb_ensenso_point_cloud_images>* point_cloud_images_signal_;
 
       /** @brief Whether an Ensenso device is opened or not */
-      bool device_open_;
+      bool device_open_{false};
 
       /** @brief Whether an TCP port is opened or not */
-      bool tcp_open_;
+      bool tcp_open_{false};
 
       /** @brief Whether an Ensenso device is running or not */
-      bool running_;
+      bool running_{false};
 
       /** @brief Point cloud capture/processing frequency */
       pcl::EventFrequency frequency_;
index 25fe20a21413acb1d8f1f9e55ed8ab74fbfafccb..b7ec74b8cdad39b528b8d70a736feb93b64d4a30 100644 (file)
@@ -342,6 +342,7 @@ namespace pcl
     }
     else {
       is.str(st);
+      is.clear(); // clear error state flags
       if (!(is >> value))
         value = static_cast<Type>(atof(st.c_str()));
     }
@@ -364,6 +365,7 @@ namespace pcl
     std::int8_t value;
     int val;
     is.str(st);
+    is.clear(); // clear error state flags
     // is >> val;  -- unfortunately this fails on older GCC versions and CLANG on MacOS
     if (!(is >> val)) {
       val = static_cast<int>(atof(st.c_str()));
@@ -388,6 +390,7 @@ namespace pcl
     std::uint8_t value;
     int val;
     is.str(st);
+    is.clear(); // clear error state flags
     // is >> val;  -- unfortunately this fails on older GCC versions and CLANG on
     // MacOS
     if (!(is >> val)) {
index c36a00c5552c3ff0b8da120d989b4c7c8df65f2f..ce6f55a08904261059834a96b4384c5a372b4710 100644 (file)
@@ -262,6 +262,7 @@ namespace pcl
       operator std::unique_ptr<Base>() const { return std::make_unique<Signal>(); }
     };
     // TODO: remove later for C++17 features: structured bindings and try_emplace
+    std::string signame{typeid (T).name ()};
     #ifdef __cpp_structured_bindings
       const auto [iterator, success] =
     #else
@@ -275,7 +276,7 @@ namespace pcl
     #else
       signals_.emplace (
     #endif
-                         std::string (typeid (T).name ()), DefferedPtr ());
+            signame, DefferedPtr ());
     if (!success)
     {
       return nullptr;
index 294ce4f1d162df67f6aab6e089e6761510e52274..5e4e4ce50fc165c35dcb63a5137591821440cf61 100644 (file)
@@ -236,7 +236,7 @@ LZFRGB24ImageReader::read (
   cloud.resize (getWidth () * getHeight ());
 
   int rgb_idx = 0;
-  auto *color_r = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
+  auto *color_r = reinterpret_cast<unsigned char*> (uncompressed_data.data());
   auto *color_g = reinterpret_cast<unsigned char*> (&uncompressed_data[getWidth () * getHeight ()]);
   auto *color_b = reinterpret_cast<unsigned char*> (&uncompressed_data[2 * getWidth () * getHeight ()]);
 
@@ -284,7 +284,7 @@ LZFRGB24ImageReader::readOMP (
   cloud.height = getHeight ();
   cloud.resize (getWidth () * getHeight ());
 
-  auto *color_r = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
+  auto *color_r = reinterpret_cast<unsigned char*> (uncompressed_data.data());
   auto *color_g = reinterpret_cast<unsigned char*> (&uncompressed_data[getWidth () * getHeight ()]);
   auto *color_b = reinterpret_cast<unsigned char*> (&uncompressed_data[2 * getWidth () * getHeight ()]);
 
@@ -341,7 +341,7 @@ LZFYUV422ImageReader::read (
   cloud.resize (getWidth () * getHeight ());
 
   int wh2 = getWidth () * getHeight () / 2;
-  auto *color_u = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
+  auto *color_u = reinterpret_cast<unsigned char*> (uncompressed_data.data());
   auto *color_y = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2]);
   auto *color_v = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2 + getWidth () * getHeight ()]);
 
@@ -399,7 +399,7 @@ LZFYUV422ImageReader::readOMP (
   cloud.resize (getWidth () * getHeight ());
 
   int wh2 = getWidth () * getHeight () / 2;
-  auto *color_u = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
+  auto *color_u = reinterpret_cast<unsigned char*> (uncompressed_data.data());
   auto *color_y = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2]);
   auto *color_v = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2 + getWidth () * getHeight ()]);
 
@@ -462,8 +462,8 @@ LZFBayer8ImageReader::read (
   // Convert Bayer8 to RGB24
   std::vector<unsigned char> rgb_buffer (getWidth () * getHeight () * 3);
   DeBayer i;
-  i.debayerEdgeAware (reinterpret_cast<unsigned char*> (&uncompressed_data[0]),
-                     static_cast<unsigned char*> (&rgb_buffer[0]),
+  i.debayerEdgeAware (reinterpret_cast<unsigned char*> (uncompressed_data.data()),
+                     static_cast<unsigned char*> (rgb_buffer.data()),
                      getWidth (), getHeight ());
   // Copy to PointT
   cloud.width  = getWidth ();
@@ -512,8 +512,8 @@ LZFBayer8ImageReader::readOMP (
   // Convert Bayer8 to RGB24
   std::vector<unsigned char> rgb_buffer (getWidth () * getHeight () * 3);
   DeBayer i;
-  i.debayerEdgeAware (reinterpret_cast<unsigned char*> (&uncompressed_data[0]),
-                     static_cast<unsigned char*> (&rgb_buffer[0]),
+  i.debayerEdgeAware (reinterpret_cast<unsigned char*> (uncompressed_data.data()),
+                     static_cast<unsigned char*> (rgb_buffer.data()),
                      getWidth (), getHeight ());
   // Copy to PointT
   cloud.width  = getWidth ();
index 20b748843d933ded121dc6520ef7cfe155d9a21f..2c832361ccf9eb132fd22358570fa3d560cefe23 100644 (file)
@@ -115,25 +115,22 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
   {
     PCL_WARN ("[pcl::PCDWriter::writeBinary] Input point cloud has no data!\n");
   }
-  int data_idx = 0;
   std::ostringstream oss;
   oss << generateHeader<PointT> (cloud) << "DATA binary\n";
   oss.flush ();
-  data_idx = static_cast<int> (oss.tellp ());
+  const auto data_idx = static_cast<unsigned int> (oss.tellp ());
 
 #ifdef _WIN32
   HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
   if (h_native_file == INVALID_HANDLE_VALUE)
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!");
-    return (-1);
   }
 #else
   int fd = io::raw_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH);
   if (fd < 0)
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!");
-    return (-1);
   }
 #endif
   // Mandatory lock file
@@ -162,13 +159,17 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
 
   // Prepare the map
 #ifdef _WIN32
-  HANDLE fm = CreateFileMappingA (h_native_file, NULL, PAGE_READWRITE, 0, (DWORD) (data_idx + data_size), NULL);
+  HANDLE fm = CreateFileMappingA (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((data_idx + data_size) >> 32), (DWORD) (data_idx + data_size), NULL);
   if (fm == NULL)
   {
       throw pcl::IOException("[pcl::PCDWriter::writeBinary] Error during memory map creation ()!");
-      return (-1);
   }
   char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size));
+  if (map == NULL)
+  {
+      CloseHandle (fm);
+      throw pcl::IOException("[pcl::PCDWriter::writeBinary] Error mapping view of file!");
+  }
   CloseHandle (fm);
 
 #else
@@ -182,7 +183,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
                data_idx + data_size, allocate_res, errno, strerror (errno));
 
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during raw_fallocate ()!");
-    return (-1);
   }
 
   char *map = static_cast<char*> (::mmap (nullptr, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
@@ -191,7 +191,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
     io::raw_close (fd);
     resetLockingPermissions (file_name, file_lock);
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!");
-    return (-1);
   }
 #endif
 
@@ -225,7 +224,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
     io::raw_close (fd);
     resetLockingPermissions (file_name, file_lock);
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!");
-    return (-1);
   }
 #endif
   // Close file
@@ -247,25 +245,22 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name,
   {
     PCL_WARN ("[pcl::PCDWriter::writeBinaryCompressed] Input point cloud has no data!\n");
   }
-  int data_idx = 0;
   std::ostringstream oss;
   oss << generateHeader<PointT> (cloud) << "DATA binary_compressed\n";
   oss.flush ();
-  data_idx = static_cast<int> (oss.tellp ());
+  const auto data_idx = static_cast<unsigned int> (oss.tellp ());
 
 #ifdef _WIN32
   HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
   if (h_native_file == INVALID_HANDLE_VALUE)
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during CreateFile!");
-    return (-1);
   }
 #else
   int fd = io::raw_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH);
   if (fd < 0)
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during open!");
-    return (-1);
   }
 #endif
 
@@ -392,7 +387,6 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name,
                compressed_final_size, allocate_res, errno, strerror (errno));
 
     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during raw_fallocate ()!");
-    return (-1);
   }
 
   char *map = static_cast<char*> (::mmap (nullptr, compressed_final_size, PROT_WRITE, MAP_SHARED, fd, 0));
@@ -401,7 +395,6 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name,
     io::raw_close (fd);
     resetLockingPermissions (file_name, file_lock);
     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during mmap ()!");
-    return (-1);
   }
 #endif
 
@@ -425,7 +418,6 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name,
     io::raw_close (fd);
     resetLockingPermissions (file_name, file_lock);
     throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during munmap ()!");
-    return (-1);
   }
 #endif
 
@@ -455,7 +447,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<
   if (cloud.width * cloud.height != cloud.size ())
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!");
-    return (-1);
   }
 
   std::ofstream fs;
@@ -464,7 +455,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<
   if (!fs.is_open () || fs.fail ())
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!");
-    return (-1);
   }
   
   // Mandatory lock file
@@ -625,25 +615,22 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
   {
     PCL_WARN ("[pcl::PCDWriter::writeBinary] Input point cloud has no data or empty indices given!\n");
   }
-  int data_idx = 0;
   std::ostringstream oss;
   oss << generateHeader<PointT> (cloud, static_cast<int> (indices.size ())) << "DATA binary\n";
   oss.flush ();
-  data_idx = static_cast<int> (oss.tellp ());
+  const auto data_idx = static_cast<unsigned int> (oss.tellp ());
 
 #ifdef _WIN32
   HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
   if (h_native_file == INVALID_HANDLE_VALUE)
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!");
-    return (-1);
   }
 #else
   int fd = io::raw_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH);
   if (fd < 0)
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!");
-    return (-1);
   }
 #endif
   // Mandatory lock file
@@ -672,7 +659,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
 
   // Prepare the map
 #ifdef _WIN32
-  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, data_idx + data_size, NULL);
+  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((data_idx + data_size) >> 32), (DWORD) (data_idx + data_size), NULL);
   char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size));
   CloseHandle (fm);
 
@@ -687,7 +674,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
                data_idx + data_size, allocate_res, errno, strerror (errno));
 
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during raw_fallocate ()!");
-    return (-1);
   }
 
   char *map = static_cast<char*> (::mmap (nullptr, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
@@ -696,7 +682,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
     io::raw_close (fd);
     resetLockingPermissions (file_name, file_lock);
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!");
-    return (-1);
   }
 #endif
 
@@ -730,7 +715,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
     io::raw_close (fd);
     resetLockingPermissions (file_name, file_lock);
     throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!");
-    return (-1);
   }
 #endif
   // Close file
@@ -759,7 +743,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name,
   if (cloud.width * cloud.height != cloud.size ())
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!");
-    return (-1);
   }
 
   std::ofstream fs;
@@ -767,7 +750,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name,
   if (!fs.is_open () || fs.fail ())
   {
     throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!");
-    return (-1);
   }
 
   // Mandatory lock file
index 9678e9b7366aad9d949aa091695dc70ebca25fc6..c5025efe9630d38952b2c458a6a56c3c45f39d07 100644 (file)
@@ -154,7 +154,7 @@ pcl::io::PointCloudImageExtractorFromLabelField<PointT>::extractImpl (const Poin
       img.height = cloud.height;
       img.step = img.width * sizeof (unsigned short);
       img.data.resize (img.step * img.height);
-      auto* data = reinterpret_cast<unsigned short*>(&img.data[0]);
+      auto* data = reinterpret_cast<unsigned short*>(img.data.data());
       for (std::size_t i = 0; i < cloud.size (); ++i)
       {
         std::uint32_t val;
@@ -255,7 +255,7 @@ pcl::io::PointCloudImageExtractorWithScaling<PointT>::extractImpl (const PointCl
   img.height = cloud.height;
   img.step = img.width * sizeof (unsigned short);
   img.data.resize (img.step * img.height);
-  auto* data = reinterpret_cast<unsigned short*>(&img.data[0]);
+  auto* data = reinterpret_cast<unsigned short*>(img.data.data());
 
   float scaling_factor = scaling_factor_;
   float data_min = 0.0f;
index fe9aaf8104ca06dff7f023d8e20ea245c7cc48ec..1e6ca9cb74daf55e8110f0ae98797db89001b86b 100644 (file)
@@ -53,7 +53,7 @@ namespace pcl
     public:
 
       SynchronizedQueue () :
-        queue_(), request_to_end_(false), enqueue_data_(true) { }
+        queue_()  { }
 
       void
       enqueue (const T& data)
@@ -127,7 +127,7 @@ namespace pcl
       mutable std::mutex mutex_;       // The mutex to synchronise on
       std::condition_variable cond_;   // The condition to wait for
 
-      bool request_to_end_;
-      bool enqueue_data_;
+      bool request_to_end_{false};
+      bool enqueue_data_{true};
   };
 }
index ab579c77a806638a34a858ed87385041b9277211..62b3289daf4c8714fb08c404995aadd3aa612b46 100644 (file)
@@ -38,5 +38,6 @@
  */
 
 #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 50dbbb22b6ae99309ed92379415d3fdb37cafb2b..b80897317bac246f7a6a9bd85cbe032541cd3605 100644 (file)
@@ -43,7 +43,7 @@
 #include <string>
 
 
-//fom <pcl/pcl_macros.h>
+//from <pcl/pcl_macros.h>
 #if defined _WIN32 && defined _MSC_VER && !defined __PRETTY_FUNCTION__
   #define __PRETTY_FUNCTION__ __FUNCTION__
 #endif
@@ -73,7 +73,7 @@ namespace pcl
         operator= (const IOException& exception);
 
         const char*
-        what () const throw () override;
+        what () const noexcept override;
 
         const std::string&
         getFunctionName () const;
index 77bd0fafd4bdcb02626316b210d3f2aea5592f7f..416cbb426fb826679af04f465ddca527234b855d 100644 (file)
@@ -161,10 +161,10 @@ namespace pcl
                     std::vector<char> &output); 
 
         /** \brief The image width, as read from the file. */
-        std::uint32_t width_;
+        std::uint32_t width_{0};
 
         /** \brief The image height, as read from the file. */
-        std::uint32_t height_;
+        std::uint32_t height_{0};
 
         /** \brief The image type string, as read from the file. */
         std::string image_type_identifier_;
@@ -189,9 +189,7 @@ namespace pcl
         using LZFImageReader::readParameters;
 
         /** Empty constructor */
-        LZFDepth16ImageReader () 
-          : z_multiplication_factor_ (0.001)      // Set default multiplication factor
-        {}
+        LZFDepth16ImageReader () = default;
 
         /** Empty destructor */
         ~LZFDepth16ImageReader () override = default;
@@ -223,7 +221,7 @@ namespace pcl
         /** \brief Z-value depth multiplication factor 
           * (i.e., if raw data is in [mm] and we want [m], we need to multiply with 0.001)
           */
-        double z_multiplication_factor_;
+        double z_multiplication_factor_{0.001};
     };
 
     /** \brief PCL-LZF 24-bit RGB image format reader.
@@ -480,9 +478,7 @@ namespace pcl
     {
       public:
         /** Empty constructor */
-        LZFDepth16ImageWriter () 
-          : z_multiplication_factor_ (0.001)      // Set default multiplication factor
-        {}
+        LZFDepth16ImageWriter () = default;
 
         /** Empty destructor */
         ~LZFDepth16ImageWriter () override = default;
@@ -519,7 +515,7 @@ namespace pcl
         /** \brief Z-value depth multiplication factor 
           * (i.e., if raw data is in [mm] and we want [m], we need to multiply with 0.001)
           */
-        double z_multiplication_factor_;
+        double z_multiplication_factor_{0.001};
     };
 
     /** \brief PCL-LZF 24-bit RGB image format writer.
index 2da7895caadfd2d221f2a24e0665bc59b90b3ac6..389db10a0996eeaf714295dbebc19f9767922a74 100644 (file)
@@ -175,23 +175,23 @@ namespace pcl
       openni_wrapper::DeviceONI::Ptr device_;
       std::string rgb_frame_id_;
       std::string depth_frame_id_;
-      bool running_;
-      unsigned image_width_;
-      unsigned image_height_;
-      unsigned depth_width_;
-      unsigned depth_height_;
-      openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle;
-      openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle;
-      openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle;
-      boost::signals2::signal<sig_cb_openni_image >*            image_signal_;
-      boost::signals2::signal<sig_cb_openni_depth_image >*      depth_image_signal_;
-      boost::signals2::signal<sig_cb_openni_ir_image >*         ir_image_signal_;
-      boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
-      boost::signals2::signal<sig_cb_openni_ir_depth_image>*    ir_depth_image_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud >*      point_cloud_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud_i >*    point_cloud_i_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud_rgb >*  point_cloud_rgb_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud_rgba >*  point_cloud_rgba_signal_;
+      bool running_{false};
+      unsigned image_width_{0};
+      unsigned image_height_{0};
+      unsigned depth_width_{0};
+      unsigned depth_height_{0};
+      openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle{};
+      openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle{};
+      openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle{};
+      boost::signals2::signal<sig_cb_openni_image >*            image_signal_{};
+      boost::signals2::signal<sig_cb_openni_depth_image >*      depth_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_ir_image >*         ir_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_ir_depth_image>*    ir_depth_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud >*      point_cloud_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud_i >*    point_cloud_i_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud_rgb >*  point_cloud_rgb_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud_rgba >*  point_cloud_rgba_signal_{};
 
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
index dd4627856269d0686e9bb017d3de828b0fa50da9..4abb5d28dd113f1a8f14eab70a835aff01a87e42 100644 (file)
@@ -315,16 +315,16 @@ namespace pcl
           mutable std::vector<OpenNI2VideoMode> color_video_modes_;
           mutable std::vector<OpenNI2VideoMode> depth_video_modes_;
 
-          bool ir_video_started_;
-          bool color_video_started_;
-          bool depth_video_started_;
+          bool ir_video_started_{false};
+          bool color_video_started_{false};
+          bool depth_video_started_{false};
 
           /** \brief distance between the projector and the IR camera in meters*/
-          float baseline_;
+          float baseline_{0.0f};
           /** the value for shadow (occluded pixels) */
-          std::uint64_t shadow_value_;
+          std::uint64_t shadow_value_{0};
           /** the value for pixels without a valid disparity measurement */
-          std::uint64_t no_sample_value_;
+          std::uint64_t no_sample_value_{0};
       };
 
       PCL_EXPORTS std::ostream& operator<< (std::ostream& stream, const OpenNI2Device& device);
index 4c110a8ffc083ed01e331493bccb8320e71fbf4e..2946e4561a2804001172f29154d29a6881e1bc45 100644 (file)
@@ -41,6 +41,7 @@
 #include <pcl/pcl_config.h>
 #ifdef HAVE_OPENNI2
 
+#include <cassert> // for assert
 #include <vector>
 #include <limits>
 
@@ -52,7 +53,7 @@ namespace openni_wrapper
   {
     public:
       /** \brief Constructor. */
-      ShiftToDepthConverter () : init_(false) {}
+      ShiftToDepthConverter () = default;
 
       /** \brief This method generates a look-up table to convert openni shift values to depth
         */
@@ -109,7 +110,7 @@ namespace openni_wrapper
 
     protected:
       std::vector<float> lookupTable_;
-      bool init_;
+      bool init_{false};
   } ;
 }
 #endif
index f4a54f09d0cf16f55050fe1fd185617fb3014a09..e42529b0c46cbc94b87f9e294e73abb34d68fc3f 100644 (file)
@@ -421,9 +421,9 @@ namespace pcl
         convertToXYZIPointCloud (const pcl::io::openni2::IRImage::Ptr &image,
           const pcl::io::openni2::DepthImage::Ptr &depth_image);
 
-        std::vector<std::uint8_t> color_resize_buffer_;
-        std::vector<std::uint16_t> depth_resize_buffer_;
-        std::vector<std::uint16_t> ir_resize_buffer_;
+        std::vector<std::uint8_t> color_resize_buffer_{};
+        std::vector<std::uint16_t> depth_resize_buffer_{};
+        std::vector<std::uint16_t> ir_resize_buffer_{};
 
         // Stream callbacks /////////////////////////////////////////////////////
         void
@@ -444,25 +444,25 @@ namespace pcl
 
         std::string rgb_frame_id_;
         std::string depth_frame_id_;
-        unsigned image_width_;
-        unsigned image_height_;
-        unsigned depth_width_;
-        unsigned depth_height_;
-
-        bool image_required_;
-        bool depth_required_;
-        bool ir_required_;
-        bool sync_required_;
-
-        boost::signals2::signal<sig_cb_openni_image>* image_signal_;
-        boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_;
-        boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_;
-        boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
-        boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
-        boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_;
-        boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_;
-        boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_;
-        boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_;
+        unsigned image_width_{0};
+        unsigned image_height_{0};
+        unsigned depth_width_{0};
+        unsigned depth_height_{0};
+
+        bool image_required_{false};
+        bool depth_required_{false};
+        bool ir_required_{false};
+        bool sync_required_{false};
+
+        boost::signals2::signal<sig_cb_openni_image>* image_signal_{};
+        boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_{};
+        boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_{};
+        boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_{};
+        boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_{};
+        boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_{};
+        boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_{};
+        boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_{};
+        boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_{};
 
         struct modeComp
         {
@@ -483,14 +483,13 @@ namespace pcl
         // Mapping from config (enum) modes to native OpenNI modes
         std::map<int, pcl::io::openni2::OpenNI2VideoMode> config2oni_map_;
 
-        pcl::io::openni2::OpenNI2Device::CallbackHandle depth_callback_handle_;
-        pcl::io::openni2::OpenNI2Device::CallbackHandle image_callback_handle_;
-        pcl::io::openni2::OpenNI2Device::CallbackHandle ir_callback_handle_;
-        bool running_;
+        pcl::io::openni2::OpenNI2Device::CallbackHandle depth_callback_handle_{};
+        pcl::io::openni2::OpenNI2Device::CallbackHandle image_callback_handle_{};
+        pcl::io::openni2::OpenNI2Device::CallbackHandle ir_callback_handle_{};
+        bool running_{false};
 
-
-        CameraParameters rgb_parameters_;
-        CameraParameters depth_parameters_;
+        CameraParameters rgb_parameters_{std::numeric_limits<double>::quiet_NaN ()};
+        CameraParameters depth_parameters_{std::numeric_limits<double>::quiet_NaN ()};
 
       public:
         PCL_MAKE_ALIGNED_OPERATOR_NEW
index 40bb47ef269dc2b1f667b2efc028818abcb85fc6..c318fc9473b5853a2755777995337d82734d79e8 100644 (file)
@@ -77,7 +77,7 @@ namespace openni_wrapper
         * \return the actual depth data of type xn::DepthMetaData.
         */
       inline const xn::DepthMetaData& 
-      getDepthMetaData () const throw ();
+      getDepthMetaData () const noexcept;
 
       /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling.
         * \param[in] width the width of the desired disparity image.
@@ -113,46 +113,46 @@ namespace openni_wrapper
         * \return baseline in meters
         */
       inline float 
-      getBaseline () const throw ();
+      getBaseline () const noexcept;
 
       /** \brief method to access the focal length of the "stereo" frame that was used to retrieve the depth image.
         * \return focal length in pixels
         */
       inline float 
-      getFocalLength () const throw ();
+      getFocalLength () const noexcept;
 
       /** \brief method to access the shadow value, that indicates pixels lying in shadow in the depth image.
         * \return shadow value
         */
       inline XnUInt64 
-      getShadowValue () const throw ();
+      getShadowValue () const noexcept;
 
       /** \brief method to access the no-sample value, that indicates pixels where no disparity could be determined for the depth image.
         * \return no-sample value
         */
       inline XnUInt64 
-      getNoSampleValue () const throw ();
+      getNoSampleValue () const noexcept;
 
       /** \return the width of the depth image */
       inline unsigned 
-      getWidth () const throw ();
+      getWidth () const noexcept;
 
       /** \return the height of the depth image */
       inline unsigned 
-      getHeight () const throw ();
+      getHeight () const noexcept;
 
       /** \return an ascending id for the depth frame
         * \attention not necessarily synchronized with other streams
         */
       inline unsigned 
-      getFrameID () const throw ();
+      getFrameID () const noexcept;
 
       /** \return a ascending timestamp for the depth frame
         * \attention its not the system time, thus can not be used directly to synchronize different sensors.
         *            But definitely synchronized with other streams
         */
       inline unsigned long 
-      getTimeStamp () const throw ();
+      getTimeStamp () const noexcept;
 
     protected:
       pcl::shared_ptr<xn::DepthMetaData> depth_md_;
@@ -172,55 +172,55 @@ namespace openni_wrapper
   DepthImage::~DepthImage () noexcept = default;
 
   const xn::DepthMetaData&
-  DepthImage::getDepthMetaData () const throw ()
+  DepthImage::getDepthMetaData () const noexcept
   {
     return *depth_md_;
   }
 
   float
-  DepthImage::getBaseline () const throw ()
+  DepthImage::getBaseline () const noexcept
   {
     return baseline_;
   }
 
   float
-  DepthImage::getFocalLength () const throw ()
+  DepthImage::getFocalLength () const noexcept
   {
     return focal_length_;
   }
 
   XnUInt64
-  DepthImage::getShadowValue () const throw ()
+  DepthImage::getShadowValue () const noexcept
   {
     return shadow_value_;
   }
 
   XnUInt64
-  DepthImage::getNoSampleValue () const throw ()
+  DepthImage::getNoSampleValue () const noexcept
   {
     return no_sample_value_;
   }
 
   unsigned
-  DepthImage::getWidth () const throw ()
+  DepthImage::getWidth () const noexcept
   {
     return depth_md_->XRes ();
   }
 
   unsigned
-  DepthImage::getHeight () const throw ()
+  DepthImage::getHeight () const noexcept
   {
     return depth_md_->YRes ();
   }
 
   unsigned
-  DepthImage::getFrameID () const throw ()
+  DepthImage::getFrameID () const noexcept
   {
     return depth_md_->FrameID ();
   }
 
   unsigned long
-  DepthImage::getTimeStamp () const throw ()
+  DepthImage::getTimeStamp () const noexcept
   {
     return static_cast<unsigned long> (depth_md_->Timestamp ());
   }
index fcc8d733995e7202f8f33109c4f82ab582b65c7c..ddda24b0cdcee2ceda2c1feb36f9a90fb68720d0 100644 (file)
@@ -98,49 +98,49 @@ namespace openni_wrapper
         * \return true, if a compatible mode could be found, false otherwise.
         */
       bool 
-      findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw ();
+      findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const noexcept;
 
       /** \brief finds a depth output mode that can be used to retrieve depth images in desired output mode.
-        *        e.g If device just supports VGA at 30Hz, then a desired mode of QVGA at 30Hz would be possbile by downsampling,
+        *        e.g If device just supports VGA at 30Hz, then a desired mode of QVGA at 30Hz would be possible by downsampling,
         *        but the modes VGA at 25Hz and SXGA at 30Hz would not be compatible.
         * \param[in] output_mode the desired output mode
         * \param[out] mode the compatible mode that the device natively supports.
         * \return true, if a compatible mode could be found, false otherwise.
         */
       bool 
-      findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw ();
+      findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const noexcept;
 
       /** \brief returns whether a given mode is natively supported by the device or not
         * \param[in] output_mode mode to be checked
         * \return true if mode natively available, false otherwise
         */
       bool 
-      isImageModeSupported (const XnMapOutputMode& output_mode) const throw ();
+      isImageModeSupported (const XnMapOutputMode& output_mode) const noexcept;
 
       /** \brief returns whether a given mode is natively supported by the device or not
         * \param[in] output_mode mode to be checked
         * \return true if mode natively available, false otherwise
         */
       bool 
-      isDepthModeSupported (const XnMapOutputMode& output_mode) const throw ();
+      isDepthModeSupported (const XnMapOutputMode& output_mode) const noexcept;
 
       /** \brief returns the default image mode, which is simply the first entry in the list of modes
         * \return the default image mode
         */
       const XnMapOutputMode& 
-      getDefaultImageMode () const throw ();
+      getDefaultImageMode () const noexcept;
 
       /** \brief  returns the default depth mode, which is simply the first entry in the list of modes
         * \return the default depth mode
         */
       const XnMapOutputMode& 
-      getDefaultDepthMode () const throw ();
+      getDefaultDepthMode () const noexcept;
 
       /** \brief  returns the default IR mode, which is simply the first entry in the list of modes
         * \return the default IR mode
         */
       const XnMapOutputMode& 
-      getDefaultIRMode () const throw ();
+      getDefaultIRMode () const noexcept;
 
       /** \brief sets the output mode of the image stream
         * \param[in] output_mode the desired output mode
@@ -180,11 +180,11 @@ namespace openni_wrapper
 
       /** \return whether the depth stream is registered to the RGB camera fram or not. */
       bool 
-      isDepthRegistered () const throw ();
+      isDepthRegistered () const noexcept;
 
       /** \return whether a registration of the depth stream to the RGB camera frame is supported or not. */
       bool 
-      isDepthRegistrationSupported () const throw ();
+      isDepthRegistrationSupported () const noexcept;
 
       /** \brief set the hardware synchronization between Depth and RGB stream on or off.
         * \param[in] on_off
@@ -194,11 +194,11 @@ namespace openni_wrapper
 
       /** \return true if Depth stream is synchronized to RGB stream, false otherwise. */
       bool 
-      isSynchronized () const throw ();
+      isSynchronized () const noexcept;
 
       /** \return true if the Device supports hardware synchronization between Depth and RGB streams or not. */ 
       virtual bool 
-      isSynchronizationSupported () const throw ();
+      isSynchronizationSupported () const noexcept;
 
       /** \return true if depth stream is a cropped version of the native depth stream, false otherwise. */
       bool 
@@ -215,23 +215,23 @@ namespace openni_wrapper
 
       /** \return true if cropping of the depth stream is supported, false otherwise. */
       bool 
-      isDepthCroppingSupported () const throw ();
+      isDepthCroppingSupported () const noexcept;
 
       /** \brief returns the focal length for the color camera in pixels. The pixels are assumed to be square.
         *        Result depends on the output resolution of the image.
         */
       inline float 
-      getImageFocalLength (int output_x_resolution = 0) const throw ();
+      getImageFocalLength (int output_x_resolution = 0) const noexcept;
 
       /** \brief returns the focal length for the IR camera in pixels. The pixels are assumed to be square.
         *        Result depends on the output resolution of the depth image.
         */
       inline float 
-      getDepthFocalLength (int output_x_resolution = 0) const throw ();
+      getDepthFocalLength (int output_x_resolution = 0) const noexcept;
 
       /** \return Baseline of the "stereo" frame. i.e. for PSDK compatible devices its the distance between the Projector and the IR camera. */
       inline float 
-      getBaseline () const throw ();
+      getBaseline () const noexcept;
 
       /** \brief starts the image stream. */
       virtual void 
@@ -259,27 +259,27 @@ namespace openni_wrapper
 
       /** \return true if the device supports an image stream, false otherwise. */
       bool 
-      hasImageStream () const throw ();
+      hasImageStream () const noexcept;
 
       /** \return true if the device supports a depth stream, false otherwise. */
       bool 
-      hasDepthStream () const throw ();
+      hasDepthStream () const noexcept;
 
       /** \return true if the device supports an IR stream, false otherwise. */
       bool 
-      hasIRStream () const throw ();
+      hasIRStream () const noexcept;
 
       /** \return true if the image stream is running / started, false otherwise. */
       virtual bool 
-      isImageStreamRunning () const throw ();
+      isImageStreamRunning () const noexcept;
 
       /** \return true if the depth stream is running / started, false otherwise. */
       virtual bool 
-      isDepthStreamRunning () const throw ();
+      isDepthStreamRunning () const noexcept;
 
       /** \return true if the IR stream is running / started, false otherwise. */
       virtual bool 
-      isIRStreamRunning () const throw ();
+      isIRStreamRunning () const noexcept;
 
       /** \brief registers a callback function of std::function type for the image stream with an optional user defined parameter.
         *        The callback will always be called with a new image and the user data "cookie".
@@ -367,35 +367,35 @@ namespace openni_wrapper
         * \attention This might be an empty string!!!
         */
       const char* 
-      getSerialNumber () const throw ();
+      getSerialNumber () const noexcept;
 
       /** \brief returns the connection string for current device, which has following format vendorID/productID\@BusID/DeviceID. */
       const char* 
-      getConnectionString () const throw ();
+      getConnectionString () const noexcept;
 
       /** \return the Vendor name of the USB device. */
       const char* 
-      getVendorName () const throw ();
+      getVendorName () const noexcept;
 
       /** \return the product name of the USB device. */
       const char* 
-      getProductName () const throw ();
+      getProductName () const noexcept;
 
       /** \return the vendor ID of the USB device. */
       unsigned short 
-      getVendorID () const throw ();
+      getVendorID () const noexcept;
 
       /** \return the product ID of the USB device. */
       unsigned short 
-      getProductID () const throw ();
+      getProductID () const noexcept;
 
       /** \return the USB bus on which the device is connected. */
       unsigned char  
-      getBus () const throw ();
+      getBus () const noexcept;
 
       /** \return the USB Address of the device. */
       unsigned char  
-      getAddress () const throw ();
+      getAddress () const noexcept;
 
       /** \brief Set the RGB image focal length.
         * \param[in] focal_length the RGB image focal length
@@ -469,13 +469,13 @@ namespace openni_wrapper
       IRDataThreadFunction ();
 
       virtual bool 
-      isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const  throw () = 0;
+      isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const  noexcept = 0;
 
       void 
       setRegistration (bool on_off);
 
       virtual Image::Ptr
-      getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_data) const throw () = 0;
+      getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_data) const noexcept = 0;
 
       void 
       Init ();
@@ -485,7 +485,7 @@ namespace openni_wrapper
 
       struct ShiftConversion
       {
-        ShiftConversion() : init_(false) {}
+        ShiftConversion() = default;
 
         XnUInt16 zero_plane_distance_;
         XnFloat zero_plane_pixel_size_;
@@ -498,7 +498,7 @@ namespace openni_wrapper
         XnUInt32 shift_scale_;
         XnUInt32 min_depth_;
         XnUInt32 max_depth_;
-        bool init_;
+        bool init_{false};
 
       } shift_conversion_parameters_;
 
@@ -560,7 +560,7 @@ namespace openni_wrapper
 
   ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
   float
-  OpenNIDevice::getImageFocalLength (int output_x_resolution) const throw ()
+  OpenNIDevice::getImageFocalLength (int output_x_resolution) const noexcept
   {
     if (output_x_resolution == 0)
       output_x_resolution = getImageOutputMode ().nXRes;
@@ -571,7 +571,7 @@ namespace openni_wrapper
 
   ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
   float
-  OpenNIDevice::getDepthFocalLength (int output_x_resolution) const throw ()
+  OpenNIDevice::getDepthFocalLength (int output_x_resolution) const noexcept
   {
     if (output_x_resolution == 0)
       output_x_resolution = getDepthOutputMode ().nXRes;
@@ -584,7 +584,7 @@ namespace openni_wrapper
 
   ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
   float
-  OpenNIDevice::getBaseline () const throw ()
+  OpenNIDevice::getBaseline () const noexcept
   {
     return (baseline_);
   }
index 00c4d82fe9209749962f9f5cd82ba459e189d57f..36d476e213dcf9b347af414e22a71a975ddf8b1f 100644 (file)
@@ -61,15 +61,15 @@ namespace openni_wrapper
     ~DeviceKinect () noexcept override;
 
     inline void setDebayeringMethod (const ImageBayerGRBG::DebayeringMethod& debayering_method) noexcept;
-    inline const ImageBayerGRBG::DebayeringMethod& getDebayeringMethod () const throw ();
+    inline const ImageBayerGRBG::DebayeringMethod& getDebayeringMethod () const noexcept;
 
-    bool isSynchronizationSupported () const throw () override;
+    bool isSynchronizationSupported () const noexcept override;
 
   protected:
-    Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const throw () override;
+    Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const noexcept override;
     void enumAvailableModes () noexcept;
-    bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override;
-    ImageBayerGRBG::DebayeringMethod debayering_method_;
+    bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override;
+    ImageBayerGRBG::DebayeringMethod debayering_method_{ImageBayerGRBG::EdgeAwareWeighted};
   } ;
 
   void
@@ -79,7 +79,7 @@ namespace openni_wrapper
   }
 
   const ImageBayerGRBG::DebayeringMethod&
-  DeviceKinect::getDebayeringMethod () const throw ()
+  DeviceKinect::getDebayeringMethod () const noexcept
   {
     return debayering_method_;
   }
index 31519eb89a0fcc37b2be8899f766cd791054ec1a..9f09c39d6743bd43862db42c96a463b808a6cba3 100644 (file)
@@ -77,11 +77,11 @@ namespace openni_wrapper
     void startIRStream () override;
     void stopIRStream () override;
 
-    bool isImageStreamRunning () const throw () override;
-    bool isDepthStreamRunning () const throw () override;
-    bool isIRStreamRunning () const throw () override;
+    bool isImageStreamRunning () const noexcept override;
+    bool isDepthStreamRunning () const noexcept override;
+    bool isIRStreamRunning () const noexcept override;
 
-    bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override;
+    bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override;
 
     /** \brief Trigger a new frame in the ONI stream.
       * \param[in] relative_offset the relative offset in case we want to seek in the file
@@ -89,7 +89,7 @@ namespace openni_wrapper
     bool 
     trigger (int relative_offset = 0);
 
-    bool isStreaming () const throw ();
+    bool isStreaming () const noexcept;
 
     /** \brief Check if there is any data left in the ONI file to process. */
     inline bool
@@ -99,7 +99,7 @@ namespace openni_wrapper
     }
 
   protected:
-    Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const throw () override;
+    Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const noexcept override;
 
     void PlayerThreadFunction ();
     static void __stdcall NewONIDepthDataAvailable (xn::ProductionNode& node, void* cookie) noexcept;
@@ -111,9 +111,9 @@ namespace openni_wrapper
     mutable std::mutex player_mutex_;
     std::condition_variable player_condition_;
     bool streaming_;
-    bool depth_stream_running_;
-    bool image_stream_running_;
-    bool ir_stream_running_;
+    bool depth_stream_running_{false};
+    bool image_stream_running_{false};
+    bool ir_stream_running_{false};
   };
 } //namespace openni_wrapper
 #endif //HAVE_OPENNI
index 4d22640f8fadacad12aa5c681fb8df619618e997..1727b459746ce30f8656956e08ec0d2d8e1fcd8a 100644 (file)
@@ -63,9 +63,9 @@ public:
   //virtual void setImageOutputMode (const XnMapOutputMode& output_mode);
 
 protected:
-  Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const throw () override;
+  Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const noexcept override;
   void enumAvailableModes () noexcept;
-  bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override;
+  bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override;
 
   void startImageStream () override;
   void startDepthStream () override;
index ad8d71746be5654e93d87b443001d6b8c54d8753..27ee8fa12b9b04f1cf88cd46dcec89a7fc07b6ca 100644 (file)
@@ -65,9 +65,9 @@ namespace openni_wrapper
     //virtual void setImageOutputMode (const XnMapOutputMode& output_mode);
 
   protected:
-    Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const throw () override;
+    Image::Ptr getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const noexcept override;
     void enumAvailableModes () noexcept;
-    bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override;
+    bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override;
 
     void startDepthStream () override;
   } ;
index 747461e1c8d0c67747a09b7a0ea47358365da47f..3ba7692c3e4453870b76b47d7abed2774732103a 100644 (file)
@@ -89,7 +89,7 @@ namespace openni_wrapper
      * @author Suat Gedikli
      * @return the number of available devices.
      */
-    inline unsigned getNumberDevices () const throw ();
+    inline unsigned getNumberDevices () const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -134,7 +134,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the serial number of the device.
      */
-    const char* getSerialNumber (unsigned index) const throw ();
+    const char* getSerialNumber (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -142,7 +142,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the connection string of the device.
      */
-    const char* getConnectionString (unsigned index) const throw ();
+    const char* getConnectionString (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -150,7 +150,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the vendor name of the USB device.
      */
-    const char* getVendorName (unsigned index) const throw ();
+    const char* getVendorName (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -158,7 +158,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the product name of the USB device.
      */
-    const char* getProductName (unsigned index) const throw ();
+    const char* getProductName (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -166,7 +166,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the vendor id of the USB device.
      */
-    unsigned short getVendorID (unsigned index) const throw ();
+    unsigned short getVendorID (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -174,7 +174,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the product id of the USB device.
      */
-    unsigned short getProductID (unsigned index) const throw ();
+    unsigned short getProductID (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -182,7 +182,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the bus id of the USB device.
      */
-    unsigned char  getBus (unsigned index) const throw ();
+    unsigned char  getBus (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -190,7 +190,7 @@ namespace openni_wrapper
      * @param[in] index the index of the device in the device list.
      * @return the address of the USB device.
      */
-    unsigned char  getAddress (unsigned index) const throw ();
+    unsigned char  getAddress (unsigned index) const noexcept;
 
     /**
      * @author Suat Gedikli
@@ -245,7 +245,7 @@ namespace openni_wrapper
   }
 
   unsigned
-  OpenNIDriver::getNumberDevices () const throw ()
+  OpenNIDriver::getNumberDevices () const noexcept
   {
     return static_cast<unsigned> (device_context_.size ());
   }
index 37c56a0d94925b781a13e713a0fdf8f88e49dc84..85e0f19a3284143f59f8a2e538eb0ffb710789a6 100644 (file)
@@ -46,7 +46,7 @@
 //#include <pcl/pcl_macros.h> <-- because current header is included in NVCC-compiled code and contains <Eigen/Core>. Consider <pcl/pcl_exports.h>
 
 
-//fom <pcl/pcl_macros.h>
+//from <pcl/pcl_macros.h>
 #if defined _WIN32 && defined _MSC_VER && !defined __PRETTY_FUNCTION__
   #define __PRETTY_FUNCTION__ __FUNCTION__  
 #endif
@@ -93,22 +93,22 @@ namespace openni_wrapper
      * @brief virtual method, derived from std::exception
      * @return the message of the exception.
      */
-    const char* what () const throw () override;
+    const char* what () const noexcept override;
 
     /**
      * @return the function name in which the exception was created.
      */
-    const std::string& getFunctionName () const throw ();
+    const std::string& getFunctionName () const noexcept;
 
     /**
      * @return the filename in which the exception was created.
      */
-    const std::string& getFileName () const throw ();
+    const std::string& getFileName () const noexcept;
 
     /**
      * @return the line number where the exception was created.
      */
-    unsigned getLineNumber () const throw ();
+    unsigned getLineNumber () const noexcept;
   protected:
     std::string function_name_;
     std::string file_name_;
index 1a3c4b2c67b0e9bb1ad4a976a6bd68b84e19225f..f42f884f527e0f65b5d01f44de6f85e0cabfb9ae 100644 (file)
@@ -116,7 +116,7 @@ namespace openni_wrapper
      * @param[in,out] rgb_buffer
      */
     inline void
-    fillRaw (unsigned char* rgb_buffer) const throw ()
+    fillRaw (unsigned char* rgb_buffer) const noexcept
     {
       memcpy (rgb_buffer, image_md_->Data (), image_md_->DataSize ());
     }
@@ -136,33 +136,33 @@ namespace openni_wrapper
      * @author Suat Gedikli
      * @return width of the image
      */
-    inline unsigned getWidth () const throw ();
+    inline unsigned getWidth () const noexcept;
 
     /**
      * @author Suat Gedikli
      * @return height of the image
      */
-    inline unsigned getHeight () const throw ();
+    inline unsigned getHeight () const noexcept;
 
     /**
      * @author Suat Gedikli
      * @return frame id of the image.
      * @note frame ids are ascending, but not necessarily synch'ed with other streams
      */
-    inline unsigned getFrameID () const throw ();
+    inline unsigned getFrameID () const noexcept;
 
     /**
      * @author Suat Gedikli
      * @return the time stamp of the image
      * @note the time value is not synche'ed with the system time
      */
-    inline unsigned long getTimeStamp () const throw ();
+    inline unsigned long getTimeStamp () const noexcept;
 
     /**
      * @author Suat Gedikli
      * @return the actual data in native OpenNI format.
      */
-    inline const xn::ImageMetaData& getMetaData () const throw ();
+    inline const xn::ImageMetaData& getMetaData () const noexcept;
 
   protected:
     pcl::shared_ptr<xn::ImageMetaData> image_md_;
@@ -176,31 +176,31 @@ namespace openni_wrapper
   Image::~Image () noexcept = default;
 
   unsigned
-  Image::getWidth () const throw ()
+  Image::getWidth () const noexcept
   {
     return image_md_->XRes ();
   }
 
   unsigned
-  Image::getHeight () const throw ()
+  Image::getHeight () const noexcept
   {
     return image_md_->YRes ();
   }
 
   unsigned
-  Image::getFrameID () const throw ()
+  Image::getFrameID () const noexcept
   {
     return image_md_->FrameID ();
   }
 
   unsigned long
-  Image::getTimeStamp () const throw ()
+  Image::getTimeStamp () const noexcept
   {
     return static_cast<unsigned long> (image_md_->Timestamp ());
   }
 
   const xn::ImageMetaData&
-  Image::getMetaData () const throw ()
+  Image::getMetaData () const noexcept
   {
     return *image_md_;
   }
index 052387f7d32d17d820f4bc38b76a9fe6777e9d15..cd09c26338e5c69b631bbdf50d2559583fda131a 100644 (file)
@@ -74,7 +74,7 @@ namespace openni_wrapper
       void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const override;
       bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const override;
       inline void setDebayeringMethod (const DebayeringMethod& method) noexcept;
-      inline DebayeringMethod getDebayeringMethod () const throw ();
+      inline DebayeringMethod getDebayeringMethod () const noexcept;
       inline static bool resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height);
 
 
@@ -89,7 +89,7 @@ namespace openni_wrapper
   }
 
   ImageBayerGRBG::DebayeringMethod
-  ImageBayerGRBG::getDebayeringMethod () const throw ()
+  ImageBayerGRBG::getDebayeringMethod () const noexcept
   {
     return debayering_method_;
   }
index 7320ef6133945cf849c6476a6fbcce7876e207c3..e06b4bab4d5742dc592e9f74377aaaf7fcde5104 100644 (file)
@@ -59,11 +59,11 @@ public:
 
   void fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step = 0) const;
 
-  inline unsigned getWidth () const throw ();
-  inline unsigned getHeight () const throw ();
-  inline unsigned getFrameID () const throw ();
-  inline unsigned long getTimeStamp () const throw ();
-  inline const xn::IRMetaData& getMetaData () const throw ();
+  inline unsigned getWidth () const noexcept;
+  inline unsigned getHeight () const noexcept;
+  inline unsigned getFrameID () const noexcept;
+  inline unsigned long getTimeStamp () const noexcept;
+  inline const xn::IRMetaData& getMetaData () const noexcept;
 
 protected:
   pcl::shared_ptr<xn::IRMetaData> ir_md_;
@@ -76,27 +76,27 @@ IRImage::IRImage (pcl::shared_ptr<xn::IRMetaData> ir_meta_data) noexcept
 
 IRImage::~IRImage () noexcept = default;
 
-unsigned IRImage::getWidth () const throw ()
+unsigned IRImage::getWidth () const noexcept
 {
   return ir_md_->XRes ();
 }
 
-unsigned IRImage::getHeight () const throw ()
+unsigned IRImage::getHeight () const noexcept
 {
   return ir_md_->YRes ();
 }
 
-unsigned IRImage::getFrameID () const throw ()
+unsigned IRImage::getFrameID () const noexcept
 {
   return ir_md_->FrameID ();
 }
 
-unsigned long IRImage::getTimeStamp () const throw ()
+unsigned long IRImage::getTimeStamp () const noexcept
 {
   return static_cast<unsigned long> (ir_md_->Timestamp ());
 }
 
-const xn::IRMetaData& IRImage::getMetaData () const throw ()
+const xn::IRMetaData& IRImage::getMetaData () const noexcept
 {
        return *ir_md_;
 }
index af911a947e7b3dfcf1185d0dc926fc6e69b3452f..b5f6258630dcb5293bd4d4fd549f3e5ebe9cfee7 100644 (file)
@@ -41,6 +41,7 @@
 #include <pcl/pcl_config.h>
 #ifdef HAVE_OPENNI
 
+#include <cassert> // for assert
 #include <cstdint>
 #include <vector>
 #include <limits>
@@ -53,7 +54,7 @@ namespace openni_wrapper
   {
     public:
       /** \brief Constructor. */
-      ShiftToDepthConverter () : init_(false) {}
+      ShiftToDepthConverter () = default;
 
       /** \brief Destructor. */
       virtual ~ShiftToDepthConverter () = default;
@@ -113,7 +114,7 @@ namespace openni_wrapper
 
     protected:
       std::vector<float> lookupTable_;
-      bool init_;
+      bool init_{false};
   } ;
 }
 
index d97ca6623c5f799d78abd5d218ebaf7b5ce38094..abcb95ee7ee06832f9b74d9bf8998eedc79a7634 100644 (file)
@@ -422,25 +422,25 @@ namespace pcl
 
       std::string rgb_frame_id_;
       std::string depth_frame_id_;
-      unsigned image_width_;
-      unsigned image_height_;
-      unsigned depth_width_;
-      unsigned depth_height_;
-
-      bool image_required_;
-      bool depth_required_;
-      bool ir_required_;
-      bool sync_required_;
-
-      boost::signals2::signal<sig_cb_openni_image>* image_signal_;
-      boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_;
-      boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_;
-      boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
-      boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_;
-      boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_;
+      unsigned image_width_{0};
+      unsigned image_height_{0};
+      unsigned depth_width_{0};
+      unsigned depth_height_{0};
+
+      bool image_required_{false};
+      bool depth_required_{false};
+      bool ir_required_{false};
+      bool sync_required_{false};
+
+      boost::signals2::signal<sig_cb_openni_image>* image_signal_{};
+      boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_{};
+      boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_{};
 
       struct modeComp
       {
@@ -460,13 +460,13 @@ namespace pcl
       } ;
       std::map<int, XnMapOutputMode> config2xn_map_;
 
-      openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle;
-      openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle;
-      openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle;
-      bool running_;
+      openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle{};
+      openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle{};
+      openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle{};
+      bool running_{false};
 
-      mutable unsigned rgb_array_size_;
-      mutable unsigned depth_buffer_size_;
+      mutable unsigned rgb_array_size_{0};
+      mutable unsigned depth_buffer_size_{0};
       mutable boost::shared_array<unsigned char> rgb_array_;
       mutable boost::shared_array<unsigned short> depth_buffer_;
       mutable boost::shared_array<unsigned short> ir_buffer_;
index 7b825ab9179680fcf712485d1d0e6189559951df..bc95c57f38d0083364750b23a061fddf14d6ab2d 100644 (file)
@@ -204,7 +204,7 @@ namespace pcl
         * \param[out] cloud the resultant point cloud dataset to be filled.
         * \param[in] pcd_version the PCD version of the stream (from readHeader()).
         * \param[in] compressed indicates whether the PCD block contains compressed
-        * data.  This should be true if the data_type returne by readHeader() == 2.
+        * data.  This should be true if the data_type returned by readHeader() == 2.
         * \param[in] data_idx the offset of the body, as reported by readHeader().
         *
         * \return
@@ -284,6 +284,7 @@ namespace pcl
         // If no error, convert the data
         if (res == 0)
           pcl::fromPCLPointCloud2 (blob, cloud);
+
         return (res);
       }
 
@@ -297,7 +298,7 @@ namespace pcl
   class PCL_EXPORTS PCDWriter : public FileWriter
   {
     public:
-      PCDWriter() : map_synchronization_(false) {}
+      PCDWriter() = default;
       ~PCDWriter() override = default;
 
       /** \brief Set whether mmap() synchornization via msync() is desired before munmap() calls.
@@ -402,6 +403,17 @@ namespace pcl
                    const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
                    const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ());
 
+      /** \brief Save point cloud data to a std::ostream containing n-D points, in BINARY format
+        * \param[out] os the stream into which to write the data
+        * \param[in] cloud the point cloud data message
+        * \param[in] origin the sensor acquisition origin
+        * \param[in] orientation the sensor acquisition orientation
+        */
+      int
+      writeBinary (std::ostream &os, const pcl::PCLPointCloud2 &cloud,
+                   const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
+                   const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ());
+
       /** \brief Save point cloud data to a PCD file containing n-D points, in BINARY_COMPRESSED format
         * \param[in] file_name the output file name
         * \param[in] cloud the point cloud data message
@@ -603,7 +615,7 @@ namespace pcl
 
     private:
       /** \brief Set to true if msync() should be called before munmap(). Prevents data loss on NFS systems. */
-      bool map_synchronization_;
+      bool map_synchronization_{false};
   };
 
   namespace io
index a64eaf219de5eb49df9419853b8dddd470ee2d78..3023d566607e053f22a1f73b3f736c03fc44fbe9 100644 (file)
@@ -293,9 +293,7 @@ namespace pcl
           using flags_type = int;
           enum flags { };
 
-          ply_parser () :
-            line_number_ (0), current_element_ ()
-          {}
+          ply_parser () = default;
               
           bool parse (const std::string& filename);
           //inline bool parse (const std::string& filename);
@@ -414,8 +412,8 @@ namespace pcl
                                const typename list_property_element_callback_type<SizeType, ScalarType>::type& list_property_element_callback, 
                                const typename list_property_end_callback_type<SizeType, ScalarType>::type& list_property_end_callback);
             
-          std::size_t line_number_;
-          element* current_element_;
+          std::size_t line_number_{0};
+          element* current_element_{nullptr};
       };
     } // namespace ply
   } // namespace io
@@ -565,7 +563,7 @@ inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format,
     if (!istream || !isspace (space))
     {
       if (error_callback_)
-        error_callback_ (line_number_, "parse error");
+        error_callback_ (line_number_, "error while parsing scalar property (file format: ascii)");
       return (false);
     }
     if (scalar_property_callback)
@@ -577,7 +575,7 @@ inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format,
   if (!istream)
   {
     if (error_callback_)
-      error_callback_ (line_number_, "parse error");
+      error_callback_ (line_number_, "error while parsing scalar property (file format: binary)");
     return (false);
   }
   if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) ||
@@ -610,7 +608,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
     {
       if (error_callback_)
       {
-        error_callback_ (line_number_, "parse error");
+        error_callback_ (line_number_, "error while parsing list (file format: ascii)");
       }
       return (false);
     }
@@ -641,7 +639,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
       {
         if (error_callback_)
         {
-          error_callback_ (line_number_, "parse error");
+          error_callback_ (line_number_, "error while parsing list (file format: ascii)");
         }
         return (false);
       }
@@ -667,7 +665,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
   {
     if (error_callback_)
     {
-      error_callback_ (line_number_, "parse error");
+      error_callback_ (line_number_, "error while parsing list (file format: binary)");
     }
     return (false);
   }
@@ -680,7 +678,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s
     istream.read (reinterpret_cast<char*> (&value), sizeof (scalar_type));
     if (!istream) {
       if (error_callback_) {
-        error_callback_ (line_number_, "parse error");
+        error_callback_ (line_number_, "error while parsing list (file format: binary)");
       }
       return (false);
     }
index 6df337227a42676107103b2101bfe31df338717a..86e540771aed96879fef7aaa3ee04249cc857b37 100644 (file)
@@ -88,30 +88,12 @@ namespace pcl
       
       PLYReader ()
         : origin_ (Eigen::Vector4f::Zero ())
-        , orientation_ (Eigen::Matrix3f::Zero ())
-        , cloud_ ()
-        , vertex_count_ (0)
-        , vertex_offset_before_ (0)
-        , range_grid_ (nullptr)
-        , rgb_offset_before_ (0)
-        , do_resize_ (false)
-        , polygons_ (nullptr)
-        , r_(0), g_(0), b_(0)
-        , a_(0), rgba_(0)
+        , orientation_ (Eigen::Matrix3f::Identity ())
       {}
 
       PLYReader (const PLYReader &p)
         : origin_ (Eigen::Vector4f::Zero ())
-        , orientation_ (Eigen::Matrix3f::Zero ())
-        , cloud_ ()
-        , vertex_count_ (0)
-        , vertex_offset_before_ (0)
-        , range_grid_ (nullptr)
-        , rgb_offset_before_ (0)
-        , do_resize_ (false)
-        , polygons_ (nullptr)
-        , r_(0), g_(0), b_(0)
-        , a_(0), rgba_(0)
+        , orientation_ (Eigen::Matrix3f::Identity ())
       {
         *this = p;
       }
@@ -138,8 +120,8 @@ namespace pcl
         *  * > 0 on success
         * \param[in] file_name the name of the file to load
         * \param[out] cloud the resultant point cloud dataset (only the header will be filled)
-        * \param[in] origin the sensor data acquisition origin (translation)
-        * \param[in] orientation the sensor data acquisition origin (rotation)
+        * \param[out] origin the sensor data acquisition origin (translation)
+        * \param[out] orientation the sensor data acquisition origin (rotation)
         * \param[out] ply_version the PLY version read from the file
         * \param[out] data_type the type of PLY data stored in the file
         * \param[out] data_idx the data index
@@ -157,8 +139,8 @@ namespace pcl
       /** \brief Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2.
         * \param[in] file_name the name of the file containing the actual PointCloud data
         * \param[out] cloud the resultant PointCloud message read from disk
-        * \param[in] origin the sensor data acquisition origin (translation)
-        * \param[in] orientation the sensor data acquisition origin (rotation)
+        * \param[out] origin the sensor data acquisition origin (translation)
+        * \param[out] orientation the sensor data acquisition origin (rotation)
         * \param[out] ply_version the PLY version read from the file
         * \param[in] offset the offset in the file where to expect the true header to begin.
         * One usage example for setting the offset parameter is for reading
@@ -217,8 +199,8 @@ namespace pcl
         *
         * \param[in] file_name the name of the file containing the actual PointCloud data
         * \param[out] mesh the resultant PolygonMesh message read from disk
-        * \param[in] origin the sensor data acquisition origin (translation)
-        * \param[in] orientation the sensor data acquisition origin (rotation)
+        * \param[out] origin the sensor data acquisition origin (translation)
+        * \param[out] orientation the sensor data acquisition origin (rotation)
         * \param[out] ply_version the PLY version read from the file
         * \param[in] offset the offset in the file where to expect the true header to begin.
         * One usage example for setting the offset parameter is for reading
@@ -524,23 +506,23 @@ namespace pcl
       Eigen::Matrix3f orientation_;
 
       //vertex element artifacts
-      pcl::PCLPointCloud2 *cloud_;
-      std::size_t vertex_count_;
-      int vertex_offset_before_;
+      pcl::PCLPointCloud2 *cloud_{nullptr};
+      std::size_t vertex_count_{0};
+      int vertex_offset_before_{0};
       //range element artifacts
-      std::vector<std::vector <int> > *range_grid_;
-      std::size_t rgb_offset_before_;
-      bool do_resize_;
+      std::vector<std::vector <int> > *range_grid_{nullptr};
+      std::size_t rgb_offset_before_{0};
+      bool do_resize_{false};
       //face element artifact
-      std::vector<pcl::Vertices> *polygons_;
+      std::vector<pcl::Vertices> *polygons_{nullptr};
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
       
     private:
       // RGB values stored by vertexColorCallback()
-      std::int32_t r_, g_, b_;
+      std::int32_t r_{0}, g_{0}, b_{0};
       // Color values stored by vertexAlphaCallback()
-      std::uint32_t a_, rgba_;
+      std::uint32_t a_{0}, rgba_{0};
   };
 
   /** \brief Point Cloud Data (PLY) file format writer.
@@ -756,9 +738,9 @@ namespace pcl
 
     /** \brief Load any PLY file into a PCLPointCloud2 type.
       * \param[in] file_name the name of the file to load
-      * \param[in] cloud the resultant templated point cloud
-      * \param[in] origin the sensor acquisition origin (only for > PLY_V7 - null if not present)
-      * \param[in] orientation the sensor acquisition orientation if available, 
+      * \param[out] cloud the resultant templated point cloud
+      * \param[out] origin the sensor acquisition origin (only for > PLY_V7 - null if not present)
+      * \param[out] orientation the sensor acquisition orientation if available, 
       * identity if not present
       * \ingroup io
       */
index 5c8993a082063cd2f2e2a16c868c32797ec448ca..d7f47646df8463d4c898c1f5d7d48832eeaec04a 100644 (file)
@@ -84,9 +84,7 @@ namespace pcl
         using ConstPtr = shared_ptr<const PointCloudImageExtractor<PointT> >;
 
         /** \brief Constructor. */
-        PointCloudImageExtractor ()
-        : paint_nans_with_black_ (false)
-        {}
+        PointCloudImageExtractor () = default;
 
         /** \brief Destructor. */
         virtual ~PointCloudImageExtractor () = default;
@@ -118,7 +116,7 @@ namespace pcl
 
         /// A flag that controls if image pixels corresponding to NaN (infinite)
         /// points should be painted black.
-        bool paint_nans_with_black_;
+        bool paint_nans_with_black_{false};
     };
 
     //////////////////////////////////////////////////////////////////////////////////////
@@ -303,7 +301,7 @@ namespace pcl
 
       private:
 
-        ColorMode color_mode_;
+        ColorMode color_mode_{COLORS_MONO};
     };
 
     //////////////////////////////////////////////////////////////////////////////////////
index 6124810146869ba7f3af94c10ec0bfb590040446..50e305a9ae2244ab90764123bdb41f874c594328 100644 (file)
@@ -101,7 +101,8 @@ namespace pcl
 
     /** \brief defined grabber name*/
     std::string
-    getName () const override { return std::string ( "RealSense2Grabber" ); }
+    getName () const override {
+      return {"RealSense2Grabber"}; }
 
     //define callback signature typedefs
     using signal_librealsense_PointXYZ = void( const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& );
@@ -198,17 +199,17 @@ namespace pcl
     /** \brief Repeat playback when reading from file */
     bool repeat_playback_;
     /** \brief controlling the state of the thread. */
-    bool quit_;
+    bool quit_{false};
     /** \brief Is the grabber running. */
-    bool running_;
+    bool running_{false};
     /** \brief Calculated FPS for the grabber. */
-    float fps_;
+    float fps_{0.0f};
     /** \brief Width for the depth and color sensor. Default 424*/
-    std::uint32_t device_width_;
+    std::uint32_t device_width_{424};
     /** \brief Height for the depth and color sensor. Default 240 */
-    std::uint32_t device_height_;
+    std::uint32_t device_height_{240};
     /** \brief Target FPS for the device. Default 30. */
-    std::uint32_t target_fps_;
+    std::uint32_t target_fps_{30};
     /** \brief Declare pointcloud object, for calculating pointclouds and texture mappings */
     rs2::pointcloud pc_;
     /** \brief Declare RealSense pipeline, encapsulating the actual device and sensors */
index 9a28c90e34d87d1fbdbbc436dd22166aa19be747..ec59640a4e4b6de9b7ccc7833ebc3f2a7987b775 100644 (file)
@@ -14,7 +14,7 @@ namespace pcl {
 
 /** \brief Lightweight tokenization function
  * This function can be used as a boost::split substitute. When benchmarked against
- * boost, this function will create much less alocations and hence it is much better
+ * boost, this function will create much less allocations and hence it is much better
  * suited for quick line tokenization.
  *
  * Cool thing is this function will work with SequenceSequenceT =
index 210ecc96820013a1fad1903713989700405e8b95..fbe997d07d0b3a3a478e46c763acfc5af914c385 100644 (file)
@@ -44,7 +44,7 @@ namespace pcl
   namespace io
   {
     /** \brief A TAR file's header, as described on 
-      * http://en.wikipedia.org/wiki/Tar_%28file_format%29. 
+      * https://en.wikipedia.org/wiki/Tar_%28file_format%29.
       */
     struct TARHeader
     {
index 654d4ca60fcd2a960d2398203358cb6e909b2617..786e501b967e07a7fb8b71dd2ba3264d56ad3e80 100644 (file)
@@ -25,7 +25,7 @@
 namespace pcl
 {
 
-//// note: Protcol named CoLaA (used by SICK) has some information.
+//// note: Protocol named CoLaA (used by SICK) has some information.
 ////       In this Grabber, only the amount_of_data is used, so other information is truncated.
 ////       Details of the protocol can be found at the following URL.
 
diff --git a/io/include/pcl/io/timestamp.h b/io/include/pcl/io/timestamp.h
new file mode 100644 (file)
index 0000000..ca987a9
--- /dev/null
@@ -0,0 +1,77 @@
+/*
+ * SPDX-License-Identifier: BSD-3-Clause
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2023-, Open Perception
+ *
+ *  All rights reserved
+ */
+
+#include <pcl/pcl_exports.h>
+
+#include <chrono>
+#include <iomanip>
+#include <sstream>
+#include <string>
+
+namespace pcl {
+/**
+ * @brief Returns a timestamp in local time as string formatted like boosts to_iso_string see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string
+ * Example: 19750101T235959.123456
+ * @param time std::chrono::timepoint to convert, defaults to now
+ * @return std::string containing the timestamp
+*/
+PCL_EXPORTS inline std::string
+getTimestamp(const std::chrono::time_point<std::chrono::system_clock>& time =
+                 std::chrono::system_clock::now())
+{
+  const auto us =
+      std::chrono::duration_cast<std::chrono::microseconds>(time.time_since_epoch());
+
+  const auto s = std::chrono::duration_cast<std::chrono::seconds>(us);
+  std::time_t tt = s.count();
+  std::size_t fractional_seconds = us.count() % 1000000;
+
+  std::tm tm = *std::localtime(&tt); // local time
+  std::stringstream ss;
+  ss << std::put_time(&tm, "%Y%m%dT%H%M%S");
+
+  if (fractional_seconds > 0) {
+    ss << "." << std::setw(6) << std::setfill('0') << fractional_seconds;
+  }
+
+  return ss.str();
+}
+
+/**
+ * @brief Parses a iso timestring (see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string) and returns a timepoint
+ * @param timestamp as string formatted like boost iso date
+ * @return std::chrono::time_point with system_clock
+*/
+PCL_EXPORTS inline std::chrono::time_point<std::chrono::system_clock>
+parseTimestamp(std::string timestamp)
+{
+  std::istringstream ss;
+
+  std::tm tm = {};
+
+  std::size_t fractional_seconds = 0;
+
+  ss.str(timestamp);
+  ss >> std::get_time(&tm, "%Y%m%dT%H%M%S");
+
+  auto timepoint = std::chrono::system_clock::from_time_t(std::mktime(&tm));
+
+  const auto pos = timestamp.find('.');
+
+  if (pos != std::string::npos) {
+    const auto frac_text = timestamp.substr(pos+1);  
+    ss.str(frac_text);
+    ss >> fractional_seconds;
+    timepoint += std::chrono::microseconds(fractional_seconds);
+  }
+
+  return timepoint;
+}
+
+} // namespace pcl
index caa55d019287cbd267470683006569cedd7a9662..9e0d3982fd55fe5a56a5087d2721760a19289f05 100644 (file)
@@ -4,7 +4,7 @@
   \section secIoPresentation Overview
   
   The \b pcl_io library contains classes and functions for reading and writing
-  point cloud data (PCD) files, as well as capturing point clouds from a
+  files, as well as capturing point clouds from a
   variety of sensing devices. An introduction to some of these capabilities can
   be found in the following tutorials:
 
        - <a href="http://pointclouds.org/documentation/tutorials/writing_pcd.php#writing-pcd">Writing PointCloud data to PCD files</a>
        - <a href="http://pointclouds.org/documentation/tutorials/openni_grabber.php#openni-grabber">The OpenNI Grabber Framework in PCL</a>
        - <a href="http://pointclouds.org/documentation/tutorials/ensenso_cameras.php">Grabbing point clouds from Ensenso cameras</a>
+
+  <table>
+    <caption>Reading from files</caption>
+    <tr><td></td><td>pcl::PointCloud</td><td>pcl::PCLPointCloud2</td><td>pcl::PolygonMesh</td><td>pcl::TextureMesh</td></tr>
+    <tr><td>PCD (ASCII/BINARY/COMPRESSED)</td><td>\link pcl::io::loadPCDFile(const std::string&,pcl::PointCloud<PointT>&) loadPCDFile \endlink</td><td>\link pcl::io::loadPCDFile(const std::string&,pcl::PCLPointCloud2&) loadPCDFile \endlink</td><td></td><td></td></tr>
+    <tr><td>PLY (ASCII/BINARY)</td><td>\link pcl::io::loadPLYFile(const std::string&,pcl::PointCloud<PointT>&) loadPLYFile \endlink</td><td>\link pcl::io::loadPLYFile(const std::string&,pcl::PCLPointCloud2&) loadPLYFile \endlink</td><td>\link pcl::io::loadPLYFile(const std::string&,pcl::PolygonMesh&) loadPLYFile \endlink</td><td></td></tr>
+    <tr><td>OBJ (ASCII)</td><td>\link pcl::io::loadOBJFile(const std::string&,pcl::PointCloud<PointT>&) loadOBJFile \endlink</td><td>\link pcl::io::loadOBJFile(const std::string&,pcl::PCLPointCloud2&) loadOBJFile \endlink</td><td>\link pcl::io::loadOBJFile(const std::string&,pcl::PolygonMesh&) loadOBJFile \endlink</td><td>\link pcl::io::loadOBJFile(const std::string&,pcl::TextureMesh&) loadOBJFile \endlink</td></tr>
+    <tr><td>IFS</td><td>\link pcl::io::loadIFSFile(const std::string&,pcl::PointCloud<PointT>&) loadIFSFile \endlink</td><td>\link pcl::io::loadIFSFile(const std::string&,pcl::PCLPointCloud2&) loadIFSFile \endlink</td><td>\link pcl::io::loadIFSFile(const std::string&,pcl::PolygonMesh&) loadIFSFile \endlink</td><td></td></tr>
+    <tr><td>STL (ASCII/BINARY)</td><td></td><td></td><td>\link pcl::io::loadPolygonFileSTL(const std::string&,pcl::PolygonMesh&) loadPolygonFileSTL \endlink</td><td></td></tr>
+    <tr><td>VTK</td><td></td><td></td><td>\link pcl::io::loadPolygonFileVTK(const std::string&,pcl::PolygonMesh&) loadPolygonFileVTK \endlink</td><td></td></tr>
+    <tr><td>CSV/ASCII</td><td colspan="2">via pcl::ASCIIReader</td><td></td><td></td></tr>
+    <tr><td>Automatic format detection</td><td>\link pcl::io::load(const std::string&,pcl::PointCloud<PointT>&) load \endlink</td><td>\link pcl::io::load(const std::string&,pcl::PCLPointCloud2&) load \endlink</td><td>\link pcl::io::load(const std::string&,pcl::PolygonMesh&) load \endlink</td><td>\link pcl::io::load(const std::string&,pcl::TextureMesh&) load \endlink</td></tr>
+  </table>
+
+  <table>
+    <caption>Writing to files</caption>
+    <tr><td></td><td>pcl::PointCloud</td><td>pcl::PCLPointCloud2</td><td>pcl::PolygonMesh</td><td>pcl::TextureMesh</td></tr>
+    <tr><td>PCD ASCII</td><td>\link pcl::io::savePCDFile(const std::string&,const pcl::PointCloud<PointT>&,bool) savePCDFile \endlink</td><td>\link pcl::io::savePCDFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,const bool) savePCDFile \endlink</td><td></td><td></td></tr>
+    <tr><td>PCD BINARY</td><td>\link pcl::io::savePCDFile(const std::string&,const pcl::PointCloud<PointT>&,bool) savePCDFile \endlink</td><td>\link pcl::io::savePCDFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,const bool) savePCDFile \endlink</td><td></td><td></td></tr>
+    <tr><td>PCD COMPRESSED</td><td>\link pcl::io::savePCDFileBinaryCompressed(const std::string&,const pcl::PointCloud<PointT>&) savePCDFileBinaryCompressed \endlink</td><td>via pcl::PCDWriter</td><td></td><td></td></tr>
+    <tr><td>PLY ASCII</td><td>\link pcl::io::savePLYFile(const std::string&,const pcl::PointCloud<PointT>&,bool) savePLYFile \endlink</td><td>\link pcl::io::savePLYFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,bool,bool) savePLYFile \endlink</td><td>\link pcl::io::savePLYFile(const std::string&,const pcl::PolygonMesh&,unsigned) savePLYFile \endlink</td><td></td></tr>
+    <tr><td>PLY BINARY</td><td>\link pcl::io::savePLYFile(const std::string&,const pcl::PointCloud<PointT>&,bool) savePLYFile \endlink</td><td>\link pcl::io::savePLYFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,bool,bool) savePLYFile \endlink</td><td>\link pcl::io::savePLYFileBinary(const std::string&,const pcl::PolygonMesh&) savePLYFileBinary \endlink</td><td></td></tr>
+    <tr><td>OBJ (ASCII)</td><td></td><td></td><td>\link pcl::io::saveOBJFile(const std::string&,const pcl::PolygonMesh&,unsigned) saveOBJFile \endlink</td><td>\link pcl::io::saveOBJFile(const std::string&,const pcl::TextureMesh&,unsigned) saveOBJFile \endlink</td></tr>
+    <tr><td>IFS</td><td>\link pcl::io::saveIFSFile(const std::string&,const pcl::PointCloud<PointT>&) saveIFSFile \endlink</td><td>\link pcl::io::saveIFSFile(const std::string&,const pcl::PCLPointCloud2&) saveIFSFile \endlink</td><td></td><td></td></tr>
+    <tr><td>STL (ASCII/BINARY)</td><td></td><td></td><td>\link pcl::io::savePolygonFileSTL(const std::string&,const pcl::PolygonMesh&,const bool) savePolygonFileSTL \endlink</td><td></td></tr>
+    <tr><td>VTK</td><td></td><td>\link pcl::io::saveVTKFile(const std::string&,const pcl::PCLPointCloud2&,unsigned) saveVTKFile \endlink</td><td>\link pcl::io::saveVTKFile(const std::string&,const pcl::PolygonMesh&,unsigned) saveVTKFile \endlink or \link pcl::io::savePolygonFileVTK(const std::string&,const pcl::PolygonMesh&,const bool) savePolygonFileVTK \endlink</td><td></td></tr>
+    <tr><td>Automatic format detection</td><td>\link pcl::io::save(const std::string&,const pcl::PointCloud<PointT>&) save \endlink</td><td>\link pcl::io::save(const std::string&,const pcl::PCLPointCloud2&,unsigned) save \endlink</td><td>\link pcl::io::save(const std::string&,const pcl::PolygonMesh&,unsigned) save \endlink</td><td>\link pcl::io::save(const std::string&,const pcl::TextureMesh&,unsigned) save \endlink</td></tr>
+  </table>
        
   PCL is agnostic with respect to the data sources that are used to generate 3D
   point clouds. While OpenNI-compatible cameras have recently been at the
index 00fd22bf27b5f9c7b69eeb9527729c5577f9c812..486ef5aba186b8f1edfe75711b146a65da49b98c 100644 (file)
@@ -95,7 +95,7 @@ pcl::ASCIIReader::readHeader (const std::string& file_name,
     PCL_ERROR ("[%s] File %s does not exist.\n", name_.c_str (), file_name.c_str ());
     return (-1);
   }
-  if (boost::filesystem::extension (fpath) != extension_)
+  if (fpath.extension ().string () != extension_)
   {
     PCL_ERROR ("[%s] File does not have %s extension. \n", name_.c_str(), extension_.c_str());
     return -1;
@@ -143,7 +143,7 @@ pcl::ASCIIReader::read (
 
   int total=0;
 
-  std::uint8_t* data = &cloud.data[0];
+  std::uint8_t* data = cloud.data.data();
   while (std::getline (ifile, line))
   {
     boost::algorithm::trim (line);
index d13fb4663d7b5edea755912e001435a8c80cb0e9..4c3da25feddb1ae42b61ff9b4df67108b6da0a47 100644 (file)
@@ -281,12 +281,12 @@ pcl::DavidSDKGrabber::grabSingleCloud (pcl::PointCloud<pcl::PointXYZ> &cloud)
     pcl::PolygonMesh mesh;
     if (file_format_ == "obj")
     {
-      if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, mesh) == 0)
+      if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, mesh) == 0)
         return (false);
     }
     else if (file_format_ == "ply")
     {
-      if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, mesh) == 0)
+      if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, mesh) == 0)
         return (false);
     }
     else if (file_format_ == "stl")
@@ -323,12 +323,12 @@ pcl::DavidSDKGrabber::grabSingleMesh (pcl::PolygonMesh &mesh)
 
     if (file_format_ == "obj")
     {
-      if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, mesh) == 0)
+      if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, mesh) == 0)
         return (false);
     }
     else if (file_format_ == "ply")
     {
-      if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, mesh) == 0)
+      if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, mesh) == 0)
         return (false);
     }
     else if (file_format_ == "stl")
@@ -400,12 +400,12 @@ pcl::DavidSDKGrabber::processGrabbing ()
 
           if (file_format_ == "obj")
           {
-            if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, *mesh) == 0)
+            if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, *mesh) == 0)
               return;
           }
           else if (file_format_ == "ply")
           {
-            if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, *mesh) == 0)
+            if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, *mesh) == 0)
               return;
           }
           else if (file_format_ == "stl")
index 4fd28781afd963edb5352eda9db79ef1dc1c2087..1cd33ba2beab0de2947cfb25c17687a62e0698e0 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 pcl::DinastGrabber::DinastGrabber (const int device_position)
-  : image_width_ (320)
-  , image_height_ (240)
-  , sync_packet_size_ (512)
-  , fov_ (64. * M_PI / 180.)
-  , context_ (nullptr)
-  , device_handle_ (nullptr)
-  , bulk_ep_ (std::numeric_limits<unsigned char>::max ())
-  , second_image_ (false)
-  , running_ (false)
 {
-  image_size_ = image_width_ * image_height_;
-  dist_max_2d_ = 1. / (image_width_ / 2.);
   onInit(device_position);
   
   point_cloud_signal_ = createSignal<sig_cb_dinast_point_cloud> ();
@@ -95,7 +84,7 @@ pcl::DinastGrabber::getFramesPerSecond () const
 { 
   static double last = pcl::getTime ();
   double now = pcl::getTime (); 
-  float rate = 1 / float(now - last);
+  float rate = 1 / static_cast<float>(now - last);
   last = now; 
 
   return (rate);
@@ -158,13 +147,13 @@ pcl::DinastGrabber::setupDevice (int device_position, const int id_vendor, const
     libusb_get_config_descriptor (devs[i], 0, &config);
 
     // Iterate over all interfaces available
-    for (int f = 0; f < int (config->bNumInterfaces); ++f)
+    for (int f = 0; f < static_cast<int>(config->bNumInterfaces); ++f)
     {
       // Iterate over the number of alternate settings
       for (int j = 0; j < config->interface[f].num_altsetting; ++j)
       {
         // Iterate over the number of end points present
-        for (int k = 0; k < int (config->interface[f].altsetting[j].bNumEndpoints); ++k) 
+        for (int k = 0; k < static_cast<int>(config->interface[f].altsetting[j].bNumEndpoints); ++k) 
         {
           if (config->interface[f].altsetting[j].endpoint[k].bmAttributes == LIBUSB_TRANSFER_TYPE_BULK)
           {
@@ -204,7 +193,7 @@ pcl::DinastGrabber::getDeviceVersion ()
      PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::getDeviceVersion] Error trying to get device version");
  
   //data[21] = 0;
-  return (std::string (reinterpret_cast<const char*> (data)));
+  return {reinterpret_cast<const char*>(data)};
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -262,7 +251,7 @@ pcl::DinastGrabber::readImage ()
     PCL_DEBUG ("[pcl::DinastGrabber::readImage] Read: %d, size of the buffer: %d\n" ,actual_length, g_buffer_.size ());
     
     // Copy data into the buffer
-    int back = int (g_buffer_.size ());
+    int back = static_cast<int>(g_buffer_.size ());
     g_buffer_.resize (back + actual_length);
 
     for (int i = 0; i < actual_length; ++i)
@@ -375,7 +364,7 @@ pcl::DinastGrabber::USBRxControlData (const unsigned char req_code,
   
   int nr_read = libusb_control_transfer (device_handle_, requesttype,
                                          req_code, value, index, buffer, static_cast<std::uint16_t> (length), timeout);
-  if (nr_read != int(length))
+  if (nr_read != (length))
     PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::USBRxControlData] Control data error");
 
   return (true);
@@ -399,7 +388,7 @@ pcl::DinastGrabber::USBTxControlData (const unsigned char req_code,
   
   int nr_read = libusb_control_transfer (device_handle_, requesttype,
                                          req_code, value, index, buffer, static_cast<std::uint16_t> (length), timeout);
-  if (nr_read != int(length))
+  if (nr_read != (length))
   {
     std::stringstream sstream;
     sstream << "[pcl::DinastGrabber::USBTxControlData] USB control data error, LIBUSB_ERROR: " << nr_read;
@@ -427,7 +416,7 @@ pcl::DinastGrabber::checkHeader ()
         (g_buffer_[i + 4] == 0xBB) && (g_buffer_[i + 5] == 0xBB) &&
         (g_buffer_[i + 6] == 0x77) && (g_buffer_[i + 7] == 0x77))
     {
-      data_ptr = int (i) + sync_packet_size_;
+      data_ptr = static_cast<int>(i) + sync_packet_size_;
       break;
     }
   }
index 1b3b6f09546ea282a9f14fbf5671e45fae101008..68feed4f43e3c04fda5267d82d7683cb4f96024f 100644 (file)
@@ -62,10 +62,7 @@ ensensoExceptionHandling (const NxLibException& ex,
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-pcl::EnsensoGrabber::EnsensoGrabber () :
-    device_open_ (false),
-    tcp_open_ (false),
-    running_ (false)
+pcl::EnsensoGrabber::EnsensoGrabber ()
 {
   point_cloud_signal_ = createSignal<sig_cb_ensenso_point_cloud> ();
   images_signal_ = createSignal<sig_cb_ensenso_images> ();
index d6234ea980d82dbcebafefe023b8e5d724468061..c54f68edf3709975b4e6a5c7ac85f7192b22c360 100644 (file)
@@ -536,6 +536,20 @@ pcl::HDLGrabber::stop ()
   terminate_read_packet_thread_ = true;
   hdl_data_.stopQueue ();
 
+  if (hdl_read_socket_ != nullptr)
+  {
+    try
+    {
+      hdl_read_socket_->shutdown (boost::asio::ip::tcp::socket::shutdown_both);
+    }
+    catch (const boost::system::system_error& e)
+    {
+      PCL_ERROR("[pcl::HDLGrabber::stop] Failed to shutdown the socket. %s\n", e.what ());
+    }
+
+    hdl_read_socket_->close ();
+  }
+
   if (hdl_read_packet_thread_ != nullptr)
   {
     hdl_read_packet_thread_->join ();
@@ -564,7 +578,7 @@ pcl::HDLGrabber::isRunning () const
 std::string
 pcl::HDLGrabber::getName () const
 {
-  return (std::string ("Velodyne High Definition Laser (HDL) Grabber"));
+  return {"Velodyne High Definition Laser (HDL) Grabber"};
 }
 
 /////////////////////////////////////////////////////////////////////////////
@@ -645,12 +659,21 @@ pcl::HDLGrabber::readPacketsFromSocket ()
 
   while (!terminate_read_packet_thread_ && hdl_read_socket_->is_open ())
   {
-    std::size_t length = hdl_read_socket_->receive_from (boost::asio::buffer (data, 1500), sender_endpoint);
+    try
+    {
+      std::size_t length = hdl_read_socket_->receive_from (boost::asio::buffer (data, 1500), sender_endpoint);
 
-    if (isAddressUnspecified (source_address_filter_)
-        || (source_address_filter_ == sender_endpoint.address () && source_port_filter_ == sender_endpoint.port ()))
+      if (isAddressUnspecified (source_address_filter_)
+          || (source_address_filter_ == sender_endpoint.address () && source_port_filter_ == sender_endpoint.port ()))
+      {
+        enqueueHDLPacket (data, length);
+      }
+    }
+    catch (const boost::system::system_error& e)
     {
-      enqueueHDLPacket (data, length);
+      // We must ignore those errors triggered on socket close/shutdown request.
+      if (!(e.code () == boost::asio::error::interrupted || e.code () == boost::asio::error::operation_aborted))
+        throw;
     }
   }
 }
index 998e1fecdf5887c5d90762860a8e017946e90460..d3bc8c7a1e4cb6229c8817786ed04a1f6a80df85 100644 (file)
@@ -213,7 +213,7 @@ pcl::IFSReader::read (const std::string &file_name,
   }
 
   // Copy the data
-  memcpy (&cloud.data[0], mapped_file.data () + data_idx, cloud.data.size ());
+  memcpy (cloud.data.data(), mapped_file.data () + data_idx, cloud.data.size ());
 
   mapped_file.close ();
 
@@ -264,7 +264,7 @@ pcl::IFSReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, int
   }
 
   // Copy the data
-  memcpy (&mesh.cloud.data[0], mapped_file.data () + data_idx, mesh.cloud.data.size ());
+  memcpy (mesh.cloud.data.data(), mapped_file.data () + data_idx, mesh.cloud.data.size ());
 
   mapped_file.close ();
 
@@ -284,13 +284,14 @@ pcl::IFSReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, int
   fs.read (reinterpret_cast<char*>(&length_of_keyword), sizeof (std::uint32_t));
   char *keyword = new char [length_of_keyword];
   fs.read (keyword, sizeof (char) * length_of_keyword);
-  if (strcmp (keyword, "TRIANGLES"))
+  const bool keyword_is_triangles = (strcmp (keyword, "TRIANGLES") == 0);
+  delete[] keyword;
+  if (!keyword_is_triangles)
   {
     PCL_ERROR ("[pcl::IFSReader::read] File %s is does not contain facets!\n", file_name.c_str ());
     fs.close ();
     return (-1);
   }
-  delete[] keyword;
   // Read the number of facets
   std::uint32_t nr_facets;
   fs.read (reinterpret_cast<char*>(&nr_facets), sizeof (std::uint32_t));
@@ -307,6 +308,7 @@ pcl::IFSReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, int
   {
     pcl::Vertices &facet = mesh.polygons[i];
     facet.vertices.resize (3);
+    // NOLINTNEXTLINE(readability-container-data-pointer)
     fs.read (reinterpret_cast<char*>(&(facet.vertices[0])), sizeof (std::uint32_t));
     fs.read (reinterpret_cast<char*>(&(facet.vertices[1])), sizeof (std::uint32_t));
     fs.read (reinterpret_cast<char*>(&(facet.vertices[2])), sizeof (std::uint32_t));
@@ -344,7 +346,7 @@ pcl::IFSWriter::write (const std::string &file_name, const pcl::PCLPointCloud2 &
                             sizeof (std::uint32_t) + cloud_name.size () + 1 +
                             sizeof (std::uint32_t) + vertices.size () + 1 +
                             sizeof (std::uint32_t));
-  char* addr = &(header[0]);
+  char* addr = header.data();
   const std::uint32_t magic_size = static_cast<std::uint32_t> (magic.size ()) + 1;
   memcpy (addr, &magic_size, sizeof (std::uint32_t));
   addr+= sizeof (std::uint32_t);
@@ -395,10 +397,10 @@ pcl::IFSWriter::write (const std::string &file_name, const pcl::PCLPointCloud2 &
   }
 
   // copy header
-  memcpy (sink.data (), &header[0], data_idx);
+  memcpy (sink.data (), header.data(), data_idx);
 
   // Copy the data
-  memcpy (sink.data () + data_idx, &cloud.data[0], cloud.data.size ());
+  memcpy (sink.data () + data_idx, cloud.data.data(), cloud.data.size ());
 
   sink.close ();
 
index 3f787369a56984b20a88edd30fccfc5def5134d8..de32f1f20deb69ed8e1ffa6488003ede3708f278 100644 (file)
@@ -36,6 +36,7 @@
  */
 // Looking for PCL_BUILT_WITH_VTK
 #include <pcl/for_each_type.h>
+#include <pcl/io/timestamp.h>
 #include <pcl/io/image_grabber.h>
 #include <pcl/io/lzf_image_io.h>
 #include <pcl/memory.h>
@@ -43,7 +44,6 @@
 #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
-#include <boost/date_time/posix_time/posix_time.hpp> // for posix_time
 
 #ifdef PCL_BUILT_WITH_VTK
   #include <vtkImageReader2.h>
@@ -267,9 +267,9 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
   boost::filesystem::directory_iterator end_itr;
   for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr)
   {
-    extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ()));
+    extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
-    basename = boost::filesystem::basename (itr->path ());
+    basename = itr->path ().stem ().string ();
     if (!boost::filesystem::is_directory (itr->status ())
         && isValidExtension (extension))
     {
@@ -310,9 +310,9 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
   // First iterate over depth images
   for (boost::filesystem::directory_iterator itr (depth_dir); itr != end_itr; ++itr)
   {
-    extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ()));
+    extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
-    basename = boost::filesystem::basename (itr->path ());
+    basename = itr->path ().stem ().string ();
     if (!boost::filesystem::is_directory (itr->status ())
         && isValidExtension (extension))
     {
@@ -325,9 +325,9 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string
   // Then iterate over RGB images
   for (boost::filesystem::directory_iterator itr (rgb_dir); itr != end_itr; ++itr)
   {
-    extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ()));
+    extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
-    basename = boost::filesystem::basename (itr->path ());
+    basename = itr->path ().stem ().string ();
     if (!boost::filesystem::is_directory (itr->status ())
         && isValidExtension (extension))
     {
@@ -366,9 +366,9 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadPCLZFFiles (const std::string &dir)
   boost::filesystem::directory_iterator end_itr;
   for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr)
   {
-    extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ()));
+    extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ());
     pathname = itr->path ().string ();
-    basename = boost::filesystem::basename (itr->path ());
+    basename = itr->path ().stem ().string ();
     if (!boost::filesystem::is_directory (itr->status ())
         && isValidExtension (extension))
     {
@@ -429,16 +429,13 @@ 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::basename (filepath).c_str (),
+  int result = std::sscanf (boost::filesystem::path (filepath).stem ().string ().c_str (),
                             "frame_%22s_%*s",
                             timestamp_str);
   if (result > 0)
   {
     // Convert to std::uint64_t, microseconds since 1970-01-01
-    boost::posix_time::ptime cur_date = boost::posix_time::from_iso_string (timestamp_str);
-    boost::posix_time::ptime zero_date (
-        boost::gregorian::date (1970,boost::gregorian::Jan,1));
-    timestamp = (cur_date - zero_date).total_microseconds ();
+    timestamp = std::chrono::duration<double,std::micro>(pcl::parseTimestamp(timestamp_str).time_since_epoch()).count();
     return (true);
   }
   return (false);
@@ -518,8 +515,8 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getCloudVTK (std::size_t idx,
   {
     // The 525 factor default is only true for VGA. If not, we should scale
     scaleFactorX = scaleFactorY = 1/525.f * 640.f / static_cast<float> (dims[0]);
-    centerX = ((float)dims[0] - 1.f)/2.f;
-    centerY = ((float)dims[1] - 1.f)/2.f;
+    centerX = (static_cast<float>(dims[0]) - 1.f)/2.f;
+    centerY = (static_cast<float>(dims[1]) - 1.f)/2.f;
   }
 
   if(!rgb_image_files_.empty ())
@@ -577,8 +574,8 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getCloudVTK (std::size_t idx,
           pt.x = pt.y = pt.z = std::numeric_limits<float>::quiet_NaN ();
         else
         {
-          pt.x = ((float)x - centerX) * scaleFactorX * depth;
-          pt.y = ((float)y - centerY) * scaleFactorY * depth;
+          pt.x = (static_cast<float>(x) - centerX) * scaleFactorX * depth;
+          pt.y = (static_cast<float>(y) - centerY) * scaleFactorY * depth;
           pt.z = depth;
         }
       }
@@ -974,7 +971,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::basename (pathname);
+  std::string basename = boost::filesystem::path (pathname).stem ().string ();
   return (basename);
 }
 //////////////////////////////////////////////////////////////////////////////////////////
@@ -986,7 +983,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::basename (pathname);
+  std::string basename = boost::filesystem::path (pathname).stem ().string ();
   return (basename);
 }
 
@@ -999,7 +996,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::basename (pathname);
+  std::string basename = boost::filesystem::path (pathname).stem ().string ();
   return (basename);
 }
 
index b0fdaa61abb0b26612dc8ea545d7735cd74b5d1a..f41e72fdbc580ed654e34cb0474d6ca5882d0981 100644 (file)
@@ -57,7 +57,7 @@ pcl::io::IOException::operator = (const IOException& exception)
 }
 
 const char*
-pcl::io::IOException::what () const throw ()
+pcl::io::IOException::what () const noexcept
 {
   return (message_long_.c_str ());
 }
index f267ed7cc255e6e50a4dc75bdf30d99a411de904..ff5cc6ec119c0ffe19f4c14ed4dd359fdc184361 100644 (file)
@@ -201,7 +201,7 @@ namespace pcl
       // Setup Exception handling
       setjmp (png_jmpbuf(png_ptr));
 
-      std::uint8_t* input_pointer = &pngData_arg[0];
+      std::uint8_t* input_pointer = pngData_arg.data();
       png_set_read_fn (png_ptr, reinterpret_cast<void*> (&input_pointer), user_read_data);
 
       png_read_info (png_ptr, info_ptr);
index c9661dd5ccc7179e59103f83131f1f18a3db7bd2..ab59a6eeb110cac9f065865f56fb40c7263e4ed5 100644 (file)
@@ -67,7 +67,7 @@ pcl::io::LZFImageWriter::saveImageBlob (const char* data,
   HANDLE h_native_file = CreateFile (filename.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
   if (h_native_file == INVALID_HANDLE_VALUE)
     return (false);
-  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, data_size, NULL);
+  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) (data_size >> 32), (DWORD) (data_size), NULL);
   char *map = static_cast<char*> (MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_size));
   CloseHandle (fm);
   std::copy(data, data + data_size, map);
@@ -120,7 +120,7 @@ pcl::io::LZFImageWriter::compress (const char* input,
   unsigned int compressed_size = pcl::lzfCompress (input,
                                                    uncompressed_size,
                                                    &output[header_size],
-                                                   std::uint32_t (finput_size * 1.5f));
+                                                   static_cast<std::uint32_t>(finput_size * 1.5f));
 
   std::uint32_t compressed_final_size = 0;
   if (compressed_size)
@@ -135,15 +135,15 @@ pcl::io::LZFImageWriter::compress (const char* input,
     if (itype.size () > 16)
     {
       PCL_WARN ("[pcl::io::LZFImageWriter::compress] Image type should be a string of maximum 16 characters! Cutting %s to %s.\n", image_type.c_str (), image_type.substr (0, 15).c_str ());
-      itype = itype.substr (0, 15);
+      itype.resize(16);
     }
     if (itype.size () < 16)
       itype.insert (itype.end (), 16 - itype.size (), ' ');
 
-    memcpy (&output[13], &itype[0], 16);
+    memcpy (&output[13], itype.data(), 16);
     memcpy (&output[29], &compressed_size, sizeof (std::uint32_t));
     memcpy (&output[33], &uncompressed_size, sizeof (std::uint32_t));
-    compressed_final_size = std::uint32_t (compressed_size + header_size);
+    compressed_final_size = static_cast<std::uint32_t>(compressed_size + header_size);
   }
 
   return (compressed_final_size);
@@ -157,7 +157,7 @@ pcl::io::LZFDepth16ImageWriter::write (const char* data,
 {
   // Prepare the compressed depth buffer
   unsigned int depth_size = width * height * 2;
-  char* compressed_depth = static_cast<char*> (malloc (std::size_t (float (depth_size) * 1.5f + float (LZF_HEADER_SIZE))));
+  char* compressed_depth = static_cast<char*> (malloc (static_cast<std::size_t>(static_cast<float>(depth_size) * 1.5f + static_cast<float>(LZF_HEADER_SIZE))));
 
   std::size_t compressed_size = compress (data,
                                      depth_size,
@@ -237,9 +237,9 @@ pcl::io::LZFRGB24ImageWriter::write (const char *data,
     rrggbb[ptr3] = data[i * 3 + 2];
   }
 
-  char* compressed_rgb = static_cast<char*> (malloc (std::size_t (float (rrggbb.size ()) * 1.5f + float (LZF_HEADER_SIZE))));
-  std::size_t compressed_size = compress (reinterpret_cast<const char*> (&rrggbb[0]), 
-                                     std::uint32_t (rrggbb.size ()),
+  char* compressed_rgb = static_cast<char*> (malloc (static_cast<std::size_t>(static_cast<float>(rrggbb.size ()) * 1.5f + static_cast<float>(LZF_HEADER_SIZE))));
+  std::size_t compressed_size = compress (reinterpret_cast<const char*> (rrggbb.data()), 
+                                     static_cast<std::uint32_t>(rrggbb.size ()),
                                      width, height,
                                      "rgb24",
                                      compressed_rgb);
@@ -298,9 +298,9 @@ pcl::io::LZFYUV422ImageWriter::write (const char *data,
     uuyyvv[ptr3] = data[i * 4 + 2];       // v
   }
 
-  char* compressed_yuv = static_cast<char*> (malloc (std::size_t (float (uuyyvv.size ()) * 1.5f + float (LZF_HEADER_SIZE))));
-  std::size_t compressed_size = compress (reinterpret_cast<const char*> (&uuyyvv[0]), 
-                                     std::uint32_t (uuyyvv.size ()),
+  char* compressed_yuv = static_cast<char*> (malloc (static_cast<std::size_t>(static_cast<float>(uuyyvv.size ()) * 1.5f + static_cast<float>(LZF_HEADER_SIZE))));
+  std::size_t compressed_size = compress (reinterpret_cast<const char*> (uuyyvv.data()), 
+                                     static_cast<std::uint32_t>(uuyyvv.size ()),
                                      width, height,
                                      "yuv422",
                                      compressed_yuv);
@@ -324,7 +324,7 @@ pcl::io::LZFBayer8ImageWriter::write (const char *data,
                                       const std::string &filename)
 {
   unsigned int bayer_size = width * height;
-  char* compressed_bayer = static_cast<char*> (malloc (std::size_t (float (bayer_size) * 1.5f + float (LZF_HEADER_SIZE))));
+  char* compressed_bayer = static_cast<char*> (malloc (static_cast<std::size_t>(static_cast<float>(bayer_size) * 1.5f + static_cast<float>(LZF_HEADER_SIZE))));
   std::size_t compressed_size = compress (data,
                                      bayer_size,
                                      width, height,
@@ -347,9 +347,7 @@ pcl::io::LZFBayer8ImageWriter::write (const char *data,
 //////////////////////////////////////////////////////////////////////////////
 //////////////////////////////////////////////////////////////////////////////
 pcl::io::LZFImageReader::LZFImageReader ()
-  : width_ ()
-  , height_ ()
-  , parameters_ ()
+  : parameters_ ()
 {
 }
 
@@ -442,7 +440,7 @@ pcl::io::LZFImageReader::loadImageBlob (const std::string &filename,
   memcpy (&uncompressed_size, &map[33], sizeof (std::uint32_t));
 
   data.resize (compressed_size);
-  memcpy (&data[0], &map[header_size], compressed_size);
+  memcpy (data.data(), &map[header_size], compressed_size);
 
 #ifdef _WIN32
   UnmapViewOfFile (map);
@@ -466,10 +464,10 @@ pcl::io::LZFImageReader::decompress (const std::vector<char> &input,
     PCL_ERROR ("[pcl::io::LZFImageReader::decompress] Output array needs to be preallocated! The correct uncompressed array value should have been stored during the compression.\n");
     return (false);
   }
-  unsigned int tmp_size = pcl::lzfDecompress (static_cast<const char*>(&input[0]), 
-                                              std::uint32_t (input.size ()), 
-                                              static_cast<char*>(&output[0]), 
-                                              std::uint32_t (output.size ()));
+  unsigned int tmp_size = pcl::lzfDecompress (static_cast<const char*>(input.data()), 
+                                              static_cast<std::uint32_t>(input.size ()), 
+                                              static_cast<char*>(output.data()), 
+                                              static_cast<std::uint32_t>(output.size ()));
 
   if (tmp_size != output.size ())
   {
index 81598a3c94380231639f22337ee2decc7ffd21ae..9cc1fdc68f769a85b69479ea4aa66b95d83cf140 100644 (file)
@@ -380,7 +380,7 @@ pcl::OBJReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
         continue;
 
       // Trim the line
-      //TOOD: we can easily do this without boost
+      //TODO: we can easily do this without boost
       boost::trim (line);
       
       // Ignore comments
@@ -678,7 +678,6 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
   try
   {
     std::size_t vn_idx = 0;
-    std::size_t vt_idx = 0;
 
     while (!fs.eof ())
     {
@@ -747,7 +746,6 @@ 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&)
         {
index 76746241fd2278cac1088c6be7d56100bbf946d2..3ba4c8b856080537a03c74272ca026d3056df37d 100644 (file)
@@ -71,17 +71,6 @@ namespace pcl
 ONIGrabber::ONIGrabber (const std::string& file_name, bool repeat, bool stream)
   : rgb_frame_id_ ("/openni_rgb_optical_frame")
   , depth_frame_id_ ("/openni_depth_optical_frame")
-  , running_ (false)
-  , image_width_ ()
-  , image_height_ ()
-  , depth_width_ ()
-  , depth_height_ ()
-  , depth_callback_handle ()
-  , image_callback_handle ()
-  , ir_callback_handle ()
-  , image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ ()
-  , ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ (), point_cloud_rgb_signal_ ()
-  , point_cloud_rgba_signal_ ()
 {
   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
   device_ = dynamic_pointer_cast< openni_wrapper::DeviceONI> (driver.createVirtualDevice (file_name, repeat, stream));
@@ -243,7 +232,7 @@ ONIGrabber::isRunning() const
 std::string 
 ONIGrabber::getName () const
 {
-  return (std::string("ONIGrabber"));
+  return {"ONIGrabber"};
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -372,7 +361,7 @@ ONIGrabber::convertToXYZPointCloud(const openni_wrapper::DepthImage::Ptr& depth_
   if (depth_image->getWidth () != depth_width_ || depth_image->getHeight () != depth_height_)
   {
     static unsigned buffer_size = 0;
-    static boost::shared_array<unsigned short> depth_buffer ((unsigned short*)nullptr);
+    static boost::shared_array<unsigned short> depth_buffer (nullptr);
 
     if (buffer_size < depth_width_ * depth_height_)
     {
@@ -412,7 +401,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr ONIGrabber::convertToXYZRGBPointCloud (
     const openni_wrapper::DepthImage::Ptr &depth_image) const
 {
   static unsigned rgb_array_size = 0;
-  static boost::shared_array<unsigned char> rgb_array((unsigned char*)nullptr);
+  static boost::shared_array<unsigned char> rgb_array(nullptr);
   static unsigned char* rgb_buffer = nullptr;
 
   pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
@@ -432,7 +421,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr ONIGrabber::convertToXYZRGBPointCloud (
   if (depth_image->getWidth() != depth_width_ || depth_image->getHeight() != depth_height_)
   {
     static unsigned buffer_size = 0;
-    static boost::shared_array<unsigned short> depth_buffer((unsigned short*)nullptr);
+    static boost::shared_array<unsigned short> depth_buffer(nullptr);
 
     if (buffer_size < depth_width_ * depth_height_)
     {
@@ -496,7 +485,7 @@ pcl::PointCloud<pcl::PointXYZRGBA>::Ptr ONIGrabber::convertToXYZRGBAPointCloud (
     const openni_wrapper::DepthImage::Ptr &depth_image) const
 {
   static unsigned rgb_array_size = 0;
-  static boost::shared_array<unsigned char> rgb_array((unsigned char*)nullptr);
+  static boost::shared_array<unsigned char> rgb_array(nullptr);
   static unsigned char* rgb_buffer = nullptr;
 
   pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGBA>);
@@ -516,7 +505,7 @@ pcl::PointCloud<pcl::PointXYZRGBA>::Ptr ONIGrabber::convertToXYZRGBAPointCloud (
   if (depth_image->getWidth() != depth_width_ || depth_image->getHeight() != depth_height_)
   {
     static unsigned buffer_size = 0;
-    static boost::shared_array<unsigned short> depth_buffer((unsigned short*)nullptr);
+    static boost::shared_array<unsigned short> depth_buffer(nullptr);
 
     if (buffer_size < depth_width_ * depth_height_)
     {
@@ -597,8 +586,8 @@ pcl::PointCloud<pcl::PointXYZI>::Ptr ONIGrabber::convertToXYZIPointCloud(const o
   if (depth_image->getWidth() != depth_width_ || depth_image->getHeight() != depth_height_)
   {
     static unsigned buffer_size = 0;
-    static boost::shared_array<unsigned short> depth_buffer((unsigned short*)nullptr);
-    static boost::shared_array<unsigned short> ir_buffer((unsigned short*)nullptr);
+    static boost::shared_array<unsigned short> depth_buffer(nullptr);
+    static boost::shared_array<unsigned short> ir_buffer(nullptr);
 
     if (buffer_size < depth_width_ * depth_height_)
     {
index 25f9fc300d9948028c9478f1a410783680cbc221..8d460471360ca9b717e60e78f8cf30cc8e0d188c 100644 (file)
@@ -48,10 +48,7 @@ using namespace pcl::io::openni2;
 using openni::VideoMode;
 using std::vector;
 
-pcl::io::openni2::OpenNI2Device::OpenNI2Device (const std::string& device_URI) :
-  ir_video_started_(false),
-  color_video_started_(false),
-  depth_video_started_(false)
+pcl::io::openni2::OpenNI2Device::OpenNI2Device (const std::string& device_URI)
 {
   openni::Status status = openni::OpenNI::initialize ();
   if (status != openni::STATUS_OK)
@@ -163,7 +160,7 @@ pcl::io::openni2::OpenNI2Device::getStringID () const
 bool
 pcl::io::openni2::OpenNI2Device::isValid () const
 {
-  return (openni_device_.get () != nullptr) && openni_device_->isValid ();
+  return (openni_device_ != nullptr) && openni_device_->isValid ();
 }
 
 float
@@ -332,7 +329,7 @@ pcl::io::openni2::OpenNI2Device::stopAllStreams ()
 void
 pcl::io::openni2::OpenNI2Device::stopIRStream ()
 {
-  if (ir_video_stream_.get () != nullptr)
+  if (ir_video_stream_ != nullptr)
   {
     ir_video_stream_->stop ();
     ir_video_started_ = false;
@@ -341,7 +338,7 @@ pcl::io::openni2::OpenNI2Device::stopIRStream ()
 void
 pcl::io::openni2::OpenNI2Device::stopColorStream ()
 {
-  if (color_video_stream_.get () != nullptr)
+  if (color_video_stream_ != nullptr)
   {
     color_video_stream_->stop ();
     color_video_started_ = false;
@@ -350,7 +347,7 @@ pcl::io::openni2::OpenNI2Device::stopColorStream ()
 void
 pcl::io::openni2::OpenNI2Device::stopDepthStream ()
 {
-  if (depth_video_stream_.get () != nullptr)
+  if (depth_video_stream_ != nullptr)
   {
     depth_video_stream_->stop ();
     depth_video_started_ = false;
@@ -360,13 +357,13 @@ pcl::io::openni2::OpenNI2Device::stopDepthStream ()
 void
 pcl::io::openni2::OpenNI2Device::shutdown ()
 {
-  if (ir_video_stream_.get () != nullptr)
+  if (ir_video_stream_ != nullptr)
     ir_video_stream_->destroy ();
 
-  if (color_video_stream_.get () != nullptr)
+  if (color_video_stream_ != nullptr)
     color_video_stream_->destroy ();
 
-  if (depth_video_stream_.get () != nullptr)
+  if (depth_video_stream_ != nullptr)
     depth_video_stream_->destroy ();
 
 }
@@ -747,7 +744,7 @@ bool OpenNI2Device::setPlaybackSpeed (double speed)
 std::shared_ptr<openni::VideoStream>
 pcl::io::openni2::OpenNI2Device::getIRVideoStream () const
 {
-  if (ir_video_stream_.get () == nullptr)
+  if (ir_video_stream_ == nullptr)
   {
     if (hasIRSensor ())
     {
@@ -764,7 +761,7 @@ pcl::io::openni2::OpenNI2Device::getIRVideoStream () const
 std::shared_ptr<openni::VideoStream>
 pcl::io::openni2::OpenNI2Device::getColorVideoStream () const
 {
-  if (color_video_stream_.get () == nullptr)
+  if (color_video_stream_ == nullptr)
   {
     if (hasColorSensor ())
     {
@@ -781,7 +778,7 @@ pcl::io::openni2::OpenNI2Device::getColorVideoStream () const
 std::shared_ptr<openni::VideoStream>
 pcl::io::openni2::OpenNI2Device::getDepthVideoStream () const
 {
-  if (depth_video_stream_.get () == nullptr)
+  if (depth_video_stream_ == nullptr)
   {
     if (hasDepthSensor ())
     {
index 145da5d3851207cf38180df31c9bc29b5530980e..648792943202fb06b88c359c1df87ccb7c9f7701 100644 (file)
@@ -41,7 +41,7 @@ namespace pcl
       std::ostream&
       operator<< (std::ostream& stream, const OpenNI2VideoMode& video_mode)
       {
-        stream << "Resolution: " << (int)video_mode.x_resolution_ << "x" << (int)video_mode.y_resolution_ <<
+        stream << "Resolution: " << static_cast<int>(video_mode.x_resolution_) << "x" << static_cast<int>(video_mode.y_resolution_) <<
           "@" << video_mode.frame_rate_ <<
           "Hz Format: ";
 
index f9a31c0e83dc1bc579da814711c190984cd28a47..2ce1b6036206bf75fa2a687321a6c4f7b9081e44 100644 (file)
@@ -73,24 +73,6 @@ namespace
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 pcl::io::OpenNI2Grabber::OpenNI2Grabber (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode)
-  : color_resize_buffer_(0)
-  , depth_resize_buffer_(0)
-  , ir_resize_buffer_(0)
-  , image_width_ ()
-  , image_height_ ()
-  , depth_width_ ()
-  , depth_height_ ()
-  , image_required_ (false)
-  , depth_required_ (false)
-  , ir_required_ (false)
-  , sync_required_ (false)
-  , image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ ()
-  , ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ ()
-  , point_cloud_rgb_signal_ (), point_cloud_rgba_signal_ ()
-  , depth_callback_handle_ (), image_callback_handle_ (), ir_callback_handle_ ()
-  , running_ (false)
-  , rgb_parameters_(std::numeric_limits<double>::quiet_NaN () )
-  , depth_parameters_(std::numeric_limits<double>::quiet_NaN () )
 {
   // initialize driver
   updateModeMaps (); // registering mapping from PCL enum modes to openni::VideoMode and vice versa
@@ -169,12 +151,9 @@ void
 pcl::io::OpenNI2Grabber::checkImageAndDepthSynchronizationRequired ()
 {
   // do we have anyone listening to images or color point clouds?
-  if (num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
+  sync_required_ = (num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
     num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
-    num_slots<sig_cb_openni_image_depth_image> () > 0)
-    sync_required_ = true;
-  else
-    sync_required_ = false;
+    num_slots<sig_cb_openni_image_depth_image> () > 0);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -182,13 +161,10 @@ void
 pcl::io::OpenNI2Grabber::checkImageStreamRequired ()
 {
   // do we have anyone listening to images or color point clouds?
-  if (num_slots<sig_cb_openni_image>             () > 0 ||
+  image_required_ = (num_slots<sig_cb_openni_image>             () > 0 ||
     num_slots<sig_cb_openni_image_depth_image> () > 0 ||
     num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
-    num_slots<sig_cb_openni_point_cloud_rgb>   () > 0)
-    image_required_ = true;
-  else
-    image_required_ = false;
+    num_slots<sig_cb_openni_point_cloud_rgb>   () > 0);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -196,28 +172,22 @@ void
 pcl::io::OpenNI2Grabber::checkDepthStreamRequired ()
 {
   // do we have anyone listening to depth images or (color) point clouds?
-  if (num_slots<sig_cb_openni_depth_image>       () > 0 ||
+  depth_required_ = (num_slots<sig_cb_openni_depth_image>       () > 0 ||
     num_slots<sig_cb_openni_image_depth_image> () > 0 ||
     num_slots<sig_cb_openni_ir_depth_image>    () > 0 ||
     num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
     num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
     num_slots<sig_cb_openni_point_cloud>       () > 0 ||
-    num_slots<sig_cb_openni_point_cloud_i>     () > 0 )
-    depth_required_ = true;
-  else
-    depth_required_ = false;
+    num_slots<sig_cb_openni_point_cloud_i>     () > 0 );
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::io::OpenNI2Grabber::checkIRStreamRequired ()
 {
-  if (num_slots<sig_cb_openni_ir_image>       () > 0 ||
+  ir_required_ = (num_slots<sig_cb_openni_ir_image>       () > 0 ||
     num_slots<sig_cb_openni_point_cloud_i>  () > 0 ||
-    num_slots<sig_cb_openni_ir_depth_image> () > 0)
-    ir_required_ = true;
-  else
-    ir_required_ = false;
+    num_slots<sig_cb_openni_ir_depth_image> () > 0);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -310,7 +280,7 @@ pcl::io::OpenNI2Grabber::signalsChanged ()
 std::string
 pcl::io::OpenNI2Grabber::getName () const
 {
-  return (std::string ("OpenNI2Grabber"));
+  return {"OpenNI2Grabber"};
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -533,8 +503,8 @@ pcl::io::OpenNI2Grabber::convertToXYZPointCloud (const DepthImage::Ptr& depth_im
 
   float constant_x = 1.0f / device_->getDepthFocalLength ();
   float constant_y = 1.0f / device_->getDepthFocalLength ();
-  float centerX = ((float)cloud->width - 1.f) / 2.f;
-  float centerY = ((float)cloud->height - 1.f) / 2.f;
+  float centerX = (static_cast<float>(cloud->width) - 1.f) / 2.f;
+  float centerY = (static_cast<float>(cloud->height) - 1.f) / 2.f;
 
   if (std::isfinite (depth_parameters_.focal_length_x))
     constant_x =  1.0f / static_cast<float> (depth_parameters_.focal_length_x);
@@ -613,8 +583,8 @@ pcl::io::OpenNI2Grabber::convertToXYZRGBPointCloud (const Image::Ptr &image, con
   // Generate default camera parameters
   float fx = device_->getDepthFocalLength (); // Horizontal focal length
   float fy = device_->getDepthFocalLength (); // Vertcal focal length
-  float cx = ((float)depth_width_ - 1.f) / 2.f;  // Center x
-  float cy = ((float)depth_height_- 1.f) / 2.f; // Center y
+  float cx = (static_cast<float>(depth_width_) - 1.f) / 2.f;  // Center x
+  float cy = (static_cast<float>(depth_height_)- 1.f) / 2.f; // Center y
 
   // Load pre-calibrated camera parameters if they exist
   if (std::isfinite (depth_parameters_.focal_length_x))
@@ -740,8 +710,8 @@ pcl::io::OpenNI2Grabber::convertToXYZIPointCloud (const IRImage::Ptr &ir_image,
 
   float fx = device_->getDepthFocalLength (); // Horizontal focal length
   float fy = device_->getDepthFocalLength (); // Vertcal focal length
-  float cx = ((float)cloud->width - 1.f) / 2.f;  // Center x
-  float cy = ((float)cloud->height - 1.f) / 2.f; // Center y
+  float cx = (static_cast<float>(cloud->width) - 1.f) / 2.f;  // Center x
+  float cy = (static_cast<float>(cloud->height) - 1.f) / 2.f; // Center y
 
   // Load pre-calibrated camera parameters if they exist
   if (std::isfinite (depth_parameters_.focal_length_x))
index 69d58fbd4f71ecf0e8d0547b2ad9f4bd456e7b96..928906542ca816be06f4341fe7a53c3ad48bc8aa 100644 (file)
@@ -394,10 +394,10 @@ void openni_wrapper::OpenNIDevice::InitShiftToDepthConversion ()
 
     for (std::uint32_t nIndex = 1; nIndex < shift_conversion_parameters_.device_max_shift_; nIndex++)
     {
-      auto nShiftValue = (std::int32_t)nIndex;
+      auto nShiftValue = static_cast<std::int32_t>(nIndex);
 
-      double dFixedRefX = (double) (nShiftValue - nConstShift) /
-                          (double) shift_conversion_parameters_.param_coeff_;
+      double dFixedRefX = static_cast<double>(nShiftValue - nConstShift) /
+                          static_cast<double>(shift_conversion_parameters_.param_coeff_);
       dFixedRefX -= 0.375;
       double dMetric = dFixedRefX * dPlanePixelSize;
       double dDepth = shift_conversion_parameters_.shift_scale_ *
@@ -407,7 +407,7 @@ void openni_wrapper::OpenNIDevice::InitShiftToDepthConversion ()
       if ((dDepth > shift_conversion_parameters_.min_depth_) &&
           (dDepth < shift_conversion_parameters_.max_depth_))
       {
-        shift_to_depth_table_[nIndex] = (std::uint16_t)(dDepth);
+        shift_to_depth_table_[nIndex] = static_cast<std::uint16_t>(dDepth);
       }
     }
 
@@ -429,67 +429,67 @@ openni_wrapper::OpenNIDevice::ReadDeviceParametersFromSensorNode ()
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the zero plane distance failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.zero_plane_distance_ =  (XnUInt16)nTemp;
+    shift_conversion_parameters_.zero_plane_distance_ =  static_cast<XnUInt16>(nTemp);
 
     status = depth_generator_.GetRealProperty ("ZPPS", dTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the zero plane pixel size failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.zero_plane_pixel_size_ =  (XnFloat)dTemp;
+    shift_conversion_parameters_.zero_plane_pixel_size_ =  static_cast<XnFloat>(dTemp);
 
     status = depth_generator_.GetRealProperty ("LDDIS", dTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the dcmos distance failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.emitter_dcmos_distace_ =  (XnFloat)dTemp;
+    shift_conversion_parameters_.emitter_dcmos_distace_ =  static_cast<XnFloat>(dTemp);
 
     status = depth_generator_.GetIntProperty ("MaxShift", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the max shift parameter failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.max_shift_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.max_shift_ =  static_cast<XnUInt32>(nTemp);
 
     status = depth_generator_.GetIntProperty ("DeviceMaxDepth", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the device max depth parameter failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.device_max_shift_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.device_max_shift_ =  static_cast<XnUInt32>(nTemp);
 
     status = depth_generator_.GetIntProperty ("ConstShift", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the const shift parameter failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.const_shift_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.const_shift_ =  static_cast<XnUInt32>(nTemp);
 
     status = depth_generator_.GetIntProperty ("PixelSizeFactor", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the pixel size factor failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.pixel_size_factor_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.pixel_size_factor_ =  static_cast<XnUInt32>(nTemp);
 
     status = depth_generator_.GetIntProperty ("ParamCoeff", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the param coeff parameter failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.param_coeff_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.param_coeff_ =  static_cast<XnUInt32>(nTemp);
 
     status = depth_generator_.GetIntProperty ("ShiftScale", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the shift scale parameter failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.shift_scale_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.shift_scale_ =  static_cast<XnUInt32>(nTemp);
 
     status = depth_generator_.GetIntProperty ("MinDepthValue", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the min depth value parameter failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.min_depth_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.min_depth_ =  static_cast<XnUInt32>(nTemp);
 
     status = depth_generator_.GetIntProperty ("MaxDepthValue", nTemp);
     if (status != XN_STATUS_OK)
       THROW_OPENNI_EXCEPTION ("reading the max depth value parameter failed. Reason: %s", xnGetStatusString (status));
 
-    shift_conversion_parameters_.max_depth_ =  (XnUInt32)nTemp;
+    shift_conversion_parameters_.max_depth_ =  static_cast<XnUInt32>(nTemp);
 
     shift_conversion_parameters_.init_ = true;
   }
@@ -611,7 +611,7 @@ openni_wrapper::OpenNIDevice::stopIRStream ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isImageStreamRunning () const throw ()
+openni_wrapper::OpenNIDevice::isImageStreamRunning () const noexcept
 {
   std::lock_guard<std::mutex> image_lock (image_mutex_);
   return (image_generator_.IsValid () && image_generator_.IsGenerating ());
@@ -619,7 +619,7 @@ openni_wrapper::OpenNIDevice::isImageStreamRunning () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isDepthStreamRunning () const throw ()
+openni_wrapper::OpenNIDevice::isDepthStreamRunning () const noexcept
 {
   std::lock_guard<std::mutex> depth_lock (depth_mutex_);
   return (depth_generator_.IsValid () && depth_generator_.IsGenerating ());
@@ -627,7 +627,7 @@ openni_wrapper::OpenNIDevice::isDepthStreamRunning () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isIRStreamRunning () const throw ()
+openni_wrapper::OpenNIDevice::isIRStreamRunning () const noexcept
 {
   std::lock_guard<std::mutex> ir_lock (ir_mutex_);
   return (ir_generator_.IsValid () && ir_generator_.IsGenerating ());
@@ -635,7 +635,7 @@ openni_wrapper::OpenNIDevice::isIRStreamRunning () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::hasImageStream () const throw ()
+openni_wrapper::OpenNIDevice::hasImageStream () const noexcept
 {
   std::lock_guard<std::mutex> lock (image_mutex_);
   return (image_generator_.IsValid () != 0);
@@ -644,7 +644,7 @@ openni_wrapper::OpenNIDevice::hasImageStream () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::hasDepthStream () const throw ()
+openni_wrapper::OpenNIDevice::hasDepthStream () const noexcept
 {
   std::lock_guard<std::mutex> lock (depth_mutex_);
   return (depth_generator_.IsValid () != 0);
@@ -653,7 +653,7 @@ openni_wrapper::OpenNIDevice::hasDepthStream () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::hasIRStream () const throw ()
+openni_wrapper::OpenNIDevice::hasIRStream () const noexcept
 {
   std::lock_guard<std::mutex> ir_lock (ir_mutex_);
   return (ir_generator_.IsValid () != 0);
@@ -692,7 +692,7 @@ openni_wrapper::OpenNIDevice::setDepthRegistration (bool on_off)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isDepthRegistered () const throw ()
+openni_wrapper::OpenNIDevice::isDepthRegistered () const noexcept
 {
   if (hasDepthStream () && hasImageStream() )
   {
@@ -708,7 +708,7 @@ openni_wrapper::OpenNIDevice::isDepthRegistered () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isDepthRegistrationSupported () const throw ()
+openni_wrapper::OpenNIDevice::isDepthRegistrationSupported () const noexcept
 {
   std::lock_guard<std::mutex> image_lock (image_mutex_);
   std::lock_guard<std::mutex> depth_lock (depth_mutex_);
@@ -718,7 +718,7 @@ openni_wrapper::OpenNIDevice::isDepthRegistrationSupported () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isSynchronizationSupported () const throw ()
+openni_wrapper::OpenNIDevice::isSynchronizationSupported () const noexcept
 {
   std::lock_guard<std::mutex> image_lock (image_mutex_);
   std::lock_guard<std::mutex> depth_lock (depth_mutex_);
@@ -754,7 +754,7 @@ openni_wrapper::OpenNIDevice::setSynchronization (bool on_off)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isSynchronized () const throw ()
+openni_wrapper::OpenNIDevice::isSynchronized () const noexcept
 {
   if (hasDepthStream () && hasImageStream())
   {
@@ -769,7 +769,7 @@ openni_wrapper::OpenNIDevice::isSynchronized () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isDepthCroppingSupported () const throw ()
+openni_wrapper::OpenNIDevice::isDepthCroppingSupported () const noexcept
 {
   std::lock_guard<std::mutex> depth_lock (depth_mutex_);
   return (image_generator_.IsValid() && depth_generator_.IsCapabilitySupported (XN_CAPABILITY_CROPPING) );
@@ -975,21 +975,21 @@ openni_wrapper::OpenNIDevice::unregisterIRCallback (const OpenNIDevice::Callback
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDevice::getSerialNumber () const throw ()
+openni_wrapper::OpenNIDevice::getSerialNumber () const noexcept
 {
   return (device_node_info_.GetInstanceName ());
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDevice::getConnectionString () const throw ()
+openni_wrapper::OpenNIDevice::getConnectionString () const noexcept
 {
   return (device_node_info_.GetCreationInfo ());
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned short 
-openni_wrapper::OpenNIDevice::getVendorID () const throw ()
+openni_wrapper::OpenNIDevice::getVendorID () const noexcept
 {
   unsigned short vendor_id;
   unsigned short product_id;
@@ -1008,7 +1008,7 @@ openni_wrapper::OpenNIDevice::getVendorID () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned short 
-openni_wrapper::OpenNIDevice::getProductID () const throw ()
+openni_wrapper::OpenNIDevice::getProductID () const noexcept
 {
   unsigned short vendor_id;
   unsigned short product_id;
@@ -1025,7 +1025,7 @@ openni_wrapper::OpenNIDevice::getProductID () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned char 
-openni_wrapper::OpenNIDevice::getBus () const throw ()
+openni_wrapper::OpenNIDevice::getBus () const noexcept
 {
   unsigned char bus = 0;
 #ifndef _WIN32
@@ -1039,7 +1039,7 @@ openni_wrapper::OpenNIDevice::getBus () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned char 
-openni_wrapper::OpenNIDevice::getAddress () const throw ()
+openni_wrapper::OpenNIDevice::getAddress () const noexcept
 {
   unsigned char address = 0;
 #ifndef _WIN32
@@ -1053,7 +1053,7 @@ openni_wrapper::OpenNIDevice::getAddress () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDevice::getVendorName () const throw ()
+openni_wrapper::OpenNIDevice::getVendorName () const noexcept
 {
   auto& description = const_cast<XnProductionNodeDescription&>(device_node_info_.GetDescription ());
   return (description.strVendor);
@@ -1061,7 +1061,7 @@ openni_wrapper::OpenNIDevice::getVendorName () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDevice::getProductName () const throw ()
+openni_wrapper::OpenNIDevice::getProductName () const noexcept
 {
   auto& description = const_cast<XnProductionNodeDescription&>(device_node_info_.GetDescription ());
   return (description.strName);
@@ -1069,7 +1069,7 @@ openni_wrapper::OpenNIDevice::getProductName () const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const throw ()
+openni_wrapper::OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const noexcept
 {
   if (isImageModeSupported (output_mode))
   {
@@ -1098,7 +1098,7 @@ openni_wrapper::OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& ou
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const throw ()
+openni_wrapper::OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const noexcept
 {
   if (isDepthModeSupported (output_mode))
   {
@@ -1127,7 +1127,7 @@ openni_wrapper::OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& ou
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isImageModeSupported (const XnMapOutputMode& output_mode) const throw ()
+openni_wrapper::OpenNIDevice::isImageModeSupported (const XnMapOutputMode& output_mode) const noexcept
 {
   for (const auto &available_image_mode : available_image_modes_)
   {
@@ -1139,7 +1139,7 @@ openni_wrapper::OpenNIDevice::isImageModeSupported (const XnMapOutputMode& outpu
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& output_mode) const throw ()
+openni_wrapper::OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& output_mode) const noexcept
 {
   for (const auto &available_depth_mode : available_depth_modes_)
   {
@@ -1151,21 +1151,21 @@ openni_wrapper::OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& outpu
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const XnMapOutputMode& 
-openni_wrapper::OpenNIDevice::getDefaultImageMode () const throw ()
+openni_wrapper::OpenNIDevice::getDefaultImageMode () const noexcept
 {
   return (available_image_modes_[0]);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const XnMapOutputMode& 
-openni_wrapper::OpenNIDevice::getDefaultDepthMode () const throw ()
+openni_wrapper::OpenNIDevice::getDefaultDepthMode () const noexcept
 {
   return (available_depth_modes_[0]);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const XnMapOutputMode& 
-openni_wrapper::OpenNIDevice::getDefaultIRMode () const throw ()
+openni_wrapper::OpenNIDevice::getDefaultIRMode () const noexcept
 {
   /// @todo Something else here?
   return (available_depth_modes_[0]);
index fee348e6ac2064813a469fc7e610da08f54039e0..e8147d0d02feb5f01a76979cb1ef25e620ec8c51 100644 (file)
@@ -53,7 +53,7 @@ namespace openni_wrapper
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceKinect::isSynchronizationSupported () const throw ()
+openni_wrapper::DeviceKinect::isSynchronizationSupported () const noexcept
 {
   return (false);
 }
@@ -61,7 +61,6 @@ openni_wrapper::DeviceKinect::isSynchronizationSupported () const throw ()
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 openni_wrapper::DeviceKinect::DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node)
 : OpenNIDevice (context, device_node, image_node, depth_node, ir_node)
-, debayering_method_ (ImageBayerGRBG::EdgeAwareWeighted)
 {
   // setup stream modes
   enumAvailableModes ();
@@ -105,7 +104,7 @@ openni_wrapper::DeviceKinect::~DeviceKinect () noexcept
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceKinect::isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw ()
+openni_wrapper::DeviceKinect::isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept
 {
   return (ImageBayerGRBG::resizingSupported (input_width, input_height, output_width, output_height));
 }
@@ -132,7 +131,7 @@ openni_wrapper::DeviceKinect::enumAvailableModes () noexcept
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 openni_wrapper::Image::Ptr 
-openni_wrapper::DeviceKinect::getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_data) const throw ()
+openni_wrapper::DeviceKinect::getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_data) const noexcept
 {
   return (Image::Ptr (new ImageBayerGRBG (image_data, debayering_method_)));
 }
index 6006649e526a081158cdb7006f9da65b0d5efbab..2a42d31402ae8abbcfdc62480a8b254bde9c53ef 100644 (file)
@@ -54,9 +54,6 @@ openni_wrapper::DeviceONI::DeviceONI (
     bool streaming)
   : OpenNIDevice (context)
   , streaming_  (streaming)
-  , depth_stream_running_ (false)
-  , image_stream_running_ (false)
-  , ir_stream_running_ (false)
 {
   XnStatus status;
 #if (XN_MINOR_VERSION >= 3)
@@ -161,21 +158,21 @@ openni_wrapper::DeviceONI::stopIRStream ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceONI::isImageStreamRunning () const throw ()
+openni_wrapper::DeviceONI::isImageStreamRunning () const noexcept
 {
  return (image_stream_running_);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceONI::isDepthStreamRunning () const throw ()
+openni_wrapper::DeviceONI::isDepthStreamRunning () const noexcept
 {
   return (depth_stream_running_);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceONI::isIRStreamRunning () const throw ()
+openni_wrapper::DeviceONI::isIRStreamRunning () const noexcept
 {
   return (ir_stream_running_);
 }
@@ -205,7 +202,7 @@ openni_wrapper::DeviceONI::trigger (int relative_offset)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceONI::isStreaming () const throw ()
+openni_wrapper::DeviceONI::isStreaming () const noexcept
 {
   return (streaming_);
 }
@@ -248,14 +245,14 @@ openni_wrapper::DeviceONI::NewONIIRDataAvailable (xn::ProductionNode&, void* coo
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 openni_wrapper::Image::Ptr 
-openni_wrapper::DeviceONI::getCurrentImage(pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const throw ()
+openni_wrapper::DeviceONI::getCurrentImage(pcl::shared_ptr<xn::ImageMetaData> image_meta_data) const noexcept
 {
   return (openni_wrapper::Image::Ptr (new openni_wrapper::ImageRGB24 (image_meta_data)));
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceONI::isImageResizeSupported(unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw ()
+openni_wrapper::DeviceONI::isImageResizeSupported(unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept
 {
   return (openni_wrapper::ImageRGB24::resizingSupported (input_width, input_height, output_width, output_height));
 }
index 20072c47cf7a011e99866186a272bf8c8a939c46..c0f66a26f7db49ded870318ce1564ab479abbbb0 100644 (file)
@@ -102,7 +102,7 @@ openni_wrapper::DevicePrimesense::isImageResizeSupported (
     unsigned input_width, 
     unsigned input_height, 
     unsigned output_width, 
-    unsigned output_height) const throw ()
+    unsigned output_height) const noexcept
 {
   return (ImageYUV422::resizingSupported (input_width, input_height, output_width, output_height));
 }
@@ -170,7 +170,7 @@ openni_wrapper::DevicePrimesense::enumAvailableModes () noexcept
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 openni_wrapper::Image::Ptr 
-openni_wrapper::DevicePrimesense::getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_data) const throw ()
+openni_wrapper::DevicePrimesense::getCurrentImage (pcl::shared_ptr<xn::ImageMetaData> image_data) const noexcept
 {
   return (openni_wrapper::Image::Ptr (new ImageYUV422 (image_data)));
 }
index 56925743cf3c56bfc3c046aaa26a76536f1cb331..f65d20fa25d1e0355a5c75c49d466a77d47d2429 100644 (file)
@@ -73,7 +73,7 @@ openni_wrapper::DeviceXtionPro::~DeviceXtionPro () noexcept
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 bool 
-openni_wrapper::DeviceXtionPro::isImageResizeSupported (unsigned, unsigned, unsigned, unsigned) const throw ()
+openni_wrapper::DeviceXtionPro::isImageResizeSupported (unsigned, unsigned, unsigned, unsigned) const noexcept
 {
   return (false);
 }
@@ -115,7 +115,7 @@ openni_wrapper::DeviceXtionPro::enumAvailableModes () noexcept
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 openni_wrapper::Image::Ptr 
-openni_wrapper::DeviceXtionPro::getCurrentImage (pcl::shared_ptr<xn::ImageMetaData>) const throw ()
+openni_wrapper::DeviceXtionPro::getCurrentImage (pcl::shared_ptr<xn::ImageMetaData>) const noexcept
 {
   return (Image::Ptr (reinterpret_cast<Image*> (0)));
 }
index 2347b4f886eb5bc2debfb13d6b2a799f937ac364..11e50769a2a9d03ad4e4dbd22f5de1f416a373c8 100644 (file)
@@ -201,7 +201,7 @@ openni_wrapper::OpenNIDriver::updateDeviceList ()
     }
     else
 #endif
-    if (vendor_id == 0x1d27 && device.image_node.get () == nullptr)
+    if (vendor_id == 0x1d27 && device.image_node == nullptr)
     {
       strcpy (const_cast<char*> (device.device_node.GetDescription ().strVendor), "ASUS");
       strcpy (const_cast<char*> (device.device_node.GetDescription ().strName), "Xtion Pro");
@@ -221,7 +221,7 @@ openni_wrapper::OpenNIDriver::stopAll ()
 
 openni_wrapper::OpenNIDriver::~OpenNIDriver () noexcept
 {
-  // no exception during destuctor
+  // no exception during destructor
   try
   {
     stopAll ();
@@ -406,7 +406,7 @@ openni_wrapper::OpenNIDriver::getDeviceInfos () noexcept
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDriver::getSerialNumber (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getSerialNumber (unsigned index) const noexcept
 {
 #ifndef _WIN32
   return (device_context_[index].device_node.GetInstanceName ());
@@ -457,28 +457,28 @@ openni_wrapper::OpenNIDriver::getDeviceType (const std::string& connectionString
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDriver::getConnectionString (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getConnectionString (unsigned index) const noexcept
 {
   return (device_context_[index].device_node.GetCreationInfo ());
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDriver::getVendorName (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getVendorName (unsigned index) const noexcept
 {
   return (device_context_[index].device_node.GetDescription ().strVendor);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 const char* 
-openni_wrapper::OpenNIDriver::getProductName (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getProductName (unsigned index) const noexcept
 {
   return (device_context_[index].device_node.GetDescription ().strName);
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned short 
-openni_wrapper::OpenNIDriver::getVendorID (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getVendorID (unsigned index) const noexcept
 {
   unsigned short vendor_id;
   unsigned short product_id;
@@ -495,7 +495,7 @@ openni_wrapper::OpenNIDriver::getVendorID (unsigned index) const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned short 
-openni_wrapper::OpenNIDriver::getProductID (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getProductID (unsigned index) const noexcept
 {
   unsigned short vendor_id;
   unsigned short product_id;
@@ -512,7 +512,7 @@ openni_wrapper::OpenNIDriver::getProductID (unsigned index) const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned char 
-openni_wrapper::OpenNIDriver::getBus (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getBus (unsigned index) const noexcept
 {
   unsigned char bus = 0;
 #ifndef _WIN32
@@ -526,7 +526,7 @@ openni_wrapper::OpenNIDriver::getBus (unsigned index) const throw ()
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 unsigned char 
-openni_wrapper::OpenNIDriver::getAddress (unsigned index) const throw ()
+openni_wrapper::OpenNIDriver::getAddress (unsigned index) const noexcept
 {
   unsigned char address = 0;
 #ifndef _WIN32
index bfc39583fd1c2d17078de8c89b69e59bfd4fd0c8..2887f5b62014041e4f6727331598e15c5787fea4 100644 (file)
@@ -62,22 +62,22 @@ OpenNIException& OpenNIException::operator = (const OpenNIException& exception)
   return *this;
 }
 
-const char* OpenNIException::what () const throw ()
+const char* OpenNIException::what () const noexcept
 {
   return message_long_.c_str();
 }
 
-const std::string& OpenNIException::getFunctionName () const throw ()
+const std::string& OpenNIException::getFunctionName () const noexcept
 {
   return function_name_;
 }
 
-const std::string& OpenNIException::getFileName () const throw ()
+const std::string& OpenNIException::getFileName () const noexcept
 {
   return file_name_;
 }
 
-unsigned OpenNIException::getLineNumber () const throw ()
+unsigned OpenNIException::getLineNumber () const noexcept
 {
   return line_number_;
 }
index 8df70a4b4d8e156fd6a220296c38995df9b976e3..04d43c765d583c552970a8b4b629aa679e2eb398 100644 (file)
@@ -53,22 +53,8 @@ using namespace std::chrono_literals;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 pcl::OpenNIGrabber::OpenNIGrabber (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode)
-  : image_width_ ()
-  , image_height_ ()
-  , depth_width_ ()
-  , depth_height_ ()
-  , image_required_ (false)
-  , depth_required_ (false)
-  , ir_required_ (false)
-  , sync_required_ (false)
-  , image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ ()
-  , ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ ()
-  , point_cloud_rgb_signal_ (), point_cloud_rgba_signal_ ()
-  , depth_callback_handle (), image_callback_handle (), ir_callback_handle ()
-  , running_ (false)
-  , rgb_array_size_ (0)
-  , depth_buffer_size_ (0)
-  , rgb_focal_length_x_ (std::numeric_limits<double>::quiet_NaN ())
+  : 
+   rgb_focal_length_x_ (std::numeric_limits<double>::quiet_NaN ())
   , rgb_focal_length_y_ (std::numeric_limits<double>::quiet_NaN ())
   , rgb_principal_point_x_ (std::numeric_limits<double>::quiet_NaN ())
   , rgb_principal_point_y_ (std::numeric_limits<double>::quiet_NaN ())
@@ -163,12 +149,9 @@ void
 pcl::OpenNIGrabber::checkImageAndDepthSynchronizationRequired ()
 {
   // do we have anyone listening to images or color point clouds?
-  if (num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
+  sync_required_ = num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
-      num_slots<sig_cb_openni_image_depth_image> () > 0)
-    sync_required_ = true;
-  else
-    sync_required_ = false;
+      num_slots<sig_cb_openni_image_depth_image> () > 0;
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -176,13 +159,10 @@ void
 pcl::OpenNIGrabber::checkImageStreamRequired ()
 {
   // do we have anyone listening to images or color point clouds?
-  if (num_slots<sig_cb_openni_image>             () > 0 ||
+  image_required_ = num_slots<sig_cb_openni_image>             () > 0 ||
       num_slots<sig_cb_openni_image_depth_image> () > 0 ||
       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
-      num_slots<sig_cb_openni_point_cloud_rgb>   () > 0)
-    image_required_ = true;
-  else
-    image_required_ = false;
+      num_slots<sig_cb_openni_point_cloud_rgb>   () > 0;
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -190,28 +170,22 @@ void
 pcl::OpenNIGrabber::checkDepthStreamRequired ()
 {
   // do we have anyone listening to depth images or (color) point clouds?
-  if (num_slots<sig_cb_openni_depth_image>       () > 0 ||
+  depth_required_ = num_slots<sig_cb_openni_depth_image>       () > 0 ||
       num_slots<sig_cb_openni_image_depth_image> () > 0 ||
       num_slots<sig_cb_openni_ir_depth_image>    () > 0 ||
       num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
       num_slots<sig_cb_openni_point_cloud>       () > 0 ||
-      num_slots<sig_cb_openni_point_cloud_i>     () > 0 )
-    depth_required_ = true;
-  else
-    depth_required_ = false;
+      num_slots<sig_cb_openni_point_cloud_i>     () > 0;
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::OpenNIGrabber::checkIRStreamRequired ()
 {
-  if (num_slots<sig_cb_openni_ir_image>       () > 0 ||
+  ir_required_ = num_slots<sig_cb_openni_ir_image>       () > 0 ||
       num_slots<sig_cb_openni_point_cloud_i>  () > 0 ||
-      num_slots<sig_cb_openni_ir_depth_image> () > 0)
-    ir_required_ = true;
-  else
-    ir_required_ = false;
+      num_slots<sig_cb_openni_ir_depth_image> () > 0;
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -317,7 +291,7 @@ pcl::OpenNIGrabber::signalsChanged ()
 std::string
 pcl::OpenNIGrabber::getName () const
 {
-  return std::string ("OpenNIGrabber");
+  return {"OpenNIGrabber"};
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -551,8 +525,8 @@ pcl::OpenNIGrabber::convertToXYZPointCloud (const openni_wrapper::DepthImage::Pt
 
   float constant_x = 1.0f / device_->getDepthFocalLength (depth_width_);
   float constant_y = 1.0f / device_->getDepthFocalLength (depth_width_);
-  float centerX = ((float)cloud->width - 1.f) / 2.f;
-  float centerY = ((float)cloud->height - 1.f) / 2.f;
+  float centerX = (static_cast<float>(cloud->width) - 1.f) / 2.f;
+  float centerY = (static_cast<float>(cloud->height) - 1.f) / 2.f;
 
   if (std::isfinite (depth_focal_length_x_))
     constant_x =  1.0f / static_cast<float> (depth_focal_length_x_);
@@ -628,8 +602,8 @@ pcl::OpenNIGrabber::convertToXYZRGBPointCloud (const openni_wrapper::Image::Ptr
   //float constant = 1.0f / device_->getImageFocalLength (depth_width_);
   float constant_x = 1.0f / device_->getDepthFocalLength (depth_width_);
   float constant_y = 1.0f / device_->getDepthFocalLength (depth_width_);
-  float centerX = ((float)cloud->width - 1.f) / 2.f;
-  float centerY = ((float)cloud->height - 1.f) / 2.f;
+  float centerX = (static_cast<float>(cloud->width) - 1.f) / 2.f;
+  float centerY = (static_cast<float>(cloud->height) - 1.f) / 2.f;
 
   if (std::isfinite (depth_focal_length_x_))
     constant_x =  1.0f / static_cast<float> (depth_focal_length_x_);
@@ -743,8 +717,8 @@ pcl::OpenNIGrabber::convertToXYZIPointCloud (const openni_wrapper::IRImage::Ptr
   //float constant = 1.0f / device_->getImageFocalLength (cloud->width);
   float constant_x = 1.0f / device_->getImageFocalLength (cloud->width);
   float constant_y = 1.0f / device_->getImageFocalLength (cloud->width);
-  float centerX = ((float)cloud->width - 1.f) / 2.f;
-  float centerY = ((float)cloud->height - 1.f) / 2.f;
+  float centerX = (static_cast<float>(cloud->width) - 1.f) / 2.f;
+  float centerY = (static_cast<float>(cloud->height) - 1.f) / 2.f;
 
   if (std::isfinite (rgb_focal_length_x_))
     constant_x =  1.0f / static_cast<float> (rgb_focal_length_x_);
index d99392be4e0869ac2bd293d8c747bfe2a539454e..2a90664c841b3465b99b9195ff7edeb70cee0a7f 100644 (file)
@@ -341,9 +341,9 @@ pcl::PCDReader::readHeader (std::istream &fs, pcl::PCLPointCloud2 &cloud,
 
   if (nr_points == 0)
   {
-    PCL_WARN ("[pcl::PCDReader::readHeader] No points to read\n");
+    PCL_WARN("[pcl::PCDReader::readHeader] number of points is zero.\n");
   }
-  
+
   // Compatibility with older PCD file versions
   if (!width_read && !height_read)
   {
@@ -397,7 +397,14 @@ pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
   fs.open (file_name.c_str (), std::ios::binary);
   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)); 
+    PCL_ERROR ("[pcl::PCDReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror (errno));
+    fs.close ();
+    return (-1);
+  }
+
+  if (fs.peek() ==  std::ifstream::traits_type::eof())
+  {
+    PCL_ERROR ("[pcl::PCDReader::readHeader] File '%s' is empty.\n", file_name.c_str ());
     fs.close ();
     return (-1);
   }
@@ -557,9 +564,14 @@ pcl::PCDReader::readBodyBinary (const unsigned char *map, pcl::PCLPointCloud2 &c
     }
 
     auto data_size = static_cast<unsigned int> (cloud.data.size ());
+    if (data_size == 0)
+    {
+      PCL_WARN("[pcl::PCDReader::read] Binary compressed file has data size of zero.\n");
+      return 0;
+    }
     std::vector<char> buf (data_size);
     // The size of the uncompressed data better be the same as what we stored in the header
-    unsigned int tmp_size = pcl::lzfDecompress (&map[data_idx + 8], compressed_size, &buf[0], data_size);
+    unsigned int tmp_size = pcl::lzfDecompress (&map[data_idx + 8], compressed_size, buf.data(), data_size);
     if (tmp_size != uncompressed_size)
     {
       PCL_ERROR ("[pcl::PCDReader::read] Size of decompressed lzf data (%u) does not match value stored in PCD header (%u). Errno: %d\n", tmp_size, uncompressed_size, errno);
@@ -604,7 +616,7 @@ pcl::PCDReader::readBodyBinary (const unsigned char *map, pcl::PCLPointCloud2 &c
   }
   else
     // Copy the data
-    memcpy (&cloud.data[0], &map[0] + data_idx, cloud.data.size ());
+    memcpy ((cloud.data).data(), &map[0] + data_idx, cloud.data.size ());
 
   // Extra checks (not needed for ASCII)
   int point_size = (cloud.width * cloud.height == 0) ? 0 : static_cast<int> (cloud.data.size () / (cloud.height * cloud.width));
@@ -930,9 +942,15 @@ pcl::PCDWriter::generateHeaderBinary (const pcl::PCLPointCloud2 &cloud,
          "\nVERSION 0.7"
          "\nFIELDS";
 
+  auto fields = cloud.fields;
+  std::sort(fields.begin(), fields.end(), [](const auto& field_a, const auto& field_b)
+                                          {
+                                            return field_a.offset < field_b.offset;
+                                          });
+
   // Compute the total size of the fields
   unsigned int fsize = 0;
-  for (const auto &field : cloud.fields)
+  for (const auto &field : fields)
     fsize += field.count * getFieldSize (field.datatype);
 
   // The size of the fields cannot be larger than point_step
@@ -945,20 +963,20 @@ pcl::PCDWriter::generateHeaderBinary (const pcl::PCLPointCloud2 &cloud,
   std::stringstream field_names, field_types, field_sizes, field_counts;
   // Check if the size of the fields is smaller than the size of the point step
   std::size_t toffset = 0;
-  for (std::size_t i = 0; i < cloud.fields.size (); ++i)
+  for (std::size_t i = 0; i < fields.size (); ++i)
   {
     // If field offsets do not match, then we need to create fake fields
-    if (toffset != cloud.fields[i].offset)
+    if (toffset != fields[i].offset)
     {
       // If we're at the last "valid" field
       int fake_offset = (i == 0) ?
         // Use the current_field offset
-        (cloud.fields[i].offset)
+        (fields[i].offset)
         :
         // Else, do cur_field.offset - prev_field.offset + sizeof (prev_field)
-        (cloud.fields[i].offset -
-        (cloud.fields[i-1].offset +
-         cloud.fields[i-1].count * getFieldSize (cloud.fields[i-1].datatype)));
+        (fields[i].offset -
+        (fields[i-1].offset +
+         fields[i-1].count * getFieldSize (fields[i-1].datatype)));
 
       toffset += fake_offset;
 
@@ -969,11 +987,11 @@ pcl::PCDWriter::generateHeaderBinary (const pcl::PCLPointCloud2 &cloud,
     }
 
     // Add the regular dimension
-    toffset += cloud.fields[i].count * getFieldSize (cloud.fields[i].datatype);
-    field_names << " " << cloud.fields[i].name;
-    field_sizes << " " << pcl::getFieldSize (cloud.fields[i].datatype);
-    field_types << " " << pcl::getFieldType (cloud.fields[i].datatype);
-    int count = std::abs (static_cast<int> (cloud.fields[i].count));
+    toffset += fields[i].count * getFieldSize (fields[i].datatype);
+    field_names << " " << fields[i].name;
+    field_sizes << " " << pcl::getFieldSize (fields[i].datatype);
+    field_types << " " << pcl::getFieldType (fields[i].datatype);
+    int count = std::abs (static_cast<int> (fields[i].count));
     if (count == 0) count = 1;  // check for 0 counts (coming from older converter code)
     field_counts << " " << count;
   }
@@ -1173,6 +1191,29 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PCLPointClo
   return (0);
 }
 
+///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+int
+pcl::PCDWriter::writeBinary (std::ostream &os, const pcl::PCLPointCloud2 &cloud,
+                             const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
+{
+  if (cloud.data.empty ())
+  {
+    PCL_WARN ("[pcl::PCDWriter::writeBinary] Input point cloud has no data!\n");
+  }
+  if (cloud.fields.empty())
+  {
+    PCL_ERROR ("[pcl::PCDWriter::writeBinary] Input point cloud has no field data!\n");
+    return (-1);
+  }
+
+  os.imbue (std::locale::classic ());
+  os << generateHeaderBinary (cloud, origin, orientation) << "DATA binary\n";
+  std::copy (cloud.data.cbegin(), cloud.data.cend(), std::ostream_iterator<char> (os));
+  os.flush ();
+
+  return (os ? 0 : -1);
+}
+
 ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 int
 pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud,
@@ -1188,13 +1229,12 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCl
     return (-1);
   }
 
-  std::streamoff data_idx = 0;
   std::ostringstream oss;
   oss.imbue (std::locale::classic ());
 
   oss << generateHeaderBinary (cloud, origin, orientation) << "DATA binary\n";
   oss.flush();
-  data_idx = static_cast<unsigned int> (oss.tellp ());
+  const auto data_idx = static_cast<unsigned int> (oss.tellp ());
 
 #ifdef _WIN32
   HANDLE h_native_file = CreateFile (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL);
@@ -1240,7 +1280,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCl
 #endif
   // Prepare the map
 #ifdef _WIN32
-  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, (DWORD) (data_idx + cloud.data.size ()), NULL);
+  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((data_idx + cloud.data.size ()) >> 32), (DWORD) (data_idx + cloud.data.size ()), NULL);
   char *map = static_cast<char*>(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + cloud.data.size ()));
   CloseHandle (fm);
 
@@ -1259,7 +1299,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCl
   memcpy (&map[0], oss.str().c_str (), static_cast<std::size_t> (data_idx));
 
   // Copy the data
-  memcpy (&map[0] + data_idx, &cloud.data[0], cloud.data.size ());
+  memcpy (&map[0] + data_idx, cloud.data.data(), cloud.data.size ());
 
 #ifndef _WIN32
   // If the user set the synchronization flag on, call msync
@@ -1341,42 +1381,43 @@ pcl::PCDWriter::writeBinaryCompressed (std::ostream &os, const pcl::PCLPointClou
     return (-2);
   }
 
-  //////////////////////////////////////////////////////////////////////
-  // Empty array holding only the valid data
-  // data_size = nr_points * point_size 
-  //           = nr_points * (sizeof_field_1 + sizeof_field_2 + ... sizeof_field_n)
-  //           = sizeof_field_1 * nr_points + sizeof_field_2 * nr_points + ... sizeof_field_n * nr_points
-  std::vector<char> only_valid_data (data_size);
-
-  // Convert the XYZRGBXYZRGB structure to XXYYZZRGBRGB to aid compression. For
-  // this, we need a vector of fields.size () (4 in this case), which points to
-  // each individual plane:
-  //   pters[0] = &only_valid_data[offset_of_plane_x];
-  //   pters[1] = &only_valid_data[offset_of_plane_y];
-  //   pters[2] = &only_valid_data[offset_of_plane_z];
-  //   pters[3] = &only_valid_data[offset_of_plane_RGB];
-  //
-  std::vector<char*> pters (fields.size ());
-  std::size_t toff = 0;
-  for (std::size_t i = 0; i < pters.size (); ++i)
-  {
-    pters[i] = &only_valid_data[toff];
-    toff += fields_sizes[i] * cloud.width * cloud.height;
-  }
+  std::vector<char> temp_buf (data_size * 3 / 2 + 8);
+  if (data_size != 0) {
 
-  // Go over all the points, and copy the data in the appropriate places
-  for (uindex_t i = 0; i < cloud.width * cloud.height; ++i)
-  {
-    for (std::size_t j = 0; j < pters.size (); ++j)
-    {
-      memcpy (pters[j], &cloud.data[i * cloud.point_step + fields[j].offset], fields_sizes[j]);
-      // Increment the pointer
-      pters[j] += fields_sizes[j];
+    //////////////////////////////////////////////////////////////////////
+    // Empty array holding only the valid data
+    // data_size = nr_points * point_size
+    //           = nr_points * (sizeof_field_1 + sizeof_field_2 + ... sizeof_field_n)
+    //           = sizeof_field_1 * nr_points + sizeof_field_2 * nr_points + ...
+    //           sizeof_field_n * nr_points
+    std::vector<char> only_valid_data(data_size);
+
+    // Convert the XYZRGBXYZRGB structure to XXYYZZRGBRGB to aid compression. For
+    // this, we need a vector of fields.size () (4 in this case), which points to
+    // each individual plane:
+    //   pters[0] = &only_valid_data[offset_of_plane_x];
+    //   pters[1] = &only_valid_data[offset_of_plane_y];
+    //   pters[2] = &only_valid_data[offset_of_plane_z];
+    //   pters[3] = &only_valid_data[offset_of_plane_RGB];
+    //
+    std::vector<char*> pters(fields.size());
+    std::size_t toff = 0;
+    for (std::size_t i = 0; i < pters.size(); ++i) {
+      pters[i] = &only_valid_data[toff];
+      toff += fields_sizes[i] * cloud.width * cloud.height;
+    }
+
+    // Go over all the points, and copy the data in the appropriate places
+    for (uindex_t i = 0; i < cloud.width * cloud.height; ++i) {
+      for (std::size_t j = 0; j < pters.size(); ++j) {
+        memcpy(pters[j],
+               &cloud.data[i * cloud.point_step + fields[j].offset],
+               fields_sizes[j]);
+        // Increment the pointer
+        pters[j] += fields_sizes[j];
+      }
     }
-  }
 
-  std::vector<char> temp_buf (data_size * 3 / 2 + 8);
-  if (data_size != 0) {
     // Compress the valid data
     unsigned int compressed_size = pcl::lzfCompress (&only_valid_data.front (),
                                                     static_cast<unsigned int> (data_size),
@@ -1387,11 +1428,11 @@ pcl::PCDWriter::writeBinaryCompressed (std::ostream &os, const pcl::PCLPointClou
     {
       return (-1);
     }
-    memcpy (&temp_buf[0], &compressed_size, 4);
+    memcpy (temp_buf.data(), &compressed_size, 4);
     memcpy (&temp_buf[4], &data_size, 4);
     temp_buf.resize (compressed_size + 8);
   } else {
-    auto *header = reinterpret_cast<std::uint32_t*>(&temp_buf[0]);
+    auto *header = reinterpret_cast<std::uint32_t*>(temp_buf.data());
     header[0] = 0; // compressed_size is 0
     header[1] = 0; // data_size is 0
   }
@@ -1465,7 +1506,7 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, const pcl::
 
   // Prepare the map
 #ifdef _WIN32
-  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, ostr.size (), NULL);
+  HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((ostr.size ()) >> 32), (DWORD) (ostr.size ()), NULL);
   char *map = static_cast<char*> (MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, ostr.size ()));
   CloseHandle (fm);
 
index 28f7c485366cb724c6c7c91b9c9c782ab65c10fd..7e79d2d6162b1461c13f0e03dcea5bd94a5cb10f 100644 (file)
@@ -40,6 +40,7 @@
 
 #include <pcl/io/ply/ply_parser.h>
 
+#include <algorithm> // for find_if
 #include <fstream> // for ifstream
 #include <sstream> // for istringstream
 
@@ -52,9 +53,6 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
 
   std::size_t number_of_format_statements = 0;
   std::size_t number_of_element_statements = 0;
-  std::size_t number_of_property_statements = 0;
-  std::size_t number_of_obj_info_statements = 0;
-  std::size_t number_of_comment_statements = 0;
 
   format_type format = pcl::io::ply::unknown;
   std::vector<std::shared_ptr<element>> elements;
@@ -262,7 +260,6 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
           error_callback_ (line_number_, "parse error: unknown type");
           return false;
         }
-        ++number_of_property_statements;
       }
       else
       {
@@ -418,7 +415,6 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
           error_callback_ (line_number_, "parse error: unknown list size type");
           return false;
         }
-        ++number_of_property_statements;
       }
     }
 
@@ -426,14 +422,12 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
     else if (keyword == "comment")
     {
       comment_callback_ (line);
-      ++number_of_comment_statements;
     }
 
     // obj_info
     else if (keyword == "obj_info")
     {
       obj_info_callback_ (line);
-      ++number_of_obj_info_statements;
     }
 
     // end_header
@@ -461,7 +455,7 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
   {
     for (const auto &element_ptr: elements)
     {
-      auto& element = *(element_ptr.get ());
+      auto& element = *(element_ptr);
       for (std::size_t element_index = 0; element_index < element.count; ++element_index)
       {
         if (element.begin_element_callback)
@@ -479,7 +473,7 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
 
         for (const auto &property_ptr: element.properties)
         {
-          auto& property = *(property_ptr.get ());
+          auto& property = *(property_ptr);
           if (!property.parse (*this, format, stringstream))
           {
             error_callback_ (line_number_, "parse error: element property count doesn't match the declaration in the header");
@@ -515,14 +509,14 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
 
   for (const auto &element_ptr: elements)
   {
-    auto& element = *(element_ptr.get ());
+    auto& element = *(element_ptr);
     for (std::size_t element_index = 0; element_index < element.count; ++element_index)
     {
       if (element.begin_element_callback)
         element.begin_element_callback ();
       for (const auto &property_ptr: element.properties)
       {
-        auto& property = *(property_ptr.get ());
+        auto& property = *(property_ptr);
         if (!property.parse (*this, format, istream))
         {
           return false;
index ea6e306b3c9fa22bb89d9d82d37f2f46933b0951..aaedca8f39d122b061bfeb0b5b3e738172e0cf86 100644 (file)
@@ -70,16 +70,12 @@ pcl::PLYReader::elementDefinitionCallback (const std::string& element_name, std:
     cloud_->point_step = 0;
     cloud_->row_step = 0;
     vertex_count_ = 0;
-    return (std::tuple<std::function<void ()>, std::function<void ()> > (
-              [this] { vertexBeginCallback (); },
-              [this] { vertexEndCallback (); }));
+    return {[this] { vertexBeginCallback(); }, [this] { vertexEndCallback(); }};
   }
   if ((element_name == "face") && polygons_)
   {
     polygons_->reserve (count);
-    return (std::tuple<std::function<void ()>, std::function<void ()> > (
-            [this] { faceBeginCallback (); },
-            [this] { faceEndCallback (); }));
+    return {[this] { faceBeginCallback(); }, [this] { faceEndCallback(); }};
   }
   if (element_name == "camera")
   {
@@ -89,9 +85,7 @@ pcl::PLYReader::elementDefinitionCallback (const std::string& element_name, std:
   if (element_name == "range_grid")
   {
     range_grid_->reserve (count);
-    return (std::tuple<std::function<void ()>, std::function<void ()> > (
-              [this] { rangeGridBeginCallback (); },
-              [this] { rangeGridEndCallback (); }));
+    return {[this] { rangeGridBeginCallback(); }, [this] { rangeGridEndCallback(); }};
   }
   return {};
 }
@@ -100,7 +94,7 @@ bool
 pcl::PLYReader::endHeaderCallback ()
 {
   cloud_->data.resize (static_cast<std::size_t>(cloud_->point_step) * cloud_->width * cloud_->height);
-  return (true);
+  return true;
 }
 
 template<typename Scalar> void
@@ -364,7 +358,7 @@ namespace pcl
         cloud_->point_step = static_cast<std::uint32_t> (std::numeric_limits<std::uint32_t>::max ());
       do_resize_ = true;
       return std::tuple<std::function<void (SizeType)>, std::function<void (ContentType)>, std::function<void ()> > (
-        std::bind (&pcl::PLYReader::vertexListPropertyBeginCallback<SizeType>, this, property_name, std::placeholders::_1),
+        [this, property_name](SizeType size) { this->vertexListPropertyBeginCallback(property_name, size); },
         [this] (ContentType value) { vertexListPropertyContentCallback (value); },
         [this] { vertexListPropertyEndCallback (); }
       );
@@ -379,16 +373,16 @@ pcl::PLYReader::vertexColorCallback (const std::string& color_name, pcl::io::ply
 {
   if ((color_name == "red") || (color_name == "diffuse_red"))
   {
-    r_ = std::int32_t (color);
+    r_ = static_cast<std::int32_t>(color);
     rgb_offset_before_ = vertex_offset_before_;
   }
   if ((color_name == "green") || (color_name == "diffuse_green"))
   {
-    g_ = std::int32_t (color);
+    g_ = static_cast<std::int32_t>(color);
   }
   if ((color_name == "blue") || (color_name == "diffuse_blue"))
   {
-    b_ = std::int32_t (color);
+    b_ = static_cast<std::int32_t>(color);
     std::int32_t rgb = r_ << 16 | g_ << 8 | b_;
     try
     {
@@ -409,7 +403,7 @@ pcl::PLYReader::vertexAlphaCallback (pcl::io::ply::uint8 alpha)
   // get anscient rgb value and store it in rgba
   rgba_ = cloud_->at<std::uint32_t>(vertex_count_, rgb_offset_before_);
   // append alpha
-  a_ = std::uint32_t (alpha);
+  a_ = static_cast<std::uint32_t>(alpha);
   rgba_ |= a_ << 24;
   // put rgba back
   cloud_->at<std::uint32_t>(vertex_count_, rgb_offset_before_) = rgba_;
@@ -568,9 +562,11 @@ pcl::PLYReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
   cloud_->width = cloud_->height = 0;
   origin = Eigen::Vector4f::Zero ();
   orientation = Eigen::Quaternionf::Identity ();
+  origin_ = Eigen::Vector4f::Zero ();
+  orientation_ = Eigen::Matrix3f::Identity ();
   if (!parse (file_name))
   {
-    PCL_ERROR ("[pcl::PLYReader::read] problem parsing header!\n");
+    PCL_ERROR ("[pcl::PLYReader::readHeader] problem parsing header!\n");
     return (-1);
   }
   cloud_->row_step = cloud_->point_step * cloud_->width;
@@ -647,7 +643,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
       }
       else
       {
-        const auto srcIdx = (*range_grid_)[r][0] * cloud_->point_step;
+        const std::size_t srcIdx = (*range_grid_)[r][0] * cloud_->point_step;
         if (srcIdx + cloud_->point_step > cloud_->data.size())
         {
           PCL_ERROR ("[pcl::PLYReader::read] invalid data index (%lu)!\n", srcIdx);
@@ -659,8 +655,8 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud,
     cloud_->data.swap (data);
   }
 
-  orientation_ = Eigen::Quaternionf (orientation);
-  origin_ = origin;
+  orientation = Eigen::Quaternionf (orientation_);
+  origin = origin_;
 
   for (auto &field : cloud_->fields)
   {
@@ -680,6 +676,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
                       Eigen::Vector4f &origin, Eigen::Quaternionf &orientation,
                       int &ply_version, const int offset)
 {
+  PCL_DEBUG("[pcl::PLYReader::read] Reading PolygonMesh from file: %s.\n", file_name.c_str());
   // kept only for backward compatibility
   int data_type;
   unsigned int data_idx;
@@ -746,7 +743,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
       }
       else
       {
-        const auto srcIdx = (*range_grid_)[r][0] * cloud_->point_step;
+        const std::size_t srcIdx = (*range_grid_)[r][0] * cloud_->point_step;
         if (srcIdx + cloud_->point_step > cloud_->data.size())
         {
           PCL_ERROR ("[pcl::PLYReader::read] invalid data index (%lu)!\n", srcIdx);
@@ -758,8 +755,8 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh,
     cloud_->data.swap (data);
   }
 
-  orientation_ = Eigen::Quaternionf (orientation);
-  origin_ = origin;
+  orientation = Eigen::Quaternionf (orientation_);
+  origin = origin_;
 
   for (auto &field : cloud_->fields)
   {
@@ -793,6 +790,7 @@ pcl::PLYWriter::generateHeader (const pcl::PCLPointCloud2 &cloud,
                                 int valid_points)
 {
   std::ostringstream oss;
+  oss.imbue (std::locale::classic ()); // mostly to make sure that no thousands separator is printed
   // Begin header
   oss << "ply";
   if (!binary)
@@ -1536,13 +1534,13 @@ pcl::io::savePLYFile (const std::string &file_name, const pcl::PolygonMesh &mesh
 
       {
         const auto& color = mesh.cloud.at<RGB>(i, mesh.cloud.fields[d].offset);
-        fs << int (color.r) << " " << int (color.g) << " " << int (color.b) << " ";
+        fs << static_cast<int>(color.r) << " " << static_cast<int>(color.g) << " " << static_cast<int>(color.b) << " ";
       }
       else if ((mesh.cloud.fields[d].datatype == pcl::PCLPointField::UINT32) &&
                (mesh.cloud.fields[d].name == "rgba"))
       {
         const auto& color = mesh.cloud.at<RGB>(i, mesh.cloud.fields[d].offset);
-        fs << int (color.r) << " " << int (color.g) << " " << int (color.b) << " " << int (color.a) << " ";
+        fs << static_cast<int>(color.r) << " " << static_cast<int>(color.g) << " " << static_cast<int>(color.b) << " " << static_cast<int>(color.a) << " ";
       }
       else if ((mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && (
                 mesh.cloud.fields[d].name == "normal_x" ||
index f8493eade432644c4e2d5313f8f3457993dd334a..4f3b17b6abd5e494af74e9ecf890b6bfde57ef19 100644 (file)
@@ -103,13 +103,13 @@ pcl::io::saveRgbPNGFile (const std::string& file_name, const unsigned char *rgb_
 void
 pcl::io::savePNGFile (const std::string& file_name, const pcl::PointCloud<unsigned char>& cloud)
 {
-  saveCharPNGFile(file_name, &cloud[0], cloud.width, cloud.height, 1);
+  saveCharPNGFile(file_name, cloud.data(), cloud.width, cloud.height, 1);
 }
 
 void
 pcl::io::savePNGFile (const std::string& file_name, const pcl::PointCloud<unsigned short>& cloud)
 {
-  saveShortPNGFile(file_name, &cloud[0], cloud.width, cloud.height, 1);
+  saveShortPNGFile(file_name, cloud.data(), cloud.width, cloud.height, 1);
 }
 
 void
@@ -117,15 +117,15 @@ pcl::io::savePNGFile (const std::string& file_name, const pcl::PCLImage& image)
 {
     if (image.encoding == "rgb8")
     {
-        saveRgbPNGFile(file_name, &image.data[0], image.width, image.height);
+        saveRgbPNGFile(file_name, image.data.data(), image.width, image.height);
     }
     else if (image.encoding == "mono8")
     {
-        saveCharPNGFile(file_name, &image.data[0], image.width, image.height, 1);
+        saveCharPNGFile(file_name, image.data.data(), image.width, image.height, 1);
     }
     else if (image.encoding == "mono16")
     {
-        saveShortPNGFile(file_name, reinterpret_cast<const unsigned short*>(&image.data[0]), image.width, image.height, 1);
+        saveShortPNGFile(file_name, reinterpret_cast<const unsigned short*>(image.data.data()), image.width, image.height, 1);
     }
     else
     {
index f5dd3ff9566755e401c70dfddfba5f150a0fa614..b034501bab4aee12dae951ecdeab660b67421a1d 100644 (file)
@@ -56,12 +56,6 @@ namespace pcl
     , signal_PointXYZRGBA ( createSignal<signal_librealsense_PointXYZRGBA> () )
     , file_name_or_serial_number_ ( file_name_or_serial_number )
     , repeat_playback_ ( repeat_playback )
-    , quit_ ( false )
-    , running_ ( false )
-    , fps_ ( 0 )
-    , device_width_ ( 424 )
-    , device_height_ ( 240 )
-    , target_fps_ ( 30 )
   {
   }
 
@@ -299,7 +293,7 @@ namespace pcl
   default(none) \
   shared(cloud, cloud_texture_ptr, cloud_vertices_ptr, mapColorFunc)
 #endif
-    for (std::size_t index = 0; index < cloud->size (); ++index)
+    for (std::ptrdiff_t index = 0; index < static_cast<std::ptrdiff_t>(cloud->size()); ++index)
     {
       const auto ptr = cloud_vertices_ptr + index;
       const auto uvptr = cloud_texture_ptr + index;
@@ -319,8 +313,8 @@ namespace pcl
   RealSense2Grabber::getTextureIdx (const rs2::video_frame & texture, float u, float v)
   {
     const int w = texture.get_width (), h = texture.get_height ();
-    int x = std::min (std::max (int (u*w + .5f), 0), w - 1);
-    int y = std::min (std::max (int (v*h + .5f), 0), h - 1);
+    int x = std::min (std::max (static_cast<int> (u*w + .5f), 0), w - 1);
+    int y = std::min (std::max (static_cast<int> (v*h + .5f), 0), h - 1);
     return x * texture.get_bytes_per_pixel () + y * texture.get_stride_in_bytes ();
   }
 
index 55566141b775cac601af7e493bcbe095e224dbb5..2db6da1790680acd9950f92b7069a5d7d243f908 100644 (file)
@@ -74,7 +74,7 @@ pcl::RobotEyeGrabber::~RobotEyeGrabber () noexcept
 std::string
 pcl::RobotEyeGrabber::getName () const
 {
-  return (std::string ("Ocular Robotics RobotEye Grabber"));
+  return {"Ocular Robotics RobotEye Grabber"};
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -234,11 +234,11 @@ pcl::RobotEyeGrabber::computeXYZI (pcl::PointXYZI& point, unsigned char* point_d
 
   buffer =  point_data[2] << 8;
   buffer |= point_data[3]; // Second 2-byte read will be Elevation
-  el = (signed short int)buffer / 100.0;
+  el = static_cast<signed short int>(buffer) / 100.0;
 
   buffer =  point_data[4] << 8;
   buffer |= point_data[5]; // Third 2-byte read will be Range
-  range = (signed short int)buffer / 100.0;
+  range = static_cast<signed short int>(buffer) / 100.0;
 
   buffer =  point_data[6] << 8;
   buffer |= point_data[7]; // Fourth 2-byte read will be Intensity
index f33e49b198771c3cf4e72ef3e1858968f0da0231..a97b9e374da466f97663824bc570c9670c35efa1 100644 (file)
@@ -83,7 +83,7 @@ pcl::TimGrabber::updateLookupTables () {
 ///////////////////////////////////////////////////////////////////////////////////////////////////
 bool
 pcl::TimGrabber::isValidPacket () const {
-  return received_packet_.data ()[length_-1] == '\03';
+  return received_packet_[length_-1] == '\03';
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////////////
@@ -215,7 +215,7 @@ pcl::TimGrabber::isRunning () const
 std::string
 pcl::TimGrabber::getName () const
 {
-  return (std::string ("Sick Tim Grabber"));
+  return {"Sick Tim Grabber"};
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////////////
index b3163eac1d62c326bbc410e45c19e5bd3551b410..b35087b74b95b947d8d4a46a1bfbe00cb0fc3eda 100644 (file)
@@ -215,7 +215,7 @@ pcl::VLPGrabber::toPointClouds (HDLDataPacket *dataPacket)
 std::string
 pcl::VLPGrabber::getName () const
 {
-  return (std::string ("Velodyne LiDAR (VLP) Grabber"));
+  return {"Velodyne LiDAR (VLP) Grabber"};
 }
 
 /////////////////////////////////////////////////////////////////////////////
index f795312f99c522c41a2fa6c20a6c9058470e1b55..bb5a5cfe0416555f75d40caed9c573e84ad219ed 100644 (file)
@@ -456,7 +456,7 @@ pcl::io::mesh2vtk (const pcl::PolygonMesh& mesh, vtkSmartPointer<vtkPolyData>& p
     Eigen::Array4i xyz_offset (mesh.cloud.fields[idx_x].offset, mesh.cloud.fields[idx_y].offset, mesh.cloud.fields[idx_z].offset, 0);
     for (vtkIdType cp = 0; cp < static_cast<vtkIdType> (nr_points); ++cp, xyz_offset += mesh.cloud.point_step)
     {
-      memcpy(&pt[0], &mesh.cloud.data[xyz_offset[0]], sizeof (float));
+      memcpy(&pt[0], &mesh.cloud.data[xyz_offset[0]], sizeof (float)); // NOLINT(readability-container-data-pointer)
       memcpy(&pt[1], &mesh.cloud.data[xyz_offset[1]], sizeof (float));
       memcpy(&pt[2], &mesh.cloud.data[xyz_offset[2]], sizeof (float));
       vtk_mesh_points->InsertPoint (cp, pt[0], pt[1], pt[2]);
diff --git a/io/tools/CMakeLists.txt b/io/tools/CMakeLists.txt
deleted file mode 100644 (file)
index 818da1d..0000000
+++ /dev/null
@@ -1,28 +0,0 @@
-set(SUBSYS_NAME tools)
-
-if(WITH_OPENNI)
-  PCL_ADD_EXECUTABLE(pcl_openni_grabber_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_example.cpp)
-  target_link_libraries(pcl_openni_grabber_example pcl_common pcl_io)
-
-  PCL_ADD_EXECUTABLE(pcl_openni_grabber_depth_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_depth_example.cpp)
-  target_link_libraries(pcl_openni_grabber_depth_example pcl_common pcl_io)
-
-
-  PCL_ADD_EXECUTABLE(pcl_openni_pcd_recorder COMPONENT ${SUBSYS_NAME} SOURCES openni_pcd_recorder.cpp)
-  target_link_libraries(pcl_openni_pcd_recorder pcl_common pcl_io Boost::date_time)
-endif()
-
-PCL_ADD_EXECUTABLE(pcl_pcd_convert_NaN_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_convert_NaN_nan.cpp)
-PCL_ADD_EXECUTABLE(pcl_pcd_introduce_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_introduce_nan.cpp)
-PCL_ADD_EXECUTABLE(pcl_convert_pcd_ascii_binary COMPONENT ${SUBSYS_NAME} SOURCES convert_pcd_ascii_binary.cpp)
-if(VTK_FOUND)
-  PCL_ADD_EXECUTABLE(pcl_converter COMPONENT ${SUBSYS_NAME} SOURCES converter.cpp)
-  target_link_libraries(pcl_converter pcl_common pcl_io)
-endif()
-PCL_ADD_EXECUTABLE(pcl_hdl_grabber COMPONENT ${SUBSYS_NAME} SOURCES hdl_grabber_example.cpp)
-target_link_libraries(pcl_convert_pcd_ascii_binary pcl_common pcl_io)
-target_link_libraries(pcl_hdl_grabber pcl_common pcl_io)
-target_link_libraries(pcl_pcd_introduce_nan pcl_common pcl_io)
-
-#libply inherited tools
-add_subdirectory(ply)
diff --git a/io/tools/convert_pcd_ascii_binary.cpp b/io/tools/convert_pcd_ascii_binary.cpp
deleted file mode 100644 (file)
index 641e373..0000000
+++ /dev/null
@@ -1,93 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2009, 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: convert_pcd_ascii_binary.cpp 33162 2010-03-10 07:41:56Z rusu $
- *
- */
-
-/**
-
-\author Radu Bogdan Rusu
-
-@b convert_pcd_ascii_binary converts PCD (Point Cloud Data) files from ascii to binary and viceversa.
-
- **/
-
-#include <iostream>
-#include <pcl/common/io.h>
-#include <pcl/io/pcd_io.h>
-#include <string>
-
-/* ---[ */
-int
-main (int argc, char** argv)
-{
-  if (argc < 4)
-  {
-    std::cerr << "Syntax is: " << argv[0] << " <file_in.pcd> <file_out.pcd> 0/1/2 (ascii/binary/binary_compressed) [precision (ASCII)]" << std::endl;
-    return (-1);
-  }
-
-  pcl::PCLPointCloud2 cloud;
-  Eigen::Vector4f origin; Eigen::Quaternionf orientation;
-
-  if (pcl::io::loadPCDFile (std::string (argv[1]), cloud, origin, orientation) < 0)
-  {
-    std::cerr << "Unable to load " << argv[1] << std::endl;
-    return (-1);
-  }
-
-  int type = atoi (argv[3]);
-
-  std::cerr << "Loaded a point cloud with " << cloud.width * cloud.height << 
-               " points (total size is " << cloud.data.size () << 
-               ") and the following channels: " << pcl::getFieldsList (cloud) << std::endl;
-
-  pcl::PCDWriter w;
-  if (type == 0)
-  {
-    std::cerr << "Saving file " << argv[2] << " as ASCII." << std::endl;
-    w.writeASCII (std::string (argv[2]), cloud, origin, orientation, (argc == 5) ? atoi (argv[4]) : 7);
-  }
-  else if (type == 1)
-  {
-    std::cerr << "Saving file " << argv[2] << " as binary." << std::endl;
-    w.writeBinary (std::string (argv[2]), cloud, origin, orientation);
-  }
-  else if (type == 2)
-  {
-    std::cerr << "Saving file " << argv[2] << " as binary_compressed." << std::endl;
-    w.writeBinaryCompressed (std::string (argv[2]), cloud, origin, orientation);
-  }
-}
-/* ]--- */
diff --git a/io/tools/converter.cpp b/io/tools/converter.cpp
deleted file mode 100644 (file)
index dd155ec..0000000
+++ /dev/null
@@ -1,308 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2014-, 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.
- */
-
-/**
- \author Victor Lamoine
- @b convert_point_clouds_meshes converts OBJ, PCD, PLY, STL, VTK files containing point clouds or meshes into every other format.
- This tool allows to specify the file output type between ASCII, binary and binary compressed.
- **/
-
-//TODO: Inform user about loss of color/alpha during conversion?
-// STL does not support color at all
-// OBJ does not support color in PCL (the format DOES support color)
-
-#include <vector>
-
-#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
-#define BINARY 1
-#define BINARY_COMPRESSED 2
-
-/**
- * Display help for this program
- * @param argc[in]
- * @param argv[in]
- */
-void
-displayHelp (int,
-             char** argv)
-{
-  PCL_INFO ("\nUsage: %s [OPTION] SOURCE DEST\n", argv[0]);
-  PCL_INFO ("Convert SOURCE point cloud or mesh to DEST.\n\n");
-
-  PCL_INFO ("Available formats types for SOURCE and DEST:\n"
-           "\tOBJ (Wavefront)\n"
-           "\tPCD (Point Cloud Library)\n"
-           "\tPLY (Polygon File Format)\n"
-           "\tSTL (STereoLithography)\n"
-           "\tVTK (The Visualization Toolkit)\n\n");
-
-  PCL_INFO ("Available options:\n"
-           "\t-f, --format Specify DEST output type, available formats are ascii, binary and binary_compressed.\n"
-           "\t             When not specified, binary is used as default.\n"
-           "\t             OBJ only supports ascii format.\n"
-           "\t             binary_compressed is only supported by the PCD file format.\n\n"
-           "\t-c --cloud   Output DEST as a point cloud, delete all faces.\n\n");
-}
-
-bool
-saveMesh (pcl::PolygonMesh& input,
-          std::string output_file,
-          int output_type);
-
-/**
- * Saves a cloud into the specified file and output type. The file format is automatically parsed.
- * @param input[in] The cloud to be saved
- * @param output_file[out] The output file to be written
- * @param output_type[in] The output file type
- * @return True on success, false otherwise.
- */
-bool
-savePointCloud (const pcl::PCLPointCloud2::Ptr& input,
-                std::string output_file,
-                int output_type)
-{
-  if (boost::filesystem::path (output_file).extension () == ".pcd")
-  {
-    //TODO Support precision, origin, orientation
-    pcl::PCDWriter w;
-    if (output_type == ASCII)
-    {
-      PCL_INFO ("Saving file %s as ASCII.\n", output_file.c_str ());
-      if (w.writeASCII (output_file, *input) != 0)
-        return (false);
-    }
-    else if (output_type == BINARY)
-    {
-      PCL_INFO ("Saving file %s as binary.\n", output_file.c_str ());
-      if (w.writeBinary (output_file, *input) != 0)
-        return (false);
-    }
-    else if (output_type == BINARY_COMPRESSED)
-    {
-      PCL_INFO ("Saving file %s as binary compressed.\n", output_file.c_str ());
-      if (w.writeBinaryCompressed (output_file, *input) != 0)
-        return (false);
-    }
-  }
-  else if (boost::filesystem::path (output_file).extension () == ".stl")
-  {
-    PCL_ERROR ("STL file format does not support point clouds! Aborting.\n");
-    return (false);
-  }
-  else  // OBJ, PLY and VTK
-  {
-    //TODO: Support precision
-    //FIXME: Color is lost during OBJ conversion (OBJ supports color)
-    pcl::PolygonMesh mesh;
-    mesh.cloud = *input;
-    if (!saveMesh (mesh, output_file, output_type))
-      return (false);
-  }
-
-  return (true);
-}
-
-/**
- * Saves a mesh into the specified file and output type. The file format is automatically parsed.
- * @param input[in] The mesh to be saved
- * @param output_file[out] The output file to be written
- * @param output_type[in]  The output file type
- * @return True on success, false otherwise.
- */
-bool
-saveMesh (pcl::PolygonMesh& input,
-          std::string output_file,
-          int output_type)
-{
-  if (boost::filesystem::path (output_file).extension () == ".obj")
-  {
-    if (output_type == BINARY || output_type == BINARY_COMPRESSED)
-      PCL_WARN ("OBJ file format only supports ASCII.\n");
-
-    //TODO: Support precision
-    //FIXME: Color is lost during conversion (OBJ supports color)
-    PCL_INFO ("Saving file %s as ASCII.\n", output_file.c_str ());
-    if (pcl::io::saveOBJFile (output_file, input) != 0)
-      return (false);
-  }
-  else if (boost::filesystem::path (output_file).extension () == ".pcd")
-  {
-    if (!input.polygons.empty ())
-      PCL_WARN ("PCD file format does not support meshes! Only points be saved.\n");
-    pcl::PCLPointCloud2::Ptr cloud = pcl::make_shared<pcl::PCLPointCloud2> (input.cloud);
-    if (!savePointCloud (cloud, output_file, output_type))
-      return (false);
-  }
-  else  // PLY, STL and VTK
-  {
-    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")
-    {
-      PCL_ERROR ("STL file format does not support point clouds! Aborting.\n");
-      return (false);
-    }
-
-    PCL_INFO ("Saving file %s as %s.\n", output_file.c_str (), (output_type == ASCII) ? "ASCII" : "binary");
-    if (!pcl::io::savePolygonFile (output_file, input, output_type != ASCII))
-      return (false);
-  }
-
-  return (true);
-}
-
-/**
- * Parse input files and options. Calls the right conversion function.
- * @param argc[in]
- * @param argv[in]
- * @return 0 on success, any other value on failure.
- */
-int
-main (int argc,
-      char** argv)
-{
-  // Display help
-  if (pcl::console::find_switch (argc, argv, "-h") != 0 || pcl::console::find_switch (argc, argv, "--help") != 0)
-  {
-    displayHelp (argc, argv);
-    return (0);
-  }
-
-  // Parse all files and options
-  std::vector<std::string> supported_extensions;
-  supported_extensions.emplace_back("obj");
-  supported_extensions.emplace_back("pcd");
-  supported_extensions.emplace_back("ply");
-  supported_extensions.emplace_back("stl");
-  supported_extensions.emplace_back("vtk");
-  std::vector<int> file_args;
-  for (int i = 1; i < argc; ++i)
-    for (const auto &supported_extension : supported_extensions)
-      if (boost::algorithm::ends_with(argv[i], supported_extension))
-      {
-        file_args.push_back(i);
-        break;
-      }
-
-  std::string parsed_output_type;
-  pcl::console::parse_argument (argc, argv, "-f", parsed_output_type);
-  pcl::console::parse_argument (argc, argv, "--format", parsed_output_type);
-  bool cloud_output (false);
-  if (pcl::console::find_switch (argc, argv, "-c") != 0 ||
-      pcl::console::find_switch (argc, argv, "--cloud") != 0)
-    cloud_output = true;
-
-  // Make sure that we have one input and one output file only
-  if (file_args.size() != 2)
-  {
-    PCL_ERROR ("Wrong input/output file count!\n");
-    displayHelp (argc, argv);
-    return (-1);
-  }
-
-  // Convert parsed output type to output type
-  int output_type (BINARY);
-  if (!parsed_output_type.empty ())
-  {
-    if (parsed_output_type == "ascii")
-      output_type = ASCII;
-    else if (parsed_output_type == "binary")
-      output_type = BINARY;
-    else if (parsed_output_type == "binary_compressed")
-      output_type = BINARY_COMPRESSED;
-    else
-    {
-      PCL_ERROR ("Wrong output type!\n");
-      displayHelp (argc, argv);
-      return (-1);
-    }
-  }
-
-  // Try to load as mesh
-  pcl::PolygonMesh mesh;
-  if (boost::filesystem::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",
-             mesh.cloud.width * mesh.cloud.height, mesh.cloud.data.size (), pcl::getFieldsList (mesh.cloud).c_str ());
-
-    if (cloud_output)
-      mesh.polygons.clear();
-
-    if (!saveMesh (mesh, argv[file_args[1]], output_type))
-      return (-1);
-  }
-  else if (boost::filesystem::path (argv[file_args[0]]).extension () == ".stl")
-  {
-    PCL_ERROR ("Unable to load %s.\n", argv[file_args[0]]);
-    return (-1);
-  }
-  else
-  {
-    // PCD, OBJ, PLY or VTK
-    if (boost::filesystem::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
-    //Eigen::Quaternionf orientation;
-    pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
-    if (pcl::io::load (argv[file_args[0]], *cloud) < 0)
-    {
-      PCL_ERROR ("Unable to load %s.\n", argv[file_args[0]]);
-      return (-1);
-    }
-
-    PCL_INFO ("Loaded a point cloud with %d points (total size is %d) and the following channels:\n%s\n", cloud->width * cloud->height, cloud->data.size (),
-              pcl::getFieldsList (*cloud).c_str ());
-
-    if (!savePointCloud (cloud, argv[file_args[1]], output_type))
-    {
-      PCL_ERROR ("Failed to save %s.\n", argv[file_args[1]]);
-      return (-1);
-    }
-  }
-  return (0);
-}
diff --git a/io/tools/hdl_grabber_example.cpp b/io/tools/hdl_grabber_example.cpp
deleted file mode 100644 (file)
index f2ae270..0000000
+++ /dev/null
@@ -1,111 +0,0 @@
-/*
- * hdl_grabber_example.cpp
- *
- *  Created on: Nov 29, 2012
- *      Author: keven
- */
-
-#include <string>
-#include <iostream>
-#include <iomanip>
-
-#include <pcl/io/hdl_grabber.h>
-#include <pcl/console/parse.h>
-#include <pcl/common/time.h>
-
-class SimpleHDLGrabber 
-{
-  public:
-    std::string calibrationFile, pcapFile;
-
-    SimpleHDLGrabber (std::string& calibFile, std::string& pcapFile) 
-      : calibrationFile (calibFile)
-      , pcapFile (pcapFile) 
-    {
-    }
-
-    void 
-    sectorScan (
-        const pcl::PointCloud<pcl::PointXYZI>::ConstPtr&,
-        float,
-        float) 
-    {
-      static unsigned count = 0;
-      static double last = pcl::getTime ();
-      if (++count == 30) 
-      {
-        double now = pcl::getTime();
-        std::cout << "got sector scan.  Avg Framerate " << double(count) / double(now - last) << " Hz" << std::endl;
-        count = 0;
-        last = now;
-      }
-    }
-
-    void 
-    sweepScan (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& sweep)
-    {
-      static unsigned count = 0;
-      static double last = pcl::getTime();
-
-      if (sweep->header.seq == 0) {
-        std::uint64_t stamp;
-        stamp = sweep->header.stamp;
-        time_t systemTime = static_cast<time_t>(((stamp & 0xffffffff00000000l) >> 32) & 0x00000000ffffffff);
-        auto usec = static_cast<std::uint32_t>(stamp & 0x00000000ffffffff);
-        std::cout << std::hex << stamp << "  " << ctime(&systemTime) << " usec: " << usec << std::endl;
-      }
-
-      if (++count == 30) 
-      {
-        double now = pcl::getTime ();
-        std::cout << "got sweep.  Avg Framerate " << double(count) / double(now - last) << " Hz" << std::endl;
-        count = 0;
-        last = now;
-      }
-    }
-
-    void 
-    run () 
-    {
-      pcl::HDLGrabber interface (calibrationFile, pcapFile);
-      // make callback function from member function
-      std::function<void(const pcl::PointCloud<pcl::PointXYZI>::ConstPtr&, float, float)> f =
-          [this] (const pcl::PointCloud<pcl::PointXYZI>::ConstPtr& p1, float p2, float p3) { sectorScan (p1, p2, p3); };
-
-      // connect callback function for desired signal. In this case its a sector with XYZ and intensity information
-      //boost::signals2::connection c = interface.registerCallback(f);
-
-      // Register a callback function that gets complete 360 degree sweeps.
-      std::function<void(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)> f2 =
-          [this] (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& sweep) { sweepScan (sweep); };
-      boost::signals2::connection c2 = interface.registerCallback(f2);
-
-      //interface.filterPackets(boost::asio::ip::address_v4::from_string("192.168.18.38"));
-
-      // start receiving point clouds
-      interface.start ();
-
-      std::cout << R"(<Esc>, 'q', 'Q': quit the program)" << std::endl;
-      char key;
-      do 
-      {
-        key = static_cast<char> (getchar ());
-      } while (key != 27 && key != 'q' && key != 'Q');
-
-      // stop the grabber
-      interface.stop ();
-    }
-};
-
-int 
-main (int argc, char **argv) 
-{
-       std::string hdlCalibration, pcapFile;
-
-       pcl::console::parse_argument (argc, argv, "-calibrationFile", hdlCalibration);
-       pcl::console::parse_argument (argc, argv, "-pcapFile", pcapFile);
-
-       SimpleHDLGrabber grabber (hdlCalibration, pcapFile);
-       grabber.run ();
-       return (0);
-}
diff --git a/io/tools/openni_grabber_depth_example.cpp b/io/tools/openni_grabber_depth_example.cpp
deleted file mode 100644 (file)
index 4f29daf..0000000
+++ /dev/null
@@ -1,114 +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.
- *
- */
-
-#include <pcl/io/openni_grabber.h>
-#include <pcl/common/time.h>
-#include <pcl/console/parse.h>
-
-class SimpleOpenNIProcessor
-{
-  public:
-    bool save;
-    openni_wrapper::OpenNIDevice::DepthMode mode;
-
-    SimpleOpenNIProcessor (openni_wrapper::OpenNIDevice::DepthMode depth_mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth) : mode (depth_mode) {}
-
-    void 
-    imageDepthImageCallback (const openni_wrapper::DepthImage::Ptr& d_img)
-    {
-      static unsigned count = 0;
-      static double last = pcl::getTime ();
-      if (++count == 30)
-      {
-        double now = pcl::getTime ();
-        std::cout << "got depth-image. Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
-        std::cout << "Depth baseline: " << d_img->getBaseline () << " and focal length: " << d_img->getFocalLength () << std::endl;
-        count = 0;
-        last = now;
-      }
-    }
-
-    void 
-    run ()
-    {
-      save = false;
-
-      // create a new grabber for OpenNI devices
-      pcl::OpenNIGrabber interface;
-
-      // Set the depth output format
-      interface.getDevice ()->setDepthOutputFormat (mode);
-
-      // make callback function from member function
-      std::function<void (const openni_wrapper::DepthImage::Ptr&)> f2 = [this] (const openni_wrapper::DepthImage::Ptr& depth)
-      {
-        imageDepthImageCallback (depth);
-      };
-
-      // connect callback function for desired signal. In this case its a point cloud with color values
-      boost::signals2::connection c2 = interface.registerCallback (f2);
-
-      // start receiving point clouds
-      interface.start ();
-
-      std::cout << R"(<Esc>, 'q', 'Q': quit the program)" << std::endl;
-      std::cout << "\' \': pause" << std::endl;
-      char key;
-      do
-      {
-        key = static_cast<char> (getchar ());
-        if (key == ' ')
-        {
-          interface.toggle ();
-        }
-      } while ((key != 27) && (key != 'q') && (key != 'Q'));
-
-      // stop the grabber
-      interface.stop ();
-    }
-};
-
-int
-main (int argc, char **argv)
-{
-  int mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
-  pcl::console::parse_argument (argc, argv, "-mode", mode);
-
-  SimpleOpenNIProcessor v (static_cast<openni_wrapper::OpenNIDevice::DepthMode> (mode));
-  v.run ();
-  return (0);
-}
diff --git a/io/tools/openni_grabber_example.cpp b/io/tools/openni_grabber_example.cpp
deleted file mode 100644 (file)
index 32448bf..0000000
+++ /dev/null
@@ -1,156 +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: Suat Gedikli (gedikli@willowgarage.com)
- */
-
-#include <pcl/point_cloud.h>
-#include <pcl/point_types.h>
-#include <pcl/io/pcd_io.h>
-#include <pcl/io/openni_grabber.h>
-#include <pcl/common/time.h>
-#include <pcl/console/parse.h>
-#include <iomanip> // for setprecision
-
-class SimpleOpenNIProcessor
-{
-  public:
-    bool save;
-    openni_wrapper::OpenNIDevice::DepthMode mode;
-
-    SimpleOpenNIProcessor (openni_wrapper::OpenNIDevice::DepthMode depth_mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth) : mode (depth_mode) {}
-
-    void 
-    cloud_cb_ (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud) const
-    {
-      static unsigned count = 0;
-      static double last = pcl::getTime ();
-      if (++count == 30)
-      {
-        double now = pcl::getTime ();
-        std::cout << "distance of center pixel :" << cloud->points [(cloud->width >> 1) * (cloud->height + 1)].z << " mm. Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
-        count = 0;
-        last = now;
-      }
-
-      if (save)
-      {
-        std::stringstream ss;
-        ss << std::setprecision (12) << pcl::getTime () * 100 << ".pcd";
-        pcl::PCDWriter w;
-        w.writeBinaryCompressed (ss.str (), *cloud);
-        std::cout << "wrote point clouds to file " << ss.str () << std::endl;
-      }
-    }
-
-    void 
-    imageDepthImageCallback (const openni_wrapper::Image::Ptr&, const openni_wrapper::DepthImage::Ptr& d_img, float constant)
-    {
-      static unsigned count = 0;
-      static double last = pcl::getTime ();
-      if (++count == 30)
-      {
-        double now = pcl::getTime ();
-        std::cout << "got synchronized image x depth-image with constant factor: " << constant << ". Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
-        std::cout << "Depth baseline: " << d_img->getBaseline () << " and focal length: " << d_img->getFocalLength () << std::endl;
-        count = 0;
-        last = now;
-      }
-    }
-
-    void 
-    run ()
-    {
-      save = false;
-
-      // create a new grabber for OpenNI devices
-      pcl::OpenNIGrabber interface;
-
-      // Set the depth output format
-      interface.getDevice ()->setDepthOutputFormat (mode);
-
-      // make callback function from member function
-      std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
-        [this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud) { cloud_cb_ (cloud); };
-
-      // connect callback function for desired signal. In this case its a point cloud with color values
-      boost::signals2::connection c = interface.registerCallback (f);
-
-      // make callback function from member function
-      std::function<void (const openni_wrapper::Image::Ptr&, const openni_wrapper::DepthImage::Ptr&, float constant)> f2 =
-        [this] (const openni_wrapper::Image::Ptr& img, const openni_wrapper::DepthImage::Ptr& depth, float constant)
-        {
-          imageDepthImageCallback (img, depth, constant);
-        };
-
-      // connect callback function for desired signal. In this case its a point cloud with color values
-      boost::signals2::connection c2 = interface.registerCallback (f2);
-
-      // start receiving point clouds
-      interface.start ();
-
-      std::cout << R"(<Esc>, 'q', 'Q': quit the program)" << std::endl;
-      std::cout << "\' \': pause" << std::endl;
-      std::cout << "\'s\': save" << std::endl;
-      char key;
-      do
-      {
-        key = static_cast<char> (getchar ());
-        switch (key)
-        {
-          case ' ':
-            if (interface.isRunning ())
-              interface.stop ();
-            else
-              interface.start ();
-            break;
-          case 's':
-            save = !save;
-        }
-      } while (key != 27 && key != 'q' && key != 'Q');
-
-      // stop the grabber
-      interface.stop ();
-    }
-};
-
-int
-main (int argc, char **argv)
-{
-  int mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
-  pcl::console::parse_argument (argc, argv, "-mode", mode);
-
-  SimpleOpenNIProcessor v (static_cast<openni_wrapper::OpenNIDevice::DepthMode> (mode));
-  v.run ();
-  return (0);
-}
diff --git a/io/tools/openni_pcd_recorder.cpp b/io/tools/openni_pcd_recorder.cpp
deleted file mode 100644 (file)
index 50f82d8..0000000
+++ /dev/null
@@ -1,489 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2012, Sudarshan Srinivasan <sudarshan85@gmail.com>
- *  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.
- * 
- *  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/point_cloud.h>
-#include <pcl/point_types.h>
-#include <pcl/io/openni_grabber.h>
-#include <boost/circular_buffer.hpp>
-#include <boost/date_time/posix_time/posix_time.hpp> // for to_iso_string, local_time
-#include <pcl/io/pcd_io.h>
-#include <pcl/console/print.h>
-#include <pcl/console/parse.h>
-#include <pcl/common/time.h> //fps calculations
-
-#include <csignal>
-#include <limits>
-#include <memory>
-#include <thread>
-
-using namespace std::chrono_literals;
-using namespace pcl;
-using namespace pcl::console;
-
-bool is_done = false;
-std::mutex io_mutex;
-
-#if defined(__linux__) || defined (TARGET_OS_MAC)
-#include <unistd.h>
-// Get the available memory size on Linux/BSD systems
-
-size_t 
-getTotalSystemMemory ()
-{
-  std::uint64_t memory = std::numeric_limits<std::size_t>::max ();
-
-#ifdef _SC_AVPHYS_PAGES
-  std::uint64_t pages = sysconf (_SC_AVPHYS_PAGES);
-  std::uint64_t page_size = sysconf (_SC_PAGE_SIZE);
-  
-  memory = pages * page_size;
-  
-#elif defined(HAVE_SYSCTL) && defined(HW_PHYSMEM)
-  // This works on *bsd and darwin.
-  unsigned int physmem;
-  std::size_t len = sizeof physmem;
-  static int mib[2] = { CTL_HW, HW_PHYSMEM };
-
-  if (sysctl (mib, ARRAY_SIZE (mib), &physmem, &len, NULL, 0) == 0 && len == sizeof (physmem))
-  {
-    memory = physmem;
-  }
-#endif
-
-  if (memory > std::uint64_t (std::numeric_limits<std::size_t>::max ()))
-  {
-    memory = std::numeric_limits<std::size_t>::max ();
-  }
-  
-  print_info ("Total available memory size: %lluMB.\n", memory / 1048576ull);
-  return std::size_t (memory);
-}
-
-const std::size_t BUFFER_SIZE = std::size_t (getTotalSystemMemory () / (640 * 480 * sizeof (pcl::PointXYZRGBA)));
-#else
-
-const std::size_t BUFFER_SIZE = 200;
-#endif
-
-//////////////////////////////////////////////////////////////////////////////////////////
-template <typename PointT>
-class PCDBuffer
-{
-  public:
-    PCDBuffer () = default;
-    PCDBuffer (const PCDBuffer&) = delete; // Disabled copy constructor
-    PCDBuffer& operator = (const PCDBuffer&) = delete; // Disabled assignment operator
-
-    bool 
-    pushBack (typename PointCloud<PointT>::ConstPtr); // thread-save wrapper for push_back() method of ciruclar_buffer
-
-    typename PointCloud<PointT>::ConstPtr 
-    getFront (); // thread-save wrapper for front() method of ciruclar_buffer
-
-    inline bool 
-    isFull ()
-    {
-      std::lock_guard<std::mutex> buff_lock (bmutex_);
-      return (buffer_.full ());
-    }
-
-    inline bool
-    isEmpty ()
-    {
-      std::lock_guard<std::mutex> buff_lock (bmutex_);
-      return (buffer_.empty ());
-    }
-
-    inline int 
-    getSize ()
-    {
-      std::lock_guard<std::mutex> buff_lock (bmutex_);
-      return (int (buffer_.size ()));
-    }
-
-    inline int 
-    getCapacity ()
-    {
-      return (int (buffer_.capacity ()));
-    }
-
-    inline void 
-    setCapacity (int buff_size)
-    {
-      std::lock_guard<std::mutex> buff_lock (bmutex_);
-      buffer_.set_capacity (buff_size);
-    }
-
-  private:
-    std::mutex bmutex_;
-    std::condition_variable buff_empty_;
-    boost::circular_buffer<typename PointCloud<PointT>::ConstPtr> buffer_;
-};
-
-//////////////////////////////////////////////////////////////////////////////////////////
-template <typename PointT> bool 
-PCDBuffer<PointT>::pushBack (typename PointCloud<PointT>::ConstPtr cloud)
-{
-  bool retVal = false;
-  {
-    std::lock_guard<std::mutex> buff_lock (bmutex_);
-    if (!buffer_.full ())
-      retVal = true;
-    buffer_.push_back (cloud);
-  }
-  buff_empty_.notify_one ();
-  return (retVal);
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////
-template <typename PointT> typename PointCloud<PointT>::ConstPtr 
-PCDBuffer<PointT>::getFront ()
-{
-  typename PointCloud<PointT>::ConstPtr cloud;
-  {
-    std::unique_lock<std::mutex> buff_lock (bmutex_);
-    while (buffer_.empty ())
-    {
-      if (is_done)
-        break;
-      {
-        std::lock_guard<std::mutex> io_lock (io_mutex);
-        //std::cerr << "No data in buffer_ yet or buffer is empty." << std::endl;
-      }
-      buff_empty_.wait (buff_lock);
-    }
-    cloud = buffer_.front ();
-    buffer_.pop_front ();
-  }
-  return (cloud);
-}
-
-#define FPS_CALC(_WHAT_, buff) \
-do \
-{ \
-    static unsigned count = 0;\
-    static double last = getTime ();\
-    double now = getTime (); \
-    ++count; \
-    if (now - last >= 1.0) \
-    { \
-      std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << "\n"; \
-      count = 0; \
-      last = now; \
-    } \
-}while(false)
-
-//////////////////////////////////////////////////////////////////////////////////////////
-// Producer thread class
-template <typename PointT>
-class Producer
-{
-  private:
-    ///////////////////////////////////////////////////////////////////////////////////////
-    void 
-    grabberCallBack (const typename PointCloud<PointT>::ConstPtr& cloud)
-    {
-      if (!buf_.pushBack (cloud))
-      {
-        {
-          std::lock_guard<std::mutex> io_lock (io_mutex);
-          print_warn ("Warning! Buffer was full, overwriting data!\n");
-        }
-      }
-      FPS_CALC ("cloud callback.", buf_);
-    }
-
-    ///////////////////////////////////////////////////////////////////////////////////////
-    void 
-    grabAndSend ()
-    {
-      auto* grabber = new OpenNIGrabber ();
-      grabber->getDevice ()->setDepthOutputFormat (depth_mode_);
-
-      Grabber* interface = grabber;
-      std::function<void (const typename PointCloud<PointT>::ConstPtr&)> f = [this] (const typename PointCloud<PointT>::ConstPtr& cloud)
-      {
-        grabberCallBack (cloud);
-      };
-      interface->registerCallback (f);
-      interface->start ();
-
-      while (true)
-      {
-        if (is_done)
-          break;
-        std::this_thread::sleep_for(1s);
-      }
-      interface->stop ();
-    }
-
-  public:
-    Producer (PCDBuffer<PointT> &buf, openni_wrapper::OpenNIDevice::DepthMode depth_mode)
-      : buf_ (buf),
-        depth_mode_ (depth_mode)
-    {
-      thread_.reset (new std::thread (&Producer::grabAndSend, this));
-    }
-
-    ///////////////////////////////////////////////////////////////////////////////////////
-    void
-    stop ()
-    {
-      thread_->join ();
-      std::lock_guard<std::mutex> io_lock (io_mutex);
-      print_highlight ("Producer done.\n");
-    }
-
-  private:
-    PCDBuffer<PointT> &buf_;
-    openni_wrapper::OpenNIDevice::DepthMode depth_mode_;
-    std::shared_ptr<std::thread> thread_;
-};
-
-//////////////////////////////////////////////////////////////////////////////////////////
-// Consumer thread class
-template <typename PointT>
-class Consumer
-{
-  private:
-    ///////////////////////////////////////////////////////////////////////////////////////
-    void 
-    writeToDisk (const typename PointCloud<PointT>::ConstPtr& cloud)
-    {
-      std::stringstream ss;
-      std::string time = boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ());
-      ss << "frame-" << time << ".pcd";
-      writer_.writeBinaryCompressed (ss.str (), *cloud);
-      FPS_CALC ("cloud write.", buf_);
-    }
-
-    ///////////////////////////////////////////////////////////////////////////////////////
-    // Consumer thread function
-    void 
-    receiveAndProcess ()
-    {
-      while (true)
-      {
-        if (is_done)
-          break;
-        writeToDisk (buf_.getFront ());
-      }
-
-      {
-        std::lock_guard<std::mutex> io_lock (io_mutex);
-        print_info ("Writing remaining %ld clouds in the buffer to disk...\n", buf_.getSize ());
-      }
-      while (!buf_.isEmpty ())
-        writeToDisk (buf_.getFront ());
-    }
-
-  public:
-    Consumer (PCDBuffer<PointT> &buf)
-      : buf_ (buf)
-    {
-      thread_.reset (new std::thread (&Consumer::receiveAndProcess, this));
-    }
-
-    ///////////////////////////////////////////////////////////////////////////////////////
-    void
-    stop ()
-    {
-      thread_->join ();
-      std::lock_guard<std::mutex> io_lock (io_mutex);
-      print_highlight ("Consumer done.\n");
-    }
-
-  private:
-    PCDBuffer<PointT> &buf_;
-    std::shared_ptr<std::thread> thread_;
-    PCDWriter writer_;
-};
-
-//////////////////////////////////////////////////////////////////////////////////////////
-void 
-ctrlC (int)
-{
-  std::lock_guard<std::mutex> io_lock (io_mutex);
-  print_info ("\nCtrl-C detected, exit condition set to true.\n");
-  is_done = true;
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////
-void
-printHelp (int default_buff_size, int, char **argv)
-{
-  using pcl::console::print_error;
-  using pcl::console::print_info;
-
-  print_error ("Syntax is: %s ((<device_id> | <path-to-oni-file>) [-xyz] [-shift] [-buf X]  | -l [<device_id>] | -h | --help)]\n", argv [0]);
-  print_info ("%s -h | --help : shows this help\n", argv [0]);
-  print_info ("%s -xyz : save only XYZ data, even if the device is RGB capable\n", argv [0]);
-  print_info ("%s -shift : use OpenNI shift values rather than 12-bit depth\n", argv [0]);
-  print_info ("%s -buf X ; use a buffer size of X frames (default: ", argv [0]);
-  print_value ("%d", default_buff_size); print_info (")\n");
-  print_info ("%s -l : list all available devices\n", argv [0]);
-  print_info ("%s -l <device-id> :list all available modes for specified device\n", argv [0]);
-  print_info ("\t\t<device_id> may be \"#1\", \"#2\", ... for the first, second etc device in the list\n");
-#ifndef _WIN32
-  print_info ("\t\t                   bus@address for the device connected to a specific usb-bus / address combination\n");
-  print_info ("\t\t                   <serial-number>\n");
-#endif
-  print_info ("\n\nexamples:\n");
-  print_info ("%s \"#1\"\n", argv [0]);
-  print_info ("\t\t uses the first device.\n");
-  print_info ("%s  \"./temp/test.oni\"\n", argv [0]);
-  print_info ("\t\t uses the oni-player device to play back oni file given by path.\n");
-  print_info ("%s -l\n", argv [0]);
-  print_info ("\t\t list all available devices.\n");
-  print_info ("%s -l \"#2\"\n", argv [0]);
-  print_info ("\t\t list all available modes for the second device.\n");
-  #ifndef _WIN32
-  print_info ("%s A00361800903049A\n", argv [0]);
-  print_info ("\t\t uses the device with the serial number \'A00361800903049A\'.\n");
-  print_info ("%s 1@16\n", argv [0]);
-  print_info ("\t\t uses the device on address 16 at USB bus 1.\n");
-  #endif
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////
-int
-main (int argc, char** argv)
-{
-  print_highlight ("PCL OpenNI Recorder for saving buffered PCD (binary compressed to disk). See %s -h for options.\n", argv[0]);
-
-  std::string device_id;
-  int buff_size = BUFFER_SIZE;
-
-  if (argc >= 2)
-  {
-    device_id = argv[1];
-    if (device_id == "--help" || device_id == "-h")
-    {
-      printHelp (buff_size, argc, argv);
-      return 0;
-    }
-    if (device_id == "-l")
-    {
-      if (argc >= 3)
-      {
-        pcl::OpenNIGrabber grabber (argv[2]);
-        openni_wrapper::OpenNIDevice::Ptr device = grabber.getDevice ();
-        std::cout << "Supported depth modes for device: " << device->getVendorName () << " , " << device->getProductName () << std::endl;
-        std::vector<std::pair<int, XnMapOutputMode > > modes = grabber.getAvailableDepthModes ();
-        for (const auto& mode : modes)
-        {
-          std::cout << mode.first << " = " << mode.second.nXRes << " x " << mode.second.nYRes << " @ " << mode.second.nFPS << std::endl;
-        }
-
-        if (device->hasImageStream ())
-        {
-          std::cout << std::endl << "Supported image modes for device: " << device->getVendorName () << " , " << device->getProductName () << std::endl;
-          modes = grabber.getAvailableImageModes ();
-          for (const auto& mode : modes)
-          {
-            std::cout << mode.first << " = " << mode.second.nXRes << " x " << mode.second.nYRes << " @ " << mode.second.nFPS << std::endl;
-          }
-        }
-      }
-      else
-      {
-        openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
-        if (driver.getNumberDevices() > 0)
-        {
-          for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
-          {
-            std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
-              << ", connected: " << driver.getBus(deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
-          }
-
-        }
-        else
-          std::cout << "No devices connected." << std::endl;
-
-        std::cout <<"Virtual Devices available: ONI player" << std::endl;
-      }
-      return 0;
-    }
-  }
-  else
-  {
-    openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
-    if (driver.getNumberDevices () > 0)
-      std::cout << "Device Id not set, using first device." << std::endl;
-  }
-
-  bool just_xyz = find_switch (argc, argv, "-xyz");
-  openni_wrapper::OpenNIDevice::DepthMode depth_mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
-  if (find_switch (argc, argv, "-shift"))
-    depth_mode = openni_wrapper::OpenNIDevice::OpenNI_shift_values;
-
-  if (parse_argument (argc, argv, "-buf", buff_size) != -1)
-    print_highlight ("Setting buffer size to %d frames.\n", buff_size);
-  else
-    print_highlight ("Using default buffer size of %d frames.\n", buff_size);
-
-  print_highlight ("Starting the producer and consumer threads... Press Ctrl+C to end\n");
-  OpenNIGrabber grabber (device_id);
-  if (grabber.providesCallback<OpenNIGrabber::sig_cb_openni_point_cloud_rgba> () && 
-      !just_xyz)
-  {
-    print_highlight ("PointXYZRGBA enabled.\n");
-    PCDBuffer<PointXYZRGBA> buf;
-    buf.setCapacity (buff_size);
-    Producer<PointXYZRGBA> producer (buf, depth_mode);
-    std::this_thread::sleep_for(2s);
-    Consumer<PointXYZRGBA> consumer (buf);
-
-    signal (SIGINT, ctrlC);
-    producer.stop ();
-    consumer.stop ();
-  }
-  else
-  {
-    print_highlight ("PointXYZ enabled.\n");
-    PCDBuffer<PointXYZ> buf;
-    buf.setCapacity (buff_size);
-    Producer<PointXYZ> producer (buf, depth_mode);
-    std::this_thread::sleep_for(2s);
-    Consumer<PointXYZ> consumer (buf);
-
-    signal (SIGINT, ctrlC);
-    producer.stop ();
-    consumer.stop ();
-  }
-  return (0);
-}
-
diff --git a/io/tools/pcd_convert_NaN_nan.cpp b/io/tools/pcd_convert_NaN_nan.cpp
deleted file mode 100644 (file)
index 541a27c..0000000
+++ /dev/null
@@ -1,80 +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.
- */
-
-#include <cstring>
-#include <fstream>
-#include <iostream>
-#include <limits>
-#include <sstream>
-#include <string>
-
-int
-main (int argc, char **argv)
-{
-  if (argc != 3)
-  {
-    std::cout << "call with " << argv[0] << " input.pcd output.pcd" << std::endl;
-    return 0;
-  }
-
-  if (!strcmp (argv[1], argv[2]))
-  {
-    std::cout << "called with same name for input and output! (done nothing)" << std::endl;
-    return 1;
-  }
-
-  std::ostringstream ss;
-  ss << std::numeric_limits<float>::quiet_NaN ();
-  std::string nanStr (ss.str ());
-
-  std::cout << R"(converting ")" << nanStr << R"(" to "nan")" << std::endl;
-
-  std::ifstream input (argv[1]);
-  std::ofstream output (argv[2]);
-  std::string str;
-
-  while (input >> str)
-  {
-    if (str == nanStr)
-      output << "nan";
-    else
-      output << str;
-    char next = static_cast<char> (input.peek ());
-    if (next == '\n' || next == '\r')
-      output << "\n";
-    else
-      output << " ";
-  }
-  return 0;
-}
diff --git a/io/tools/pcd_introduce_nan.cpp b/io/tools/pcd_introduce_nan.cpp
deleted file mode 100644 (file)
index cedebda..0000000
+++ /dev/null
@@ -1,85 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2014-, 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/io/pcd_io.h>
-#include <boost/lexical_cast.hpp> // for lexical_cast
-
-/** @brief PCL point object */
-using PointT = pcl::PointXYZRGBA;
-
-/** @brief PCL Point cloud object */
-using PointCloudT = pcl::PointCloud<PointT>;
-
-int
-main (int argc,
-      char** argv)
-{
-  if (argc != 3 && argc != 4)
-  {
-    PCL_ERROR ("Usage: %s cloud_in.pcd cloud_out_ascii.pcd percentage_of_NaN \n", argv[0]);
-    return (-1);
-  }
-
-  int percentage_of_NaN = 20;
-  if (argc == 4)
-    percentage_of_NaN = boost::lexical_cast<int>(argv[3]);
-
-  PCL_INFO ("Replacing approximately %d%% of the cloud with NaN values (already existing NaN values are conserved)\n", percentage_of_NaN);
-  PointCloudT::Ptr cloud (new PointCloudT);
-  if (pcl::io::loadPCDFile (argv[1], *cloud) != 0)
-    return (-1);
-
-  for (auto &point : *cloud)
-  {
-    int random = 1 + (rand () % (int) (100));
-    int random_xyz = 1 + (rand () % (int) (3 - 1 + 1));
-
-    if (random < percentage_of_NaN)
-    {
-      if (random_xyz == 1)
-        point.x = std::numeric_limits<double>::quiet_NaN ();
-      else if (random_xyz == 2)
-        point.y = std::numeric_limits<double>::quiet_NaN ();
-      else
-        point.z = std::numeric_limits<double>::quiet_NaN ();
-    }
-  }
-
-  pcl::io::savePCDFile (argv[2], *cloud);
-  return (0);
-}
-
diff --git a/io/tools/ply/CMakeLists.txt b/io/tools/ply/CMakeLists.txt
deleted file mode 100644 (file)
index 16d054c..0000000
+++ /dev/null
@@ -1,11 +0,0 @@
-PCL_ADD_EXECUTABLE(pcl_ply2obj COMPONENT ${SUBSYS_NAME} SOURCES ply2obj.cpp)
-target_link_libraries(pcl_ply2obj pcl_io_ply)
-
-PCL_ADD_EXECUTABLE(pcl_ply2ply COMPONENT ${SUBSYS_NAME} SOURCES ply2ply.cpp)
-target_link_libraries(pcl_ply2ply pcl_io_ply)
-
-PCL_ADD_EXECUTABLE(pcl_ply2raw COMPONENT ${SUBSYS_NAME} SOURCES ply2raw.cpp)
-target_link_libraries(pcl_ply2raw pcl_io_ply)
-
-PCL_ADD_EXECUTABLE(pcl_plyheader COMPONENT ${SUBSYS_NAME} SOURCES plyheader.cpp)
-target_link_libraries(pcl_plyheader pcl_io_ply)
diff --git a/io/tools/ply/ply2obj.cpp b/io/tools/ply/ply2obj.cpp
deleted file mode 100644 (file)
index b248e32..0000000
+++ /dev/null
@@ -1,464 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2007-2012, Ares Lagae
- *  Copyright (c) 2012, 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$
- *
- */
-
-#include <pcl/io/ply/ply_parser.h>
-
-#include <cstdlib>
-#include <cstring>
-#include <fstream>
-#include <iostream>
-#include <tuple>
-
-/** \class ply_to_obj_converter
-  * Convert a PLY file, optionally meshed to an OBJ file.
-  * The following PLY elements and properties are supported.
-  *  element vertex
-  *    property float32 x
-  *    property float32 y
-  *    property float32 z
-  *  element face
-  *    property list uint8 int32 vertex_indices.
-  *
-  * \author Ares Lagae
-  * \ingroup io
-  */ 
-class ply_to_obj_converter
-{
-  public:
-    using flags_type = int;
-    enum { triangulate = 1 << 0 };
-
-    ply_to_obj_converter (flags_type flags = 0);
-
-    bool 
-    convert (std::istream& istream, const std::string& istream_filename, std::ostream& ostream, const std::string& ostream_filename);
-
-  private:
-
-    void
-    info_callback (const std::string& filename, std::size_t line_number, const std::string& message);
-
-    void
-    warning_callback (const std::string& filename, std::size_t line_number, const std::string& message);
-
-    void
-    error_callback (const std::string& filename, std::size_t line_number, const std::string& message);
-
-    std::tuple<std::function<void ()>, std::function<void ()> > 
-    element_definition_callback (const std::string& element_name, std::size_t count);
-
-    template <typename ScalarType> std::function<void (ScalarType)> 
-    scalar_property_definition_callback (const std::string& element_name, const std::string& property_name);
-
-    template <typename SizeType, typename ScalarType> std::tuple<std::function<void (SizeType)>, 
-                                                                      std::function<void (ScalarType)>, 
-                                                                      std::function<void ()> > 
-    list_property_definition_callback (const std::string& element_name, const std::string& property_name);
-
-    void
-    vertex_begin ();
-
-    void
-    vertex_x (pcl::io::ply::float32 x);
-
-    void
-    vertex_y (pcl::io::ply::float32 y);
-
-    void
-    vertex_z (pcl::io::ply::float32 z);
-
-    void
-    vertex_end ();
-
-    void
-    face_begin ();
-
-    void
-    face_vertex_indices_begin (pcl::io::ply::uint8 size);
-
-    void
-    face_vertex_indices_element (pcl::io::ply::int32 vertex_index);
-
-    void
-    face_vertex_indices_end ();
-
-    void
-    face_end ();
-
-    flags_type flags_;
-    std::ostream* ostream_;
-    double vertex_x_, vertex_y_, vertex_z_;
-    std::size_t face_vertex_indices_element_index_, face_vertex_indices_first_element_, face_vertex_indices_previous_element_;
-};
-
-ply_to_obj_converter::ply_to_obj_converter (flags_type flags)
-  : flags_ (flags), ostream_ (), 
-  vertex_x_ (0), vertex_y_ (0), vertex_z_ (0),
-  face_vertex_indices_element_index_ (), 
-  face_vertex_indices_first_element_ (),
-  face_vertex_indices_previous_element_ ()
-{
-}
-
-void 
-ply_to_obj_converter::info_callback (const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ":" << line_number << ": " << "info: " << message << std::endl;
-}
-
-void 
-ply_to_obj_converter::warning_callback (const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ":" << line_number << ": " << "warning: " << message << std::endl;
-}
-
-void 
-ply_to_obj_converter::error_callback (const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ":" << line_number << ": " << "error: " << message << std::endl;
-}
-
-std::tuple<std::function<void ()>, std::function<void ()> > 
-ply_to_obj_converter::element_definition_callback (const std::string& element_name, std::size_t)
-{
-  if (element_name == "vertex") 
-  {
-    return std::tuple<std::function<void ()>, std::function<void ()> > (
-      [this] { vertex_begin (); },
-      [this] { vertex_end (); }
-    );
-  }
-  if (element_name == "face") 
-  {
-    return std::tuple<std::function<void ()>, std::function<void ()> > (
-      [this] { face_begin (); },
-      [this] { face_end (); }
-    );
-  }
-  return {};
-}
-
-template <> std::function<void (pcl::io::ply::float32)> 
-ply_to_obj_converter::scalar_property_definition_callback (const std::string& element_name, const std::string& property_name)
-{
-  if (element_name == "vertex") {
-    if (property_name == "x") {
-      return [this] (pcl::io::ply::float32 x) { vertex_x (x); };
-    }
-    if (property_name == "y") {
-      return [this] (pcl::io::ply::float32 y) { vertex_y (y); };
-    }
-    if (property_name == "z") {
-      return [this] (pcl::io::ply::float32 z) { vertex_z (z); };
-    }
-  }
-  return {};
-}
-
-template <> std::tuple<std::function<void (pcl::io::ply::uint8)>, std::function<void (pcl::io::ply::int32)>, std::function<void ()> > 
-ply_to_obj_converter::list_property_definition_callback (const std::string& element_name, const std::string& property_name)
-{
-  if ((element_name == "face") && (property_name == "vertex_indices")) {
-    return std::tuple<std::function<void (pcl::io::ply::uint8)>, std::function<void (pcl::io::ply::int32)>, std::function<void ()> > (
-      [this] (pcl::io::ply::uint8 p){ face_vertex_indices_begin (p); },
-      [this] (pcl::io::ply::int32 vertex_index) { face_vertex_indices_element (vertex_index); },
-      [this] { face_vertex_indices_end (); }
-    );
-  }
-  return {};
-}
-
-void 
-ply_to_obj_converter::vertex_begin ()
-{
-}
-
-void 
-ply_to_obj_converter::vertex_x (pcl::io::ply::float32 x)
-{
-  vertex_x_ = x;
-}
-
-void 
-ply_to_obj_converter::vertex_y (pcl::io::ply::float32 y)
-{
-  vertex_y_ = y;
-}
-
-void 
-ply_to_obj_converter::vertex_z (pcl::io::ply::float32 z)
-{
-  vertex_z_ = z;
-}
-
-void 
-ply_to_obj_converter::vertex_end ()
-{
-  (*ostream_) << "v " << vertex_x_ << " " << vertex_y_ << " " << vertex_z_ << "\n";
-}
-
-void 
-ply_to_obj_converter::face_begin ()
-{
-  if (!(flags_ & triangulate)) {
-    (*ostream_) << "f";
-  }
-}
-
-void 
-ply_to_obj_converter::face_vertex_indices_begin (pcl::io::ply::uint8)
-{
-  face_vertex_indices_element_index_ = 0;
-}
-
-void 
-ply_to_obj_converter::face_vertex_indices_element (pcl::io::ply::int32 vertex_index)
-{
-  if (flags_ & triangulate) {
-    if (face_vertex_indices_element_index_ == 0) {
-      face_vertex_indices_first_element_ = vertex_index;
-    }
-    else if (face_vertex_indices_element_index_ == 1) {
-      face_vertex_indices_previous_element_ = vertex_index;
-    }
-    else {
-      (*ostream_) << "f " << (face_vertex_indices_first_element_ + 1) << " " << (face_vertex_indices_previous_element_ + 1) << " " << (vertex_index + 1) << "\n";
-      face_vertex_indices_previous_element_ = vertex_index;
-    }
-    ++face_vertex_indices_element_index_;
-  }
-  else {
-    (*ostream_) << " " << (vertex_index + 1);
-  }
-}
-
-void 
-ply_to_obj_converter::face_vertex_indices_end ()
-{
-  if (!(flags_ & triangulate)) {
-    (*ostream_) << "\n";
-  }
-}
-
-void 
-ply_to_obj_converter::face_end ()
-{
-}
-
-bool 
-ply_to_obj_converter::convert (std::istream&, const std::string& istream_filename, std::ostream& ostream, const std::string&)
-{
-  pcl::io::ply::ply_parser ply_parser;
-
-  ply_parser.info_callback ([&, this] (std::size_t line_number, const std::string& message) { info_callback (istream_filename, line_number, message); });
-  ply_parser.warning_callback ([&, this] (std::size_t line_number, const std::string& message) { warning_callback (istream_filename, line_number, message); });
-  ply_parser.error_callback ([&, this] (std::size_t line_number, const std::string& message) { error_callback (istream_filename, line_number, message); });
-
-  ply_parser.element_definition_callback ([this] (const std::string& element_name, std::size_t count) { return element_definition_callback (element_name, count); });
-
-  pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
-  pcl::io::ply::ply_parser::at<pcl::io::ply::float32> (scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
-  {
-    return scalar_property_definition_callback<pcl::io::ply::float32> (element_name, property_name);
-  };
-  ply_parser.scalar_property_definition_callbacks (scalar_property_definition_callbacks);
-
-  pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int32> (list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
-  {
-    return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32> (element_name, property_name);
-  };
-  ply_parser.list_property_definition_callbacks (list_property_definition_callbacks);
-
-  ostream_ = &ostream;
-
-  return ply_parser.parse (istream_filename);
-}
-
-int main (int argc, char* argv[])
-{
-  ply_to_obj_converter::flags_type ply_to_obj_converter_flags = 0;
-
-  int argi;
-  for (argi = 1; argi < argc; ++argi) {
-
-    if (argv[argi][0] != '-') {
-      break;
-    }
-    if (argv[argi][1] == 0) {
-      ++argi;
-      break;
-    }
-    char short_opt, *long_opt, *opt_arg;
-    if (argv[argi][1] != '-') {
-      short_opt = argv[argi][1];
-      opt_arg = &argv[argi][2];
-      long_opt = &argv[argi][2];
-      while (*long_opt != '\0') {
-        ++long_opt;
-      }
-    }
-    else {
-      short_opt = 0;
-      long_opt = &argv[argi][2];
-      opt_arg = long_opt;
-      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
-        ++opt_arg;
-      }
-      if (*opt_arg == '=') {
-        *opt_arg++ = '\0';
-      }
-    }
-
-    if ((short_opt == 'h') || (std::strcmp (long_opt, "help") == 0)) {
-      std::cout << "Usage: ply2obj [OPTION] [[INFILE] OUTFILE]\n";
-      std::cout << "Convert a PLY file to an OBJ file.\n";
-      std::cout << "\n";
-      std::cout << "  -h, --help       display this help and exit\n";
-      std::cout << "  -v, --version    output version information and exit\n";
-      std::cout << "  -f, --flag=FLAG  set flag\n";
-      std::cout << "\n";
-      std::cout << "FLAG may be one of the following: triangulate.\n";
-      std::cout << "\n";
-      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
-      std::cout << "\n";
-      std::cout << "The following PLY elements and properties are supported.\n";
-      std::cout << "  element vertex\n";
-      std::cout << "    property float32 x\n";
-      std::cout << "    property float32 y\n";
-      std::cout << "    property float32 z\n";
-      std::cout << "  element face\n";
-      std::cout << "    property list uint8 int32 vertex_indices.\n";
-      std::cout << "\n";
-      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
-      return EXIT_SUCCESS;
-    }
-
-    if ((short_opt == 'v') || (std::strcmp (long_opt, "version") == 0)) {
-      std::cout << "ply2obj \n";
-      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
-      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
-      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
-      std::cout << " All rights reserved.\n";
-      std::cout << " Redistribution and use in source and binary forms, with or without\n";
-      std::cout << " modification, are permitted provided that the following conditions\n";
-      std::cout << " are met:\n";
-      std::cout << "  * Redistributions of source code must retain the above copyright\n";
-      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
-      std::cout << "  * Redistributions in binary form must reproduce the above\n";
-      std::cout << "    copyright notice, this list of conditions and the following\n";
-      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
-      std::cout << "    with the distribution.\n";
-      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
-      std::cout << "    contributors may be used to endorse or promote products derived\n";
-      std::cout << "    from this software without specific prior written permission.\n";
-      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
-      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
-      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
-      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
-      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
-      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
-      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
-      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
-      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
-      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
-      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
-      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
-      return EXIT_SUCCESS;
-    }
-
-    if ((short_opt == 'f') || (std::strcmp (long_opt, "flag") == 0)) {
-      if (strcmp (opt_arg, "triangulate") == 0) {
-        ply_to_obj_converter_flags |= ply_to_obj_converter::triangulate;
-      }
-      else {
-        std::cerr << "ply2obj : " << "invalid option `" << argv[argi] << "'" << "\n";
-        std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-        return EXIT_FAILURE;
-      }
-    }
-
-    else {
-      std::cerr << "ply2obj: " << "invalid option `" << argv[argi] << "'" << "\n";
-      std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-      return EXIT_FAILURE;
-    }
-  }
-
-  int parc = argc - argi;
-  char** parv = argv + argi;
-  if (parc > 2) {
-    std::cerr << "ply2obj: " << "too many parameters" << "\n";
-    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-    return EXIT_FAILURE;
-  }
-
-  std::ifstream ifstream;
-  const char* istream_filename = "";
-  if (parc > 0) {
-    istream_filename = parv[0];
-    if (std::strcmp (istream_filename, "-") != 0) {
-      ifstream.open (istream_filename);
-      if (!ifstream.is_open ()) {
-        std::cerr << "ply2obj: " << istream_filename << ": " << "no such file or directory" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::ofstream ofstream;
-  const char* ostream_filename = "";
-  if (parc > 1) {
-    ostream_filename = parv[1];
-    if (std::strcmp (ostream_filename, "-") != 0) {
-      ofstream.open (ostream_filename);
-      if (!ofstream.is_open ()) {
-        std::cerr << "ply2obj: " << ostream_filename << ": " << "could not open file" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::istream& istream = ifstream.is_open () ? ifstream : std::cin;
-  std::ostream& ostream = ofstream.is_open () ? ofstream : std::cout;
-
-  class ply_to_obj_converter ply_to_obj_converter (ply_to_obj_converter_flags);
-  return ply_to_obj_converter.convert (istream, istream_filename, ostream, ostream_filename);
-}
diff --git a/io/tools/ply/ply2ply.cpp b/io/tools/ply/ply2ply.cpp
deleted file mode 100644 (file)
index c313704..0000000
+++ /dev/null
@@ -1,557 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2007-2012, Ares Lagae
- *  Copyright (c) 2012, 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$
- *
- */
-
-#include <pcl/io/ply/ply_parser.h>
-
-#include <cstdlib>
-#include <cstring>
-#include <fstream>
-#include <iostream>
-#include <tuple>
-
-/** \class ply_to_ply_converter
-  * Converts a PLY file with format FORMAT_IN to PLY file with format FORMAT_OUT.
-  * Format may be one of the following: ascii, binary, binary_big_endian, binary_little_endian.
-  * If no format is given, the format of input is kept.
-  *
-  * \author Ares Lagae
-  * \ingroup io
-  */
-class ply_to_ply_converter
-{
-  public:
-    using format_type = int;
-    enum format
-    {
-      same_format,
-      ascii_format,
-      binary_format,
-      binary_big_endian_format,
-      binary_little_endian_format
-    };
-  
-    ply_to_ply_converter(format_type format) : 
-      format_(format), input_format_(), output_format_(), 
-      bol_ (), ostream_ () {}
-
-    bool 
-    convert (const std::string &filename, std::istream& istream, std::ostream& ostream);
-
-  private:
-    void
-    info_callback(const std::string& filename, std::size_t line_number, const std::string& message);
-    
-    void
-    warning_callback(const std::string& filename, std::size_t line_number, const std::string& message);
-    
-    void
-    error_callback(const std::string& filename, std::size_t line_number, const std::string& message);
-    
-    void
-    magic_callback();
-    
-    void
-    format_callback(pcl::io::ply::format_type format, const std::string& version);
-    
-    void
-    element_begin_callback();
-    
-    void
-    element_end_callback();
-
-    std::tuple<std::function<void()>, std::function<void()> > 
-    element_definition_callback(const std::string& element_name, std::size_t count);
-
-    template <typename ScalarType> void
-    scalar_property_callback(ScalarType scalar);
-
-    template <typename ScalarType> std::function<void (ScalarType)> 
-    scalar_property_definition_callback(const std::string& element_name, const std::string& property_name);
-
-    template <typename SizeType, typename ScalarType> void
-    list_property_begin_callback(SizeType size);
-
-    template <typename SizeType, typename ScalarType> void
-    list_property_element_callback(ScalarType scalar);
-
-    template <typename SizeType, typename ScalarType> void
-    list_property_end_callback();
-
-    template <typename SizeType, typename ScalarType> std::tuple<std::function<void (SizeType)>, 
-                                                                      std::function<void (ScalarType)>, 
-                                                                      std::function<void ()> > 
-    list_property_definition_callback(const std::string& element_name, const std::string& property_name);
-    
-    void
-    comment_callback(const std::string& comment);
-    
-    void
-    obj_info_callback(const std::string& obj_info);
-
-    bool 
-    end_header_callback();
-
-    format_type format_;
-    pcl::io::ply::format_type input_format_, output_format_;
-    bool bol_;
-    std::ostream* ostream_;
-};
-
-void
-ply_to_ply_converter::info_callback(const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ": " << line_number << ": " << "info: " << message << std::endl;
-}
-
-void
-ply_to_ply_converter::warning_callback(const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ": " << line_number << ": " << "warning: " << message << std::endl;
-}
-
-void
-ply_to_ply_converter::error_callback(const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ": " << line_number << ": " << "error: " << message << std::endl;
-}
-
-void
-ply_to_ply_converter::magic_callback()
-{
-  (*ostream_) << "ply" << "\n";
-}
-
-void
-ply_to_ply_converter::format_callback(pcl::io::ply::format_type format, const std::string& version)
-{
-  input_format_ = format;
-
-  switch (format_) {
-    case same_format:
-      output_format_ = input_format_;
-      break;
-    case ascii_format:
-      output_format_ = pcl::io::ply::ascii_format;
-      break;
-    case binary_format:
-      output_format_ = pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order ? pcl::io::ply::binary_little_endian_format : pcl::io::ply::binary_big_endian_format;
-      break;
-    case binary_big_endian_format:
-      output_format_ = pcl::io::ply::binary_big_endian_format;
-      break;
-    case binary_little_endian_format:
-      output_format_ = pcl::io::ply::binary_little_endian_format;
-      break;
-  };
-
-  (*ostream_) << "format ";
-  switch (output_format_) {
-    case pcl::io::ply::ascii_format:
-      (*ostream_) << "ascii";
-      break;
-    case pcl::io::ply::binary_little_endian_format:
-      (*ostream_) << "binary_little_endian";
-      break;
-    case pcl::io::ply::binary_big_endian_format:
-      (*ostream_) << "binary_big_endian";
-      break;
-  }
-  (*ostream_) << " " << version << "\n";
-}
-
-void
-ply_to_ply_converter::element_begin_callback()
-{
-  if (output_format_ == pcl::io::ply::ascii_format) {
-    bol_ = true;
-  }
-}
-
-void
-ply_to_ply_converter::element_end_callback()
-{
-  if (output_format_ == pcl::io::ply::ascii_format) {
-    (*ostream_) << "\n";
-  }
-}
-
-std::tuple<std::function<void()>, std::function<void()> > ply_to_ply_converter::element_definition_callback(const std::string& element_name, std::size_t count)
-{
-  (*ostream_) << "element " << element_name << " " << count << "\n";
-  return std::tuple<std::function<void()>, std::function<void()> >(
-    [this] { element_begin_callback (); },
-    [this] { element_end_callback (); }
-  );
-}
-
-template <typename ScalarType>
-void
-ply_to_ply_converter::scalar_property_callback(ScalarType scalar)
-{
-  if (output_format_ == pcl::io::ply::ascii_format) {
-    using namespace pcl::io::ply::io_operators;
-    if (bol_) {
-      bol_ = false;
-      (*ostream_) << scalar;
-    }
-    else {
-      (*ostream_) << " " << scalar;
-    }
-  }
-  else {
-    if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format))
-      || ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format))) {
-      pcl::io::ply::swap_byte_order(scalar);
-    }
-    ostream_->write(reinterpret_cast<char*>(&scalar), sizeof(scalar));
-  }
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-template <typename ScalarType> std::function<void (ScalarType)> 
-ply_to_ply_converter::scalar_property_definition_callback (const std::string&, const std::string& property_name)
-{
-  (*ostream_) << "property " << pcl::io::ply::type_traits<ScalarType>::old_name() << " " << property_name << "\n";
-  return [this] (ScalarType scalar) { scalar_property_callback<ScalarType> (scalar); };
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-template <typename SizeType, typename ScalarType> void
-ply_to_ply_converter::list_property_begin_callback (SizeType size)
-{
-  if (output_format_ == pcl::io::ply::ascii_format) 
-  {
-    using namespace pcl::io::ply::io_operators;
-    if (bol_) 
-    {
-      bol_ = false;
-      (*ostream_) << size;
-    }
-    else 
-      (*ostream_) << " " << size;
-  }
-  else 
-  {
-    if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format))
-      || ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format))) {
-      pcl::io::ply::swap_byte_order(size);
-    }
-    ostream_->write(reinterpret_cast<char*>(&size), sizeof(size));
-  }
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-template <typename SizeType, typename ScalarType> void
-ply_to_ply_converter::list_property_element_callback (ScalarType scalar)
-{
-  if (output_format_ == pcl::io::ply::ascii_format) 
-  {
-    using namespace pcl::io::ply::io_operators;
-    (*ostream_) << " " << scalar;
-  }
-  else 
-  {
-    if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format)) || 
-        ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format)))
-      pcl::io::ply::swap_byte_order(scalar);
-
-    ostream_->write(reinterpret_cast<char*>(&scalar), sizeof(scalar));
-  }
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-template <typename SizeType, typename ScalarType> void
-ply_to_ply_converter::list_property_end_callback() {}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-template <typename SizeType, typename ScalarType> std::tuple<std::function<void (SizeType)>, 
-                                                                  std::function<void (ScalarType)>, 
-                                                                  std::function<void ()> > 
-ply_to_ply_converter::list_property_definition_callback (const std::string&, const std::string& property_name)
-{
-  (*ostream_) << "property list " << pcl::io::ply::type_traits<SizeType>::old_name() << " " << pcl::io::ply::type_traits<ScalarType>::old_name() << " " << property_name << "\n";
-  return std::tuple<std::function<void (SizeType)>, std::function<void (ScalarType)>, std::function<void ()> >(
-    [this] (SizeType size) { list_property_begin_callback<SizeType, ScalarType> (size); },
-    [this] (ScalarType scalar) { list_property_element_callback<SizeType, ScalarType> (scalar); },
-    [this] { list_property_end_callback<SizeType, ScalarType> (); }
-  );
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-void
-ply_to_ply_converter::comment_callback(const std::string& comment)
-{
-  (*ostream_) << comment << "\n";
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-void
-ply_to_ply_converter::obj_info_callback(const std::string& obj_info)
-{
-  (*ostream_) << obj_info << "\n";
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-bool 
-ply_to_ply_converter::end_header_callback()
-{
-  (*ostream_) << "end_header" << "\n";
-  return true;
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-bool 
-ply_to_ply_converter::convert (const std::string &ifilename, std::istream&, std::ostream& ostream)
-{
-  pcl::io::ply::ply_parser ply_parser;
-
-  ply_parser.info_callback ([&, this] (std::size_t line_number, const std::string& message) { info_callback (ifilename, line_number, message); });
-  ply_parser.warning_callback ([&, this] (std::size_t line_number, const std::string& message) { warning_callback (ifilename, line_number, message); });
-  ply_parser.error_callback ([&, this] (std::size_t line_number, const std::string& message) { error_callback (ifilename, line_number, message); });
-
-  ply_parser.magic_callback ([this] { magic_callback (); });
-  ply_parser.format_callback ([this] (pcl::io::ply::format_type format, const std::string& version) { format_callback (format, version); });
-  ply_parser.element_definition_callback ([this] (const std::string& element_name, std::size_t count) { return element_definition_callback (element_name, count); });
-
-  pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
-
-  pcl::io::ply::ply_parser::at<pcl::io::ply::int8>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::int8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::int16>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::int16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::int32>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::int32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::uint8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::uint16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::uint32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::float32>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::float32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::float64>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::float64> (element_name, property_name); };
-
-  ply_parser.scalar_property_definition_callbacks(scalar_property_definition_callbacks);
-
-  pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
-
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::uint8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::uint16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::uint32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::float32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::float32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::float64>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::float64> (element_name, property_name); };
-
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::int8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::int16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::int32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::uint8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::uint16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::uint32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::float32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::float32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::float64>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::float64> (element_name, property_name); };
-
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::int8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::int16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::int32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::uint8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint8> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::uint16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint16> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::uint32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::float32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::float32> (element_name, property_name); };
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::float64>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::float64> (element_name, property_name); };
-
-  ply_parser.list_property_definition_callbacks(list_property_definition_callbacks);
-
-  ply_parser.comment_callback([this] (const std::string& comment) { comment_callback (comment); });
-  ply_parser.obj_info_callback([this] (const std::string& obj_info) { obj_info_callback (obj_info); });
-  ply_parser.end_header_callback( [this] { return end_header_callback (); });
-
-  ostream_ = &ostream;
-  return ply_parser.parse(ifilename);
-}
-
-//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-int 
-main(int argc, char* argv[])
-{
-  ply_to_ply_converter::format_type ply_to_ply_converter_format = ply_to_ply_converter::same_format;
-
-  int argi;
-  for (argi = 1; argi < argc; ++argi) {
-
-    if (argv[argi][0] != '-') {
-      break;
-    }
-    if (argv[argi][1] == 0) {
-      ++argi;
-      break;
-    }
-    char short_opt, *long_opt, *opt_arg;
-    if (argv[argi][1] != '-') {
-      short_opt = argv[argi][1];
-      opt_arg = &argv[argi][2];
-      long_opt = &argv[argi][2];
-      while (*long_opt != '\0') {
-        ++long_opt;
-      }
-    }
-    else {
-      short_opt = 0;
-      long_opt = &argv[argi][2];
-      opt_arg = long_opt;
-      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
-        ++opt_arg;
-      }
-      if (*opt_arg == '=') {
-        *opt_arg++ = '\0';
-      }
-    }
-
-    if ((short_opt == 'h') || (std::strcmp(long_opt, "help") == 0)) {
-      std::cout << "Usage: ply2ply [OPTION] [[INFILE] OUTFILE]\n";
-      std::cout << "Parse an PLY file.\n";
-      std::cout << "\n";
-      std::cout << "  -h, --help           display this help and exit\n";
-      std::cout << "  -v, --version        output version information and exit\n";
-      std::cout << "  -f, --format=FORMAT  set format\n";
-      std::cout << "\n";
-      std::cout << "FORMAT may be one of the following: ascii, binary, binary_big_endian,\n";
-      std::cout << "binary_little_endian.\n";
-      std::cout << "If no format is given, the format of INFILE is kept.\n";
-      std::cout << "\n";
-      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
-      std::cout << "\n";
-      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
-      return EXIT_SUCCESS;
-    }
-
-    if ((short_opt == 'v') || (std::strcmp(long_opt, "version") == 0)) {
-      std::cout << "ply2ply\n";
-      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
-      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
-      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
-      std::cout << " All rights reserved.\n";
-      std::cout << " Redistribution and use in source and binary forms, with or without\n";
-      std::cout << " modification, are permitted provided that the following conditions\n";
-      std::cout << " are met:\n";
-      std::cout << "  * Redistributions of source code must retain the above copyright\n";
-      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
-      std::cout << "  * Redistributions in binary form must reproduce the above\n";
-      std::cout << "    copyright notice, this list of conditions and the following\n";
-      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
-      std::cout << "    with the distribution.\n";
-      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
-      std::cout << "    contributors may be used to endorse or promote products derived\n";
-      std::cout << "    from this software without specific prior written permission.\n";
-      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
-      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
-      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
-      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
-      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
-      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
-      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
-      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
-      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
-      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
-      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
-      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
-      return EXIT_SUCCESS;
-    }
-
-    if ((short_opt == 'f') || (std::strcmp(long_opt, "format") == 0)) {
-      if (strcmp(opt_arg, "ascii") == 0) {
-        ply_to_ply_converter_format = ply_to_ply_converter::ascii_format;
-      }
-      else if (strcmp(opt_arg, "binary") == 0) {
-        ply_to_ply_converter_format = ply_to_ply_converter::binary_format;
-      }
-      else if (strcmp(opt_arg, "binary_little_endian") == 0) {
-        ply_to_ply_converter_format = ply_to_ply_converter::binary_little_endian_format;
-      }
-      else if (strcmp(opt_arg, "binary_big_endian") == 0) {
-        ply_to_ply_converter_format = ply_to_ply_converter::binary_big_endian_format;
-      }
-      else {
-        std::cerr << "ply2ply: " << "invalid option `" << argv[argi] << "'" << "\n";
-        std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-        return EXIT_FAILURE;
-      }
-    }
-
-    else {
-      std::cerr << "ply2ply: " << "invalid option `" << argv[argi] << "'" << "\n";
-      std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-      return EXIT_FAILURE;
-    }
-  }
-
-  int parc = argc - argi;
-  char** parv = argv + argi;
-  if (parc > 2) {
-    std::cerr << "ply2ply: " << "too many parameters" << "\n";
-    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-    return EXIT_FAILURE;
-  }
-
-  std::ifstream ifstream;
-  const char* ifilename = "";
-  if (parc > 0) {
-    ifilename = parv[0];
-    if (std::strcmp(ifilename, "-") != 0) {
-      ifstream.open(ifilename);
-      if (!ifstream.is_open()) {
-        std::cerr << "ply2ply: " << ifilename << ": " << "no such file or directory" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::ofstream ofstream;
-  if (parc > 1) {
-    const char* ofilename = parv[1];
-    if (std::strcmp(ofilename, "-") != 0) {
-      ofstream.open(ofilename);
-      if (!ofstream.is_open()) {
-        std::cerr << "ply2ply: " << ofilename << ": " << "could not open file" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::istream& istream = ifstream.is_open() ? ifstream : std::cin;
-  std::ostream& ostream = ofstream.is_open() ? ofstream : std::cout;
-
-  class ply_to_ply_converter ply_to_ply_converter(ply_to_ply_converter_format);
-  return ply_to_ply_converter.convert (ifilename, istream, ostream);
-}
diff --git a/io/tools/ply/ply2raw.cpp b/io/tools/ply/ply2raw.cpp
deleted file mode 100644 (file)
index 118aa8c..0000000
+++ /dev/null
@@ -1,450 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2007-2012, Ares Lagae
- *  Copyright (c) 2012, 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$
- *
- */
-
-#include <pcl/io/ply/ply_parser.h>
-
-#include <cstdlib>
-#include <cstring>
-#include <fstream>
-#include <iostream>
-#include <tuple>
-
-/** Class ply_to_raw_converter converts a PLY file to a povray (www.povray.org) RAW file
-  * The following PLY elements and properties are supported.
-  *   element vertex
-  *     property float32 x
-  *     property float32 y
-  *     property float32 z
-  *   element face
-  *     property list uint8 int32 vertex_indices.
-  * 
-  * \author Ares Lagae
-  * \ingroup io
-  */
-
-class ply_to_raw_converter
-{
-  public:
-    ply_to_raw_converter () : 
-      ostream_ (), vertex_x_ (0), vertex_y_ (0), vertex_z_ (0), 
-      face_vertex_indices_element_index_ (),
-      face_vertex_indices_first_element_ (), 
-      face_vertex_indices_previous_element_ ()
-    {}
-
-    ply_to_raw_converter (const ply_to_raw_converter &f) :
-      ostream_ (), vertex_x_ (0), vertex_y_ (0), vertex_z_ (0), 
-      face_vertex_indices_element_index_ (),
-      face_vertex_indices_first_element_ (), 
-      face_vertex_indices_previous_element_ ()
-    {
-      *this = f;
-    }
-
-    ply_to_raw_converter&
-    operator = (const ply_to_raw_converter &f)
-    {
-      ostream_ = f.ostream_;
-      vertex_x_ = f.vertex_x_;
-      vertex_y_ = f.vertex_y_;
-      vertex_z_ = f.vertex_z_;
-      face_vertex_indices_element_index_ = f.face_vertex_indices_element_index_;
-      face_vertex_indices_first_element_ = f.face_vertex_indices_first_element_;
-      face_vertex_indices_previous_element_ = f.face_vertex_indices_previous_element_;
-      return (*this);
-    }
-
-    bool 
-    convert (std::istream& istream, const std::string& istream_filename, std::ostream& ostream, const std::string& ostream_filename);
-
-  private:
-    void
-    info_callback (const std::string& filename, std::size_t line_number, const std::string& message);
-
-    void
-    warning_callback (const std::string& filename, std::size_t line_number, const std::string& message);
-
-    void
-    error_callback (const std::string& filename, std::size_t line_number, const std::string& message);
-
-    std::tuple<std::function<void ()>, std::function<void ()> > 
-    element_definition_callback (const std::string& element_name, std::size_t count);
-
-    template <typename ScalarType> std::function<void (ScalarType)> 
-    scalar_property_definition_callback (const std::string& element_name, const std::string& property_name);
-
-    template <typename SizeType, typename ScalarType>  std::tuple<std::function<void (SizeType)>, 
-                                                                       std::function<void (ScalarType)>, 
-                                                                       std::function<void ()> > 
-    list_property_definition_callback (const std::string& element_name, const std::string& property_name);
-
-    void
-    vertex_begin ();
-
-    void
-    vertex_x (pcl::io::ply::float32 x);
-
-    void
-    vertex_y (pcl::io::ply::float32 y);
-
-    void
-    vertex_z (pcl::io::ply::float32 z);
-
-    void
-    vertex_end ();
-
-    void
-    face_begin ();
-
-    void
-    face_vertex_indices_begin (pcl::io::ply::uint8 size);
-
-    void
-    face_vertex_indices_element (pcl::io::ply::int32 vertex_index);
-
-    void
-    face_vertex_indices_end ();
-
-    void
-    face_end ();
-
-    std::ostream* ostream_;
-    pcl::io::ply::float32 vertex_x_, vertex_y_, vertex_z_;
-    pcl::io::ply::int32 face_vertex_indices_element_index_, face_vertex_indices_first_element_, face_vertex_indices_previous_element_;
-    std::vector<std::tuple<pcl::io::ply::float32, pcl::io::ply::float32, pcl::io::ply::float32> > vertices_;
-};
-
-void
-ply_to_raw_converter::info_callback (const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ":" << line_number << ": " << "info: " << message << std::endl;
-}
-
-void
-ply_to_raw_converter::warning_callback (const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ":" << line_number << ": " << "warning: " << message << std::endl;
-}
-
-void
-ply_to_raw_converter::error_callback (const std::string& filename, std::size_t line_number, const std::string& message)
-{
-  std::cerr << filename << ":" << line_number << ": " << "error: " << message << std::endl;
-}
-
-std::tuple<std::function<void ()>, std::function<void ()> > 
-ply_to_raw_converter::element_definition_callback (const std::string& element_name, std::size_t)
-{
-  if (element_name == "vertex") {
-    return std::tuple<std::function<void ()>, std::function<void ()> > (
-      [this] { vertex_begin (); },
-      [this] { vertex_end (); }
-    );
-  }
-  if (element_name == "face") {
-    return std::tuple<std::function<void ()>, std::function<void ()> > (
-      [this] { face_begin (); },
-      [this] { face_end (); }
-    );
-  }
-  return {};
-}
-
-template <> std::function<void (pcl::io::ply::float32)> 
-ply_to_raw_converter::scalar_property_definition_callback (const std::string& element_name, const std::string& property_name)
-{
-  if (element_name == "vertex") {
-    if (property_name == "x") {
-      return [this] (pcl::io::ply::float32 x) { vertex_x (x); };
-    }
-    if (property_name == "y") {
-      return [this] (pcl::io::ply::float32 y) { vertex_y (y); };
-    }
-    if (property_name == "z") {
-      return [this] (pcl::io::ply::float32 z) { vertex_z (z); };
-    }
-  }
-  return {};
-}
-
-template <> std::tuple<std::function<void (pcl::io::ply::uint8)>, 
-                            std::function<void (pcl::io::ply::int32)>, 
-                            std::function<void ()> > 
-ply_to_raw_converter::list_property_definition_callback (const std::string& element_name, const std::string& property_name)
-{
-  if ((element_name == "face") && (property_name == "vertex_indices")) 
-  {
-    return std::tuple<std::function<void (pcl::io::ply::uint8)>, 
-      std::function<void (pcl::io::ply::int32)>, 
-      std::function<void ()> > (
-        [this] (pcl::io::ply::uint8 p){ face_vertex_indices_begin (p); },
-        [this] (pcl::io::ply::int32 vertex_index) { face_vertex_indices_element (vertex_index); },
-        [this] { face_vertex_indices_end (); }
-    );
-  }
-  return {};
-}
-
-void
-ply_to_raw_converter::vertex_begin () {}
-
-void
-ply_to_raw_converter::vertex_x (pcl::io::ply::float32 x)
-{
-  vertex_x_ = x;
-}
-
-void
-ply_to_raw_converter::vertex_y (pcl::io::ply::float32 y)
-{
-  vertex_y_ = y;
-}
-
-void
-ply_to_raw_converter::vertex_z (pcl::io::ply::float32 z)
-{
-  vertex_z_ = z;
-}
-
-void
-ply_to_raw_converter::vertex_end ()
-{
-  vertices_.emplace_back(vertex_x_, vertex_y_, vertex_z_);
-}
-
-void
-ply_to_raw_converter::face_begin () {}
-
-void
-ply_to_raw_converter::face_vertex_indices_begin (pcl::io::ply::uint8)
-{
-  face_vertex_indices_element_index_ = 0;
-}
-
-void
-ply_to_raw_converter::face_vertex_indices_element (pcl::io::ply::int32 vertex_index)
-{
-  if (face_vertex_indices_element_index_ == 0) {
-    face_vertex_indices_first_element_ = vertex_index;
-  }
-  else if (face_vertex_indices_element_index_ == 1) {
-    face_vertex_indices_previous_element_ = vertex_index;
-  }
-  else {
-    (*ostream_) << std::get<0> (vertices_[   face_vertex_indices_first_element_])
-         << " " << std::get<1> (vertices_[   face_vertex_indices_first_element_])
-         << " " << std::get<2> (vertices_[   face_vertex_indices_first_element_])
-         << " " << std::get<0> (vertices_[face_vertex_indices_previous_element_])
-         << " " << std::get<1> (vertices_[face_vertex_indices_previous_element_])
-         << " " << std::get<2> (vertices_[face_vertex_indices_previous_element_])
-         << " " << std::get<0> (vertices_[                         vertex_index])
-         << " " << std::get<1> (vertices_[                         vertex_index])
-         << " " << std::get<2> (vertices_[                         vertex_index]) << "\n";
-    face_vertex_indices_previous_element_ = vertex_index;
-  }
-  ++face_vertex_indices_element_index_;
-}
-
-void
-ply_to_raw_converter::face_vertex_indices_end () {}
-
-void
-ply_to_raw_converter::face_end () {}
-
-bool 
-ply_to_raw_converter::convert (std::istream&, const std::string& istream_filename, std::ostream& ostream, const std::string&)
-{
-  pcl::io::ply::ply_parser ply_parser;
-
-  ply_parser.info_callback ([&, this] (std::size_t line_number, const std::string& message) { info_callback (istream_filename, line_number, message); });
-  ply_parser.warning_callback ([&, this] (std::size_t line_number, const std::string& message) { warning_callback (istream_filename, line_number, message); });
-  ply_parser.error_callback ([&, this] (std::size_t line_number, const std::string& message) { error_callback (istream_filename, line_number, message); });
-
-  ply_parser.element_definition_callback ([this] (const std::string& element_name, std::size_t count) { return element_definition_callback (element_name, count); });
-
-  pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
-  pcl::io::ply::ply_parser::at<pcl::io::ply::float32> (scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
-  {
-    return scalar_property_definition_callback<pcl::io::ply::float32> (element_name, property_name);
-  };
-  ply_parser.scalar_property_definition_callbacks (scalar_property_definition_callbacks);
-
-  pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
-  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int32> (list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
-  {
-    return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32> (element_name, property_name);
-  };
-  ply_parser.list_property_definition_callbacks (list_property_definition_callbacks);
-
-  ostream_ = &ostream;
-
-  return ply_parser.parse (istream_filename);
-}
-
-int main (int argc, char* argv[])
-{
-  int argi;
-  for (argi = 1; argi < argc; ++argi) {
-
-    if (argv[argi][0] != '-') {
-      break;
-    }
-    if (argv[argi][1] == 0) {
-      ++argi;
-      break;
-    }
-    char short_opt, *long_opt;
-    if (argv[argi][1] != '-') {
-      short_opt = argv[argi][1];
-      long_opt = &argv[argi][2];
-      while (*long_opt != '\0') {
-        ++long_opt;
-      }
-    }
-    else {
-      short_opt = 0;
-      long_opt = &argv[argi][2];
-      char *opt_arg = long_opt;
-      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
-        ++opt_arg;
-      }
-      if (*opt_arg == '=') {
-        *opt_arg++ = '\0';
-      }
-    }
-
-    if ((short_opt == 'h') || (std::strcmp (long_opt, "help") == 0)) {
-      std::cout << "Usage: ply2raw [OPTION] [[INFILE] OUTFILE]\n";
-      std::cout << "Convert from PLY to POV-Ray RAW triangle format.\n";
-      std::cout << "\n";
-      std::cout << "  -h, --help       display this help and exit\n";
-      std::cout << "  -v, --version    output version information and exit\n";
-      std::cout << "\n";
-      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
-      std::cout << "\n";
-      std::cout << "The following PLY elements and properties are supported.\n";
-      std::cout << "  element vertex\n";
-      std::cout << "    property float32 x\n";
-      std::cout << "    property float32 y\n";
-      std::cout << "    property float32 z\n";
-      std::cout << "  element face\n";
-      std::cout << "    property list uint8 int32 vertex_indices.\n";
-      std::cout << "\n";
-      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
-      return EXIT_SUCCESS;
-    }
-
-    if ((short_opt == 'v') || (std::strcmp (long_opt, "version") == 0)) {
-      std::cout << "ply2raw \n";
-      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
-      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
-      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
-      std::cout << " All rights reserved.\n";
-      std::cout << " Redistribution and use in source and binary forms, with or without\n";
-      std::cout << " modification, are permitted provided that the following conditions\n";
-      std::cout << " are met:\n";
-      std::cout << "  * Redistributions of source code must retain the above copyright\n";
-      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
-      std::cout << "  * Redistributions in binary form must reproduce the above\n";
-      std::cout << "    copyright notice, this list of conditions and the following\n";
-      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
-      std::cout << "    with the distribution.\n";
-      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
-      std::cout << "    contributors may be used to endorse or promote products derived\n";
-      std::cout << "    from this software without specific prior written permission.\n";
-      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
-      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
-      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
-      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
-      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
-      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
-      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
-      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
-      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
-      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
-      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
-      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
-      return EXIT_SUCCESS;
-    }
-
-    std::cerr << "ply2raw: " << "invalid option `" << argv[argi] << "'" << "\n";
-    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-    return EXIT_FAILURE;
-  }
-
-  int parc = argc - argi;
-  char** parv = argv + argi;
-  if (parc > 2) {
-    std::cerr << "ply2raw: " << "too many parameters" << "\n";
-    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-    return EXIT_FAILURE;
-  }
-
-  std::ifstream ifstream;
-  const char* istream_filename = "";
-  if (parc > 0) {
-    istream_filename = parv[0];
-    if (std::strcmp (istream_filename, "-") != 0) {
-      ifstream.open (istream_filename);
-      if (!ifstream.is_open ()) {
-        std::cerr << "ply2raw: " << istream_filename << ": " << "no such file or directory" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::ofstream ofstream;
-  const char* ostream_filename = "";
-  if (parc > 1) {
-    ostream_filename = parv[1];
-    if (std::strcmp (ostream_filename, "-") != 0) {
-      ofstream.open (ostream_filename);
-      if (!ofstream.is_open ()) {
-        std::cerr << "ply2raw: " << ostream_filename << ": " << "could not open file" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::istream& istream = ifstream.is_open () ? ifstream : std::cin;
-  std::ostream& ostream = ofstream.is_open () ? ofstream : std::cout;
-
-  class ply_to_raw_converter ply_to_raw_converter;
-  return ply_to_raw_converter.convert (istream, istream_filename, ostream, ostream_filename);
-}
diff --git a/io/tools/ply/plyheader.cpp b/io/tools/ply/plyheader.cpp
deleted file mode 100644 (file)
index d9907f9..0000000
+++ /dev/null
@@ -1,184 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *  Copyright (c) 2007-2012, Ares Lagae
- *  Copyright (c) 2012, 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$
- *
- */
-
-#include <fstream>
-#include <iostream>
-#include <cstring>
-#include <string>
-#include <cstdlib>
-
-/** \file plheader extracts and prints out the header of a PLY file
-  * 
-  * \author Ares Lagae
-  * \ingroup io
-  */
-int main (int argc, char* argv[])
-{
-  int argi;
-  for (argi = 1; argi < argc; ++argi) {
-
-    if (argv[argi][0] != '-') {
-      break;
-    }
-    if (argv[argi][1] == 0) {
-      ++argi;
-      break;
-    }
-    char short_opt, *long_opt;
-    if (argv[argi][1] != '-') {
-      short_opt = argv[argi][1];
-      long_opt = &argv[argi][2];
-      while (*long_opt != '\0') {
-        ++long_opt;
-      }
-    }
-    else {
-      short_opt = 0;
-      long_opt = &argv[argi][2];
-      char *opt_arg = long_opt;
-      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
-        ++opt_arg;
-      }
-      if (*opt_arg == '=') {
-        *opt_arg++ = '\0';
-      }
-    }
-
-    if ((short_opt == 'h') || (strcmp (long_opt, "help") == 0)) {
-      std::cout << "Usage: plyheader [OPTION] [[INFILE] OUTFILE]\n";
-      std::cout << "Extract the header from a PLY file.\n";
-      std::cout << "\n";
-      std::cout << "  -h, --help       display this help and exit\n";
-      std::cout << "  -v, --version    output version information and exit\n";
-      std::cout << "\n";
-      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
-      std::cout << "\n";
-      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
-      return EXIT_SUCCESS;
-    }
-
-    if ((short_opt == 'v') || (strcmp (long_opt, "version") == 0)) {
-      std::cout << "plyheader \n";
-      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
-      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
-      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
-      std::cout << " All rights reserved.\n";
-      std::cout << " Redistribution and use in source and binary forms, with or without\n";
-      std::cout << " modification, are permitted provided that the following conditions\n";
-      std::cout << " are met:\n";
-      std::cout << "  * Redistributions of source code must retain the above copyright\n";
-      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
-      std::cout << "  * Redistributions in binary form must reproduce the above\n";
-      std::cout << "    copyright notice, this list of conditions and the following\n";
-      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
-      std::cout << "    with the distribution.\n";
-      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
-      std::cout << "    contributors may be used to endorse or promote products derived\n";
-      std::cout << "    from this software without specific prior written permission.\n";
-      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
-      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
-      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
-      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
-      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
-      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
-      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
-      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
-      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
-      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
-      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
-      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
-      return EXIT_SUCCESS;
-    }
-
-    std::cerr << "plyheader: " << "invalid option `" << argv[argi] << "'" << "\n";
-    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-    return EXIT_FAILURE;
-  }
-
-  int parc = argc - argi;
-  char** parv = argv + argi;
-  if (parc > 2) {
-    std::cerr << "plyheader: " << "too many parameters" << "\n";
-    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
-    return EXIT_FAILURE;
-  }
-
-  std::ifstream ifstream;
-  if (parc > 0) {
-    const char* ifilename = parv[0];
-    if (strcmp (ifilename, "-") != 0) {
-      ifstream.open (ifilename);
-      if (!ifstream.is_open ()) {
-        std::cerr << "plyheader: " << ifilename << ": " << "no such file or directory" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::ofstream ofstream;
-  if (parc > 1) {
-    const char* ofilename = parv[1];
-    if (strcmp (ofilename, "-") != 0) {
-      ofstream.open (ofilename);
-      if (!ofstream.is_open ()) {
-        std::cerr << "plyheader: " << ofilename << ": " << "could not open file" << "\n";
-        return EXIT_FAILURE;
-      }
-    }
-  }
-
-  std::istream& istream = ifstream.is_open () ? ifstream : std::cin;
-  std::ostream& ostream = ofstream.is_open () ? ofstream : std::cout;
-
-  char magic[3];
-  istream.read (magic, 3);
-  if (!istream || (magic[0] != 'p') || (magic[1] != 'l') || (magic[2] != 'y')){
-    return EXIT_FAILURE;
-  }
-  istream.ignore (1);
-  ostream << magic[0] << magic[1] << magic[2] << "\n";
-  std::string line;
-  while (std::getline (istream, line)) {
-    ostream << line << "\n";
-    if (line == "end_header") {
-      break;
-    }
-  }
-  return istream ? EXIT_SUCCESS : EXIT_FAILURE;
-}
index d276dee8a17c542b4aee7ee031b07ada2c002ae1..7edaf7a80dfa85670c41761484cd1db26090cdcb 100644 (file)
@@ -49,9 +49,8 @@ template <typename PointT, typename Dist>
 pcl::KdTreeFLANN<PointT, Dist>::KdTreeFLANN (bool sorted)
   : pcl::KdTree<PointT> (sorted)
   , flann_index_ ()
-  , identity_mapping_ (false)
-  , dim_ (0), total_nr_points_ (0)
-  , param_k_ (::flann::SearchParams (-1 , epsilon_))
+  , 
+   param_k_ (::flann::SearchParams (-1 , epsilon_))
   , param_radius_ (::flann::SearchParams (-1, epsilon_, sorted))
 {
   if (!std::is_same<std::size_t, pcl::index_t>::value) {
@@ -71,9 +70,8 @@ template <typename PointT, typename Dist>
 pcl::KdTreeFLANN<PointT, Dist>::KdTreeFLANN (const KdTreeFLANN<PointT, Dist> &k)
   : pcl::KdTree<PointT> (false)
   , flann_index_ ()
-  , identity_mapping_ (false)
-  , dim_ (0), total_nr_points_ (0)
-  , param_k_ (::flann::SearchParams (-1 , epsilon_))
+  , 
+   param_k_ (::flann::SearchParams (-1 , epsilon_))
   , param_radius_ (::flann::SearchParams (-1, epsilon_, false))
 {
   *this = k;
@@ -169,7 +167,7 @@ knn_search(A& index, B& query, C& k_indices, D& dists, unsigned int k, F& params
   std::vector<std::size_t> indices(k);
   k_indices.resize(k);
   // Wrap indices vector (no data allocation)
-  ::flann::Matrix<std::size_t> indices_mat(&indices[0], 1, k);
+  ::flann::Matrix<std::size_t> indices_mat(indices.data(), 1, k);
   auto ret = index.knnSearch(query, indices_mat, dists, k, params);
   // cast appropriately
   std::transform(indices.cbegin(),
@@ -253,10 +251,10 @@ pcl::KdTreeFLANN<PointT, Dist>::nearestKSearch (const PointT &point, unsigned in
   point_representation_->vectorize (static_cast<PointT> (point), query);
 
   // Wrap the k_distances vector (no data copy)
-  ::flann::Matrix<float> k_distances_mat (&k_distances[0], 1, k);
+  ::flann::Matrix<float> k_distances_mat (k_distances.data(), 1, k);
 
   knn_search(*flann_index_,
-             ::flann::Matrix<float>(&query[0], 1, dim_),
+             ::flann::Matrix<float>(query.data(), 1, dim_),
              k_indices,
              k_distances_mat,
              k,
@@ -392,7 +390,7 @@ pcl::KdTreeFLANN<PointT, Dist>::radiusSearch (const PointT &point, double radius
   else
     params.max_neighbors = max_nn;
 
-  auto query_mat = ::flann::Matrix<float>(&query[0], 1, dim_);
+  auto query_mat = ::flann::Matrix<float>(query.data(), 1, dim_);
   int neighbors_in_radius = radius_search(*flann_index_,
                                           query_mat,
                                           k_indices,
index 3a72725ee01115ddf009142c5fd8db0ca8a943bc..fd5e357fb09d9562cb757fff591419f2ecd19cef 100644 (file)
@@ -43,6 +43,7 @@
 #include <pcl/point_cloud.h>
 #include <pcl/point_representation.h>
 #include <pcl/common/copy_point.h>
+#include <cassert>
 
 namespace pcl
 {
@@ -72,7 +73,7 @@ namespace pcl
         * \param[in] sorted set to true if the application that the tree will be used for requires sorted nearest neighbor indices (default). False otherwise.
         */
       KdTree (bool sorted = true) : input_(),
-                                    epsilon_(0.0f), min_pts_(1), sorted_(sorted),
+                                     sorted_(sorted),
                                     point_representation_ (new DefaultPointRepresentation<PointT>)
       {
       };
@@ -339,10 +340,10 @@ namespace pcl
       IndicesConstPtr indices_;
 
       /** \brief Epsilon precision (error bound) for nearest neighbors searches. */
-      float epsilon_;
+      float epsilon_{0.0f};
 
       /** \brief Minimum allowed number of k nearest neighbors points that a viable result must contain. */
-      int min_pts_;
+      int min_pts_{1};
 
       /** \brief Return the radius search neighbours sorted **/
       bool sorted_;
index 92659038a9b3f881272428c1d3bb2bc978cc03bd..4396cb8b71757a68f6a5c5bf3a635784bff23229 100644 (file)
@@ -296,14 +296,14 @@ private:
   std::vector<int> index_mapping_;
 
   /** \brief whether the mapping between internal and external indices is identity */
-  bool identity_mapping_;
+  bool identity_mapping_{false};
 
   /** \brief Tree dimensionality (i.e. the number of dimensions per point). */
-  int dim_;
+  int dim_{0};
 
   /** \brief The total size of the data (either equal to the number of points in the
    * input cloud or to the number of indices - if passed). */
-  uindex_t total_nr_points_;
+  uindex_t total_nr_points_{0};
 
   /** \brief The KdTree search parameters for K-nearest neighbors. */
   ::flann::SearchParams param_k_;
index 9bf527c3206545eb3fa3075951cbc37b013fbdb2..2cf493823b7f3c0829d26457b1b3f65016a26084 100644 (file)
@@ -5,9 +5,9 @@
 
   The <b>pcl_kdtree</b> library provides the kd-tree data-structure, using
   <a href="http://www.cs.ubc.ca/research/flann/">FLANN</a>,
-  that allows for fast <a href="http://en.wikipedia.org/wiki/Nearest_neighbor_search">nearest neighbor searches</a>.
+  that allows for fast <a href="https://en.wikipedia.org/wiki/Nearest_neighbor_search">nearest neighbor searches</a>.
 
-  A <a href="http://en.wikipedia.org/wiki/Kd-tree">Kd-tree</a> (<i>k</i>-dimensional tree) is a space-partitioning data 
+  A <a href="https://en.wikipedia.org/wiki/Kd-tree">Kd-tree</a> (<i>k</i>-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 
index 92180e4062a8d01c322adb20bd8a3def7364952e..480e022f253b8a7d7fa07ae5af140fbbb20fd8b9 100644 (file)
@@ -4,7 +4,7 @@ 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})
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
index 6089e705f34027474533d19492b93a4474cf0ab6..5346e75c4484f7bc27b31bb2cfdb763b86d26577 100644 (file)
@@ -106,7 +106,7 @@ namespace pcl
           /** \brief Applies non-max-suppression. 
             * \param[in] intensity_data the image data
             * \param[in] input the keypoint positions
-            * \param[out] output the resultant keypoints after non-max-supression
+            * \param[out] output the resultant keypoints after non-max-suppression
             */
           void
           applyNonMaxSuppression (const std::vector<unsigned char>& intensity_data, 
@@ -116,7 +116,7 @@ namespace pcl
           /** \brief Applies non-max-suppression. 
             * \param[in] intensity_data the image data
             * \param[in] input the keypoint positions
-            * \param[out] output the resultant keypoints after non-max-supression
+            * \param[out] output the resultant keypoints after non-max-suppression
             */
           void
           applyNonMaxSuppression (const std::vector<float>& intensity_data, 
@@ -213,7 +213,7 @@ namespace pcl
           /** \brief Non-max-suppression helper method.
             * \param[in] input the keypoint positions
             * \param[in] scores the keypoint scores computed on the image data
-            * \param[out] output the resultant keypoints after non-max-supression
+            * \param[out] output the resultant keypoints after non-max-suppression
             */
           void
           applyNonMaxSuppression (const pcl::PointCloud<pcl::PointUV> &input, 
@@ -570,10 +570,8 @@ namespace pcl
 
       /** \brief Constructor */
       AgastKeypoint2DBase ()
-        : threshold_ (10)
-        , apply_non_max_suppression_ (true)
-        , bmax_ (255)
-        , nr_max_keypoints_ (std::numeric_limits<unsigned int>::max ())
+        : 
+         nr_max_keypoints_ (std::numeric_limits<unsigned int>::max ())
       {
         k_ = 1;
       }
@@ -673,13 +671,13 @@ namespace pcl
       IntensityT intensity_;
       
       /** \brief Threshold for corner detection. */
-      double threshold_;
+      double threshold_{10};
 
       /** \brief Determines whether non-max-suppression is activated. */
-      bool apply_non_max_suppression_;
+      bool apply_non_max_suppression_{true};
 
       /** \brief Max image value. */
-      double bmax_;
+      double bmax_{255};
 
       /** \brief The Agast detector to use. */
       AgastDetectorPtr detector_;
index 332015390e1502bcc7189b07afa72a2bfb44e4f0..e530e6a5669e9d6a4471ac17e514eea6518c55b1 100644 (file)
@@ -90,7 +90,6 @@ namespace pcl
       BriskKeypoint2D (int octaves = 4, int threshold = 60)
         : threshold_ (threshold)
         , octaves_ (octaves)
-        , remove_invalid_3D_keypoints_ (false)
       {
         k_ = 1;
         name_ = "BriskKeypoint2D";
@@ -157,8 +156,8 @@ namespace pcl
                              float x, float y,
                              PointOutT &pt)
       {
-        int u = int (x);
-        int v = int (y);
+        int u = static_cast<int>(x);
+        int v = static_cast<int>(y);
         
         pt.x = pt.y = pt.z = 0;
 
@@ -167,7 +166,7 @@ namespace pcl
         const PointInT &p3 = (*cloud)(u,   v+1);
         const PointInT &p4 = (*cloud)(u+1, v+1);
         
-        float fx = x - float (u), fy = y - float (v);
+        float fx = x - static_cast<float>(u), fy = y - static_cast<float>(v);
         float fx1 = 1.0f - fx, fy1 = 1.0f - fy;
 
         float w1 = fx1 * fy1, w2 = fx * fy1, w3 = fx1 * fy, w4 = fx * fy;
@@ -232,7 +231,7 @@ namespace pcl
       /** \brief Specify whether the keypoints that do not have a valid 3D position are
         * kept (false) or removed (true).
         */
-      bool remove_invalid_3D_keypoints_;
+      bool remove_invalid_3D_keypoints_{false};
   };
 
   ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -473,8 +472,8 @@ namespace pcl
           std::uint8_t safe_threshold_;
 
           // some constant parameters
-          float safety_factor_;
-          float basic_size_;
+          float safety_factor_{1.0};
+          float basic_size_{12.0};
       };
     } // namespace brisk
   } // namespace keypoints
index 2754e858ec17e0c64dc5711e71cc08b0df86b837..5305d4f0eaf954a9d28e7b998d1b7132096c7afe 100644 (file)
@@ -121,7 +121,7 @@ namespace pcl
 
       /** \brief whether the detected key points should be refined or not. If turned of, the key points are a subset of 
         * the original point cloud. Otherwise the key points may be arbitrary.
-        * \brief note non maxima supression needs to be on in order to use this feature.
+        * \brief note non maxima suppression needs to be on in order to use this feature.
         * \param[in] do_refine
         */
       void setRefine (bool do_refine);
index d6a3bf56c771a3c584f8bd8791ae9792b1dc4c00..9ba689a0b5772d141dc09f08418857df30e13c8e 100644 (file)
@@ -84,10 +84,7 @@ namespace pcl
         */
       HarrisKeypoint3D (ResponseMethod method = HARRIS, float radius = 0.01f, float threshold = 0.0f)
       : threshold_ (threshold)
-      , refine_ (true)
-      , nonmax_ (true)
       , method_ (method)
-      , threads_ (0)
       {
         name_ = "HarrisKeypoint3D";
         search_radius_ = radius;
@@ -108,7 +105,7 @@ namespace pcl
       void 
       setMethod (ResponseMethod type);
 
-      /** \brief Set the radius for normal estimation and non maxima supression.
+      /** \brief Set the radius for normal estimation and non maxima suppression.
         * \param[in] radius
         */
       void 
@@ -129,7 +126,7 @@ namespace pcl
       setNonMaxSupression (bool = false);
 
       /** \brief Whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary.
-        * \brief note non maxima supression needs to be on in order to use this feature.
+        * \brief note non maxima suppression needs to be on in order to use this feature.
         * \param[in] do_refine
         */
       void 
@@ -171,11 +168,11 @@ namespace pcl
       void calculateNormalCovar (const pcl::Indices& neighbors, float* coefficients) const;
     private:
       float threshold_;
-      bool refine_;
-      bool nonmax_;
+      bool refine_{true};
+      bool nonmax_{true};
       ResponseMethod method_;
       PointCloudNConstPtr normals_;
-      unsigned int threads_;
+      unsigned int threads_{0};
   };
 }
 
index 91ba241a8a2b72f085a4187a982830340b96055e..8b3b3ad880b73fbb808bd9b0251dab188a315829 100644 (file)
@@ -74,10 +74,8 @@ namespace pcl
        */
       HarrisKeypoint6D (float radius = 0.01, float threshold = 0.0)
       : threshold_ (threshold)
-      , refine_ (true)
-      , nonmax_ (true)
-      , threads_ (0)
-      , normals_ (new pcl::PointCloud<NormalT>)
+      , 
+       normals_ (new pcl::PointCloud<NormalT>)
       , intensity_gradients_ (new pcl::PointCloud<pcl::IntensityGradient>)
       {
         name_ = "HarrisKeypoint6D";
@@ -88,7 +86,7 @@ namespace pcl
       virtual ~HarrisKeypoint6D () = default;
 
       /**
-       * @brief set the radius for normal estimation and non maxima supression.
+       * @brief set the radius for normal estimation and non maxima suppression.
        * @param radius
        */
       void setRadius (float radius);
@@ -109,7 +107,7 @@ namespace pcl
 
       /**
        * @brief whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary.
-       * @brief note non maxima supression needs to be on in order to use this feature.
+       * @brief note non maxima suppression needs to be on in order to use this feature.
        * @param do_refine
        */
       void setRefine (bool do_refine);
@@ -129,9 +127,9 @@ namespace pcl
       void calculateCombinedCovar (const pcl::Indices& neighbors, float* coefficients) const;
     private:
       float threshold_;
-      bool refine_;
-      bool nonmax_;
-      unsigned int threads_;    
+      bool refine_{true};
+      bool nonmax_{true};
+      unsigned int threads_{0};    
       typename pcl::PointCloud<NormalT>::Ptr normals_;
       pcl::PointCloud<pcl::IntensityGradient>::Ptr intensity_gradients_;
   } ;
index 68e0b965d9b9c2d4a10908035416e6474b10f41b..f0b0cfa9221e13a36d5cbb2316b925f4ba6f57bc 100644 (file)
@@ -69,8 +69,8 @@ template <typename PointInT, typename PointOutT, typename IntensityT> void
 BriskKeypoint2D<PointInT, PointOutT, IntensityT>::detectKeypoints (PointCloudOut &output)
 {
   // image size
-  const int width = int (input_->width);
-  const int height = int (input_->height);
+  const int width = static_cast<int>(input_->width);
+  const int height = static_cast<int>(input_->height);
 
   // destination for intensity data; will be forwarded to BRISK
   std::vector<unsigned char> image_data (width*height);
index 542d5bae86b4fe8ca1abdbec8722d8e73d678e0d..17c56ef55cf3ecc0ceb71ebf0a344db25b1ac12f 100644 (file)
@@ -148,12 +148,12 @@ pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::calculateNormalCovar (const
   }
   if (count > 0)
   {
-    norm2 = _mm_set1_ps (float(count));
+    norm2 = _mm_set1_ps (static_cast<float>(count));
     vec1 = _mm_div_ps (vec1, norm2);
     vec2 = _mm_div_ps (vec2, norm2);
     _mm_store_ps (coefficients, vec1);
     _mm_store_ps (coefficients + 4, vec2);
-    coefficients [7] = zz / float(count);
+    coefficients [7] = zz / static_cast<float>(count);
   }
   else
     std::fill_n(coefficients, 8, 0);
@@ -504,9 +504,8 @@ pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::refineCorners (PointCloudOu
   Eigen::Matrix3f nnT;
   Eigen::Matrix3f NNT;
   Eigen::Vector3f NNTp;
-  const unsigned max_iterations = 10;
+  constexpr unsigned max_iterations = 10;
 #pragma omp parallel for \
-  default(none) \
   shared(corners) \
   firstprivate(nnT, NNT, NNTp) \
   num_threads(threads_)
index 066256e5ad9db35b307ef7042802829187e23a39..d5f9a3537c9d0a1fedd3c211ed2ced17585e15e9 100644 (file)
@@ -112,7 +112,7 @@ pcl::HarrisKeypoint6D<PointInT, PointOutT, NormalT>::calculateCombinedCovar (con
   }
   if (count > 0)
   {
-    float norm = 1.0 / float (count);
+    float norm = 1.0 / static_cast<float>(count);
     coefficients[ 0] *= norm;
     coefficients[ 1] *= norm;
     coefficients[ 2] *= norm;
index 398bee6e18482b4da891495eca3dee90514a053d..6c298c7b2c4d54067a82993e7882f025a2d17eb6 100644 (file)
@@ -132,7 +132,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::getBoundaryPoints (PointCloudI
   shared(angle_threshold, boundary_estimator, border_radius, edge_points, input) \
   firstprivate(u, v) \
   num_threads(threads_)
-  for (int index = 0; index < int (input.size ()); index++)
+  for (int index = 0; index < static_cast<int>(input.size ()); index++)
   {
     edge_points[index] = false;
     PointInT current_point = input[index];
@@ -314,7 +314,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut
   default(none) \
   shared(borders) \
   num_threads(threads_)
-  for (int index = 0; index < int (input_->size ()); index++)
+  for (int index = 0; index < static_cast<int>(input_->size ()); index++)
   {
     borders[index] = false;
     PointInT current_point = (*input_)[index];
@@ -338,7 +338,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut
   }
 
 #ifdef _OPENMP
-  Eigen::Vector3d *omp_mem = new Eigen::Vector3d[threads_];
+  auto *omp_mem = new Eigen::Vector3d[threads_];
 
   for (std::size_t i = 0; i < threads_; i++)
     omp_mem[i].setZero (3);
@@ -398,7 +398,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut
         prg_mem[index][d] = omp_mem[tid][d];
   }
 
-  for (int index = 0; index < int (input_->size ()); index++)
+  for (int index = 0; index < static_cast<int>(input_->size ()); index++)
   {
    if (!borders[index])
     {
@@ -413,7 +413,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut
   default(none) \
   shared(feat_max) \
   num_threads(threads_)
-  for (int index = 0; index < int (input_->size ()); index++)
+  for (int index = 0; index < static_cast<int>(input_->size ()); index++)
   {
     feat_max [index] = false;
     PointInT current_point = (*input_)[index];
@@ -445,7 +445,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut
   default(none) \
   shared(feat_max, output) \
   num_threads(threads_)
-  for (int index = 0; index < int (input_->size ()); index++)
+  for (int index = 0; index < static_cast<int>(input_->size ()); index++)
   {
     if (feat_max[index])
 #pragma omp critical
index c9a5e100e6c1d160e35e4e3da0f51922e4d38066..b5c43e957de605e0bb8f150a78266768122824a6 100644 (file)
@@ -128,7 +128,7 @@ pcl::SIFTKeypoint<PointInT, PointOutT>::detectKeypoints (PointCloudOut &output)
     cloud = temp;
 
     // Make sure the downsampled cloud still has enough points
-    const std::size_t min_nr_points = 25;
+    constexpr std::size_t min_nr_points = 25;
     if (cloud->size () < min_nr_points)
       break;
 
@@ -261,7 +261,7 @@ pcl::SIFTKeypoint<PointInT, PointOutT>::findScaleSpaceExtrema (
     const PointCloudIn &input, KdTree &tree, const Eigen::MatrixXf &diff_of_gauss, 
     pcl::Indices &extrema_indices, std::vector<int> &extrema_scales)
 {
-  const int k = 25;
+  constexpr int k = 25;
   pcl::Indices nn_indices (k);
   std::vector<float> nn_dist (k);
 
index 2c1a3dff2ca9ad40e79cf36566d1a82c8fe0f476..4f612bcb6498b6b32a449588055af6b2ecfa977a 100644 (file)
@@ -52,7 +52,7 @@ pcl::SmoothedSurfacesKeypoint<PointT, PointNT>::addSmoothedPointCloud (const Poi
   clouds_.push_back (cloud);
   cloud_normals_.push_back (normals);
   cloud_trees_.push_back (kdtree);
-  scales_.push_back (std::pair<float, std::size_t> (scale, scales_.size ()));
+  scales_.emplace_back(scale, scales_.size ());
 }
 
 
@@ -115,15 +115,15 @@ pcl::SmoothedSurfacesKeypoint<PointT, PointNT>::detectKeypoints (PointCloudT &ou
     if (is_min || is_max)
     {
       bool passed_min = true, passed_max = true;
-      for (std::size_t scale_i = 0; scale_i < scales_.size (); ++scale_i)
+      for (const auto & scale : scales_)
       {
-        std::size_t cloud_i = scales_[scale_i].second;
+        std::size_t cloud_i = scale.second;
         // skip input cloud
         if (cloud_i == clouds_.size () - 1)
           continue;
 
         nn_indices.clear (); nn_distances.clear ();
-        cloud_trees_[cloud_i]->radiusSearch (point_i, scales_[scale_i].first * neighborhood_constant_, nn_indices, nn_distances);
+        cloud_trees_[cloud_i]->radiusSearch (point_i, scale.first * neighborhood_constant_, nn_indices, nn_distances);
 
         bool is_min_other_scale = true, is_max_other_scale = true;
         for (const auto &nn_index : nn_indices)
@@ -225,7 +225,7 @@ pcl::SmoothedSurfacesKeypoint<PointT, PointNT>::initCompute ()
   }
 
   // Add the input cloud as the last index
-  scales_.push_back (std::pair<float, std::size_t> (input_scale_, scales_.size ()));
+  scales_.emplace_back(input_scale_, scales_.size ());
   clouds_.push_back (input_);
   cloud_normals_.push_back (normals_);
   cloud_trees_.push_back (tree_);
@@ -241,7 +241,7 @@ pcl::SmoothedSurfacesKeypoint<PointT, PointNT>::initCompute ()
     }
 
   PCL_INFO ("Scales: ");
-  for (std::size_t i = 0; i < scales_.size (); ++i) PCL_INFO ("(%d %f), ", scales_[i].second, scales_[i].first);
+  for (const auto & scale : scales_) PCL_INFO ("(%d %f), ", scale.second, scale.first);
   PCL_INFO ("\n");
 
   return (true);
index 94c465aa1a577398019486fd638a69ae27d82fc2..8b1c1463834823f10714c1959a5cdfd35eaef815 100644 (file)
@@ -246,6 +246,8 @@ TrajkovicKeypoint2D<PointInT, PointOutT, IntensityT>::detectKeypoints (PointClou
   shared(height, indices, occupency_map, output, width) \
   num_threads(threads_)
 #endif
+  // Disable lint since this 'for' is part of the pragma
+  // NOLINTNEXTLINE(modernize-loop-convert)
   for (std::ptrdiff_t i = 0; i < static_cast<std::ptrdiff_t> (indices.size ()); ++i)
   {
     int idx = indices[i];
index 2a686907df847f59c882ec786feacfc3e715329c..de5017f957c6bdda4db9c8f419a5777cf2f57d54 100644 (file)
@@ -111,17 +111,8 @@ namespace pcl
         */
       ISSKeypoint3D (double salient_radius = 0.0001)
       : salient_radius_ (salient_radius)
-      , non_max_radius_ (0.0)
-      , normal_radius_ (0.0)
-      , border_radius_ (0.0)
-      , gamma_21_ (0.975)
-      , gamma_32_ (0.975)
-      , third_eigen_value_ (nullptr)
-      , edge_points_ (nullptr)
-      , min_neighbors_ (5)
       , normals_ (new pcl::PointCloud<NormalT>)
       , angle_threshold_ (static_cast<float> (M_PI) / 2.0f)
-      , threads_ (0)
       {
         name_ = "ISSKeypoint3D";
         search_radius_ = salient_radius_;
@@ -141,7 +132,7 @@ namespace pcl
       void
       setSalientRadius (double salient_radius);
 
-      /** \brief Set the radius for the application of the non maxima supression algorithm.
+      /** \brief Set the radius for the application of the non maxima suppression algorithm.
         * \param[in] non_max_radius the non maxima suppression radius
         */
       void
@@ -236,28 +227,28 @@ namespace pcl
       double salient_radius_;
 
       /** \brief The non maxima suppression radius. */
-      double non_max_radius_;
+      double non_max_radius_{0.0};
 
       /** \brief The radius used to compute the normals of the input cloud. */
-      double normal_radius_;
+      double normal_radius_{0.0};
 
       /** \brief The radius used to compute the boundary points of the input cloud. */
-      double border_radius_;
+      double border_radius_{0.0};
 
       /** \brief The upper bound on the ratio between the second and the first eigenvalue returned by the EVD. */
-      double gamma_21_;
+      double gamma_21_{0.975};
 
       /** \brief The upper bound on the ratio between the third and the second eigenvalue returned by the EVD. */
-      double gamma_32_;
+      double gamma_32_{0.975};
 
       /** \brief Store the third eigen value associated to each point in the input cloud. */
-      double *third_eigen_value_;
+      double *third_eigen_value_{nullptr};
 
       /** \brief Store the information about the boundary points of the input cloud. */
-      bool *edge_points_;
+      bool *edge_points_{nullptr};
 
       /** \brief Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm. */
-      int min_neighbors_;
+      int min_neighbors_{5};
 
       /** \brief The cloud of normals related to the input surface. */
       PointCloudNConstPtr normals_;
@@ -266,7 +257,7 @@ namespace pcl
       float angle_threshold_;
 
       /** \brief The number of threads that has to be used by the scheduler. */
-      unsigned int threads_;
+      unsigned int threads_{0};
 
   };
 
index 56f96c3065ae19c6dd86cf00350e36bb12eca1e1..ef224f20791a2d24d6505987a11706f61e7b8a2e 100644 (file)
@@ -76,10 +76,8 @@ namespace pcl
         BaseClass (), 
         search_method_surface_ (),
         surface_ (), 
-        tree_ (), 
-        search_parameter_ (0), 
-        search_radius_ (0), 
-        k_ (0) 
+        tree_ () 
+        
       {};
       
       /** \brief Empty destructor */
@@ -181,13 +179,13 @@ namespace pcl
       KdTreePtr tree_;
 
       /** \brief The actual search parameter (casted from either \a search_radius_ or \a k_). */
-      double search_parameter_;
+      double search_parameter_{0.0};
 
       /** \brief The nearest neighbors search radius for each point. */
-      double search_radius_;
+      double search_radius_{0.0};
 
       /** \brief The number of K nearest neighbors to use for each point. */
-      int k_;
+      int k_{0};
 
       /** \brief Indices of the keypoints in the input cloud. */
       pcl::PointIndicesPtr keypoints_indices_;
index d9a4121afb227e4a92d58acdc0c6d0645f989492..c5034d16a98d22c393118416f0a7297f246d5197 100644 (file)
@@ -72,46 +72,40 @@ class PCL_EXPORTS NarfKeypoint : public Keypoint<PointWithRange, int>
     //! Parameters used in this class
     struct Parameters
     {
-      Parameters() : support_size(-1.0f), max_no_of_interest_points(-1), min_distance_between_interest_points(0.25f),
-                     optimal_distance_to_high_surface_change(0.25), min_interest_value(0.45f),
-                     min_surface_change_score(0.2f), optimal_range_image_patch_size(10),
-                     distance_for_additional_points(0.0f), add_points_on_straight_edges(false),
-                     do_non_maximum_suppression(true), no_of_polynomial_approximations_per_point(false),
-                     max_no_of_threads(1), use_recursive_scale_reduction(false),
-                     calculate_sparse_interest_image(true) {}
+      Parameters() = default;
       
-      float support_size;  //!< This defines the area 'covered' by an interest point (in meters)
-      int max_no_of_interest_points;  //!< The maximum number of interest points that will be returned
-      float min_distance_between_interest_points;  /**< Minimum distance between maximas
+      float support_size{-1.0f};  //!< This defines the area 'covered' by an interest point (in meters)
+      int max_no_of_interest_points{-1};  //!< The maximum number of interest points that will be returned
+      float min_distance_between_interest_points{0.25f};  /**< Minimum distance between maximas
                                                      *  (this is a factor for support_size, i.e. the distance is
                                                      *  min_distance_between_interest_points*support_size) */
-      float optimal_distance_to_high_surface_change;  /**< The distance we want keep between keypoints and areas
+      float optimal_distance_to_high_surface_change{0.25};  /**< The distance we want keep between keypoints and areas
                                                         *  of high surface change
                                                         *  (this is a factor for support_size, i.e., the distance is
                                                         *  optimal_distance_to_high_surface_change*support_size) */
-      float min_interest_value;  //!< The minimum value to consider a point as an interest point
-      float min_surface_change_score;  //!< The minimum value  of the surface change score to consider a point
-      int optimal_range_image_patch_size;  /**< The size (in pixels) of the image patches from which the interest value
+      float min_interest_value{0.45f};  //!< The minimum value to consider a point as an interest point
+      float min_surface_change_score{0.2f};  //!< The minimum value  of the surface change score to consider a point
+      int optimal_range_image_patch_size{10};  /**< The size (in pixels) of the image patches from which the interest value
                                              *  should be computed. This influences, which range image is selected from
                                              *  the scale space to compute the interest value of a pixel at a certain
                                              *  distance. */
       // TODO:
-      float distance_for_additional_points;  /**< All points in this distance to a found maximum, that
+      float distance_for_additional_points{0.0f};  /**< All points in this distance to a found maximum, that
                                                *  are above min_interest_value are also added as interest points
                                                *  (this is a factor for support_size, i.e. the distance is
                                                *  distance_for_additional_points*support_size) */
-      bool add_points_on_straight_edges;  /**< If this is set to true, there will also be interest points on
+      bool add_points_on_straight_edges{false};  /**< If this is set to true, there will also be interest points on
                                             *   straight edges, e.g., just indicating an area of high surface change */
-      bool do_non_maximum_suppression;  /**< If this is set to false there will be much more points
+      bool do_non_maximum_suppression{true};  /**< If this is set to false there will be much more points
                                           *  (can be used to spread points over the whole scene
                                           *  (combined with a low min_interest_value)) */
-      bool no_of_polynomial_approximations_per_point; /**< If this is >0, the exact position of the interest point is
+      bool no_of_polynomial_approximations_per_point{false}; /**< If this is >0, the exact position of the interest point is
                                                            determined using bivariate polynomial approximations of the
                                                            interest values of the area. */
-      int max_no_of_threads;  //!< The maximum number of threads this code is allowed to use with OPNEMP
-      bool use_recursive_scale_reduction;  /**< Try to decrease runtime by extracting interest points at lower reolution
+      int max_no_of_threads{1};  //!< The maximum number of threads this code is allowed to use with OPNEMP
+      bool use_recursive_scale_reduction{false};  /**< Try to decrease runtime by extracting interest points at lower reolution
                                              *  in areas that contain enough points, i.e., have lower range. */
-      bool calculate_sparse_interest_image;  /**< Use some heuristics to decide which areas of the interest image
+      bool calculate_sparse_interest_image{true};  /**< Use some heuristics to decide which areas of the interest image
                                                   can be left out to improve the runtime. */
     };
     
@@ -182,8 +176,8 @@ class PCL_EXPORTS NarfKeypoint : public Keypoint<PointWithRange, int>
     using BaseClass::name_;
     RangeImageBorderExtractor* range_image_border_extractor_;
     Parameters parameters_;
-    float* interest_image_;
-    ::pcl::PointCloud<InterestPoint>* interest_points_;
+    float* interest_image_{nullptr};
+    ::pcl::PointCloud<InterestPoint>* interest_points_{nullptr};
     std::vector<bool> is_interest_point_image_;
     std::vector<RangeImage*> range_image_scale_space_;
     std::vector<RangeImageBorderExtractor*> border_extractor_scale_space_;
index 688d87d4020f34acf0607711875e03045ec7beb6..5077096343f0d006b334d40f0f76f60eddde6709 100644 (file)
@@ -108,8 +108,8 @@ namespace pcl
       using Keypoint<PointInT, PointOutT>::initCompute;    
 
       /** \brief Empty constructor. */
-      SIFTKeypoint () : min_scale_ (0.0), nr_octaves_ (0), nr_scales_per_octave_ (0), 
-        min_contrast_ (-std::numeric_limits<float>::max ()), scale_idx_ (-1), 
+      SIFTKeypoint () :  
+        min_contrast_ (-std::numeric_limits<float>::max ()),  
         getFieldValue_ ()
       {
         name_ = "SIFTKeypoint";
@@ -178,20 +178,20 @@ namespace pcl
 
 
       /** \brief The standard deviation of the smallest scale in the scale space.*/
-      float min_scale_;
+      float min_scale_{0.0};
 
       /** \brief The number of octaves (i.e. doublings of scale) over which to search for keypoints.*/
-      int nr_octaves_;
+      int nr_octaves_{0};
 
       /** \brief The number of scales to be computed for each octave.*/
-      int nr_scales_per_octave_;
+      int nr_scales_per_octave_{0};
 
       /** \brief The minimum contrast required for detection.*/
       float min_contrast_;
 
       /** \brief Set to a value different than -1 if the output cloud has a "scale" field and we have to save 
         * the keypoints scales. */
-      int scale_idx_;
+      int scale_idx_{-1};
 
       /** \brief The list of fields present in the output point cloud data. */
       std::vector<pcl::PCLPointField> out_fields_;
index bc021967d3240433663e3437b20ccb07abf61bf7..cc9759530a61217af5538f1ae3bad6c23b090924 100644 (file)
@@ -72,13 +72,10 @@ namespace pcl
 
       SmoothedSurfacesKeypoint ()
         : Keypoint<PointT, PointT> (),
-          neighborhood_constant_ (0.5f),
           clouds_ (),
           cloud_normals_ (),
           cloud_trees_ (),
-          normals_ (),
-          input_scale_ (0.0f),
-          input_index_ ()
+          normals_ ()
       {
         name_ = "SmoothedSurfacesKeypoint";
 
@@ -116,14 +113,14 @@ namespace pcl
       initCompute () override;
 
     private:
-      float neighborhood_constant_;
+      float neighborhood_constant_{0.5f};
       std::vector<PointCloudTConstPtr> clouds_;
       std::vector<PointCloudNTConstPtr> cloud_normals_;
       std::vector<KdTreePtr> cloud_trees_;
       PointCloudNTConstPtr normals_;
       std::vector<std::pair<float, std::size_t> > scales_;
-      float input_scale_;
-      std::size_t input_index_;
+      float input_scale_{0.0f};
+      std::size_t input_index_{0u};
 
       static bool
       compareScalesFunction (const std::pair<float, std::size_t> &a,
index f11199b90aae0b881a7c8c108159636fb9f02d74..1b767bd2e03e39f498472914fa54f1adeb0ad698 100644 (file)
@@ -93,8 +93,6 @@ namespace pcl
         , angular_threshold_ (angular_threshold)
         , intensity_threshold_ (intensity_threshold)
         , normals_ (new pcl::PointCloud<NormalT>)
-        , threads_ (0)
-        , label_idx_ (-1)
       {
         name_ = "SUSANKeypoint";
         search_radius_ = radius;
@@ -182,7 +180,7 @@ namespace pcl
       float intensity_threshold_;
       float tolerance_;
       PointCloudNConstPtr normals_;
-      unsigned int threads_;
+      unsigned int threads_{0};
       bool geometric_validation_;
       bool nonmax_;
       /// intensity field accessor
@@ -190,7 +188,7 @@ namespace pcl
       /** \brief Set to a value different than -1 if the output cloud has a "label" field and we have 
         * to save the keypoints indices. 
         */
-      int label_idx_;
+      int label_idx_{-1};
       /** \brief The list of fields present in the output point cloud data. */
       std::vector<pcl::PCLPointField> out_fields_;
       pcl::common::IntensityFieldAccessor<PointOutT> intensity_out_;
index 355cdf537a5638bdc01891354f64594000aa6eae..9baf1adb7b0746a570a8924429124356229cc2ab 100644 (file)
@@ -43,7 +43,7 @@
 namespace pcl
 {
   /** \brief TrajkovicKeypoint2D implements Trajkovic and Hedley corner detector on
-    * organized pooint cloud using intensity information.
+    * organized point cloud using intensity information.
     * It uses first order statistics to find variation of intensities in horizontal
     * or vertical directions.
     *
@@ -81,7 +81,6 @@ namespace pcl
         , window_size_ (window_size)
         , first_threshold_ (first_threshold)
         , second_threshold_ (second_threshold)
-        , threads_ (1)
       {
         name_ = "TrajkovicKeypoint2D";
       }
@@ -164,7 +163,7 @@ namespace pcl
       /// second threshold for corner evaluation
       float second_threshold_;
       /// number of threads to be used
-      unsigned int threads_;
+      unsigned int threads_{1};
       /// point cloud response
       pcl::PointCloud<float>::Ptr response_;
   };
index fe9f3b2d84f05f4b47b12aa8541cc3a986a244ed..1758c6723878e2a2d3bbc4b3de3171fa9631c3d5 100644 (file)
@@ -85,7 +85,6 @@ namespace pcl
         , window_size_ (window_size)
         , first_threshold_ (first_threshold)
         , second_threshold_ (second_threshold)
-        , threads_ (1)
       {
         name_ = "TrajkovicKeypoint3D";
       }
@@ -204,7 +203,7 @@ namespace pcl
       /// second threshold for corner evaluation
       float second_threshold_;
       /// number of threads to be used
-      unsigned int threads_;
+      unsigned int threads_{1};
       /// point cloud normals
       NormalsConstPtr normals_;
       /// point cloud response
index f3f79b71c28a05004ceb85f79e41a39d3eb7ff7e..7c363a29ef8282cd4a4322f4f2b92152e597cbe9 100644 (file)
@@ -4,7 +4,7 @@
   \section secKeypointsPresentation Overview
 
   The <b>pcl_keypoints</b> library contains implementations of two point cloud keypoint detection algorithms.
-  Keypoints (also referred to as <a href="http://en.wikipedia.org/wiki/Interest_point_detection">interest points</a>) 
+  Keypoints (also referred to as <a href="https://en.wikipedia.org/wiki/Interest_point_detection">interest points</a>) 
   are points in an image or point cloud that are stable, distinctive, and can be identified using a well-defined 
   detection criterion.  Typically, the number of interest points in a point cloud will be much smaller than the total
   number of points in the cloud, and when used in combination with local feature descriptors at each keypoint, the 
index fa2266cc0d6ce79adba9f5e847443e588de7619b..f81fc9198e354af845c5ba84703162d81dcd38d6 100644 (file)
@@ -81,7 +81,7 @@ pcl::keypoints::agast::AbstractAgastDetector::detectKeypoints (
     const std::vector<unsigned char> & intensity_data,
     pcl::PointCloud<pcl::PointUV> &output) const
 {
-  detect (&(intensity_data[0]), output.points);
+  detect (intensity_data.data(), output.points);
 
   output.height = 1;
   output.width = output.size ();
@@ -93,7 +93,7 @@ pcl::keypoints::agast::AbstractAgastDetector::detectKeypoints (
     const std::vector<float> & intensity_data,
     pcl::PointCloud<pcl::PointUV> &output) const
 {
-  detect (&(intensity_data[0]), output.points);
+  detect (intensity_data.data(), output.points);
 
   output.height = 1;
   output.width = output.size ();
@@ -115,8 +115,8 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression (
   std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> >::const_iterator curr_corner;
   int lastRowCorner_ind = 0, next_lastRowCorner_ind = 0;
   std::vector<int>::iterator nms_flags_p;
-  int num_corners_all = int (corners_all.size ());
-  int n_max_corners = int (corners_nms.capacity ());
+  int num_corners_all = static_cast<int>(corners_all.size ());
+  int n_max_corners = static_cast<int>(corners_nms.capacity ());
 
   curr_corner = corners_all.begin ();
 
@@ -159,7 +159,7 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression (
     }
     if (next_lastRow != curr_corner->v)
     {
-      next_lastRow = int (curr_corner->v);
+      next_lastRow = static_cast<int>(curr_corner->v);
       next_lastRowCorner_ind = curr_corner_ind;
     }
     if (lastRow+1 == curr_corner->v)
@@ -244,7 +244,7 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression (
   pcl::PointCloud<pcl::PointUV> &output)
 {
   std::vector<ScoreIndex> scores;
-  computeCornerScores (&(intensity_data[0]), input.points, scores);
+  computeCornerScores (intensity_data.data(), input.points, scores);
 
   // If a threshold for the maximum number of keypoints is given
   if (nr_max_keypoints_ <= scores.size ()) //std::numeric_limits<unsigned int>::max ())
@@ -272,7 +272,7 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression (
   pcl::PointCloud<pcl::PointUV> &output)
 {
   std::vector<ScoreIndex> scores;
-  computeCornerScores (&(intensity_data[0]), input.points, scores);
+  computeCornerScores (intensity_data.data(), input.points, scores);
 
   // If a threshold for the maximum number of keypoints is given
   if (nr_max_keypoints_ <= scores.size ()) //std::numeric_limits<unsigned int>::max ())
@@ -373,7 +373,7 @@ namespace pcl
           std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> >& corners)
       {
         int total = 0;
-        int n_expected_corners = int (corners.capacity ());
+        int n_expected_corners = static_cast<int>(corners.capacity ());
         pcl::PointUV h;
         int width_b  = img_width - 3; //2, +1 due to faster test x>width_b
         int height_b = img_height - 2;
@@ -409,8 +409,8 @@ namespace pcl
             else
             {
               const T1* const p = im + y * width + x;
-              const T2 cb = *p + T2 (threshold);
-              const T2 c_b = *p - T2 (threshold);
+              const T2 cb = *p + static_cast<T2>(threshold);
+              const T2 c_b = *p - static_cast<T2>(threshold);
               if (p[offset0] > cb)
                 if (p[offset2] > cb)
                 if (p[offset5] > cb)
@@ -1447,8 +1447,8 @@ namespace pcl
             else
             {
               const T1* const p = im + y * width + x;
-              const T2 cb = *p + T2 (threshold);
-              const T2 c_b = *p - T2 (threshold);
+              const T2 cb = *p + static_cast<T2>(threshold);
+              const T2 c_b = *p - static_cast<T2>(threshold);
               if (p[offset0] > cb)
                 if (p[offset2] > cb)
                 if (p[offset5] > cb)
@@ -2416,8 +2416,8 @@ namespace pcl
                 corners.reserve (n_expected_corners);
               }
             }
-            h.u = float (x);
-            h.v = float (y);
+            h.u = static_cast<float>(x);
+            h.v = static_cast<float>(y);
             corners.push_back (h);
             total++;
             goto homogeneous;
@@ -2435,8 +2435,8 @@ namespace pcl
                 corners.reserve (n_expected_corners);
               }
             }
-            h.u = float (x);
-            h.v = float (y);
+            h.u = static_cast<float>(x);
+            h.v = static_cast<float>(y);
             corners.push_back (h);
             total++;
             goto structured;
@@ -3460,14 +3460,14 @@ namespace pcl
           double score_threshold,
           const std::array<std::int_fast16_t, 12> &offset)
       {
-        T2 bmin = T2 (score_threshold);
-        T2 bmax = T2 (im_bmax); // 255;
-        int b_test = int ((bmax + bmin) / 2);
+        T2 bmin = static_cast<T2>(score_threshold);
+        T2 bmax = static_cast<T2>(im_bmax); // 255;
+        int b_test = static_cast<int> ((bmax + bmin) / 2);
 
         while (true)
         {
-          const T2 cb = *p + T2 (b_test);
-          const T2 c_b = *p - T2 (b_test);
+          const T2 cb = *p + static_cast<T2> (b_test);
+          const T2 c_b = *p - static_cast<T2> (b_test);
 
           if (AgastDetector7_12s_is_a_corner(p, cb, c_b,
             offset[0],
@@ -3483,16 +3483,16 @@ namespace pcl
             offset[10],
             offset[11]))
           {
-            bmin = T2 (b_test);
+            bmin = static_cast<T2> (b_test);
           }
           else
           {
-            bmax = T2 (b_test);
+            bmax = static_cast<T2> (b_test);
           }
 
           if (bmin == bmax - 1 || bmin == bmax)
-            return (int (bmin));
-          b_test = int ((bmin + bmax) / 2);
+            return (static_cast<int> (bmin));
+          b_test = static_cast<int> ((bmin + bmax) / 2);
         }
       }
     } // namespace agast
@@ -3523,14 +3523,14 @@ pcl::keypoints::agast::AgastDetector7_12s::initPattern ()
 void
 pcl::keypoints::agast::AgastDetector7_12s::detect (const unsigned char* im, std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > & corners) const
 {
-  return (AgastDetector7_12s_detect<unsigned char, int> (im, int (width_), int (height_), threshold_, offset_, corners));
+  return (AgastDetector7_12s_detect<unsigned char, int> (im, static_cast<int>(width_), static_cast<int>(height_), threshold_, offset_, corners));
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::keypoints::agast::AgastDetector7_12s::detect (const float* im, std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > & corners) const
 {
-  return (AgastDetector7_12s_detect<float, float> (im, int (width_), int (height_), threshold_, offset_, corners));
+  return (AgastDetector7_12s_detect<float, float> (im, static_cast<int>(width_), static_cast<int>(height_), threshold_, offset_, corners));
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
@@ -3567,10 +3567,10 @@ namespace pcl
           std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> >& corners)
       {
         int total = 0;
-        int n_expected_corners = int (corners.capacity ());
+        int n_expected_corners = static_cast<int>(corners.capacity ());
         pcl::PointUV h;
-        int xsize_b = int (img_width) - 2;
-        int ysize_b = int (img_height) - 1;
+        int xsize_b = (img_width) - 2;
+        int ysize_b = (img_height) - 1;
         std::int_fast16_t offset0, offset1, offset2, offset3, offset4, offset5, offset6, offset7;
         int width;
 
@@ -3584,7 +3584,7 @@ namespace pcl
         offset5 = offset[5];
         offset6 = offset[6];
         offset7 = offset[7];
-        width   = int (img_width);
+        width   = (img_width);
 
         for (int y = 1; y < ysize_b; y++)
         {
@@ -3599,8 +3599,8 @@ namespace pcl
             else
             {
               const T1* const p = im + y * width + x;
-              const T2 cb = *p + T2 (threshold);
-              const T2 c_b = *p - T2 (threshold);
+              const T2 cb = *p + static_cast<T2>(threshold);
+              const T2 c_b = *p - static_cast<T2>(threshold);
               if (p[offset0] > cb)
                 if (p[offset2] > cb)
                 if (p[offset3] > cb)
@@ -3935,8 +3935,8 @@ namespace pcl
             else
             {
               const T1* const p = im + y * width + x;
-              const T2 cb = *p + T2 (threshold);
-              const T2 c_b = *p - T2 (threshold);
+              const T2 cb = *p + static_cast<T2>(threshold);
+              const T2 c_b = *p - static_cast<T2>(threshold);
               if (p[offset0] > cb)
                 if (p[offset2] > cb)
                 if (p[offset3] > cb)
@@ -4289,8 +4289,8 @@ namespace pcl
                 corners.reserve (n_expected_corners);
               }
             }
-            h.u = float (x);
-            h.v = float (y);
+            h.u = static_cast<float>(x);
+            h.v = static_cast<float>(y);
             corners.push_back (h);
             total++;
             goto homogeneous;
@@ -4308,8 +4308,8 @@ namespace pcl
                 corners.reserve (n_expected_corners);
               }
             }
-            h.u = float (x);
-            h.v = float (y);
+            h.u = static_cast<float>(x);
+            h.v = static_cast<float>(y);
             corners.push_back (h);
             total++;
             goto structured;
@@ -4444,14 +4444,14 @@ namespace pcl
           double score_threshold,
           const std::array<std::int_fast16_t, 8> &offset)
       {
-        T2 bmin = T2 (score_threshold);
-        T2 bmax = T2 (im_bmax);
-        int b_test = int ((bmax + bmin) / 2);
+        T2 bmin = static_cast<T2>(score_threshold);
+        T2 bmax = static_cast<T2>(im_bmax);
+        int b_test = static_cast<int> ((bmax + bmin) / 2);
 
         while (true)
         {
-          const T2 cb = *p + T2 (b_test);
-          const T2 c_b = *p - T2 (b_test);
+          const T2 cb = *p + static_cast<T2> (b_test);
+          const T2 c_b = *p - static_cast<T2> (b_test);
 
           if (AgastDetector5_8_is_a_corner(p, cb, c_b,
             offset[0],
@@ -4463,16 +4463,16 @@ namespace pcl
             offset[6],
             offset[7]))
           {
-            bmin = T2 (b_test);
+            bmin = static_cast<T2> (b_test);
           }
           else
           {
-            bmax = T2 (b_test);
+            bmax = static_cast<T2> (b_test);
           }
 
           if (bmin == bmax - 1 || bmin == bmax)
-            return (int (bmin));
-          b_test = int ((bmin + bmax) / 2);
+            return (static_cast<int> (bmin));
+          b_test = static_cast<int> ((bmin + bmax) / 2);
         }
       }
     } // namespace agast
@@ -4498,14 +4498,14 @@ pcl::keypoints::agast::AgastDetector5_8::initPattern ()
 void
 pcl::keypoints::agast::AgastDetector5_8::detect (const unsigned char* im, std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > & corners) const
 {
-  return (AgastDetector5_8_detect<unsigned char, int> (im, int (width_), int (height_), threshold_, offset_, corners));
+  return (AgastDetector5_8_detect<unsigned char, int> (im, static_cast<int>(width_), static_cast<int>(height_), threshold_, offset_, corners));
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::keypoints::agast::AgastDetector5_8::detect (const float* im, std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > & corners) const
 {
-  return (AgastDetector5_8_detect<float, float> (im, int (width_), int (height_), threshold_, offset_, corners));
+  return (AgastDetector5_8_detect<float, float> (im, static_cast<int>(width_), static_cast<int>(height_), threshold_, offset_, corners));
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
@@ -4542,10 +4542,10 @@ namespace pcl
           std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> >& corners)
       {
         int total = 0;
-        int n_expected_corners = int (corners.capacity ());
+        int n_expected_corners = static_cast<int>(corners.capacity ());
         pcl::PointUV h;
-        int xsize_b = int (img_width) - 4;
-        int ysize_b = int (img_height) - 3;
+        int xsize_b = (img_width) - 4;
+        int ysize_b = (img_height) - 3;
         std::int_fast16_t offset0, offset1, offset2, offset3, offset4, offset5, offset6, offset7, offset8, offset9, offset10, offset11, offset12, offset13, offset14, offset15;
         int width;
 
@@ -4567,7 +4567,7 @@ namespace pcl
         offset13 = offset[13];
         offset14 = offset[14];
         offset15 = offset[15];
-        width    = int (img_width);
+        width    = (img_width);
 
         for (int y = 3; y < ysize_b; y++)
         {
@@ -4580,8 +4580,8 @@ namespace pcl
             else
             {
               const T1* const p = im + y * width + x;
-              const T2 cb = *p + T2 (threshold);
-              const T2 c_b = *p - T2 (threshold);
+              const T2 cb = *p + static_cast<T2>(threshold);
+              const T2 c_b = *p - static_cast<T2>(threshold);
               if (p[offset0] > cb)
                 if (p[offset2] > cb)
                 if (p[offset4] > cb)
@@ -6625,8 +6625,8 @@ namespace pcl
                 corners.reserve (n_expected_corners);
               }
             }
-            h.u = float (x);
-            h.v = float (y);
+            h.u = static_cast<float>(x);
+            h.v = static_cast<float>(y);
             corners.push_back (h);
             total++;
           }
@@ -6642,9 +6642,9 @@ namespace pcl
           double score_threshold,
           const std::array<std::int_fast16_t, 16> &offset)
       {
-        T2 bmin = T2 (score_threshold);
-        T2 bmax = T2 (im_bmax);
-        int b_test = int ((bmax + bmin) / 2);
+        T2 bmin = static_cast<T2>(score_threshold);
+        T2 bmax = static_cast<T2>(im_bmax);
+        int b_test = static_cast<int> ((bmax + bmin) / 2);
 
         std::int_fast16_t offset0  = offset[0];
         std::int_fast16_t offset1  = offset[1];
@@ -6665,8 +6665,8 @@ namespace pcl
 
         while (true)
         {
-          const T2 cb = *p + T2 (b_test);
-          const T2 c_b = *p - T2 (b_test);
+          const T2 cb = *p + static_cast<T2> (b_test);
+          const T2 c_b = *p - static_cast<T2> (b_test);
           if (p[offset0] > cb)
             if (p[offset2] > cb)
               if (p[offset4] > cb)
@@ -8698,18 +8698,18 @@ namespace pcl
               goto is_not_a_corner;
 
           is_a_corner:
-            bmin = T2 (b_test);
+            bmin = static_cast<T2> (b_test);
             goto end;
 
           is_not_a_corner:
-            bmax = T2 (b_test);
+            bmax = static_cast<T2> (b_test);
             goto end;
 
           end:
 
           if (bmin == bmax - 1 || bmin == bmax)
-            return (int (bmin));
-          b_test = int ((bmin + bmax) / 2);
+            return (static_cast<int> (bmin));
+          b_test = static_cast<int> ((bmin + bmax) / 2);
         }
       }
     } // namespace agast
@@ -8744,14 +8744,14 @@ pcl::keypoints::agast::OastDetector9_16::initPattern ()
 void
 pcl::keypoints::agast::OastDetector9_16::detect (const unsigned char* im, std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > & corners) const
 {
-  return (OastDetector9_16_detect<unsigned char, int> (im, int (width_), int (height_), threshold_, offset_, corners));
+  return (OastDetector9_16_detect<unsigned char, int> (im, static_cast<int>(width_), static_cast<int>(height_), threshold_, offset_, corners));
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
 void
 pcl::keypoints::agast::OastDetector9_16::detect (const float* im, std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > & corners) const
 {
-  return (OastDetector9_16_detect<float, float> (im, int (width_), int (height_), threshold_, offset_, corners));
+  return (OastDetector9_16_detect<float, float> (im, static_cast<int>(width_), static_cast<int>(height_), threshold_, offset_, corners));
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
index 79c0085a339afc3aa81f53997fbe98d400f5f9cc..4b3d52c903176876aafe8fc1c8e0be4c6e58e021 100644 (file)
@@ -54,13 +54,11 @@ const int pcl::keypoints::brisk::Layer::CommonParams::TWOTHIRDSAMPLE = 1;
 /////////////////////////////////////////////////////////////////////////////////////////
 // construct telling the octaves number:
 pcl::keypoints::brisk::ScaleSpace::ScaleSpace (int octaves)
-  : safety_factor_ (1.0)
-  , basic_size_ (12.0)
 {
   if (octaves == 0)
     layers_ = 1;
   else
-    layers_ = std::uint8_t (2 * octaves);
+    layers_ = static_cast<std::uint8_t>(2 * octaves);
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
@@ -100,8 +98,8 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints (
   keypoints.reserve (2000);
 
   // assign thresholds
-  threshold_ = std::uint8_t (threshold);
-  safe_threshold_ = std::uint8_t (threshold_ * safety_factor_);
+  threshold_ = static_cast<std::uint8_t>(threshold);
+  safe_threshold_ = static_cast<std::uint8_t>(threshold_ * safety_factor_);
   std::vector<std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > > agast_points;
   agast_points.resize (layers_);
 
@@ -116,12 +114,12 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints (
   if (layers_ == 1)
   {
     // just do a simple 2d subpixel refinement...
-    const int num = int (agast_points[0].size ());
+    const int num = static_cast<int>(agast_points[0].size ());
     for (int n = 0; n < num; n++)
     {
       const pcl::PointUV& point = agast_points.at (0)[n];
       // first check if it is a maximum:
-      if (!isMax2D (0, int (point.u), int (point.v)))
+      if (!isMax2D (0, static_cast<int>(point.u), static_cast<int>(point.v)))
         continue;
 
       // let's do the subpixel and float scale refinement:
@@ -151,7 +149,7 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints (
   for (std::uint8_t i = 0; i < layers_; i++)
   {
     pcl::keypoints::brisk::Layer& l = pyramid_[i];
-    const int num = int (agast_points[i].size ());
+    const int num = static_cast<int>(agast_points[i].size ());
     
     if (i == layers_ - 1)
     {
@@ -160,12 +158,12 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints (
         const pcl::PointUV& point = agast_points.at (i)[n];
 
         // consider only 2D maxima...
-        if (!isMax2D (i, int (point.u), int (point.v)))
+        if (!isMax2D (i, static_cast<int>(point.u), static_cast<int>(point.v)))
           continue;
 
         bool ismax;
         float dx, dy;
-        getScoreMaxBelow (i, int (point.u), int (point.v),
+        getScoreMaxBelow (i, static_cast<int>(point.u), static_cast<int>(point.v),
                           l.getAgastScore (point.u, point.v, safe_threshold_), ismax,
                           dx, dy);
         if (!ismax)
@@ -205,20 +203,20 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints (
         const pcl::PointUV& point = agast_points.at (i)[n];
 
         // first check if it is a maximum:
-        if (!isMax2D (i, int (point.u), int (point.v)))
+        if (!isMax2D (i, static_cast<int>(point.u), static_cast<int>(point.v)))
         {
           continue;
         }
 
         // let's do the subpixel and float scale refinement:
         bool ismax;
-        score = refine3D (i, int (point.u), int (point.v), x, y, scale, ismax);
+        score = refine3D (i, static_cast<int>(point.u), static_cast<int>(point.v), x, y, scale, ismax);
 
         if (!ismax)
           continue;
 
         // finally store the detected keypoint:
-        if (score > float (threshold_))
+        if (score > static_cast<float>(threshold_))
         {
           keypoints.emplace_back(x, y, 0.0f, basic_size_ * scale, -1, score, i);
         }
@@ -290,28 +288,28 @@ pcl::keypoints::brisk::ScaleSpace::getScoreBelow (
   if (layer % 2 == 0)
   { // octave
     int sixth_x = 8 * x_layer + 1;
-    xf = float (sixth_x) / 6.0f;
+    xf = static_cast<float>(sixth_x) / 6.0f;
     int sixth_y = 8 * y_layer + 1;
-    yf = float (sixth_y) / 6.0f;
+    yf = static_cast<float>(sixth_y) / 6.0f;
 
     // scaling:
     offs = 2.0f / 3.0f;
     area = 4.0f * offs * offs;
     scaling  = static_cast<int> (4194304.0f / area);
-    scaling2 = static_cast<int> (float (scaling) * area);
+    scaling2 = static_cast<int> (static_cast<float>(scaling) * area);
   }
   else
   {
     int quarter_x = 6 * x_layer + 1;
-    xf = float (quarter_x) / 4.0f;
+    xf = static_cast<float>(quarter_x) / 4.0f;
     int quarter_y = 6 * y_layer + 1;
-    yf = float (quarter_y) / 4.0f;
+    yf = static_cast<float>(quarter_y) / 4.0f;
 
     // scaling:
     offs = 3.0f / 4.0f;
     area = 4.0f * offs * offs;
     scaling  = static_cast<int> (4194304.0f / area);
-    scaling2 = static_cast<int> (float (scaling) * area);
+    scaling2 = static_cast<int> (static_cast<float>(scaling) * area);
   }
 
   // calculate borders
@@ -320,49 +318,49 @@ pcl::keypoints::brisk::ScaleSpace::getScoreBelow (
   const float y_1 = yf - offs;
   const float y1  = yf + offs;
 
-  const int x_left   = int (x_1 + 0.5);
-  const int y_top    = int (y_1 + 0.5);
-  const int x_right  = int (x1  + 0.5);
-  const int y_bottom = int (y1  + 0.5);
+  const int x_left   = static_cast<int>(x_1 + 0.5);
+  const int y_top    = static_cast<int>(y_1 + 0.5);
+  const int x_right  = static_cast<int>(x1  + 0.5);
+  const int y_bottom = static_cast<int>(y1  + 0.5);
 
   // overlap area - multiplication factors:
-  const float r_x_1 = float (x_left) - x_1 + 0.5f;
-  const float r_y_1 = float (y_top) - y_1  + 0.5f;
-  const float r_x1  = x1 - float (x_right) + 0.5f;
-  const float r_y1  = y1 - float (y_bottom) + 0.5f;
+  const float r_x_1 = static_cast<float>(x_left) - x_1 + 0.5f;
+  const float r_y_1 = static_cast<float>(y_top) - y_1  + 0.5f;
+  const float r_x1  = x1 - static_cast<float>(x_right) + 0.5f;
+  const float r_y1  = y1 - static_cast<float>(y_bottom) + 0.5f;
   const int dx  = x_right - x_left - 1;
   const int dy = y_bottom - y_top - 1;
-  const int A = static_cast<int> ((r_x_1 * r_y_1) * float (scaling));
-  const int B = static_cast<int> ((r_x1  * r_y_1) * float (scaling));
-  const int C = static_cast<int> ((r_x1  * r_y1)  * float (scaling));
-  const int D = static_cast<int> ((r_x_1 * r_y1)  * float (scaling));
-  const int r_x_1_i = static_cast<int> (r_x_1 * float (scaling));
-  const int r_y_1_i = static_cast<int> (r_y_1 * float (scaling));
-  const int r_x1_i  = static_cast<int> (r_x1  * float (scaling));
-  const int r_y1_i  = static_cast<int> (r_y1  * float (scaling));
+  const int A = static_cast<int> ((r_x_1 * r_y_1) * static_cast<float>(scaling));
+  const int B = static_cast<int> ((r_x1  * r_y_1) * static_cast<float>(scaling));
+  const int C = static_cast<int> ((r_x1  * r_y1)  * static_cast<float>(scaling));
+  const int D = static_cast<int> ((r_x_1 * r_y1)  * static_cast<float>(scaling));
+  const int r_x_1_i = static_cast<int> (r_x_1 * static_cast<float>(scaling));
+  const int r_y_1_i = static_cast<int> (r_y_1 * static_cast<float>(scaling));
+  const int r_x1_i  = static_cast<int> (r_x1  * static_cast<float>(scaling));
+  const int r_y1_i  = static_cast<int> (r_y1  * static_cast<float>(scaling));
 
   // first row:
-  int ret_val = A * int (l.getAgastScore (x_left, y_top, 1));
+  int ret_val = A * static_cast<int>(l.getAgastScore (x_left, y_top, 1));
   for (int X = 1; X <= dx; X++)
-    ret_val += r_y_1_i * int (l.getAgastScore (x_left + X, y_top, 1));
+    ret_val += r_y_1_i * static_cast<int>(l.getAgastScore (x_left + X, y_top, 1));
 
-  ret_val += B * int (l.getAgastScore (x_left + dx + 1, y_top, 1));
+  ret_val += B * static_cast<int>(l.getAgastScore (x_left + dx + 1, y_top, 1));
   // middle ones:
   for (int Y = 1; Y <= dy; Y++)
   {
-    ret_val += r_x_1_i * int (l.getAgastScore (x_left, y_top + Y, 1));
+    ret_val += r_x_1_i * static_cast<int>(l.getAgastScore (x_left, y_top + Y, 1));
 
     for (int X = 1; X <= dx; X++)
-      ret_val += int (l.getAgastScore (x_left + X, y_top + Y, 1)) * scaling;
+      ret_val += static_cast<int>(l.getAgastScore (x_left + X, y_top + Y, 1)) * scaling;
 
-    ret_val += r_x1_i * int (l.getAgastScore (x_left + dx + 1, y_top + Y, 1));
+    ret_val += r_x1_i * static_cast<int>(l.getAgastScore (x_left + dx + 1, y_top + Y, 1));
   }
   // last row:
-  ret_val += D * int (l.getAgastScore (x_left, y_top + dy + 1, 1));
+  ret_val += D * static_cast<int>(l.getAgastScore (x_left, y_top + dy + 1, 1));
   for (int X = 1; X <= dx; X++)
-    ret_val += r_y1_i * int (l.getAgastScore (x_left + X, y_top + dy + 1, 1));
+    ret_val += r_y1_i * static_cast<int>(l.getAgastScore (x_left + X, y_top + dy + 1, 1));
 
-  ret_val += C * int (l.getAgastScore (x_left + dx + 1, y_top + dy + 1, 1));
+  ret_val += C * static_cast<int>(l.getAgastScore (x_left + dx + 1, y_top + dy + 1, 1));
 
   return ((ret_val + scaling2 / 2) / scaling2);
 }
@@ -374,7 +372,7 @@ pcl::keypoints::brisk::ScaleSpace::isMax2D (
 {
   const std::vector<unsigned char>& scores = pyramid_[layer].getScores ();
   const int scorescols = pyramid_[layer].getImageWidth ();
-  const unsigned char* data = &scores[0] + y_layer * scorescols + x_layer;
+  const unsigned char* data = scores.data() + y_layer * scorescols + x_layer;
 
   // decision tree:
   const unsigned char center = (*data);
@@ -456,7 +454,7 @@ pcl::keypoints::brisk::ScaleSpace::isMax2D (
     
     for (unsigned int i = 0; i < deltasize; i+= 2)
     {
-      data = &scores[0] + (y_layer - 1 + delta[i+1]) * scorescols + x_layer + delta[i] - 1;
+      data = scores.data() + (y_layer - 1 + delta[i+1]) * scorescols + x_layer + delta[i] - 1;
 
       int othercenter = *data;
       data++;
@@ -563,18 +561,18 @@ pcl::keypoints::brisk::ScaleSpace::refine3D (
 
     // calculate the relative scale (1D maximum):
     if (layer == 0)
-      scale = refine1D_2 (max_below_float, std::max (float (center), max_layer), max_above,max);
+      scale = refine1D_2 (max_below_float, std::max (static_cast<float>(center), max_layer), max_above,max);
     else
-      scale = refine1D (max_below_float, std::max (float (center), max_layer), max_above,max);
+      scale = refine1D (max_below_float, std::max (static_cast<float>(center), max_layer), max_above,max);
 
     if (scale > 1.0)
     {
       // interpolate the position:
       const float r0 = (1.5f - scale) / .5f;
       const float r1 = 1.0f - r0;
-      x = (r0 * delta_x_layer + r1 * delta_x_above + float (x_layer))
+      x = (r0 * delta_x_layer + r1 * delta_x_above + static_cast<float>(x_layer))
           * this_layer.getScale () + this_layer.getOffset ();
-      y = (r0 * delta_y_layer + r1 * delta_y_above + float (y_layer))
+      y = (r0 * delta_y_layer + r1 * delta_y_above + static_cast<float>(y_layer))
           * this_layer.getScale () + this_layer.getOffset ();
     }
     else
@@ -584,17 +582,17 @@ pcl::keypoints::brisk::ScaleSpace::refine3D (
         // interpolate the position:
         const float r0 = (scale - 0.5f) / 0.5f;
         const float r_1 = 1.0f - r0;
-        x = r0 * delta_x_layer + r_1 * delta_x_below + float (x_layer);
-        y = r0 * delta_y_layer + r_1 * delta_y_below + float (y_layer);
+        x = r0 * delta_x_layer + r_1 * delta_x_below + static_cast<float>(x_layer);
+        y = r0 * delta_y_layer + r_1 * delta_y_below + static_cast<float>(y_layer);
       }
       else
       {
         // interpolate the position:
         const float r0 = (scale - 0.75f) / 0.25f;
         const float r_1 = 1.0f -r0;
-        x = (r0 * delta_x_layer + r_1 * delta_x_below + float (x_layer))
+        x = (r0 * delta_x_layer + r_1 * delta_x_below + static_cast<float>(x_layer))
             * this_layer.getScale () +this_layer.getOffset ();
-        y = (r0 * delta_y_layer + r_1 * delta_y_below + float (y_layer))
+        y = (r0 * delta_y_layer + r_1 * delta_y_below + static_cast<float>(y_layer))
             * this_layer.getScale () + this_layer.getOffset ();
       }
     }
@@ -626,15 +624,15 @@ pcl::keypoints::brisk::ScaleSpace::refine3D (
                                   delta_x_layer, delta_y_layer);
 
     // calculate the relative scale (1D maximum):
-    scale = refine1D_1 (max_below, std::max (float (center),max_layer), max_above,max);
+    scale = refine1D_1 (max_below, std::max (static_cast<float>(center),max_layer), max_above,max);
     if (scale > 1.0)
     {
       // interpolate the position:
       const float r0 = 4.0f - scale * 3.0f;
       const float r1 = 1.0f - r0;
-      x = (r0 * delta_x_layer + r1 * delta_x_above + float (x_layer))
+      x = (r0 * delta_x_layer + r1 * delta_x_above + static_cast<float>(x_layer))
            * this_layer.getScale () + this_layer.getOffset ();
-      y = (r0 * delta_y_layer + r1 * delta_y_above + float (y_layer))
+      y = (r0 * delta_y_layer + r1 * delta_y_above + static_cast<float>(y_layer))
           * this_layer.getScale () + this_layer.getOffset ();
     }
     else
@@ -642,9 +640,9 @@ pcl::keypoints::brisk::ScaleSpace::refine3D (
       // interpolate the position:
       const float r0 = scale * 3.0f - 2.0f;
       const float r_1 = 1.0f - r0;
-      x = (r0 * delta_x_layer + r_1 * delta_x_below + float (x_layer))
+      x = (r0 * delta_x_layer + r_1 * delta_x_below + static_cast<float>(x_layer))
            * this_layer.getScale () + this_layer.getOffset ();
-      y = (r0 * delta_y_layer + r_1 * delta_y_below + float (y_layer))
+      y = (r0 * delta_y_layer + r_1 * delta_y_below + static_cast<float>(y_layer))
            * this_layer.getScale () + this_layer.getOffset ();
     }
   }
@@ -677,33 +675,33 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove (
   if (layer % 2 == 0) 
   {
     // octave
-    x_1  = float (4 * (x_layer) - 1 - 2) / 6.0f;
-    x1   = float (4 * (x_layer) - 1 + 2) / 6.0f;
-    y_1  = float (4 * (y_layer) - 1 - 2) / 6.0f;
-    y1   = float (4 * (y_layer) - 1 + 2) / 6.0f;
+    x_1  = static_cast<float>(4 * (x_layer) - 1 - 2) / 6.0f;
+    x1   = static_cast<float>(4 * (x_layer) - 1 + 2) / 6.0f;
+    y_1  = static_cast<float>(4 * (y_layer) - 1 - 2) / 6.0f;
+    y1   = static_cast<float>(4 * (y_layer) - 1 + 2) / 6.0f;
   }
   else
   {
     // intra
-    x_1 = float (6 * (x_layer) - 1 - 3) / 8.0f;
-    x1  = float (6 * (x_layer) - 1 + 3) / 8.0f;
-    y_1 = float (6 * (y_layer) - 1 - 3) / 8.0f;
-    y1  = float (6 * (y_layer) - 1 + 3) / 8.0f;
+    x_1 = static_cast<float>(6 * (x_layer) - 1 - 3) / 8.0f;
+    x1  = static_cast<float>(6 * (x_layer) - 1 + 3) / 8.0f;
+    y_1 = static_cast<float>(6 * (y_layer) - 1 - 3) / 8.0f;
+    y1  = static_cast<float>(6 * (y_layer) - 1 + 3) / 8.0f;
   }
 
   // check the first row
   //int max_x = int (x_1) + 1;
   //int max_y = int (y_1) + 1;
-  int max_x = int (x_1 + 1.0f);
-  int max_y = int (y_1 + 1.0f);
+  int max_x = static_cast<int>(x_1 + 1.0f);
+  int max_y = static_cast<int>(y_1 + 1.0f);
   float tmp_max = 0;
   float max = layer_above.getAgastScore (x_1, y_1, 1,1.0f);
 
   if (max > threshold) return (0);
   //for (int x = int (x_1) + 1; x <= int (x1); x++)
-  for (int x = int (x_1 + 1.0f); x <= int (x1); x++)
+  for (int x = static_cast<int>(x_1 + 1.0f); x <= static_cast<int>(x1); x++)
   {
-    tmp_max = layer_above.getAgastScore (float (x), y_1, 1,1.0f);
+    tmp_max = layer_above.getAgastScore (static_cast<float>(x), y_1, 1,1.0f);
 
     if (tmp_max > threshold) return (0);
     if (tmp_max > max)
@@ -718,22 +716,22 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove (
   if (tmp_max > max)
   {
     max = tmp_max;
-    max_x = int (x1);
+    max_x = static_cast<int>(x1);
   }
 
   // middle rows
-  for (int y = int (y_1) + 1; y <= int (y1); y++)
+  for (int y = static_cast<int>(y_1) + 1; y <= static_cast<int>(y1); y++)
   {
-    tmp_max = layer_above.getAgastScore (x_1, float (y), 1);
+    tmp_max = layer_above.getAgastScore (x_1, static_cast<float>(y), 1);
     
     if (tmp_max > threshold) return (0);
     if (tmp_max > max)
     {
       max   = tmp_max;
-      max_x = int (x_1 + 1);
+      max_x = static_cast<int>(x_1 + 1);
       max_y = y;
     }
-    for (int x = int (x_1) + 1; x <= int (x1); x++)
+    for (int x = static_cast<int>(x_1) + 1; x <= static_cast<int>(x1); x++)
     {
       tmp_max = layer_above.getAgastScore (x, y, 1);
 
@@ -745,13 +743,13 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove (
         max_y = y;
       }
     }
-    tmp_max = layer_above.getAgastScore(x1,float(y),1);
+    tmp_max = layer_above.getAgastScore(x1,static_cast<float>(y),1);
 
     if (tmp_max > threshold) return 0;
     if (tmp_max > max)
     {
       max   = tmp_max;
-      max_x = int (x1);
+      max_x = static_cast<int>(x1);
       max_y = y;
     }
   }
@@ -762,18 +760,18 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove (
   if (tmp_max > max)
   {
     max   = tmp_max;
-    max_x = int (x_1 + 1);
-    max_y = int (y1);
+    max_x = static_cast<int>(x_1 + 1);
+    max_y = static_cast<int>(y1);
   }
-  for (int x = int (x_1) + 1; x <= int (x1); x++)
+  for (int x = static_cast<int>(x_1) + 1; x <= static_cast<int>(x1); x++)
   {
-    tmp_max = layer_above.getAgastScore (float (x), y1, 1);
+    tmp_max = layer_above.getAgastScore (static_cast<float>(x), y1, 1);
 
     if (tmp_max > max)
     {
       max   = tmp_max;
       max_x = x;
-      max_y = int (y1);
+      max_y = static_cast<int>(y1);
     }
   }
   tmp_max = layer_above.getAgastScore (x1, y1, 1);
@@ -781,8 +779,8 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove (
   if (tmp_max > max)
   {
     max   = tmp_max;
-    max_x = int (x1);
-    max_y = int (y1);
+    max_x = static_cast<int>(x1);
+    max_y = static_cast<int>(y1);
   }
 
   //find dx/dy:
@@ -802,18 +800,18 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove (
                                   dx_1, dy_1);
 
   // calculate dx/dy in above coordinates
-  float real_x = float (max_x) + dx_1;
-  float real_y = float (max_y) + dy_1;
+  float real_x = static_cast<float>(max_x) + dx_1;
+  float real_y = static_cast<float>(max_y) + dy_1;
   bool returnrefined = true;
   if (layer % 2 == 0)
   {
-    dx = (real_x * 6.0f + 1.0f) / 4.0f - float (x_layer);
-    dy = (real_y * 6.0f + 1.0f) / 4.0f - float (y_layer);
+    dx = (real_x * 6.0f + 1.0f) / 4.0f - static_cast<float>(x_layer);
+    dy = (real_y * 6.0f + 1.0f) / 4.0f - static_cast<float>(y_layer);
   }
   else
   {
-    dx = (real_x * 8.0f + 1.0f) / 6.0f - float (x_layer);
-    dy = (real_y * 8.0f + 1.0f) / 6.0f - float (y_layer);
+    dx = (real_x * 8.0f + 1.0f) / 6.0f - static_cast<float>(x_layer);
+    dy = (real_y * 8.0f + 1.0f) / 6.0f - static_cast<float>(y_layer);
   }
 
   // saturate
@@ -846,17 +844,17 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow (
   if (layer % 2 == 0)
   {
     // octave
-    x_1 = float (8 * (x_layer) + 1 - 4) / 6.0f;
-    x1  = float (8 * (x_layer) + 1 + 4) / 6.0f;
-    y_1 = float (8 * (y_layer) + 1 - 4) / 6.0f;
-    y1  = float (8 * (y_layer) + 1 + 4) / 6.0f;
+    x_1 = static_cast<float>(8 * (x_layer) + 1 - 4) / 6.0f;
+    x1  = static_cast<float>(8 * (x_layer) + 1 + 4) / 6.0f;
+    y_1 = static_cast<float>(8 * (y_layer) + 1 - 4) / 6.0f;
+    y1  = static_cast<float>(8 * (y_layer) + 1 + 4) / 6.0f;
   }
   else
   {
-    x_1 = float (6 * (x_layer) + 1 - 3) / 4.0f;
-    x1  = float (6 * (x_layer) + 1 + 3) / 4.0f;
-    y_1 = float (6 * (y_layer) + 1 - 3) / 4.0f;
-    y1  = float (6 * (y_layer) + 1 + 3) / 4.0f;
+    x_1 = static_cast<float>(6 * (x_layer) + 1 - 3) / 4.0f;
+    x1  = static_cast<float>(6 * (x_layer) + 1 + 3) / 4.0f;
+    y_1 = static_cast<float>(6 * (y_layer) + 1 - 3) / 4.0f;
+    y1  = static_cast<float>(6 * (y_layer) + 1 + 3) / 4.0f;
   }
 
   // the layer below
@@ -864,14 +862,14 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow (
   pcl::keypoints::brisk::Layer& layer_below = pyramid_[layer-1];
 
   // check the first row
-  int max_x = int (x_1) + 1;
-  int max_y = int (y_1) + 1;
+  int max_x = static_cast<int>(x_1) + 1;
+  int max_y = static_cast<int>(y_1) + 1;
   float tmp_max;
   float max = layer_below.getAgastScore (x_1, y_1, 1);
   if (max > threshold) return (0);
-  for (int x = int (x_1) + 1; x <= int (x1); x++)
+  for (int x = static_cast<int>(x_1) + 1; x <= static_cast<int>(x1); x++)
   {
-    tmp_max = layer_below.getAgastScore (float (x), y_1, 1);
+    tmp_max = layer_below.getAgastScore (static_cast<float>(x), y_1, 1);
     if (tmp_max > threshold) return (0);
     if (tmp_max > max)
     {
@@ -884,21 +882,21 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow (
   if (tmp_max > max)
   {
     max   = tmp_max;
-    max_x = int (x1);
+    max_x = static_cast<int>(x1);
   }
 
   // middle rows
-  for (int y = int (y_1) + 1; y <= int (y1); y++)
+  for (int y = static_cast<int>(y_1) + 1; y <= static_cast<int>(y1); y++)
   {
-    tmp_max = layer_below.getAgastScore (x_1, float (y), 1);
+    tmp_max = layer_below.getAgastScore (x_1, static_cast<float>(y), 1);
     if (tmp_max > threshold) return (0);
     if (tmp_max > max)
     {
       max   = tmp_max;
-      max_x = int (x_1 + 1);
+      max_x = static_cast<int>(x_1 + 1);
       max_y = y;
     }
-    for (int x = int (x_1) + 1; x <= int (x1); x++)
+    for (int x = static_cast<int>(x_1) + 1; x <= static_cast<int>(x1); x++)
     {
       tmp_max = layer_below.getAgastScore (x, y, 1);
       if (tmp_max > threshold) return (0);
@@ -935,12 +933,12 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow (
         max_y = y;
       }
     }
-    tmp_max = layer_below.getAgastScore (x1, float (y), 1);
+    tmp_max = layer_below.getAgastScore (x1, static_cast<float>(y), 1);
     if (tmp_max > threshold) return (0);
     if (tmp_max > max)
     {
       max   = tmp_max;
-      max_x = int (x1);
+      max_x = static_cast<int>(x1);
       max_y = y;
     }
   }
@@ -950,25 +948,25 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow (
   if (tmp_max > max)
   {
     max   = tmp_max;
-    max_x = int (x_1 + 1);
-    max_y = int (y1);
+    max_x = static_cast<int>(x_1 + 1);
+    max_y = static_cast<int>(y1);
   }
-  for (int x = int (x_1) + 1; x <= int (x1); x++)
+  for (int x = static_cast<int>(x_1) + 1; x <= static_cast<int>(x1); x++)
   {
-    tmp_max = layer_below.getAgastScore (float (x), y1, 1);
+    tmp_max = layer_below.getAgastScore (static_cast<float>(x), y1, 1);
     if (tmp_max>max)
     {
       max   = tmp_max;
       max_x = x;
-      max_y = int (y1);
+      max_y = static_cast<int>(y1);
     }
   }
   tmp_max = layer_below.getAgastScore (x1, y1, 1);
   if (tmp_max > max)
   {
     max   = tmp_max;
-    max_x = int (x1);
-    max_y = int (y1);
+    max_x = static_cast<int>(x1);
+    max_y = static_cast<int>(y1);
   }
 
   //find dx/dy:
@@ -988,18 +986,18 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow (
                                   dx_1, dy_1);
 
   // calculate dx/dy in above coordinates
-  float real_x = float (max_x) + dx_1;
-  float real_y = float (max_y) + dy_1;
+  float real_x = static_cast<float>(max_x) + dx_1;
+  float real_y = static_cast<float>(max_y) + dy_1;
   bool returnrefined = true;
   if (layer % 2 == 0)
   {
-    dx = (real_x * 6.0f + 1.0f) / 8.0f - float (x_layer);
-    dy = (real_y * 6.0f + 1.0f) / 8.0f - float (y_layer);
+    dx = (real_x * 6.0f + 1.0f) / 8.0f - static_cast<float>(x_layer);
+    dy = (real_y * 6.0f + 1.0f) / 8.0f - static_cast<float>(y_layer);
   }
   else
   {
-    dx = (real_x * 4.0f - 1.0f) / 6.0f - float (x_layer);
-    dy = (real_y * 4.0f - 1.0f) / 6.0f - float (y_layer);
+    dx = (real_x * 4.0f - 1.0f) / 6.0f - static_cast<float>(x_layer);
+    dy = (real_y * 4.0f - 1.0f) / 6.0f - static_cast<float>(y_layer);
   }
 
   // saturate
@@ -1021,9 +1019,9 @@ float
 pcl::keypoints::brisk::ScaleSpace::refine1D ( 
     const float s_05, const float s0, const float s05, float& max)
 {
-  int i_05 = int (1024.0 * s_05 + 0.5);
-  int i0   = int (1024.0 * s0   + 0.5);
-  int i05  = int (1024.0 * s05  + 0.5);
+  int i_05 = static_cast<int>(1024.0 * s_05 + 0.5);
+  int i0   = static_cast<int>(1024.0 * s0   + 0.5);
+  int i05  = static_cast<int>(1024.0 * s05  + 0.5);
 
   //   16.0000  -24.0000    8.0000
   //  -40.0000   54.0000  -14.0000
@@ -1052,7 +1050,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D (
 
   int three_b = -40 * i_05 + 54 * i0 - 14 * i05;
   // calculate max location:
-  float ret_val = -float (three_b) / float (2 * three_a);
+  float ret_val = -static_cast<float>(three_b) / static_cast<float>(2 * three_a);
   // saturate and return
   if (ret_val < 0.75f)
     ret_val= 0.75f;
@@ -1060,7 +1058,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D (
     if (ret_val > 1.5f) 
       ret_val= 1.5f; // allow to be slightly off bounds ...?
   int three_c = +24 * i_05  -27 * i0    +6 * i05;
-  max = float (three_c) + float (three_a) * ret_val * ret_val + float (three_b) * ret_val;
+  max = static_cast<float>(three_c) + static_cast<float>(three_a) * ret_val * ret_val + static_cast<float>(three_b) * ret_val;
   max /= 3072.0f;
   return (ret_val);
 }
@@ -1070,9 +1068,9 @@ float
 pcl::keypoints::brisk::ScaleSpace::refine1D_1 (
     const float s_05, const float s0, const float s05, float& max)
 {
-  int i_05 = int (1024.0 *s_05 + 0.5);
-  int i0   = int (1024.0 *s0   + 0.5);
-  int i05  = int (1024.0 *s05  + 0.5);
+  int i_05 = static_cast<int>(1024.0 *s_05 + 0.5);
+  int i0   = static_cast<int>(1024.0 *s0   + 0.5);
+  int i05  = static_cast<int>(1024.0 *s05  + 0.5);
 
     //  4.5000   -9.0000    4.5000
     //-10.5000   18.0000   -7.5000
@@ -1101,7 +1099,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_1 (
 
   int two_b = -21 * i_05 + 36 * i0 - 15 * i05;
   // calculate max location:
-  float ret_val = -float (two_b) / float (2 * two_a);
+  float ret_val = -static_cast<float>(two_b) / static_cast<float>(2 * two_a);
   // saturate and return
   if (ret_val < 0.6666666666666666666666666667f)
     ret_val = 0.666666666666666666666666667f;
@@ -1109,7 +1107,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_1 (
     if (ret_val > 1.33333333333333333333333333f) 
       ret_val = 1.333333333333333333333333333f;
   int two_c = +12 * i_05  -16 * i0    +6 * i05;
-  max = float (two_c) + float (two_a) * ret_val * ret_val + float (two_b) * ret_val;
+  max = static_cast<float>(two_c) + static_cast<float>(two_a) * ret_val * ret_val + static_cast<float>(two_b) * ret_val;
   max /= 2048.0f;
   return (ret_val);
 }
@@ -1119,9 +1117,9 @@ float
 pcl::keypoints::brisk::ScaleSpace::refine1D_2 (
     const float s_05, const float s0, const float s05, float& max)
 {
-  int i_05 = int (1024.0 * s_05 + 0.5);
-  int i0   = int (1024.0 * s0   + 0.5);
-  int i05  = int (1024.0 * s05  + 0.5);
+  int i_05 = static_cast<int>(1024.0 * s_05 + 0.5);
+  int i0   = static_cast<int>(1024.0 * s0   + 0.5);
+  int i05  = static_cast<int>(1024.0 * s05  + 0.5);
 
   //   18.0000  -30.0000   12.0000
   //  -45.0000   65.0000  -20.0000
@@ -1150,7 +1148,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_2 (
 
   int b = -5 * i_05 + 8 * i0 - 3 * i05;
   // calculate max location:
-  float ret_val = -float (b) / float (2 * a);
+  float ret_val = -static_cast<float>(b) / static_cast<float>(2 * a);
   // saturate and return
   if (ret_val < 0.7f) 
     ret_val = 0.7f;
@@ -1158,7 +1156,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_2 (
     if (ret_val > 1.5f) 
       ret_val = 1.5f; // allow to be slightly off bounds ...?
   int c = +3 * i_05  -3 * i0    +1 * i05;
-  max = float (c) + float(a) * ret_val * ret_val + float (b) * ret_val;
+  max = static_cast<float>(c) + static_cast<float>(a) * ret_val * ret_val + static_cast<float>(b) * ret_val;
   max /= 1024.0f;
   return (ret_val);
 }
@@ -1191,7 +1189,7 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D (
   {
     delta_x = 0.0f;
     delta_y = 0.0f;
-    return (float (coeff6) / 18.0f);
+    return (static_cast<float>(coeff6) / 18.0f);
   }
 
   if (!(H_det > 0 && coeff1 < 0))
@@ -1218,12 +1216,12 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D (
       tmp_max = tmp;
       delta_x = -1.0f; delta_y = -1.0f;
     }
-    return (float (tmp_max + coeff1 + coeff2 + coeff6) / 18.0f);
+    return (static_cast<float>(tmp_max + coeff1 + coeff2 + coeff6) / 18.0f);
   }
 
   // this is hopefully the normal outcome of the Hessian test
-  delta_x = float (2 * coeff2 * coeff3 - coeff4 * coeff5) / float (-H_det);
-  delta_y = float (2 * coeff1 * coeff4 - coeff3 * coeff5) / float (-H_det);
+  delta_x = static_cast<float>(2 * coeff2 * coeff3 - coeff4 * coeff5) / static_cast<float>(-H_det);
+  delta_y = static_cast<float>(2 * coeff1 * coeff4 - coeff3 * coeff5) / static_cast<float>(-H_det);
   // TODO: this is not correct, but easy, so perform a real boundary maximum search:
   bool tx = false; bool tx_ = false; bool ty = false; bool ty_ = false;
   if (delta_x > 1.0f) tx = true;
@@ -1238,36 +1236,36 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D (
     if (tx) 
     {
       delta_x1 = 1.0f;
-      delta_y1 = -float (coeff4 + coeff5) / float (2.0 * coeff2);
+      delta_y1 = -static_cast<float>(coeff4 + coeff5) / static_cast<float>(2.0 * coeff2);
       if (delta_y1 > 1.0f) delta_y1 = 1.0f; else if (delta_y1 < -1.0f) delta_y1 = -1.0f;
     }
     else if (tx_) 
     {
       delta_x1 = -1.0f;
-      delta_y1 = -float (coeff4 - coeff5) / float (2.0 * coeff2);
+      delta_y1 = -static_cast<float>(coeff4 - coeff5) / static_cast<float>(2.0 * coeff2);
       if (delta_y1 > 1.0f) delta_y1 = 1.0f; else if (delta_y1 < -1.0f) delta_y1 = -1.0f;
     }
     if (ty) 
     {
       delta_y2 = 1.0f;
-      delta_x2 = -float (coeff3 + coeff5) / float (2.0 * coeff1);
+      delta_x2 = -static_cast<float>(coeff3 + coeff5) / static_cast<float>(2.0 * coeff1);
       if (delta_x2 > 1.0f) delta_x2 = 1.0f; else if (delta_x2 < -1.0f) delta_x2 = -1.0f;
     }
     else if (ty_) 
     {
       delta_y2 = -1.0f;
-      delta_x2 = -float (coeff3 - coeff5) / float (2.0 * coeff1);
+      delta_x2 = -static_cast<float>(coeff3 - coeff5) / static_cast<float>(2.0 * coeff1);
       if (delta_x2 > 1.0f) delta_x2 = 1.0f; else if (delta_x2 < -1.0f) delta_x2 = -1.0f;
     }
     // insert both options for evaluation which to pick
-    float max1 = (float (coeff1) * delta_x1 * delta_x1 + float (coeff2) * delta_y1 * delta_y1
-                 +float (coeff3) * delta_x1 + float (coeff4) * delta_y1
-                 +float (coeff5) * delta_x1 * delta_y1
-                 +float (coeff6)) / 18.0f;
-    float max2 = (float (coeff1) * delta_x2 * delta_x2 + float (coeff2) * delta_y2 * delta_y2
-                 +float (coeff3) * delta_x2 + float (coeff4) * delta_y2
-                 +float (coeff5) * delta_x2 * delta_y2
-                 +float (coeff6)) / 18.0f;
+    float max1 = (static_cast<float>(coeff1) * delta_x1 * delta_x1 + static_cast<float>(coeff2) * delta_y1 * delta_y1
+                 +static_cast<float>(coeff3) * delta_x1 + static_cast<float>(coeff4) * delta_y1
+                 +static_cast<float>(coeff5) * delta_x1 * delta_y1
+                 +static_cast<float>(coeff6)) / 18.0f;
+    float max2 = (static_cast<float>(coeff1) * delta_x2 * delta_x2 + static_cast<float>(coeff2) * delta_y2 * delta_y2
+                 +static_cast<float>(coeff3) * delta_x2 + static_cast<float>(coeff4) * delta_y2
+                 +static_cast<float>(coeff5) * delta_x2 * delta_y2
+                 +static_cast<float>(coeff6)) / 18.0f;
     if (max1 > max2) 
     {
       delta_x = delta_x1;
@@ -1280,10 +1278,10 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D (
   }
 
   // this is the case of the maximum inside the boundaries:
-  return ((float (coeff1) * delta_x * delta_x + float (coeff2) * delta_y * delta_y
-          +float (coeff3) * delta_x + float (coeff4) * delta_y
-          +float (coeff5) * delta_x * delta_y
-          +float (coeff6)) / 18.0f);
+  return ((static_cast<float>(coeff1) * delta_x * delta_x + static_cast<float>(coeff2) * delta_y * delta_y
+          +static_cast<float>(coeff3) * delta_x + static_cast<float>(coeff4) * delta_y
+          +static_cast<float>(coeff5) * delta_x * delta_y
+          +static_cast<float>(coeff6)) / 18.0f);
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////
@@ -1347,16 +1345,16 @@ pcl::keypoints::brisk::Layer::getAgastPoints (
     std::uint8_t threshold, std::vector<pcl::PointUV, Eigen::aligned_allocator<pcl::PointUV> > &keypoints)
 {
   oast_detector_->setThreshold (threshold);
-  oast_detector_->detect (&img_[0], keypoints);
+  oast_detector_->detect (img_.data(), keypoints);
 
   // also write scores
-  const int num = int (keypoints.size ());
+  const int num = static_cast<int>(keypoints.size ());
   const int imcols = img_width_;
 
   for (int i = 0; i < num; i++)
   {
-    const int offs = int (keypoints[i].u + keypoints[i].v * float (imcols));
-    *(&scores_[0] + offs) = static_cast<unsigned char> (oast_detector_->computeCornerScore (&img_[0] + offs));
+    const int offs = static_cast<int>(keypoints[i].u + keypoints[i].v * static_cast<float>(imcols));
+    *((scores_).data() + offs) = static_cast<unsigned char> (oast_detector_->computeCornerScore (img_.data() + offs));
   }
 }
 
@@ -1372,13 +1370,13 @@ pcl::keypoints::brisk::Layer::getAgastScore (int x, int y, std::uint8_t threshol
   {
     return (0);
   }
-  std::uint8_t& score = *(&scores_[0] + x + y * img_width_);
+  std::uint8_t& score = *(scores_.data() + x + y * img_width_);
   if (score > 2) 
   {
     return (score);
   }
   oast_detector_->setThreshold (threshold - 1);
-  score = std::uint8_t (oast_detector_->computeCornerScore (&img_[0] + x + y * img_width_));
+  score = static_cast<std::uint8_t>(oast_detector_->computeCornerScore (img_.data() + x + y * img_width_));
   if (score < threshold) score = 0;
   return (score);
 }
@@ -1398,7 +1396,7 @@ pcl::keypoints::brisk::Layer::getAgastScore_5_8 (int x, int y, std::uint8_t thre
   }
 
   agast_detector_5_8_->setThreshold (threshold - 1);
-  auto score = std::uint8_t (agast_detector_5_8_->computeCornerScore (&img_[0] + x + y * img_width_));
+  auto score = static_cast<std::uint8_t>(agast_detector_5_8_->computeCornerScore (img_.data() + x + y * img_width_));
   if (score < threshold) score = 0;
   return (score);
 }
@@ -1410,11 +1408,11 @@ pcl::keypoints::brisk::Layer::getAgastScore (float xf, float yf, std::uint8_t th
   if (scale <= 1.0f)
   {
     // just do an interpolation inside the layer
-    const int x = int (xf);
-    const float rx1 = xf - float (x);
+    const int x = static_cast<int>(xf);
+    const float rx1 = xf - static_cast<float>(x);
     const float rx = 1.0f - rx1;
-    const int y = int (yf);
-    const float ry1 = yf -float (y);
+    const int y = static_cast<int>(yf);
+    const float ry1 = yf -static_cast<float>(y);
     const float ry  = 1.0f -ry1;
 
     const float value = rx  * ry  * getAgastScore (x,     y,     threshold)+
@@ -1429,8 +1427,8 @@ pcl::keypoints::brisk::Layer::getAgastScore (float xf, float yf, std::uint8_t th
   // this means we overlap area smoothing
   const float halfscale = scale / 2.0f;
   // get the scores first:
-  for (int x = int (xf - halfscale); x <= int (xf + halfscale + 1.0f); x++)
-    for (int y = int (yf - halfscale); y <= int (yf + halfscale + 1.0f); y++)
+  for (int x = static_cast<int>(xf - halfscale); x <= static_cast<int>(xf + halfscale + 1.0f); x++)
+    for (int y = static_cast<int>(yf - halfscale); y <= static_cast<int>(yf + halfscale + 1.0f); y++)
       getAgastScore (x, y, threshold);
   // get the smoothed value
   return (getValue (scores_, img_width_, img_height_, xf, yf, scale));
@@ -1447,8 +1445,8 @@ pcl::keypoints::brisk::Layer::getValue (
   pcl::utils::ignore(height);
   assert (!mat.empty ());
   // get the position
-  const int x = int (std::floor (xf));
-  const int y = int (std::floor (yf));
+  const int x = static_cast<int>(std::floor (xf));
+  const int y = static_cast<int>(std::floor (yf));
   const std::vector<unsigned char>& image = mat;
   const int& imagecols = width;
 
@@ -1461,20 +1459,20 @@ pcl::keypoints::brisk::Layer::getValue (
   if (sigma_half < 0.5)
   {
     // interpolation multipliers:
-               const int r_x   = static_cast<int> ((xf - float (x)) * 1024);
-               const int r_y   = static_cast<int> ((yf - float (y)) * 1024);
+               const int r_x   = static_cast<int> ((xf - static_cast<float>(x)) * 1024);
+               const int r_y   = static_cast<int> ((yf - static_cast<float>(y)) * 1024);
     const int r_x_1 = (1024 - r_x);
     const int r_y_1 = (1024 - r_y);
-    const unsigned char* ptr = &image[0] + x + y * imagecols;
+    const unsigned char* ptr = image.data() + x + y * imagecols;
 
     // just interpolate:
-    ret_val = (r_x_1 * r_y_1 * int (*ptr));
+    ret_val = (r_x_1 * r_y_1 * static_cast<int>(*ptr));
     ptr++;
-    ret_val += (r_x * r_y_1 * int (*ptr));
+    ret_val += (r_x * r_y_1 * static_cast<int>(*ptr));
     ptr += imagecols;
-    ret_val += (r_x * r_y * int (*ptr));
+    ret_val += (r_x * r_y * static_cast<int>(*ptr));
     ptr--;
-    ret_val += (r_x_1 * r_y * int (*ptr));
+    ret_val += (r_x_1 * r_y * static_cast<int>(*ptr));
     return (static_cast<std::uint8_t> (0xFF & ((ret_val + 512) / 1024 / 1024)));
   }
 
@@ -1482,7 +1480,7 @@ pcl::keypoints::brisk::Layer::getValue (
 
   // scaling:
   const int scaling  = static_cast<int> (4194304.0f / area);
-  const int scaling2 = static_cast<int> (float (scaling) * area / 1024.0f);
+  const int scaling2 = static_cast<int> (static_cast<float>(scaling) * area / 1024.0f);
 
   // calculate borders
   const float x_1 = xf - sigma_half;
@@ -1490,37 +1488,37 @@ pcl::keypoints::brisk::Layer::getValue (
   const float y_1 = yf - sigma_half;
   const float y1  = yf + sigma_half;
 
-  const int x_left   = int (x_1 + 0.5f);
-  const int y_top    = int (y_1 + 0.5f);
-  const int x_right  = int (x1 + 0.5f);
-  const int y_bottom = int (y1 + 0.5f);
+  const int x_left   = static_cast<int>(x_1 + 0.5f);
+  const int y_top    = static_cast<int>(y_1 + 0.5f);
+  const int x_right  = static_cast<int>(x1 + 0.5f);
+  const int y_bottom = static_cast<int>(y1 + 0.5f);
 
   // overlap area - multiplication factors:
-  const float r_x_1 = float (x_left) - x_1 + 0.5f;
-  const float r_y_1 = float (y_top)  - y_1 + 0.5f;
-  const float r_x1  = x1 - float (x_right) + 0.5f;
-  const float r_y1  = y1 - float (y_bottom) + 0.5f;
+  const float r_x_1 = static_cast<float>(x_left) - x_1 + 0.5f;
+  const float r_y_1 = static_cast<float>(y_top)  - y_1 + 0.5f;
+  const float r_x1  = x1 - static_cast<float>(x_right) + 0.5f;
+  const float r_y1  = y1 - static_cast<float>(y_bottom) + 0.5f;
   const int dx = x_right  - x_left - 1;
   const int dy = y_bottom - y_top  - 1;
-  const int A = static_cast<int> ((r_x_1 * r_y_1) * float (scaling));
-  const int B = static_cast<int> ((r_x1  * r_y_1) * float (scaling));
-  const int C = static_cast<int> ((r_x1  * r_y1)  * float (scaling));
-  const int D = static_cast<int> ((r_x_1 * r_y1)  * float (scaling));
-  const int r_x_1_i = static_cast<int> (r_x_1 * float (scaling));
-  const int r_y_1_i = static_cast<int> (r_y_1 * float (scaling));
-  const int r_x1_i  = static_cast<int> (r_x1  * float (scaling));
-  const int r_y1_i  = static_cast<int> (r_y1  * float (scaling));
+  const int A = static_cast<int> ((r_x_1 * r_y_1) * static_cast<float>(scaling));
+  const int B = static_cast<int> ((r_x1  * r_y_1) * static_cast<float>(scaling));
+  const int C = static_cast<int> ((r_x1  * r_y1)  * static_cast<float>(scaling));
+  const int D = static_cast<int> ((r_x_1 * r_y1)  * static_cast<float>(scaling));
+  const int r_x_1_i = static_cast<int> (r_x_1 * static_cast<float>(scaling));
+  const int r_y_1_i = static_cast<int> (r_y_1 * static_cast<float>(scaling));
+  const int r_x1_i  = static_cast<int> (r_x1  * static_cast<float>(scaling));
+  const int r_y1_i  = static_cast<int> (r_y1  * static_cast<float>(scaling));
 
   // now the calculation:
-  const unsigned char* ptr = &image[0] + x_left + imagecols * y_top;
+  const unsigned char* ptr = image.data() + x_left + imagecols * y_top;
   // first row:
-  ret_val = A * int (*ptr);
+  ret_val = A * static_cast<int>(*ptr);
   ptr++;
   const unsigned char* end1 = ptr + dx;
   for (; ptr < end1; ptr++)
-    ret_val += r_y_1_i * int (*ptr);
+    ret_val += r_y_1_i * static_cast<int>(*ptr);
 
-  ret_val += B * int (*ptr);
+  ret_val += B * static_cast<int>(*ptr);
 
   // middle ones:
   ptr += imagecols - dx - 1;
@@ -1528,23 +1526,23 @@ pcl::keypoints::brisk::Layer::getValue (
 
   for (; ptr < end_j; ptr += imagecols - dx - 1)
   {
-    ret_val += r_x_1_i * int (*ptr);
+    ret_val += r_x_1_i * static_cast<int>(*ptr);
     ptr++;
     const unsigned char* end2 = ptr + dx;
     for (; ptr < end2; ptr++)
-      ret_val += int (*ptr) * scaling;
+      ret_val += static_cast<int>(*ptr) * scaling;
 
-    ret_val += r_x1_i * int (*ptr);
+    ret_val += r_x1_i * static_cast<int>(*ptr);
   }
 
   // last row:
-  ret_val += D * int (*ptr);
+  ret_val += D * static_cast<int>(*ptr);
   ptr++;
   const unsigned char* end3 = ptr + dx;
   for (; ptr < end3; ptr++)
-    ret_val += r_y1_i * int (*ptr);
+    ret_val += r_y1_i * static_cast<int>(*ptr);
 
-  ret_val += C * int (*ptr);
+  ret_val += C * static_cast<int>(*ptr);
 
   return (static_cast<std::uint8_t> (0xFF & ((ret_val + scaling2 / 2) / scaling2 / 1024)));
 }
@@ -1571,9 +1569,9 @@ pcl::keypoints::brisk::Layer::halfsample (
   __m128i mask = _mm_set_epi32 (0x00FF00FF, 0x00FF00FF, 0x00FF00FF, 0x00FF00FF);
 
   // data pointers:
-  const auto* p1 = reinterpret_cast<const __m128i*> (&srcimg[0]);
-  const auto* p2 = reinterpret_cast<const __m128i*> (&srcimg[0] + srcwidth);
-  auto* p_dest = reinterpret_cast<__m128i*> (&dstimg[0]);
+  const auto* p1 = reinterpret_cast<const __m128i*> (srcimg.data());
+  const auto* p2 = reinterpret_cast<const __m128i*> (srcimg.data() + srcwidth);
+  auto* p_dest = reinterpret_cast<__m128i*> (dstimg.data());
   unsigned char* p_dest_char;//=(unsigned char*)p_dest;
 
   // size:
@@ -1675,8 +1673,8 @@ pcl::keypoints::brisk::Layer::halfsample (
     if (noleftover)
     {
       row++;
-      p_dest = reinterpret_cast<__m128i*> (&dstimg[0] + row * dstwidth);
-      p1 = reinterpret_cast<const __m128i*> (&srcimg[0] + 2 * row * srcwidth);
+      p_dest = reinterpret_cast<__m128i*> (dstimg.data() + row * dstwidth);
+      p1 = reinterpret_cast<const __m128i*> (srcimg.data() + 2 * row * srcwidth);
       //p2=(__m128i*)(srcimg.data+(2*row+1)*srcwidth);
       //p1+=hsize;
       p2 = p1 + hsize;
@@ -1692,9 +1690,9 @@ pcl::keypoints::brisk::Layer::halfsample (
       }
       // done with the two rows:
       row++;
-      p_dest = reinterpret_cast<__m128i*> (&dstimg[0] + row * dstwidth);
-      p1 = reinterpret_cast<const __m128i*> (&srcimg[0] + 2 * row * srcwidth);
-      p2 = reinterpret_cast<const __m128i*> (&srcimg[0] + (2 * row + 1) * srcwidth);
+      p_dest = reinterpret_cast<__m128i*> (dstimg.data() + row * dstwidth);
+      p1 = reinterpret_cast<const __m128i*> (srcimg.data() + 2 * row * srcwidth);
+      p2 = reinterpret_cast<const __m128i*> (srcimg.data() + (2 * row + 1) * srcwidth);
     }
   }
 #else
@@ -1720,16 +1718,16 @@ pcl::keypoints::brisk::Layer::twothirdsample (
   assert (std::floor (double (srcheight) / 3.0 * 2.0) == dstheight);
 
   // masks:
-  __m128i mask1 = _mm_set_epi8 (char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),12,char(0x80),10,char(0x80),7,char(0x80),4,char(0x80),1);
-  __m128i mask2 = _mm_set_epi8 (char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),12,char(0x80),10,char(0x80),7,char(0x80),4,char(0x80),1,char(0x80));
-  __m128i mask = _mm_set_epi8 (char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),14,12,11,9,8,6,5,3,2,0);
-  __m128i store_mask = _mm_set_epi8 (0x0,0x0,0x0,0x0,0x0,0x0,char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80));
+  __m128i mask1 = _mm_set_epi8 (static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),12,static_cast<char>(0x80),10,static_cast<char>(0x80),7,static_cast<char>(0x80),4,static_cast<char>(0x80),1);
+  __m128i mask2 = _mm_set_epi8 (static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),12,static_cast<char>(0x80),10,static_cast<char>(0x80),7,static_cast<char>(0x80),4,static_cast<char>(0x80),1,static_cast<char>(0x80));
+  __m128i mask = _mm_set_epi8 (static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),14,12,11,9,8,6,5,3,2,0);
+  __m128i store_mask = _mm_set_epi8 (0x0,0x0,0x0,0x0,0x0,0x0,static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80),static_cast<char>(0x80));
 
   // data pointers:
-  const unsigned char* p1 = &srcimg[0];
+  const unsigned char* p1 = srcimg.data();
   const unsigned char* p2 = p1 + srcwidth;
   const unsigned char* p3 = p2 + srcwidth;
-  unsigned char* p_dest1 = &dstimg[0];
+  unsigned char* p_dest1 = dstimg.data();
   unsigned char* p_dest2 = p_dest1 + dstwidth;
   const unsigned char* p_end = p1 + (srcwidth * srcheight);
 
@@ -1801,10 +1799,10 @@ pcl::keypoints::brisk::Layer::twothirdsample (
     row_dest += 2;
 
     // reset pointers
-    p1 = &srcimg[0] + row * srcwidth;
+    p1 = srcimg.data() + row * srcwidth;
     p2 = p1 + srcwidth;
     p3 = p2 + srcwidth;
-    p_dest1 = &dstimg[0] + row_dest * dstwidth;
+    p_dest1 = dstimg.data() + row_dest * dstwidth;
     p_dest2 = p_dest1 + dstwidth;
   }
 #else
index da466453f9375620e18de543d575b639337dcf29..35d5811d34ae1b350a64894bb011f2f1edc3c857 100644 (file)
@@ -45,8 +45,7 @@ namespace pcl
 {
 
 /////////////////////////////////////////////////////////////////////////
-NarfKeypoint::NarfKeypoint (RangeImageBorderExtractor* range_image_border_extractor, float support_size) :
-    interest_image_ (nullptr), interest_points_ (nullptr)
+NarfKeypoint::NarfKeypoint (RangeImageBorderExtractor* range_image_border_extractor, float support_size)
 {
   name_ = "NarfKeypoint";
   clearData ();
@@ -240,8 +239,8 @@ NarfKeypoint::calculateCompleteInterestImage ()
   
   std::vector<float> start_usage_ranges;
   start_usage_ranges.resize (range_image_scale_space_.size ());
-  start_usage_ranges[int (range_image_scale_space_.size ())-1] = 0.0f;
-  for (int scale_idx = int (range_image_scale_space_.size ())-2;  scale_idx >= 0; --scale_idx)
+  start_usage_ranges[static_cast<int>(range_image_scale_space_.size ())-1] = 0.0f;
+  for (int scale_idx = static_cast<int>(range_image_scale_space_.size ())-2;  scale_idx >= 0; --scale_idx)
   {
     start_usage_ranges[scale_idx] = parameters_.support_size / 
       tanf (static_cast<float> (parameters_.optimal_range_image_patch_size) * range_image_scale_space_[scale_idx+1]->getAngularResolution ());
@@ -251,7 +250,7 @@ NarfKeypoint::calculateCompleteInterestImage ()
   //double interest_value_calculation_start_time = getTime ();
   interest_image_scale_space_.clear ();
   interest_image_scale_space_.resize (range_image_scale_space_.size (), nullptr);
-  for (int scale_idx = int (range_image_scale_space_.size ())-1;  scale_idx >= 0; --scale_idx)
+  for (int scale_idx = static_cast<int>(range_image_scale_space_.size ())-1;  scale_idx >= 0; --scale_idx)
   {
     const RangeImage& range_image = *range_image_scale_space_[scale_idx];
     RangeImageBorderExtractor& border_extractor = *border_extractor_scale_space_[scale_idx];
@@ -305,8 +304,8 @@ NarfKeypoint::calculateCompleteInterestImage ()
       {
         const RangeImage& half_range_image = *range_image_scale_space_[scale_idx+1];
         float* half_interest_image = interest_image_scale_space_[scale_idx+1];
-        int half_x = std::min (x/2, int (half_range_image.width)-1),
-            half_y = std::min (y/2, int (half_range_image.height)-1);
+        int half_x = std::min (x/2, static_cast<int>(half_range_image.width)-1),
+            half_y = std::min (y/2, static_cast<int>(half_range_image.height)-1);
         interest_value = half_interest_image[half_y*half_range_image.width + half_x];
         continue;
       }
@@ -343,9 +342,9 @@ NarfKeypoint::calculateCompleteInterestImage ()
             continue;
         }
         
-        for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,int (range_image.height)-1); ++y3)
+        for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,static_cast<int>(range_image.height)-1); ++y3)
         {
-          for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,int (range_image.width)-1); ++x3)
+          for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,static_cast<int>(range_image.width)-1); ++x3)
           {
             int index3 = y3*range_image.width + x3;
             if (!was_touched[index3])
@@ -390,7 +389,7 @@ NarfKeypoint::calculateCompleteInterestImage ()
           if (angle_histogram[histogram_cell2]==0.0f)
             continue;
           // TODO: lookup table for the following:
-          float normalized_angle_diff = 2.0f*float (histogram_cell2-histogram_cell1)/float (angle_histogram_size);
+          float normalized_angle_diff = 2.0f*static_cast<float>(histogram_cell2-histogram_cell1)/static_cast<float>(angle_histogram_size);
           normalized_angle_diff = (normalized_angle_diff <= 1.0f ? normalized_angle_diff : 2.0f-normalized_angle_diff);
           
           angle_change_value = std::max (angle_histogram[histogram_cell1] * angle_histogram[histogram_cell2] *
@@ -479,7 +478,6 @@ NarfKeypoint::calculateSparseInterestImage ()
   
   //double interest_value_calculation_start_time = getTime ();
 #pragma omp parallel for \
-  default(none) \
   shared(array_size, border_descriptions, increased_radius_squared, radius_reciprocal, radius_overhead_squared, range_image, search_radius, \
          surface_change_directions, surface_change_scores) \
   num_threads(parameters_.max_no_of_threads) \
@@ -534,9 +532,9 @@ NarfKeypoint::calculateSparseInterestImage ()
           continue;
       }
       
-      for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,int (range_image.height)-1); ++y3)
+      for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,static_cast<int>(range_image.height)-1); ++y3)
       {
-        for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,int (range_image.width)-1); ++x3)
+        for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,static_cast<int>(range_image.width)-1); ++x3)
         {
           int index3 = y3*range_image.width + x3;
           if (!was_touched[index3])
@@ -574,7 +572,7 @@ NarfKeypoint::calculateSparseInterestImage ()
         if (angle_histogram[histogram_cell2]==0.0f)
           continue;
         // TODO: lookup table for the following:
-        float normalized_angle_diff = 2.0f*float (histogram_cell2-histogram_cell1)/float (angle_histogram_size);
+        float normalized_angle_diff = 2.0f*static_cast<float>(histogram_cell2-histogram_cell1)/static_cast<float>(angle_histogram_size);
         normalized_angle_diff = (normalized_angle_diff <= 1.0f ? normalized_angle_diff : 2.0f-normalized_angle_diff);
         
         angle_change_value = std::max (angle_histogram[histogram_cell1] * angle_histogram[histogram_cell2] *
@@ -608,12 +606,12 @@ NarfKeypoint::calculateSparseInterestImage ()
         std::sort(relevent_point_indices.begin(), relevent_point_indices.end(), secondPairElementIsGreater);
         relevant_point_still_valid.clear();
         relevant_point_still_valid.resize(relevent_point_indices.size(), true);
-        for (int rpi_idx1=0; rpi_idx1<int(relevent_point_indices.size ())-1; ++rpi_idx1)
+        for (int rpi_idx1=0; rpi_idx1<static_cast<int>(relevent_point_indices.size ())-1; ++rpi_idx1)
         {
           if (!relevant_point_still_valid[rpi_idx1])
             continue;
           const PointWithRange& relevant_point1 = range_image.getPoint (relevent_point_indices[rpi_idx1].first);
-          for (int rpi_idx2=rpi_idx1+1; rpi_idx2<int(relevent_point_indices.size ()); ++rpi_idx2)
+          for (int rpi_idx2=rpi_idx1+1; rpi_idx2<static_cast<int>(relevent_point_indices.size ()); ++rpi_idx2)
           {
             if (!relevant_point_still_valid[rpi_idx2])
               continue;
@@ -625,14 +623,14 @@ NarfKeypoint::calculateSparseInterestImage ()
           }
         }
         int newPointIdx=0;
-        for (int oldPointIdx=0; oldPointIdx<int(relevant_point_still_valid.size()); ++oldPointIdx) {
+        for (int oldPointIdx=0; oldPointIdx<static_cast<int>(relevant_point_still_valid.size()); ++oldPointIdx) {
           if (relevant_point_still_valid[oldPointIdx])
             relevent_point_indices[newPointIdx++] = relevent_point_indices[oldPointIdx];
         }
         relevent_point_indices.resize(newPointIdx);
       }
 
-      // Caclulate interest values for neighbors
+      // Calculate interest values for neighbors
       for (const int &index2 : neighbors_within_radius_overhead)
       {
         int y2 = index2/range_image.width,
@@ -677,7 +675,7 @@ NarfKeypoint::calculateSparseInterestImage ()
             if (angle_histogram[histogram_cell2]==0.0f)
               continue;
             // TODO: lookup table for the following:
-            float normalized_angle_diff = 2.0f*float (histogram_cell2-histogram_cell1)/float (angle_histogram_size);
+            float normalized_angle_diff = 2.0f*static_cast<float>(histogram_cell2-histogram_cell1)/static_cast<float>(angle_histogram_size);
             normalized_angle_diff = (normalized_angle_diff <= 1.0f ? normalized_angle_diff : 2.0f-normalized_angle_diff);
             angle_change_value = std::max (angle_change_value, angle_histogram[histogram_cell1] *
                                                                angle_histogram[histogram_cell2] *
@@ -842,7 +840,7 @@ NarfKeypoint::calculateInterestPoints ()
   float min_distance_squared = powf (parameters_.min_distance_between_interest_points*parameters_.support_size, 2);
   for (const auto &interest_point : tmp_interest_points)
   {
-    if (parameters_.max_no_of_interest_points > 0  &&  int (interest_points_->size ()) >= parameters_.max_no_of_interest_points)
+    if (parameters_.max_no_of_interest_points > 0  &&  static_cast<int>(interest_points_->size ()) >= parameters_.max_no_of_interest_points)
       break;
     bool better_point_too_close = false;
     for (const auto &interest_point2 : interest_points_->points)
index 70d56650bbca0438b314e22ae00c973178d24922..c93d01ac4220bba564eaeabc9b8242abeeafc055 100644 (file)
@@ -155,7 +155,7 @@ protected:
   std::vector<PairwisePotential*> pairwise_potential_;
 
   /** Input types */
-  bool xyz_, rgb_, normal_;
+  bool xyz_{false}, rgb_{false}, normal_{false};
 
 public:
   PCL_MAKE_ALIGNED_OPERATOR_NEW
index b177198622ee127d8870ea8a23c92c264292ae70..135a90352dfe11af132ac6df61843a6f75f2fb4b 100644 (file)
@@ -211,7 +211,7 @@ public:
 
 private:
   /** The number of trees to train. */
-  std::size_t num_of_trees_to_train_;
+  std::size_t num_of_trees_to_train_{1};
 
   /** The trainer for the decision trees of the forest. */
   pcl::DecisionTreeTrainer<FeatureType, DataSet, LabelType, ExampleIndex, NodeType>
index 3920182af96832496b43bad66d7fc8aff17d970f..312aa2200c5687e52ac4a279f907796b60ba609f 100644 (file)
@@ -215,7 +215,7 @@ protected:
                         std::size_t max_depth,
                         NodeType& node);
 
-  /** Creates uniformely distrebuted thresholds over the range of the supplied
+  /** Creates uniformly distributed thresholds over the range of the supplied
    *  values.
    *
    * \param[in] num_of_thresholds the number of thresholds to create
@@ -229,28 +229,29 @@ protected:
 
 private:
   /** Maximum depth of the learned tree. */
-  std::size_t max_tree_depth_;
+  std::size_t max_tree_depth_{15};
   /** Number of features used to find optimal decision features. */
-  std::size_t num_of_features_;
+  std::size_t num_of_features_{1000};
   /** Number of thresholds. */
-  std::size_t num_of_thresholds_;
+  std::size_t num_of_thresholds_{10};
 
   /** FeatureHandler instance, responsible for creating and evaluating features. */
-  pcl::FeatureHandler<FeatureType, DataSet, ExampleIndex>* feature_handler_;
+  pcl::FeatureHandler<FeatureType, DataSet, ExampleIndex>* feature_handler_{nullptr};
   /** StatsEstimator instance, responsible for gathering stats about a node. */
-  pcl::StatsEstimator<LabelType, NodeType, DataSet, ExampleIndex>* stats_estimator_;
+  pcl::StatsEstimator<LabelType, NodeType, DataSet, ExampleIndex>* stats_estimator_{
+      nullptr};
 
   /** The training data set. */
-  DataSet data_set_;
+  DataSet data_set_{};
   /** The label data. */
-  std::vector<LabelType> label_data_;
+  std::vector<LabelType> label_data_{};
   /** The example data. */
-  std::vector<ExampleIndex> examples_;
+  std::vector<ExampleIndex> examples_{};
 
   /** Minimum number of examples to split a node. */
-  std::size_t min_examples_for_split_;
+  std::size_t min_examples_for_split_{0u};
   /** Thresholds to be used instead of generating uniform distributed thresholds. */
-  std::vector<float> thresholds_;
+  std::vector<float> thresholds_{};
   /** The data provider which is called before training a specific tree, if pointer is
    *   NULL, then data_set_ is used. */
   typename pcl::DecisionTreeTrainerDataProvider<FeatureType,
@@ -258,10 +259,10 @@ private:
                                                 LabelType,
                                                 ExampleIndex,
                                                 NodeType>::Ptr
-      decision_tree_trainer_data_provider_;
+      decision_tree_trainer_data_provider_{nullptr};
   /** If true, random features are generated at each node, otherwise, at start of
    *  training the tree */
-  bool random_features_at_split_node_;
+  bool random_features_at_split_node_{false};
 };
 
 } // namespace pcl
index 8657c2cd30966280911ed709b1aac41e58ac19cf..4c9b35dc569269fcdf438dde7ba99e8da3623489 100644 (file)
@@ -149,7 +149,7 @@ public:
   train(Fern<FeatureType, NodeType>& fern);
 
 protected:
-  /** Creates uniformely distrebuted thresholds over the range of the supplied
+  /** Creates uniformly distributed thresholds over the range of the supplied
    *  values.
    *
    * \param[in] num_of_thresholds the number of thresholds to create
index a7657651bc8f0db66e7007cd586739308581ca5e..1109420604046924562841a50da82438b4bfd458 100644 (file)
@@ -46,7 +46,7 @@ template <class FeatureType,
           class NodeType>
 DecisionForestTrainer<FeatureType, DataSet, LabelType, ExampleIndex, NodeType>::
     DecisionForestTrainer()
-: num_of_trees_to_train_(1), decision_tree_trainer_()
+: decision_tree_trainer_()
 {}
 
 template <class FeatureType,
index be2d36108479c0e6bda25f85333b30d79efc739f..f04e1b3438ae38dd03f024910dba88a6aa2f69b3 100644 (file)
@@ -45,18 +45,7 @@ template <class FeatureType,
           class ExampleIndex,
           class NodeType>
 DecisionTreeTrainer<FeatureType, DataSet, LabelType, ExampleIndex, NodeType>::
-    DecisionTreeTrainer()
-: max_tree_depth_(15)
-, num_of_features_(1000)
-, num_of_thresholds_(10)
-, feature_handler_(nullptr)
-, stats_estimator_(nullptr)
-, data_set_()
-, label_data_()
-, examples_()
-, decision_tree_trainer_data_provider_()
-, random_features_at_split_node_(false)
-{}
+    DecisionTreeTrainer() = default;
 
 template <class FeatureType,
           class DataSet,
@@ -159,21 +148,15 @@ DecisionTreeTrainer<FeatureType, DataSet, LabelType, ExampleIndex, NodeType>::
     if (!thresholds_.empty()) {
       // compute information gain for each threshold and store threshold with highest
       // information gain
-      for (std::size_t threshold_index = 0; threshold_index < thresholds_.size();
-           ++threshold_index) {
+      for (const float& threshold : thresholds_) {
 
-        const float information_gain =
-            stats_estimator_->computeInformationGain(data_set_,
-                                                     examples,
-                                                     label_data,
-                                                     feature_results,
-                                                     flags,
-                                                     thresholds_[threshold_index]);
+        const float information_gain = stats_estimator_->computeInformationGain(
+            data_set_, examples, label_data, feature_results, flags, threshold);
 
         if (information_gain > best_feature_information_gain) {
           best_feature_information_gain = information_gain;
           best_feature_index = static_cast<int>(feature_index);
-          best_feature_threshold = thresholds_[threshold_index];
+          best_feature_threshold = threshold;
         }
       }
     }
index 5f4017e2c251cb41756b4060ea3795732ed27a5c..d1ec89a702e704180216733ebf42f0c3c59fecc4 100644 (file)
@@ -102,7 +102,7 @@ public:
   void
   debug();
 
-  /** Pseudo radnom generator. */
+  /** Pseudo random generator. */
   inline std::size_t
   generateHashKey(const std::vector<short>& k)
   {
index b4cd634dcab11b10c070a7d38ddf613d0a0e789e..e0c775b3bfa2020845c287049e0a90410220bed2 100644 (file)
@@ -47,7 +47,7 @@ namespace pcl {
 class PCL_EXPORTS PointXY32f {
 public:
   /** Constructor. */
-  inline PointXY32f() : x(0.0f), y(0.0f) {}
+  inline PointXY32f() = default;
   /** Destructor. */
   inline virtual ~PointXY32f() = default;
 
@@ -85,9 +85,9 @@ public:
 
 public:
   /** The x-coordinate of the point. */
-  float x;
+  float x{0.0f};
   /** The y-coordinate of the point. */
-  float y;
+  float y{0.0f};
 };
 
 } // namespace pcl
index c1ca352a38da80554fe1d2ebcbf1fcd498026b77..deeba22f8f8b6f00e7fe79895de95798eb608504 100644 (file)
@@ -47,7 +47,7 @@ namespace pcl {
 class PCL_EXPORTS PointXY32i {
 public:
   /** Constructor. */
-  inline PointXY32i() : x(0), y(0) {}
+  inline PointXY32i() = default;
 
   /** Destructor. */
   inline virtual ~PointXY32i() = default;
@@ -86,9 +86,9 @@ public:
 
 public:
   /** The x-coordinate of the point. */
-  int x;
+  int x{0};
   /** The y-coordinate of the point. */
-  int y;
+  int y{0};
 };
 
 } // namespace pcl
index 72424be49bc46e629f29f4afd5c92f227a26d85b..f42cc3c9300cb683879d0a766bfcacaa635d41fc 100644 (file)
@@ -52,7 +52,7 @@ public:
   /** Destructor. */
   virtual ~StatsEstimator() = default;
 
-  /** Returns the number of brances a node can have (e.g. a binary tree has 2). */
+  /** Returns the number of branches a node can have (e.g. a binary tree has 2). */
   virtual std::size_t
   getNumOfBranches() const = 0;
 
index d1d8619bd82fbb393606c2f99eccaac57a51d420..22daf28165464a760ee62c6b404c21ea765ef848 100644 (file)
@@ -64,9 +64,9 @@ struct svm_scaling {
   struct svm_node* obj;
 
   // max features scaled
-  int max;
+  int max{0};
 
-  svm_scaling() : max(0) {}
+  svm_scaling() = default;
 };
 
 enum { C_SVC, NU_SVC, ONE_CLASS, EPSILON_SVR, NU_SVR }; /* svm_type */
index 00eab956b2d76e6efed4fed5834bb455a7163cda..b125b700798417f8678e84abfa216d4acda1e20d 100644 (file)
@@ -98,11 +98,11 @@ struct SVMModel : svm_model {
  */
 struct SVMDataPoint {
   /// It's the feature index. It has to be an integer number greater or equal to zero
-  int idx;
+  int idx{-1};
   /// The value assigned to the correspondent feature.
-  float value;
+  float value{0.0f};
 
-  SVMDataPoint() : idx(-1), value(0) {}
+  SVMDataPoint() = default;
 };
 
 /** The structure stores the features and the label of a single sample which has to be
@@ -128,9 +128,10 @@ protected:
   SVMParam param_;      // it stores the training parameters
   std::string class_name_; // The SVM class name.
 
-  char* line_;                 // buffer for line reading
-  int max_line_len_;           // max line length in the input file
-  bool labelled_training_set_; // it stores whether the input set of samples is labelled
+  char* line_{nullptr};     // buffer for line reading
+  int max_line_len_{10000}; // max line length in the input file
+  bool labelled_training_set_{
+      true}; // it stores whether the input set of samples is labelled
 
   /** Set for output printings during classification. */
   static void
@@ -177,7 +178,7 @@ protected:
 
 public:
   /**  Constructor. */
-  SVM() : prob_(), line_(nullptr), max_line_len_(10000), labelled_training_set_(true) {}
+  SVM() : prob_() {}
 
   /** Destructor. */
   ~SVM()
@@ -243,12 +244,12 @@ protected:
   using SVM::training_set_;
 
   /// Set to 1 to see the training output
-  bool debug_;
+  bool debug_{false};
   /// Set too 1 for cross validating the classifier
-  int cross_validation_;
+  int cross_validation_{0};
   /// Number of folds to be used during cross validation. It indicates in how many parts
   /// is split the input training set.
-  int nr_fold_;
+  int nr_fold_{0};
 
   /** To cross validate the classifier. It is automatic for probability estimate. */
   void
@@ -263,7 +264,7 @@ protected:
 
 public:
   /** Constructor. */
-  SVMTrain() : debug_(false), cross_validation_(0), nr_fold_(0)
+  SVMTrain()
   {
     class_name_ = "SVMTrain";
     svm_set_print_string_function(
@@ -385,8 +386,9 @@ protected:
   using SVM::scaling_;
   using SVM::training_set_;
 
-  bool model_extern_copied_; // Set to 0 if the model is loaded from an extern file.
-  bool predict_probability_; // Set to 1 to predict probabilities.
+  bool model_extern_copied_{
+      false}; // Set to 0 if the model is loaded from an extern file.
+  bool predict_probability_{false};             // Set to 1 to predict probabilities.
   std::vector<std::vector<double>> prediction_; // It stores the resulting prediction.
 
   /** It scales the input dataset using the model information. */
@@ -395,10 +397,7 @@ protected:
 
 public:
   /** Constructor. */
-  SVMClassify() : model_extern_copied_(false), predict_probability_(false)
-  {
-    class_name_ = "SvmClassify";
-  }
+  SVMClassify() { class_name_ = "SvmClassify"; }
 
   /** Destructor. */
   ~SVMClassify()
@@ -499,7 +498,7 @@ public:
 
   /** Read in a normalized classification problem (in svmlight format).
    *
-   *  The data are kept whitout normalizing.
+   *  The data is kept without normalizing.
    *
    * \return false if fails
    */
index d1cf11a7242b23f9c66c25037c441e94974a71e9..e0dd25d78604647bfef086ee7effc42fe71ad8ca 100644 (file)
@@ -39,8 +39,7 @@
 
 #include <pcl/ml/densecrf.h>
 
-pcl::DenseCrf::DenseCrf(int N, int m)
-: N_(N), M_(m), xyz_(false), rgb_(false), normal_(false)
+pcl::DenseCrf::DenseCrf(int N, int m) : N_(N), M_(m)
 {
   current_.resize(N_ * M_, 0.0f);
   next_.resize(N_ * M_, 0.0f);
index fed0447c34849326cf1ada649b74b469ea54c529..3e450979f1c1d935cda3538acc6b8efc2d4e00f5 100644 (file)
@@ -106,7 +106,7 @@ pcl::Permutohedral::init(const std::vector<float>& feature,
 
     // Elevate the feature  (y = Ep, see p.5 in [Adams etal 2010])
     int index = k * feature_dimension;
-    // sm contains the sum of 1..n of our faeture vector
+    // sm contains the sum of 1..n of our feature vector
     float sm = 0;
     for (int j = d_; j > 0; j--) {
       float cf = feature[index + j - 1] * scale_factor(j - 1);
@@ -367,7 +367,7 @@ pcl::Permutohedral::initOLD(const std::vector<float>& feature,
     // const float * f = feature + k*feature_size;
     int index = k * feature_dimension;
 
-    // sm contains the sum of 1..n of our faeture vector
+    // sm contains the sum of 1..n of our feature vector
     float sm = 0;
     for (int j = d_; j > 0; j--) {
       // float cf = f[j-1]*scale_factor[j-1];
@@ -388,7 +388,7 @@ pcl::Permutohedral::initOLD(const std::vector<float>& feature,
     }
 
     // Find the simplex we are in and store it in rank (where rank describes what
-    // position coorinate i has in the sorted order of the features values)
+    // position coordinate i has in the sorted order of the features values)
     for (int i = 0; i <= d_; i++)
       rank[i] = 0;
     for (int i = 0; i < d_; i++) {
@@ -530,7 +530,7 @@ pcl::Permutohedral::computeOLD(std::vector<float>& out,
   }
   // Alpha is a magic scaling constant (write Andrew if you really wanna understand
   // this)
-  float alpha = 1.0f / (1.0f + powf(2.0f, -float(d_)));
+  float alpha = 1.0f / (1.0f + powf(2.0f, -static_cast<float>(d_)));
 
   // Slicing
   for (int i = 0; i < out_size; i++) {
index 072337f9ce68cb61ac086a2553f739ae86827b77..1a27bf9a99fa14baf457a2a443ad3162475d198f 100644 (file)
@@ -971,7 +971,7 @@ Solver::select_working_set(int& out_i, int& out_j)
   // return i,j such that
   // i: maximizes -y_i * grad(f)_i, i in I_up(\alpha)
   // j: minimizes the decrease of obj value
-  //    (if quadratic coefficeint <= 0, replace it with tau)
+  //    (if quadratic coefficient <= 0, replace it with tau)
   //    -y_j*grad(f)_j < -y_i*grad(f)_i, j in I_low(\alpha)
 
   double Gmax = -INF;
@@ -1215,7 +1215,7 @@ Solver_NU::select_working_set(int& out_i, int& out_j)
   // return i,j such that y_i = y_j and
   // i: maximizes -y_i * grad(f)_i, i in I_up(\alpha)
   // j: minimizes the decrease of obj value
-  //    (if quadratic coefficeint <= 0, replace it with tau)
+  //    (if quadratic coefficient <= 0, replace it with tau)
   //    -y_j*grad(f)_j < -y_i*grad(f)_i, j in I_low(\alpha)
 
   double Gmaxp = -INF;
@@ -3365,8 +3365,6 @@ svm_load_model(const char* model_file_name)
       model->sv_coef[k][i] = strtod(p, nullptr);
     }
 
-    int jj = 0;
-
     while (true) {
       char* idx = strtok(nullptr, ":");
       char* val = strtok(nullptr, " \t");
@@ -3378,10 +3376,6 @@ svm_load_model(const char* model_file_name)
 
       x_space[j].value = strtod(val, nullptr);
 
-      //             printf("i=%d, j=%d, %f ,%d e %f\n",i,j,model->sv_coef[0][i],
-      //                    model->SV[i][jj].index, model->SV[i][jj].value);
-      jj++;
-
       ++j;
     }
 
index cbde3caba1583006f7397652b6749d928a5401fa..76552693a311f6f3d209a062c2364737ef5a920a 100644 (file)
@@ -56,7 +56,7 @@ pcl::SVM::readline(FILE* input)
   while (strrchr(line_, '\n') == nullptr) {
     max_line_len_ *= 2;
     line_ = static_cast<char*>(realloc(line_, max_line_len_));
-    int len = int(strlen(line_));
+    int len = static_cast<int>(strlen(line_));
 
     // if the new read part of the string is unavailable, break the while
     if (fgets(line_ + len, max_line_len_ - len, input) == nullptr)
@@ -166,7 +166,7 @@ pcl::SVM::adaptLibSVMToInput(std::vector<SVMData>& training_set, svm_problem pro
 
       if (std::isfinite(prob.x[i][j].value)) {
         seed.idx = prob.x[i][j].index;
-        seed.value = float(prob.x[i][j].value);
+        seed.value = static_cast<float>(prob.x[i][j].value);
         parent.SV.push_back(seed);
       }
 
@@ -190,7 +190,7 @@ pcl::SVM::adaptInputToLibSVM(std::vector<SVMData> training_set, svm_problem& pro
     return;
   }
 
-  prob.l = int(training_set.size()); // n of elements/points
+  prob.l = static_cast<int>(training_set.size()); // n of elements/points
   prob.y = Malloc(double, prob.l);
   prob.x = Malloc(struct svm_node*, prob.l);
 
@@ -371,7 +371,7 @@ pcl::SVM::loadProblem(const char* filename, svm_problem& prob)
       // std::cout << idx << ":" << val<< " ";
       errno = 0;
 
-      x_space_[j].index = int(strtol(idx, &endptr, 10));
+      x_space_[j].index = static_cast<int>(strtol(idx, &endptr, 10));
 
       if (endptr == idx || errno != 0 || *endptr != '\0' ||
           x_space_[j].index <= inst_max_index)
@@ -408,7 +408,8 @@ pcl::SVM::loadProblem(const char* filename, svm_problem& prob)
         return false;
       }
 
-      if (int(prob.x[i][0].value) <= 0 || int(prob.x[i][0].value) > max_index) {
+      if (static_cast<int>(prob.x[i][0].value) <= 0 ||
+          static_cast<int>(prob.x[i][0].value) > max_index) {
         PCL_ERROR("[pcl::%s] Wrong input format: sample_serial_number out of range.\n",
                   getClassName().c_str());
         return false;
@@ -552,7 +553,7 @@ pcl::SVMClassify::classificationTest()
   if (predict_probability_) {
     if (svm_check_probability_model(&model_) == 0) {
       PCL_WARN("[pcl::%s::classificationTest] Classifier model does not support "
-               "probabiliy estimates. Automatically disabled.\n",
+               "probability estimates. Automatically disabled.\n",
                getClassName().c_str());
       predict_probability_ = false;
     }
@@ -641,7 +642,7 @@ pcl::SVMClassify::classificationTest()
   else {
     pcl::console::print_info(" - Accuracy (classification) = ");
     pcl::console::print_value(
-        "%g%% (%d/%d)\n", double(correct) / total * 100, correct, total);
+        "%g%% (%d/%d)\n", static_cast<double>(correct) / total * 100, correct, total);
   }
 
   if (predict_probability_)
@@ -667,9 +668,10 @@ pcl::SVMClassify::classification()
 
   if (predict_probability_) {
     if (svm_check_probability_model(&model_) == 0) {
-      PCL_WARN("[pcl::%s::classification] Classifier model does not support probabiliy "
-               "estimates. Automatically disabled.\n",
-               getClassName().c_str());
+      PCL_WARN(
+          "[pcl::%s::classification] Classifier model does not support probability "
+          "estimates. Automatically disabled.\n",
+          getClassName().c_str());
       predict_probability_ = false;
     }
   }
@@ -680,8 +682,6 @@ pcl::SVMClassify::classification()
                getClassName().c_str());
   }
 
-  // int correct = 0;
-  int total = 0;
   int svm_type = svm_get_svm_type(&model_);
   int nr_class = svm_get_nr_class(&model_);
 
@@ -724,8 +724,6 @@ pcl::SVMClassify::classification()
       prediction_[ii].push_back(predict_label);
     }
 
-    ++total;
-
     ii++;
   }
 
@@ -748,9 +746,10 @@ pcl::SVMClassify::classification(pcl::SVMData in)
 
   if (predict_probability_) {
     if (svm_check_probability_model(&model_) == 0) {
-      PCL_WARN("[pcl::%s::classification] Classifier model does not support probabiliy "
-               "estimates. Automatically disabled.\n",
-               getClassName().c_str());
+      PCL_WARN(
+          "[pcl::%s::classification] Classifier model does not support probability "
+          "estimates. Automatically disabled.\n",
+          getClassName().c_str());
       predict_probability_ = false;
     }
   }
index 5f939f351ee52be9d7c7bdf257719c2c0d32ffb1..b91b03baf01688a3da5903880e51bf3ea1e9ab2a 100644 (file)
@@ -44,14 +44,7 @@ namespace octree {
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename LeafContainerT, typename BranchContainerT>
 Octree2BufBase<LeafContainerT, BranchContainerT>::Octree2BufBase()
-: leaf_count_(0)
-, branch_count_(1)
-, root_node_(new BranchNode())
-, depth_mask_(0)
-, buffer_selector_(0)
-, tree_dirty_flag_(false)
-, octree_depth_(0)
-, dynamic_depth_enabled_(false)
+: root_node_(new BranchNode())
 {}
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -71,7 +64,12 @@ Octree2BufBase<LeafContainerT, BranchContainerT>::setMaxVoxelIndex(
 {
   uindex_t treeDepth;
 
-  assert(max_voxel_index_arg > 0);
+  if (max_voxel_index_arg <= 0) {
+    PCL_ERROR("[pcl::octree::Octree2BufBase::setMaxVoxelIndex] Max voxel index (%lu) "
+              "must be > 0!\n",
+              max_voxel_index_arg);
+    return;
+  }
 
   // tree depth == amount of bits of maxVoxels
   treeDepth =
@@ -88,7 +86,12 @@ template <typename LeafContainerT, typename BranchContainerT>
 void
 Octree2BufBase<LeafContainerT, BranchContainerT>::setTreeDepth(uindex_t depth_arg)
 {
-  assert(depth_arg > 0);
+  if (depth_arg <= 0) {
+    PCL_ERROR(
+        "[pcl::octree::Octree2BufBase::setTreeDepth] Tree depth (%lu) must be > 0!\n",
+        depth_arg);
+    return;
+  }
 
   // set octree depth
   octree_depth_ = depth_arg;
index a8d4b7787a7bc8ec6303ab36a14a8e31598e23ff..92b0489ef1e64cc9230afc7943baa1a23af99181 100644 (file)
@@ -46,12 +46,7 @@ namespace octree {
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename LeafContainerT, typename BranchContainerT>
 OctreeBase<LeafContainerT, BranchContainerT>::OctreeBase()
-: leaf_count_(0)
-, branch_count_(1)
-, root_node_(new BranchNode())
-, depth_mask_(0)
-, octree_depth_(0)
-, dynamic_depth_enabled_(false)
+: root_node_(new BranchNode())
 {}
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -71,7 +66,12 @@ OctreeBase<LeafContainerT, BranchContainerT>::setMaxVoxelIndex(
 {
   uindex_t tree_depth;
 
-  assert(max_voxel_index_arg > 0);
+  if (max_voxel_index_arg <= 0) {
+    PCL_ERROR("[pcl::octree::OctreeBase::setMaxVoxelIndex] Max voxel index (%lu) must "
+              "be > 0!\n",
+              max_voxel_index_arg);
+    return;
+  }
 
   // tree depth == bitlength of maxVoxels
   tree_depth =
@@ -86,8 +86,18 @@ template <typename LeafContainerT, typename BranchContainerT>
 void
 OctreeBase<LeafContainerT, BranchContainerT>::setTreeDepth(uindex_t depth_arg)
 {
-  assert(depth_arg > 0);
-  assert(depth_arg <= OctreeKey::maxDepth);
+  if (depth_arg <= 0) {
+    PCL_ERROR("[pcl::octree::OctreeBase::setTreeDepth] Tree depth (%lu) must be > 0!\n",
+              depth_arg);
+    return;
+  }
+  if (depth_arg > OctreeKey::maxDepth) {
+    PCL_ERROR("[pcl::octree::OctreeBase::setTreeDepth] Tree depth (%lu) must be <= max "
+              "depth(%lu)!\n",
+              depth_arg,
+              OctreeKey::maxDepth);
+    return;
+  }
 
   // set octree depth
   octree_depth_ = depth_arg;
index 7bcd151661b27728f40bd608aa2d30bf4a97fdbb..ae37008105929462f5f51a1f31be9786842da7ed 100644 (file)
@@ -55,18 +55,16 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
 : OctreeT()
 , input_(PointCloudConstPtr())
 , indices_(IndicesConstPtr())
-, epsilon_(0)
 , resolution_(resolution)
-, min_x_(0.0f)
 , max_x_(resolution)
-, min_y_(0.0f)
 , max_y_(resolution)
-, min_z_(0.0f)
 , max_z_(resolution)
-, bounding_box_defined_(false)
-, max_objs_per_leaf_(0)
 {
-  assert(resolution > 0.0f);
+  if (resolution <= 0.0) {
+    PCL_THROW_EXCEPTION(InitFailedException,
+                        "[pcl::octree::OctreePointCloud::OctreePointCloud] Resolution "
+                            << resolution << " must be > 0!");
+  }
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -339,7 +337,12 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
   PointT max_pt;
 
   // bounding box cannot be changed once the octree contains elements
-  assert(this->leaf_count_ == 0);
+  if (this->leaf_count_ != 0) {
+    PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
+              "must be 0\n",
+              this->leaf_count_);
+    return;
+  }
 
   pcl::getMinMax3D(*input_, min_pt, max_pt);
 
@@ -372,7 +375,12 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
                       const double max_z_arg)
 {
   // bounding box cannot be changed once the octree contains elements
-  assert(this->leaf_count_ == 0);
+  if (this->leaf_count_ != 0) {
+    PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
+              "must be 0\n",
+              this->leaf_count_);
+    return;
+  }
 
   min_x_ = std::min(min_x_arg, max_x_arg);
   min_y_ = std::min(min_y_arg, max_y_arg);
@@ -400,7 +408,12 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
                       const double max_z_arg)
 {
   // bounding box cannot be changed once the octree contains elements
-  assert(this->leaf_count_ == 0);
+  if (this->leaf_count_ != 0) {
+    PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
+              "must be 0\n",
+              this->leaf_count_);
+    return;
+  }
 
   min_x_ = std::min(0.0, max_x_arg);
   min_y_ = std::min(0.0, max_y_arg);
@@ -426,7 +439,12 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
     defineBoundingBox(const double cubeLen_arg)
 {
   // bounding box cannot be changed once the octree contains elements
-  assert(this->leaf_count_ == 0);
+  if (this->leaf_count_ != 0) {
+    PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) "
+              "must be 0\n",
+              this->leaf_count_);
+    return;
+  }
 
   min_x_ = std::min(0.0, cubeLen_arg);
   min_y_ = std::min(0.0, cubeLen_arg);
@@ -475,7 +493,7 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
     adoptBoundingBoxToPoint(const PointT& point_arg)
 {
 
-  const float minValue = std::numeric_limits<float>::epsilon();
+  constexpr float minValue = std::numeric_limits<float>::epsilon();
 
   // increase octree size until point fits into bounding box
   while (true) {
@@ -499,9 +517,9 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
 
         // octree not empty - we add another tree level and thus increase its size by a
         // factor of 2*2*2
-        child_idx = static_cast<unsigned char>(((!bUpperBoundViolationX) << 2) |
-                                               ((!bUpperBoundViolationY) << 1) |
-                                               ((!bUpperBoundViolationZ)));
+        child_idx = static_cast<unsigned char>(((bLowerBoundViolationX) << 2) |
+                                               ((bLowerBoundViolationY) << 1) |
+                                               ((bLowerBoundViolationZ)));
 
         BranchNode* newRootBranch;
 
@@ -514,13 +532,13 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
 
         octreeSideLen = static_cast<double>(1 << this->octree_depth_) * resolution_;
 
-        if (!bUpperBoundViolationX)
+        if (bLowerBoundViolationX)
           min_x_ -= octreeSideLen;
 
-        if (!bUpperBoundViolationY)
+        if (bLowerBoundViolationY)
           min_y_ -= octreeSideLen;
 
-        if (!bUpperBoundViolationZ)
+        if (bLowerBoundViolationZ)
           min_z_ -= octreeSideLen;
 
         // configure tree depth of octree
@@ -679,7 +697,7 @@ void
 pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>::
     getKeyBitSize()
 {
-  const float minValue = std::numeric_limits<float>::epsilon();
+  constexpr float minValue = std::numeric_limits<float>::epsilon();
 
   // find maximum key values for x, y, z
   const auto max_key_x =
index 88577e36e2399be6089d2bd51365a2838582d0b9..54963e8f57c038412978540fba6490e453338310 100644 (file)
@@ -89,8 +89,8 @@ public:
   }
 
   /** \brief Get child pointer in current branch node
-   *  \param buffer_arg: buffer selector
-   *  \param index_arg: index of child in node
+   *  \param buffer_arg: buffer selector, must be less than 2
+   *  \param index_arg: index of child in node, must be less than 8
    *  \return pointer to child node
    */
   inline OctreeNode*
@@ -101,8 +101,8 @@ public:
   }
 
   /** \brief Set child pointer in current branch node
-   *  \param buffer_arg: buffer selector
-   *  \param index_arg: index of child in node
+   *  \param buffer_arg: buffer selector, must be less than 2
+   *  \param index_arg: index of child in node, must be less than 8
    *  \param newNode_arg: pointer to new child node
    */
   inline void
@@ -115,8 +115,8 @@ public:
   }
 
   /** \brief Check if branch is pointing to a particular child node
-   *  \param buffer_arg: buffer selector
-   *  \param index_arg: index of child in node
+   *  \param buffer_arg: buffer selector, must be less than 2
+   *  \param index_arg: index of child in node, must be less than 8
    *  \return "true" if pointer to child node exists; "false" otherwise
    */
   inline bool
@@ -258,7 +258,7 @@ public:
   using LeafNodeIterator = OctreeLeafNodeDepthFirstIterator<OctreeT>;
   using ConstLeafNodeIterator = const OctreeLeafNodeDepthFirstIterator<OctreeT>;
 
-  // The currently valide names
+  // The currently valid names
   using LeafNodeDepthFirstIterator = OctreeLeafNodeDepthFirstIterator<OctreeT>;
   using ConstLeafNodeDepthFirstIterator =
       const OctreeLeafNodeDepthFirstIterator<OctreeT>;
@@ -972,33 +972,33 @@ protected:
   //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 
   /** \brief Amount of leaf nodes   **/
-  std::size_t leaf_count_;
+  std::size_t leaf_count_{0};
 
   /** \brief Amount of branch nodes   **/
-  std::size_t branch_count_;
+  std::size_t branch_count_{1};
 
   /** \brief Pointer to root branch node of octree   **/
   BranchNode* root_node_;
 
   /** \brief Depth mask based on octree depth   **/
-  uindex_t depth_mask_;
+  uindex_t depth_mask_{0};
 
   /** \brief key range */
   OctreeKey max_key_;
 
   /** \brief Currently active octree buffer  **/
-  unsigned char buffer_selector_;
+  unsigned char buffer_selector_{0};
 
   /** \brief flags indicating if unused branches and leafs might exist in previous
    * buffer  **/
-  bool tree_dirty_flag_;
+  bool tree_dirty_flag_{false};
 
   /** \brief Octree depth */
-  uindex_t octree_depth_;
+  uindex_t octree_depth_{0};
 
   /** \brief Enable dynamic_depth
    *  \note Note that this parameter is ignored in octree2buf! */
-  bool dynamic_depth_enabled_;
+  bool dynamic_depth_enabled_{false};
 };
 } // namespace octree
 } // namespace pcl
index 7ee6ddabcbf6e2643d1f1e5d8301ea491c8cc4db..d0157eef64cba7e8c966b5c97cff02da9fc9902e 100644 (file)
@@ -75,22 +75,22 @@ protected:
   ///////////////////////////////////////////////////////////////////////
 
   /** \brief Amount of leaf nodes   **/
-  std::size_t leaf_count_;
+  std::size_t leaf_count_{0};
 
   /** \brief Amount of branch nodes   **/
-  std::size_t branch_count_;
+  std::size_t branch_count_{1};
 
   /** \brief Pointer to root branch node of octree   **/
   BranchNode* root_node_;
 
   /** \brief Depth mask based on octree depth   **/
-  uindex_t depth_mask_;
+  uindex_t depth_mask_{0};
 
   /** \brief Octree depth */
-  uindex_t octree_depth_;
+  uindex_t octree_depth_{0};
 
   /** \brief Enable dynamic_depth **/
-  bool dynamic_depth_enabled_;
+  bool dynamic_depth_enabled_{false};
 
   /** \brief key range */
   OctreeKey max_key_;
index 61384670535b29ca461573b26b8677332cbab990..cd549cb6dcb1fb8b099dcf4e4d7750afd2791258 100644 (file)
@@ -38,6 +38,7 @@
 
 #pragma once
 
+#include <pcl/console/print.h>
 #include <pcl/types.h>
 
 #include <cassert>
@@ -161,7 +162,8 @@ public:
   index_t
   getPointIndex() const override
   {
-    assert("getPointIndex: undefined point index");
+    PCL_ERROR(
+        "[pcl::octree::OctreeContainerBase::getPointIndex] Undefined point index!\n");
     return -1;
   }
 
index 9fa4330be97185ecbb1c1691827027653f4f7d40..e555039c1cd1dabdd53478e388033b87d43e5003 100644 (file)
@@ -57,9 +57,13 @@ namespace octree {
 
 // Octree iterator state pushed on stack/list
 struct IteratorState {
-  OctreeNode* node_;
-  OctreeKey key_;
-  uindex_t depth_;
+  OctreeNode* node_{nullptr};
+  OctreeKey key_{};
+  uindex_t depth_{0};
+  IteratorState() = default;
+  IteratorState(OctreeNode* node, const OctreeKey& key, uindex_t depth)
+  : node_(node), key_(key), depth_(depth)
+  {}
 };
 
 /** \brief @b Abstract octree iterator class
index 86ac2533e5a8b48c026c7735ccfef74848e843a2..bf54471009db8bf56cfaac6e6cb01f27221728cd 100644 (file)
@@ -143,7 +143,7 @@ public:
       static_cast<unsigned char>(sizeof(uindex_t) * 8);
 
   // Indices addressing a voxel at (X, Y, Z)
-
+  // NOLINTBEGIN(modernize-use-default-member-init)
   union {
     struct {
       uindex_t x;
@@ -152,6 +152,7 @@ public:
     };
     uindex_t key_[3];
   };
+  // NOLINTEND(modernize-use-default-member-init)
 };
 } // namespace octree
 } // namespace pcl
index 6775ac8111c1719aa0db61b25d5c7fef51079732..d085f0f84a41328353fedbbc38373f1e4b9c6024 100644 (file)
@@ -84,10 +84,9 @@ public:
   OctreeLeafNode() : OctreeNode() {}
 
   /** \brief Copy constructor. */
-  OctreeLeafNode(const OctreeLeafNode& source) : OctreeNode()
-  {
-    container_ = source.container_;
-  }
+  OctreeLeafNode(const OctreeLeafNode& source)
+  : OctreeNode(), container_(source.container_)
+  {}
 
   /** \brief Empty deconstructor. */
 
@@ -180,17 +179,11 @@ template <typename ContainerT>
 class OctreeBranchNode : public OctreeNode {
 public:
   /** \brief Empty constructor. */
-  OctreeBranchNode() : OctreeNode()
-  {
-    // reset pointer to child node vectors
-    child_node_array_ = {};
-  }
+  OctreeBranchNode() : OctreeNode() {}
 
-  /** \brief Empty constructor. */
+  /** \brief Copy constructor. */
   OctreeBranchNode(const OctreeBranchNode& source) : OctreeNode()
   {
-    child_node_array_ = {};
-
     for (unsigned char i = 0; i < 8; ++i)
       if (source.child_node_array_[i]) {
         child_node_array_[i] = source.child_node_array_[i]->deepCopy();
@@ -223,7 +216,7 @@ public:
   ~OctreeBranchNode() override = default;
 
   /** \brief Access operator.
-   *  \param child_idx_arg: index to child node
+   *  \param child_idx_arg: index to child node, must be less than 8
    *  \return OctreeNode pointer
    * */
   inline OctreeNode*&
@@ -234,7 +227,7 @@ public:
   }
 
   /** \brief Get pointer to child
-   *  \param child_idx_arg: index to child node
+   *  \param child_idx_arg: index to child node, must be less than 8
    *  \return OctreeNode pointer
    * */
   inline OctreeNode*
@@ -245,6 +238,7 @@ public:
   }
 
   /** \brief Get pointer to child
+   *  \param index: index to child node, must be less than 8
    *  \return OctreeNode pointer
    * */
   inline void
@@ -255,7 +249,7 @@ public:
   }
 
   /** \brief Check if branch is pointing to a particular child node
-   *  \param child_idx_arg: index to child node
+   *  \param child_idx_arg: index to child node, must be less than 8
    *  \return "true" if pointer to child node exists; "false" otherwise
    * */
   inline bool
index de6c58fcdced440d2588e4f73fff833680a27204..aa9c58d5b63c28810798361900f9b4276203a8f8 100644 (file)
@@ -164,7 +164,11 @@ public:
   setResolution(double resolution_arg)
   {
     // octree needs to be empty to change its resolution
-    assert(this->leaf_count_ == 0);
+    if (this->leaf_count_ > 0) {
+      PCL_ERROR("[pcl::octree::OctreePointCloud::setResolution] Octree needs to be "
+                "empty to change its resolution(leaf count should must be 0)!\n");
+      return;
+    }
 
     resolution_ = resolution_arg;
 
@@ -416,7 +420,11 @@ public:
   inline void
   enableDynamicDepth(std::size_t maxObjsPerLeaf)
   {
-    assert(this->leaf_count_ == 0);
+    if (this->leaf_count_ > 0) {
+      PCL_ERROR("[pcl::octree::OctreePointCloud::enableDynamicDepth] Leaf count should "
+                "must be 0!\n");
+      return;
+    }
     max_objs_per_leaf_ = maxObjsPerLeaf;
 
     this->dynamic_depth_enabled_ = max_objs_per_leaf_ > 0;
@@ -575,28 +583,28 @@ protected:
   IndicesConstPtr indices_;
 
   /** \brief Epsilon precision (error bound) for nearest neighbors searches. */
-  double epsilon_;
+  double epsilon_{0.0};
 
   /** \brief Octree resolution. */
   double resolution_;
 
   // Octree bounding box coordinates
-  double min_x_;
+  double min_x_{0.0};
   double max_x_;
 
-  double min_y_;
+  double min_y_{0.0};
   double max_y_;
 
-  double min_z_;
+  double min_z_{0.0};
   double max_z_;
 
   /** \brief Flag indicating if octree has defined bounding box. */
-  bool bounding_box_defined_;
+  bool bounding_box_defined_{false};
 
   /** \brief Amount of DataT objects per leafNode before expanding branch
    *  \note zero indicates a fixed/maximum depth octree structure
    * **/
-  std::size_t max_objs_per_leaf_;
+  std::size_t max_objs_per_leaf_{0};
 };
 
 } // namespace octree
index 1a25343862f7b4bca621dcad70ccf1e14989561d..87890a90d0a064dcff1845d8174030d97b8f4805 100644 (file)
@@ -50,7 +50,7 @@ namespace octree {
 class OctreePointCloudDensityContainer : public OctreeContainerBase {
 public:
   /** \brief Class initialization. */
-  OctreePointCloudDensityContainer() : point_counter_(0) {}
+  OctreePointCloudDensityContainer() = default;
 
   /** \brief Empty class deconstructor. */
   ~OctreePointCloudDensityContainer() override = default;
@@ -99,7 +99,7 @@ public:
   }
 
 private:
-  uindex_t point_counter_;
+  uindex_t point_counter_{0};
 };
 
 /** \brief @b Octree pointcloud density class
index cff49c39cc854978f9a10dcc497ac93e85741350..c22fa85473e9ff374faa687ad35b26d2556c7836 100644 (file)
@@ -403,7 +403,7 @@ protected:
    * \param[in] key octree key addressing a leaf node.
    * \param[in] tree_depth current depth/level in the octree
    * \param[in] squared_search_radius squared search radius distance
-   * \param[out] point_candidates priority queue of nearest neigbor point candidates
+   * \param[out] point_candidates priority queue of nearest neighbor point candidates
    * \return squared search radius based on current point candidate set found
    */
   double
@@ -534,7 +534,7 @@ protected:
                        unsigned char& a) const
   {
     // Account for division by zero when direction vector is 0.0
-    const float epsilon = 1e-10f;
+    constexpr float epsilon = 1e-10f;
     if (direction.x() == 0.0)
       direction.x() = epsilon;
     if (direction.y() == 0.0)
index c24b090b940d411e4b39d673ee82962ff86483cc..9bdef7920fdb3b501c8ce230c7c0f2bafd164323 100644 (file)
@@ -38,7 +38,7 @@ public:
   using CacheIterator = typename Cache::iterator;
 
   LRUCache (std::size_t c) :
-      capacity_ (c), size_ (0)
+      capacity_ (c)
   {
     assert(capacity_ != 0);
   }
@@ -169,7 +169,7 @@ public:
   std::size_t capacity_;
 
   // Current cache size in kilobytes
-  std::size_t size_;
+  std::size_t size_{0};
 
   // LRU key index LRU[0] ... MRU[N]
   KeyIndex key_index_;
index e4bad953b677a7f85d70ff3d6b02f6bb9d01008d..f3a8e6f3f0b197ac6338e3773e1efd0079fec36e 100644 (file)
@@ -93,7 +93,7 @@ namespace pcl
       root_node_->m_tree_ = this;
 
       // Set the path to the outofcore octree metadata (unique to the root folder) ending in .octree
-      boost::filesystem::path treepath = root_name.parent_path () / (boost::filesystem::basename (root_name) + TREE_EXTENSION_);
+      boost::filesystem::path treepath = root_name.parent_path () / (root_name.stem ().string () + TREE_EXTENSION_);
 
       //Load the JSON metadata
       metadata_->loadMetadataFromDisk (treepath);
@@ -169,7 +169,7 @@ namespace pcl
       root_node_->m_tree_ = this;
       
       // Set root nodes file path
-      boost::filesystem::path treepath = dir / (boost::filesystem::basename (root_name) + TREE_EXTENSION_);
+      boost::filesystem::path treepath = dir / (root_name.stem ().string () + TREE_EXTENSION_);
 
       //fill the fields of the metadata
       metadata_->setCoordinateSystem (coord_sys);
@@ -209,7 +209,7 @@ namespace pcl
     {
       std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
 
-      const bool _FORCE_BB_CHECK = true;
+      constexpr bool _FORCE_BB_CHECK = true;
       
       std::uint64_t pt_added = root_node_->addDataToLeaf (p, _FORCE_BB_CHECK);
 
@@ -569,7 +569,7 @@ namespace pcl
 
       std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
 
-      const int number_of_nodes = 1;
+      constexpr int number_of_nodes = 1;
 
       std::vector<BranchNode*> current_branch (number_of_nodes, static_cast<BranchNode*>(nullptr));
       current_branch[0] = root_node_;
@@ -699,9 +699,9 @@ namespace pcl
     template<typename ContainerT, typename PointT> bool
     OutofcoreOctreeBase<ContainerT, PointT>::checkExtension (const boost::filesystem::path& path_name)
     {
-      if (boost::filesystem::extension (path_name) != OutofcoreOctreeBaseNode<ContainerT, PointT>::node_index_extension)
+      if (path_name.extension ().string () != OutofcoreOctreeBaseNode<ContainerT, PointT>::node_index_extension)
       {
-        PCL_ERROR ( "[pcl::outofcore::OutofcoreOctreeBase] Wrong root node file extension: %s. The tree must have a root node ending in %s\n", boost::filesystem::extension (path_name).c_str (), OutofcoreOctreeBaseNode<ContainerT, PointT>::node_index_extension.c_str () );
+        PCL_ERROR ( "[pcl::outofcore::OutofcoreOctreeBase] Wrong root node file extension: %s. The tree must have a root node ending in %s\n", path_name.extension ().string ().c_str (), OutofcoreOctreeBaseNode<ContainerT, PointT>::node_index_extension.c_str () );
         return (false);
       }
 
index 1a28dd1988bb2e00ebd3ae65af88b39072ee9250..53778768ac8b8fefcb8e574102565cb6b376508e 100644 (file)
@@ -151,7 +151,7 @@ namespace pcl
 
           if (!boost::filesystem::is_directory (file))
           {
-            if (boost::filesystem::extension (file) == node_index_extension)
+            if (file.extension ().string () == node_index_extension)
             {
               b_loaded = node_metadata_->loadMetadataFromDisk (file);
               break;
@@ -576,7 +576,7 @@ namespace pcl
       }
 
       // Derive percentage from specified sample_percent and tree depth
-      const double percent = pow(sample_percent_, double((this->root_node_->m_tree_->getDepth () - depth_)));
+      const double percent = pow(sample_percent_, static_cast<double>((this->root_node_->m_tree_->getDepth () - depth_)));
       const auto samplesize = static_cast<std::uint64_t>(percent * static_cast<double>(sampleBuff.size()));
       const std::uint64_t inputsize = sampleBuff.size();
 
@@ -1937,7 +1937,7 @@ namespace pcl
     template<typename ContainerT, typename PointT> void
     OutofcoreOctreeBaseNode<ContainerT, PointT>::convertToXYZRecursive ()
     {
-      std::string fname = boost::filesystem::basename (node_metadata_->getPCDFilename ()) + std::string (".dat.xyz");
+      std::string fname = node_metadata_->getPCDFilename ().stem ().string () + ".dat.xyz";
       boost::filesystem::path xyzfile = node_metadata_->getDirectoryPathname () / fname;
       payload_->convertToXYZ (xyzfile);
 
@@ -2050,7 +2050,7 @@ namespace pcl
           const boost::filesystem::path& file = *diter;
           if (!boost::filesystem::is_directory (file))
           {
-            if (boost::filesystem::extension (file) == OutofcoreOctreeBaseNode<ContainerT, PointT>::node_index_extension)
+            if (file.extension ().string () == OutofcoreOctreeBaseNode<ContainerT, PointT>::node_index_extension)
             {
               thisnode->thisnodeindex_ = file;
               loaded = true;
index a726b9ff6ab40cd950e4364e27d47e660724ca52..6fbc4ed07083708b630b7d12d69e8c164a854d2c 100644 (file)
@@ -106,7 +106,7 @@ namespace pcl
 
     ////////////////////////////////////////////////////////////////////////////////
 
-  }//namesapce pcl
+  }//namespace pcl
 }//namespace outofcore
 
 #endif //PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_
index 18fa677ed8cff19b4e3e69d015e3d69ce0305481..a7d15386619fcb0b07124f5249c1f17f5f0c054a 100644 (file)
@@ -47,8 +47,8 @@ namespace pcl
     template<typename PointT, typename ContainerT> 
     OutofcoreDepthFirstIterator<PointT, ContainerT>::OutofcoreDepthFirstIterator (OutofcoreOctreeBase<ContainerT, PointT>& octree_arg) 
     : OutofcoreIteratorBase<PointT, ContainerT> (octree_arg)
-    , currentChildIdx_ (0)
-    , stack_ (0)
+    , 
+     stack_ (0)
     {
       stack_.reserve (this->octree_.getTreeDepth ());
       OutofcoreIteratorBase<PointT,ContainerT>::reset ();
@@ -142,7 +142,7 @@ namespace pcl
 
     ////////////////////////////////////////////////////////////////////////////////
 
-  }//namesapce pcl
+  }//namespace pcl
 }//namespace outofcore
 
 #endif //PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_IMPL_H_
index fd447bbb0e66d25bba59551caa7990bc3906ebb4..7085d530227da76bb441a73ee13508bf60c2d720 100644 (file)
@@ -281,7 +281,7 @@ namespace pcl
           return (res);
         }
 
-        /** \brief Count loaded chilren */
+        /** \brief Count loaded children */
         virtual std::size_t
         getNumLoadedChildren ()  const
         {
@@ -346,8 +346,8 @@ namespace pcl
         virtual std::size_t
         countNumChildren () const;
 
-        /** \brief Counts the number of loaded chilren by testing the \c children_ array; 
-         *  used to update num_loaded_chilren_ internally 
+        /** \brief Counts the number of loaded children by testing the \c children_ array; 
+         *  used to update num_loaded_children_ internally 
          */
         virtual std::size_t
         countNumLoadedChildren () const;
index a0d89a709b467890c6c75fada68287ccfd54f050..0f9c0acf31004e646aef9bb72fb8768abe0d7469 100644 (file)
@@ -210,7 +210,7 @@ namespace pcl
           writebuff_.clear ();
           //remove the binary data in the directory
           PCL_DEBUG ("[Octree Disk Container] Removing the point data from disk, in file %s\n", disk_storage_filename_.c_str ());
-          boost::filesystem::remove (boost::filesystem::path (disk_storage_filename_.c_str ()));
+          boost::filesystem::remove (static_cast<boost::filesystem::path> (disk_storage_filename_.c_str ()));
           //reset the size-of-file counter
           filelen_ = 0;
         }
index 5d5210cd3c59f3ebe0f5c58a9ede7e027f5c696d..fec59893f23d56fd27cb07c1407d95b75bf91913 100644 (file)
@@ -80,7 +80,7 @@ namespace pcl
         skipChildVoxels ();
       
       protected:
-        unsigned char currentChildIdx_;
+        unsigned char currentChildIdx_{0};
         std::vector<std::pair<OctreeDiskNode*, unsigned char> > stack_;
     };
   }
index 2627436e7e42216d7de80be0caba13f665f51b25..09a85876e83c06f475b07d21540eb30eb810d15b 100644 (file)
@@ -176,7 +176,7 @@ namespace pcl
         /** \brief Metadata (JSON) file pathname (oct_idx extension JSON file) */
         boost::filesystem::path metadata_filename_;
         /** \brief Outofcore library version identifier */
-        int outofcore_version_;
+        int outofcore_version_{0};
 
         /** \brief Computes the midpoint; used when bounding box is changed */
         inline void 
index e2d57b13829d9ba31e7ea4e7ea7e9a524bfd4c96..cf2d84c837b444b36a80bc79768b4b4103807d82 100644 (file)
@@ -97,6 +97,10 @@ public:
   Eigen::Matrix4d
   getViewProjectionMatrix ()
   {
+    // Disable check for braced-initialization,
+    // since the compiler complains that the constructor selected
+    // with {projection_matrix_ * model_view_matrix_} is explicit
+    // NOLINTNEXTLINE(modernize-return-braced-init-list)
     return Eigen::Matrix4d (projection_matrix_ * model_view_matrix_);
   }
 
index fde2b1773fc39eb22fdc5e913be3826eea7c6f3a..69d8edf606febeb1accff76d8b63ade0751b0b2b 100644 (file)
@@ -265,15 +265,15 @@ class OutofcoreCloud : public Object
     // -----------------------------------------------------------------------------
     OctreeDiskPtr octree_;
 
-    std::uint64_t display_depth_;
-    std::uint64_t points_loaded_;
-    std::uint64_t data_loaded_;
+    std::uint64_t display_depth_{1};
+    std::uint64_t points_loaded_{0};
+    std::uint64_t data_loaded_{0};
 
     Eigen::Vector3d bbox_min_, bbox_max_;
 
-    Camera *render_camera_;
+    Camera *render_camera_{nullptr};
 
-    int lod_pixel_threshold_;
+    int lod_pixel_threshold_{10000};
 
     vtkSmartPointer<vtkActor> voxel_actor_;
 
index 54b9c6949a3ecf6067dab07cc952a84435f370c4..cb2dcc770ff632e712884409859fe0ad2cba2b2a 100644 (file)
@@ -53,10 +53,7 @@ namespace pcl
   namespace outofcore
   {
     
-    OutofcoreOctreeNodeMetadata::OutofcoreOctreeNodeMetadata () 
-      : outofcore_version_ ()
-    {
-    }
+    OutofcoreOctreeNodeMetadata::OutofcoreOctreeNodeMetadata () = default;
 
     ////////////////////////////////////////////////////////////////////////////////
 
index cf051c38bbfbca5158a3c9e06dd26c2870169692..cee7fdaf1a402a09353140f71036f80a4f9b929f 100644 (file)
 
 // Operators
 // -----------------------------------------------------------------------------
-Camera::Camera (std::string name) :
-    Object (name), display_ (false)
+Camera::Camera (std::string name)
+  : Object (name)
+  , camera_ (vtkSmartPointer<vtkCamera>::New ())
+  , display_ (false)
 {
-  camera_ = vtkSmartPointer<vtkCamera>::New ();
   camera_->SetClippingRange(0.0001, 100000);
 
   camera_actor_ = vtkSmartPointer<vtkCameraActor>::New ();
@@ -43,10 +44,11 @@ Camera::Camera (std::string name) :
   hull_actor_->GetProperty ()->SetOpacity (0.25);
 }
 
-Camera::Camera (std::string name, vtkSmartPointer<vtkCamera> camera) :
-    Object (name), display_ (false)
+Camera::Camera (std::string name, vtkSmartPointer<vtkCamera> camera)
+  : Object (name)
+  , camera_ (camera)
+  , display_ (false)
 {
-  camera_ = camera;
   camera_->SetClippingRange(0.0001, 100000);
 
   camera_actor_ = vtkSmartPointer<vtkCameraActor>::New ();
index 247479e38af170e64237747feb99eb8bcae4daff..d4109a20faec285ef9f73a4c257f28bfa05d7b33 100644 (file)
@@ -26,7 +26,7 @@ Grid::Grid (std::string name, int size/*=10*/, double spacing/*=1.0*/) :
 
   // Fill arrays
   for (int i = -size / 2; i <= size / 2; i++)
-    xz_array->InsertNextValue ((double)i * spacing);
+    xz_array->InsertNextValue (static_cast<double>(i) * spacing);
   y_array->InsertNextValue (0.0);
 
   grid_->SetXCoordinates (xz_array);
index 8665640b67eae9729d5460f3ef687918f1356084..8d3fcf018d21709190c37377ce4b660cd0c4bcb9 100644 (file)
@@ -1,4 +1,3 @@
-// PCL
 #include <pcl/point_types.h>
 
 #include <pcl/io/pcd_io.h>
@@ -105,7 +104,7 @@ OutofcoreCloud::pcdReaderThread ()
 // Operators
 // -----------------------------------------------------------------------------
 OutofcoreCloud::OutofcoreCloud (std::string name, boost::filesystem::path& tree_root) :
-    Object (name), display_depth_ (1), points_loaded_ (0), data_loaded_(0), render_camera_(nullptr), lod_pixel_threshold_(10000)
+    Object (name)
 {
 
   // Create the pcd reader thread once for all outofcore nodes
index 82c8f67fa547fc632d78834f0079d3b1e0ae10d4..0620f4242fe48e49b3e604f2c929ca284659b0dd 100644 (file)
@@ -25,8 +25,8 @@
 // -----------------------------------------------------------------------------
 Viewport::Viewport (vtkSmartPointer<vtkRenderWindow> window, double xmin/*=0.0*/, double ymin/*=0.0*/,
                     double xmax/*=1.0*/, double ymax/*=1.0*/)
+  : renderer_ (vtkSmartPointer<vtkRenderer>::New ())
 {
-  renderer_ = vtkSmartPointer<vtkRenderer>::New ();
   renderer_->SetViewport (xmin, ymin, xmax, ymax);
   renderer_->GradientBackgroundOn ();
   renderer_->SetBackground (.1, .1, .1);
index 71b51934a28704bf5bc56499c0b01052c4cb4266..885a87076974acce16dace48ef0bc02561564c6d 100644 (file)
@@ -299,7 +299,7 @@ main (int argc, char* argv[])
       const boost::filesystem::path& file = *diter;
       if (!boost::filesystem::is_directory (file))
       {
-        if (boost::filesystem::extension (file) == OctreeDiskNode::node_index_extension)
+        if (file.extension ().string () == OctreeDiskNode::node_index_extension)
         {
           tree_root = file;
         }
index 9f966cb2db7bc70b819e17c9728266c4e8543f7f..ac57843215a9096c9bb023202f5af9422ba3148c 100644 (file)
@@ -70,8 +70,8 @@ using pcl::console::print_info;
 
 using octree_disk = OutofcoreOctreeBase<>;
 
-const int OCTREE_DEPTH (0);
-const int OCTREE_RESOLUTION (1);
+constexpr int OCTREE_DEPTH (0);
+constexpr int OCTREE_RESOLUTION(1);
 
 PCLPointCloud2::Ptr
 getCloudFromFile (boost::filesystem::path pcd_path)
index 6ec57e093598184bcd112f8fc0503619f10f1302..1a5c4775c1e1759f416318bfdd32bfd33147d8ce 100644 (file)
@@ -112,7 +112,6 @@ using AlignedPointT = Eigen::aligned_allocator<PointT>;
 #include <vtkLODActor.h>
 #include <vtkMath.h>
 #include <vtkMatrix4x4.h>
-#include <vtkMutexLock.h>
 #include <vtkObjectFactory.h>
 #include <vtkPolyData.h>
 #include <vtkProperty.h>
@@ -383,7 +382,7 @@ main (int argc, char* argv[])
       const boost::filesystem::path& file = *diter;
       if (!boost::filesystem::is_directory (file))
       {
-        if (boost::filesystem::extension (file) == octree_disk_node::node_index_extension)
+        if (file.extension ().string () == octree_disk_node::node_index_extension)
         {
           tree_root = file;
         }
index 4395043129a96ba3bde7e769721351053c7e72db..13d04c3fbfc54032d1f7a4b6ba5b1d8fcb340313 100644 (file)
@@ -34,8 +34,6 @@
   #endif //PCL_MINOR_VERSION
 #endif 
 
-#cmakedefine HAVE_TBB 1
-
 #cmakedefine HAVE_OPENNI 1
 
 #cmakedefine HAVE_OPENNI2 1
@@ -54,6 +52,8 @@
 
 #cmakedefine HAVE_PNG
 
+#cmakedefine HAVE_ZLIB
+
 /* Precompile for a minimal set of point types instead of all. */
 #cmakedefine PCL_ONLY_CORE_POINT_TYPES
 
index 8ae58151cb7dea3634e386397b82872e43bf1fb9..ce0c79033a6ad279d3555f3b59efe8de41d44fcf 100644 (file)
@@ -167,7 +167,7 @@ int main (int argc, char** argv)
   PointCloudT::Ptr clicked_points_3d (new PointCloudT);
   cb_args.clicked_points_3d = clicked_points_3d;
   cb_args.viewerPtr = pcl::visualization::PCLVisualizer::Ptr(&viewer);
-  viewer.registerPointPickingCallback (pp_callback, (void*)&cb_args);
+  viewer.registerPointPickingCallback (pp_callback, reinterpret_cast<void*>(&cb_args));
   std::cout << "Shift+click on three floor points, then press 'Q'..." << std::endl;
 
   // Spin until 'Q' is pressed:
@@ -244,7 +244,7 @@ int main (int argc, char** argv)
       if (++count == 30)
       {
         double now = pcl::getTime ();
-        std::cout << "Average framerate: " << double(count)/double(now - last) << " Hz" <<  std::endl;
+        std::cout << "Average framerate: " << static_cast<double>(count)/(now - last) << " Hz" <<  std::endl;
         count = 0;
         last = now;
       }
index 3710c87cb4e77665ba52b85e000e6de4e18433ac..920c843045c087ac1087a14e8798f8a3662ec7d3 100644 (file)
@@ -148,8 +148,8 @@ pcl::people::GroundBasedPeopleDetectionApp<PointT>::setSensorPortraitOrientation
 template<typename PointT>
 void pcl::people::GroundBasedPeopleDetectionApp<PointT>::updateMinMaxPoints ()
 {
-  min_points_ = (int) (min_height_ * min_width_ / voxel_size_ / voxel_size_);
-  max_points_ = (int) (max_height_ * max_width_ / voxel_size_ / voxel_size_);
+  min_points_ = static_cast<int> (min_height_ * min_width_ / voxel_size_ / voxel_size_);
+  max_points_ = static_cast<int> (max_height_ * max_width_ / voxel_size_ / voxel_size_);
 }
 
 template <typename PointT> void
index f8586e7397029d7199e62a8a0e87c645e5016cf0..7c9866fcf2788e2198cd22151fe1a3d8cd65ee89 100644 (file)
@@ -270,9 +270,9 @@ pcl::people::HeadBasedSubclustering<PointT>::subcluster (std::vector<pcl::people
   }
 
   // Person clusters creation from clusters indices:
-  for(std::vector<pcl::PointIndices>::const_iterator it = cluster_indices_.begin(); it != cluster_indices_.end(); ++it)
+  for(const auto & cluster_index : cluster_indices_)
   {
-    pcl::people::PersonCluster<PointT> cluster(cloud_, *it, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_);  // PersonCluster creation
+    pcl::people::PersonCluster<PointT> cluster(cloud_, cluster_index, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_);  // PersonCluster creation
     clusters.push_back(cluster);
   }
 
@@ -291,7 +291,7 @@ pcl::people::HeadBasedSubclustering<PointT>::subcluster (std::vector<pcl::people
   clusters = new_clusters;
 
   std::vector<pcl::people::PersonCluster<PointT> > subclusters;
-  int cluster_min_points_sub = int(float(min_points_) * 1.5);
+  int cluster_min_points_sub = static_cast<int>(static_cast<float>(min_points_) * 1.5);
   //  int cluster_max_points_sub = max_points_;
 
   // create HeightMap2D object:
index 0591e27c7824fc213f27b7c37d2348e97ce90aa7..e8640ebd768d71856876face3f4b33010da41df6 100644 (file)
@@ -80,9 +80,9 @@ pcl::people::HeightMap2D<PointT>::compute (pcl::people::PersonCluster<PointT>& c
 
   // Create a height map with the projection of cluster points onto the ground plane:
   if (!vertical_)    // camera horizontal
-    buckets_.resize(std::size_t((cluster.getMax()(0) - cluster.getMin()(0)) / bin_size_) + 1, 0);
+    buckets_.resize(static_cast<std::size_t>((cluster.getMax()(0) - cluster.getMin()(0)) / bin_size_) + 1, 0);
   else        // camera vertical
-    buckets_.resize(std::size_t((cluster.getMax()(1) - cluster.getMin()(1)) / bin_size_) + 1, 0);
+    buckets_.resize(static_cast<std::size_t>((cluster.getMax()(1) - cluster.getMin()(1)) / bin_size_) + 1, 0);
   buckets_cloud_indices_.resize(buckets_.size(), 0);
 
   for(const auto& cluster_idx : cluster.getIndices().indices)
@@ -90,9 +90,9 @@ pcl::people::HeightMap2D<PointT>::compute (pcl::people::PersonCluster<PointT>& c
     PointT* p = &(*cloud_)[cluster_idx];
     int index;
     if (!vertical_)    // camera horizontal
-      index = int((p->x - cluster.getMin()(0)) / bin_size_);
+      index = static_cast<int>((p->x - cluster.getMin()(0)) / bin_size_);
     else        // camera vertical
-      index = int((p->y - cluster.getMin()(1)) / bin_size_);
+      index = static_cast<int>((p->y - cluster.getMin()(1)) / bin_size_);
     if (index > (static_cast<int> (buckets_.size ()) - 1))
       std::cout << "Error: out of array - " << index << " of " << buckets_.size() << std::endl;
     else
@@ -122,8 +122,8 @@ pcl::people::HeightMap2D<PointT>::searchLocalMaxima ()
   maxima_number_ = 0;
   int left = buckets_[0];         // current left element
   float offset = 0;           // used to center the maximum to the right place
-  maxima_indices_.resize(std::size_t(buckets_.size()), 0);
-  maxima_cloud_indices_.resize(std::size_t(buckets_.size()), 0);
+  maxima_indices_.resize(static_cast<std::size_t>(buckets_.size()), 0);
+  maxima_cloud_indices_.resize(static_cast<std::size_t>(buckets_.size()), 0);
 
   // Handle first element:
   if (buckets_[0] > buckets_[1])
@@ -153,7 +153,7 @@ pcl::people::HeightMap2D<PointT>::searchLocalMaxima ()
         maxima_cloud_indices_[m] = maxima_cloud_indices_[m-1];
       }
       // Insert the new element:
-      maxima_indices_[t] = i - int(offset/2 + 0.5);
+      maxima_indices_[t] = i - static_cast<int>(offset/2 + 0.5);
       maxima_cloud_indices_[t] = buckets_cloud_indices_[maxima_indices_[t]];
       left = buckets_[i+1];
       i +=2;
@@ -191,7 +191,7 @@ pcl::people::HeightMap2D<PointT>::searchLocalMaxima ()
       maxima_cloud_indices_[m] = maxima_cloud_indices_[m-1];
     }
     // Insert the new element:
-    maxima_indices_[t] = i - int(offset/2 + 0.5);
+    maxima_indices_[t] = i - static_cast<int>(offset/2 + 0.5);
     maxima_cloud_indices_[t] = buckets_cloud_indices_[maxima_indices_[t]];
 
     maxima_number_++;
index 1bc86572aa7490f4b796f135e4bb27ee4deccd04..1c23d26ba63e09ef2da3ce5698eeae81357c6efe 100644 (file)
@@ -122,8 +122,8 @@ pcl::people::PersonClassifier<PointT>::resize (PointCloudPtr& input_image,
   output_image->width = width;
 
   // Compute scale factor:
-  float scale1 = float(height) / float(input_image->height);
-  float scale2 = float(width) / float(input_image->width);
+  float scale1 = static_cast<float>(height) / static_cast<float>(input_image->height);
+  float scale2 = static_cast<float>(width) / static_cast<float>(input_image->width);
 
   Eigen::Matrix3f T_inv;
   T_inv << 1/scale1, 0, 0,
@@ -163,9 +163,9 @@ pcl::people::PersonClassifier<PointT>::resize (PointCloudPtr& input_image,
 
     w1 = (A(0) - f1);
     w2 = (A(1) - f2);
-    new_point.r = int((1 - w1) * ((1 - w2) * g1.r + w2 * g4.r) + w1 * ((1 - w2) * g3.r + w2 * g4.r));
-    new_point.g = int((1 - w1) * ((1 - w2) * g1.g + w2 * g4.g) + w1 * ((1 - w2) * g3.g + w2 * g4.g));
-    new_point.b = int((1 - w1) * ((1 - w2) * g1.b + w2 * g4.b) + w1 * ((1 - w2) * g3.b + w2 * g4.b));
+    new_point.r = static_cast<int>((1 - w1) * ((1 - w2) * g1.r + w2 * g4.r) + w1 * ((1 - w2) * g3.r + w2 * g4.r));
+    new_point.g = static_cast<int>((1 - w1) * ((1 - w2) * g1.g + w2 * g4.g) + w1 * ((1 - w2) * g3.g + w2 * g4.g));
+    new_point.b = static_cast<int>((1 - w1) * ((1 - w2) * g1.b + w2 * g4.b) + w1 * ((1 - w2) * g3.b + w2 * g4.b));
 
     // Insert the point in the output image:
     (*output_image)(j,i) = new_point;
@@ -190,9 +190,9 @@ pcl::people::PersonClassifier<PointT>::copyMakeBorder (PointCloudPtr& input_imag
   output_image->height = height;
 
   int x_start_in = std::max(0, xmin);
-  int x_end_in = std::min(int(input_image->width-1), xmin+width-1);
+  int x_end_in = std::min(static_cast<int>(input_image->width-1), xmin+width-1);
   int y_start_in = std::max(0, ymin);
-  int y_end_in = std::min(int(input_image->height-1), ymin+height-1);
+  int y_end_in = std::min(static_cast<int>(input_image->height-1), ymin+height-1);
 
   int x_start_out = std::max(0, -xmin);
   //int x_end_out = x_start_out + (x_end_in - x_start_in);
@@ -243,9 +243,9 @@ pcl::people::PersonClassifier<PointT>::evaluate (float height_person,
     {
       for (std::uint32_t col = 0; col < sample->width; col++)
       {
-        sample_float[row + sample->height * col] = ((float) ((*sample)(col, row).r))/255; //ptr[col * 3 + 2];
-        sample_float[row + sample->height * col + delta] = ((float) ((*sample)(col, row).g))/255; //ptr[col * 3 + 1];
-        sample_float[row + sample->height * col + delta * 2] = (float) (((*sample)(col, row).b))/255; //ptr[col * 3];
+        sample_float[row + sample->height * col] = (static_cast<float> ((*sample)(col, row).r))/255; //ptr[col * 3 + 2];
+        sample_float[row + sample->height * col + delta] = (static_cast<float> ((*sample)(col, row).g))/255; //ptr[col * 3 + 1];
+        sample_float[row + sample->height * col + delta * 2] = static_cast<float> (((*sample)(col, row).b))/255; //ptr[col * 3];
       }
     }
 
index 2b3880b614637317c10ece03db9f7b295c6c21ab..c29b48991c2592e2a52d0680616cd2fa041680b9 100644 (file)
@@ -105,7 +105,7 @@ pcl::people::HOG::gradMag( float *I, int h, int w, int d, float *M, float *O ) c
 
   std::copy(M2, M2 + h, M + x * h);
   // compute and store gradient orientation (O) via table lookup
-  if(O!=nullptr) for( y=0; y<h; y++ ) O[x*h+y] = acost[(int)Gx[y]];
+  if(O!=nullptr) for( y=0; y<h; y++ ) O[x*h+y] = acost[static_cast<int>(Gx[y])];
   }
   alFree(Gx); alFree(Gy); alFree(M2); 
 #else
@@ -170,7 +170,7 @@ void
 pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int n_orients, bool soft_bin, float *H ) const
 {
   const int hb=h/bin_size, wb=w/bin_size, h0=hb*bin_size, w0=wb*bin_size, nb=wb*hb;
-  const float s=(float)bin_size, sInv=1/s, sInv2=1/s/s;
+  const float s=static_cast<float>(bin_size), sInv=1/s, sInv2=1/s/s;
   float *H0, *H1, *M0, *M1; int *O0, *O1;
   O0=reinterpret_cast<int*>(alMalloc(h*sizeof(int),16)); M0=reinterpret_cast<float*>(alMalloc(h*sizeof(float),16));
   O1=reinterpret_cast<int*>(alMalloc(h*sizeof(int),16)); M1=reinterpret_cast<float*>(alMalloc(h*sizeof(float),16));
@@ -203,7 +203,7 @@ pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int
       float ms[4], xyd, yb, xd, yd; __m128 _m, _m0, _m1;
       bool hasLf, hasRt; int xb0, yb0;
       if( x==0 ) { init=(0+.5f)*sInv-0.5f; xb=init; }
-      hasLf = xb>=0; xb0 = hasLf?(int)xb:-1; hasRt = xb0 < wb-1;
+      hasLf = xb>=0; xb0 = hasLf?static_cast<int>(xb):-1; hasRt = xb0 < wb-1;
       xd=xb-xb0; xb+=sInv; yb=init;
       int y=0;
       // lambda for code conciseness
@@ -233,16 +233,38 @@ pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int
       }
       // main rows, has top and bottom bins, use SSE for minor speedup
       for( ; ; y++ ) {
-        yb0 = (int) yb; if(yb0>=hb-1) break; GHinit();
+        // We must stop at hb-3, otherwise the SSE functions access memory outside the valid regions
+        yb0 = static_cast<int>(yb); if(yb0>=(hb-3)) break; GHinit();
         _m0=pcl::sse_set(M0[y]); _m1=pcl::sse_set(M1[y]);
         if(hasLf) { _m=pcl::sse_set(0,0,ms[1],ms[0]);
         GH(H0+O0[y],_m,_m0); GH(H0+O1[y],_m,_m1); }
         if(hasRt) { _m=pcl::sse_set(0,0,ms[3],ms[2]);
         GH(H0+O0[y]+hb,_m,_m0); GH(H0+O1[y]+hb,_m,_m1); }
       }      
+      for( ; ; y++ ) { // Do the two remaining steps without SSE, just like in the #else case below
+        yb0 = static_cast<int>(yb);
+        if(yb0>=hb-1)
+          break;
+        GHinit();
+
+        if(hasLf)
+        {
+          H0[O0[y]+1]+=ms[1]*M0[y];
+          H0[O1[y]+1]+=ms[1]*M1[y];
+          H0[O0[y]]+=ms[0]*M0[y];
+          H0[O1[y]]+=ms[0]*M1[y];
+        }
+        if(hasRt)
+        {
+          H0[O0[y]+hb+1]+=ms[3]*M0[y];
+          H0[O1[y]+hb+1]+=ms[3]*M1[y];
+          H0[O0[y]+hb]+=ms[2]*M0[y];
+          H0[O1[y]+hb]+=ms[2]*M1[y];
+        }
+      }
       // final rows, no bottom bin_size
       for( ; y<h0; y++ ) {
-        yb0 = (int) yb; GHinit();
+        yb0 = static_cast<int>(yb); GHinit();
         if(hasLf) { H0[O0[y]]+=ms[0]*M0[y]; H0[O1[y]]+=ms[0]*M1[y]; }
         if(hasRt) { H0[O0[y]+hb]+=ms[2]*M0[y]; H0[O1[y]+hb]+=ms[2]*M1[y]; }
       }       
@@ -315,7 +337,7 @@ pcl::people::HOG::normalization (float *H, int h, int w, int bin_size, int n_ori
   N = reinterpret_cast<float*>(calloc(nb,sizeof(float)));
   for( o=0; o<n_orients; o++ ) for( x=0; x<nb; x++ ) N[x]+=H[x+o*nb]*H[x+o*nb];
   for( x=0; x<wb-1; x++ ) for( y=0; y<hb-1; y++ ) {
-    N1=N+x*hb+y; *N1=1/float(std::sqrt( N1[0] + N1[1] + N1[hb] + N1[hb+1] +eps )); }
+    N1=N+x*hb+y; *N1=1/(std::sqrt( N1[0] + N1[1] + N1[hb] + N1[hb+1] +eps )); }
   // perform 4 normalizations per spatial block (handling boundary regions)
   for( o=0; o<n_orients; o++ ) for( x=0; x<wb; x++ ) {
     H1=H+o*nb+x*hb; N1=N+x*hb; float *Gs[4]; Gs[0]=G+o*nb+x*hb;
@@ -403,7 +425,7 @@ pcl::people::HOG::grad1 (float *I, float *Gx, float *Gy, int h, int w, int x) co
     r = 1;
     In -= h;
   }
-  if( h<4 || h%4>0 || (std::size_t(I)&15) || (std::size_t(Gx)&15) )
+  if( h<4 || h%4>0 || (reinterpret_cast<std::size_t>(I)&15) || (reinterpret_cast<std::size_t>(Gx)&15) )
   {
     for( y = 0; y < h; y++ )
       *Gx++ = (*In++ - *Ip++) * r;
@@ -483,12 +505,12 @@ pcl::people::HOG::acosTable () const
   static float a[25000];
   static bool init = false;
   if( init ) return a+n2;
-  float ni = 2.02f/(float) n;
+  float ni = 2.02f/static_cast<float>(n);
   for(int i=0; i<n; i++ )
   {
     float t = i*ni - 1.01f;
     t = t<-1 ? -1 : (t>1 ? 1 : t);
-    t = (float) std::acos( t );
+    t = std::acos( t );
     a[i] = (t <= M_PI-1e-5f) ? t : 0;
   }
   init = true;
@@ -499,7 +521,7 @@ void
 pcl::people::HOG::gradQuantize (float *O, float *M, int *O0, int *O1, float *M0, float *M1, int n_orients, int nb, int n, float norm) const
 {
   // define useful constants
-  const float oMult = (float)n_orients/M_PI;
+  const float oMult = static_cast<float>(n_orients)/M_PI;
   const int oMax = n_orients * nb;
 
   int i = 0;
@@ -508,7 +530,7 @@ pcl::people::HOG::gradQuantize (float *O, float *M, int *O0, int *O1, float *M0,
   __m128i _o0, _o1, *_O0, *_O1; __m128 _o, _o0f, _m, *_M0, *_M1;
   const __m128 _norm = pcl::sse_set(norm);
   const __m128 _oMult = pcl::sse_set(oMult);
-  const __m128 _nbf = pcl::sse_set((float)nb);
+  const __m128 _nbf = pcl::sse_set(static_cast<float>(nb));
   const __m128i _oMax = pcl::sse_set(oMax);
   const __m128i _nb = pcl::sse_set(nb);
 
@@ -535,7 +557,7 @@ pcl::people::HOG::gradQuantize (float *O, float *M, int *O0, int *O1, float *M0,
   for( ; i < n; i++ ) {
     float o = O[i] * oMult;
     float m = M[i] * norm;
-    int o0 = (int) o;
+    int o0 = static_cast<int>(o);
     float od = o - o0;
     o0 *= nb;
     int o1 = o0 + nb;
index 43008e00e3d3f09521cf88fc4f26dff3d3473831..0cbef3f7907a41b30f89c64afb7ee997cce51f79 100644 (file)
@@ -34,7 +34,7 @@
 
 #ifndef METS_ABSTRACT_SEARCH_HH_
 #define METS_ABSTRACT_SEARCH_HH_
-
+//NOLINTBEGIN
 namespace mets {
 
   /// @defgroup common Common components
@@ -346,5 +346,5 @@ mets::best_ever_solution::accept(const mets::feasible_solution& sol)
     }
   return false;
 }
-
+//NOLINTEND
 #endif
index d2403bfc484281e2d6b57b8597e1728234b391d8..50657e39f905f37af18fe5555961d498b77762c1 100644 (file)
@@ -36,6 +36,8 @@
 #define METS_MODEL_HH_
 
 namespace mets {
+// Exempt third-party code from clang-tidy
+// NOLINTBEGIN
 
   /// @brief Type of the objective/cost function.
   ///
@@ -656,7 +658,7 @@ namespace mets {
 
     /// @brief Dtor.
     ~swap_full_neighborhood() override { 
-      for(auto it = moves_m.begin(); 
+      for(auto it = moves_m.begin();
          it != moves_m.end(); ++it)
        delete *it;
     }
@@ -681,7 +683,7 @@ namespace mets {
 
     /// @brief Dtor.
     ~invert_full_neighborhood() override { 
-      for(auto it = moves_m.begin(); 
+      for(auto it = moves_m.begin();
          it != moves_m.end(); ++it)
        delete *it;
     }
@@ -711,7 +713,7 @@ namespace mets {
                    const Tp r) const 
     { return l->operator==(*r); }
   };
-
+// NOLINTEND
 }
 
 //________________________________________________________________________
index 98ee923de6d375fb9f615cfe2556002944e47c67..9887e0c65324c5b9fad94affbba628e40ea1ebaa 100644 (file)
@@ -33,7 +33,7 @@
 
 #ifndef METS_SIMULATED_ANNEALING_HH_
 #define METS_SIMULATED_ANNEALING_HH_
-
+//NOLINTBEGIN
 namespace mets {
 
   /// @defgroup simulated_annealing Simulated Annealing
@@ -271,4 +271,5 @@ mets::simulated_annealing<move_manager_t>::search()
       cooling_schedule_m(current_temp_m, base_t::working_solution_m);
     }
 }
+//NOLINTEND
 #endif
index 1a92a0bf7e79c107a3f526375a5e25328d13d15b..dfe82d960ebdc2ad07b5cc7b306b61f86cbdfeaa 100644 (file)
@@ -497,7 +497,9 @@ mets::tabu_list_chain::is_tabu(feasible_solution& sol, /* const */ move& mov) co
 
 inline mets::simple_tabu_list::~simple_tabu_list()
 { 
-  for(move_map_type::iterator m = tabu_hash_m.begin(); 
+  // Disable lint for third-party code
+  // NOLINTNEXTLINE(modernize-loop-convert)
+  for(move_map_type::iterator m = tabu_hash_m.begin();
       m!=tabu_hash_m.end(); ++m)
     delete m->first;
 }
index 41d3ef5f35f88560b12f28c2421b67918507302a..d1936b1d97193e93affe19899832b0bd288ec5a3 100644 (file)
@@ -3,7 +3,7 @@
  *
  *  Point Cloud Library (PCL) - www.pointclouds.org
  *  Copyright (c) 2010-2012, Willow Garage, Inc.
- *  
+ *
  *  All rights reserved.
  *
  *  Redistribution and use in source and binary forms, with or without
@@ -44,7 +44,7 @@
 
 namespace pcl
 {
+
   /** \brief Class implementing a 3D correspondence grouping enforcing geometric consistency among feature correspondences
     *
     * \author Federico Tombari, Tommaso Cavallari, Aitor Aldoma
@@ -61,14 +61,10 @@ namespace pcl
       using SceneCloudConstPtr = typename pcl::CorrespondenceGrouping<PointModelT, PointSceneT>::SceneCloudConstPtr;
 
       /** \brief Constructor */
-      GeometricConsistencyGrouping () 
-        : gc_threshold_ (3)
-        , gc_size_ (1.0)
-      {}
+      GeometricConsistencyGrouping () = default;
 
-      
       /** \brief Sets the minimum cluster size
-        * \param[in] threshold the minimum cluster size 
+        * \param[in] threshold the minimum cluster size
         */
       inline void
       setGCThreshold (int threshold)
@@ -77,7 +73,7 @@ namespace pcl
       }
 
       /** \brief Gets the minimum cluster size.
-        * 
+        *
         * \return the minimum cluster size used by GC.
         */
       inline int
@@ -87,7 +83,7 @@ namespace pcl
       }
 
       /** \brief Sets the consensus set resolution. This should be in metric units.
-        * 
+        *
         * \param[in] gc_size consensus set resolution.
         */
       inline void
@@ -97,7 +93,7 @@ namespace pcl
       }
 
       /** \brief Gets the consensus set resolution.
-        * 
+        *
         * \return the consensus set resolution.
         */
       inline double
@@ -107,7 +103,7 @@ namespace pcl
       }
 
       /** \brief The main function, recognizes instances of the model into the scene set by the user.
-        * 
+        *
         * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene.
         *
         * \return true if the recognition had been successful or false if errors have occurred.
@@ -116,7 +112,7 @@ namespace pcl
       recognize (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > &transformations);
 
       /** \brief The main function, recognizes instances of the model into the scene set by the user.
-        * 
+        *
         * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene.
         * \param[out] clustered_corrs a vector containing the correspondences for each instance of the model found within the input data (the same output of clusterCorrespondences).
         *
@@ -131,19 +127,19 @@ namespace pcl
       using CorrespondenceGrouping<PointModelT, PointSceneT>::model_scene_corrs_;
 
       /** \brief Minimum cluster size. It shouldn't be less than 3, since at least 3 correspondences are needed to compute the 6DOF pose */
-      int gc_threshold_;
+      int gc_threshold_{3};
 
       /** \brief Resolution of the consensus set used to cluster correspondences together*/
-      double gc_size_;
+      double gc_size_{1.0};
 
       /** \brief Transformations found by clusterCorrespondences method. */
       std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > found_transformations_;
 
       /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene.
-        * 
+        *
         * \param[out] model_instances a vector containing the clustered correspondences for each model found on the scene.
         * \return true if the clustering had been successful or false if errors have occurred.
-        */ 
+        */
       void
       clusterCorrespondences (std::vector<Correspondences> &model_instances) override;
   };
index cd18a78b267b991405892c1640d1a7a3a36aa63c..2a736805e3ca68ef1b0ae89c05b9c451db535305 100644 (file)
@@ -118,10 +118,10 @@ namespace pcl
         Eigen::Vector3i bin_count_;
 
         /** \brief Used to access hough_space_ as if it was a matrix. */
-        int partial_bin_products_[4];
+        int partial_bin_products_[4]{};
 
         /** \brief Total number of bins in the Hough Space. */
-        int total_bins_count_;
+        int total_bins_count_{0};
 
         /** \brief The Hough Space. */
         std::vector<double> hough_space_;
@@ -166,14 +166,6 @@ namespace pcl
       Hough3DGrouping ()
         : input_rf_ ()
         , scene_rf_ ()
-        , needs_training_ (true)
-        ,hough_threshold_ (-1)
-        , hough_bin_size_ (1.0)
-        , use_interpolation_ (true)
-        , use_distance_weight_ (false)
-        , local_rf_normals_search_radius_ (0.0f)
-        , local_rf_search_radius_ (0.0f)
-        , hough_space_initialized_ (false)
       {}
 
       /** \brief Provide a pointer to the input dataset.
@@ -445,28 +437,28 @@ namespace pcl
       SceneRfCloudConstPtr scene_rf_;
 
       /** \brief If the training of the Hough space is needed; set on change of either the input cloud or the input_rf. */
-      bool needs_training_;
+      bool needs_training_{true};
 
       /** \brief The result of the training. The vector between each model point and the centroid of the model adjusted by its local reference frame.*/
       std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > model_votes_;
 
       /** \brief The minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud. */
-      double hough_threshold_;
+      double hough_threshold_{-1.0};
 
       /** \brief The size of each bin of the hough space. */
-      double hough_bin_size_;
+      double hough_bin_size_{1.0};
 
       /** \brief Use the interpolation between neighboring Hough bins when casting votes. */
-      bool use_interpolation_;
+      bool use_interpolation_{true};
 
       /** \brief Use the weighted correspondence distance when casting votes. */
-      bool use_distance_weight_;
+      bool use_distance_weight_{false};
 
       /** \brief Normals search radius for the potential Rf calculation. */
-      float local_rf_normals_search_radius_;
+      float local_rf_normals_search_radius_{0.0f};
 
       /** \brief Search radius for the potential Rf calculation. */
-      float local_rf_search_radius_;
+      float local_rf_search_radius_{0.0f};
 
       /** \brief The Hough space. */
       pcl::recognition::HoughSpace3D::Ptr hough_space_;
@@ -477,7 +469,7 @@ namespace pcl
       /** \brief Whether the Hough space already contains the correct votes for the current input parameters and so the cluster and recognize calls don't need to recompute each value.
         * Reset on the change of any parameter except the hough_threshold.
         */
-      bool hough_space_initialized_;
+      bool hough_space_initialized_{false};
 
       /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene.
         *
index bd7ae7a876fce0b2bf46831c32c0e99d163c678f..89ca02cb49cbd880905e8717c7f237506cc50047 100644 (file)
@@ -240,7 +240,7 @@ namespace pcl
     private:
 
       /** \brief Determines whether variable numbers of features are extracted or not. */
-      bool variable_feature_nr_;
+      bool variable_feature_nr_{false};
 
       /** \brief Stores a smoothed version of the input cloud. */
            pcl::PointCloud<pcl::RGB>::Ptr smoothed_input_;
@@ -249,15 +249,15 @@ namespace pcl
       FeatureSelectionMethod feature_selection_method_;
 
       /** \brief The threshold applied on the gradient magnitudes (for quantization). */
-      float gradient_magnitude_threshold_;
+      float gradient_magnitude_threshold_{10.0f};
       /** \brief The threshold applied on the gradient magnitudes for feature extraction. */
-      float gradient_magnitude_threshold_feature_extraction_;
+      float gradient_magnitude_threshold_feature_extraction_{55.0f};
 
       /** \brief The point cloud which holds the max-RGB gradients. */
       pcl::PointCloud<pcl::GradientXY> color_gradients_;
 
       /** \brief The spreading size. */
-      std::size_t spreading_size_;
+      std::size_t spreading_size_{8};
   
       /** \brief The map which holds the quantized max-RGB gradients. */
       pcl::QuantizedMap quantized_color_gradients_;
@@ -274,12 +274,8 @@ namespace pcl
 template <typename PointInT>
 pcl::ColorGradientModality<PointInT>::
 ColorGradientModality ()
-  : variable_feature_nr_ (false)
-  , smoothed_input_ (new pcl::PointCloud<pcl::RGB> ())
+  : smoothed_input_ (new pcl::PointCloud<pcl::RGB> ())
   , feature_selection_method_ (DISTANCE_MAGNITUDE_SCORE)
-  , gradient_magnitude_threshold_ (10.0f)
-  , gradient_magnitude_threshold_feature_extraction_ (55.0f)
-  , spreading_size_ (8)
 {
 }
 
@@ -294,8 +290,8 @@ pcl::ColorGradientModality<PointInT>::
 computeGaussianKernel (const std::size_t kernel_size, const float sigma, std::vector <float> & kernel_values)
 {
   // code taken from OpenCV
-  const int n = int (kernel_size);
-  const int SMALL_GAUSSIAN_SIZE = 7;
+  const int n = static_cast<int>(kernel_size);
+  constexpr int SMALL_GAUSSIAN_SIZE = 7;
   static const float small_gaussian_tab[][SMALL_GAUSSIAN_SIZE] =
   {
       {1.f},
@@ -310,7 +306,7 @@ computeGaussianKernel (const std::size_t kernel_size, const float sigma, std::ve
   //CV_Assert( ktype == CV_32F || ktype == CV_64F );
   /*Mat kernel(n, 1, ktype);*/
   kernel_values.resize (n);
-  float* cf = &(kernel_values[0]);
+  float* cf = kernel_values.data();
   //double* cd = (double*)kernel.data;
 
   double sigmaX = sigma > 0 ? sigma : ((n-1)*0.5 - 1)*0.3 + 0.8;
@@ -320,16 +316,16 @@ computeGaussianKernel (const std::size_t kernel_size, const float sigma, std::ve
   for( int i = 0; i < n; i++ )
   {
     double x = i - (n-1)*0.5;
-    double t = fixed_kernel ? double (fixed_kernel[i]) : std::exp (scale2X*x*x);
+    double t = fixed_kernel ? static_cast<double>(fixed_kernel[i]) : std::exp (scale2X*x*x);
 
-    cf[i] = float (t);
+    cf[i] = static_cast<float>(t);
     sum += cf[i];
   }
 
   sum = 1./sum;
   for ( int i = 0; i < n; i++ )
   {
-    cf[i] = float (cf[i]*sum);
+    cf[i] = static_cast<float>(cf[i]*sum);
   }
 }
 
@@ -340,7 +336,7 @@ pcl::ColorGradientModality<PointInT>::
 processInputData ()
 {
   // compute gaussian kernel values
-  const std::size_t kernel_size = 7;
+  constexpr std::size_t kernel_size = 7;
   std::vector<float> kernel_values;
   computeGaussianKernel (kernel_size, 0.0f, kernel_values);
 
@@ -971,7 +967,7 @@ quantizeColorGradients ()
 
   quantized_color_gradients_.resize (width, height);
 
-  const float angleScale = 16.0f/360.0f;
+  constexpr float angleScale = 16.0f / 360.0f;
 
   //float min_angle = std::numeric_limits<float>::max ();
   //float max_angle = -std::numeric_limits<float>::max ();
index 74ff8f55ec26d21594dc25957b78f84da7a1061a..a8853e6f57d1755d7b2fcd2721c07063b842f2f3 100644 (file)
@@ -64,7 +64,7 @@ namespace pcl
 
       /** \brief computes the transformation to the z-axis
         * \param[in] centroid
-        * \param[out] trasnformation to z-axis
+        * \param[out] transformation to z-axis
         */
       void
       computeTransformToZAxes (Eigen::Vector3f & centroid, Eigen::Affine3f & transform)
index 92353f22f1c5756378ee0d89454fbb4fe1463a12..1eb6fc29d61a99ee4e8bc84c19ce0a3ddd366e22 100644 (file)
@@ -4,7 +4,7 @@
  *  Point Cloud Library (PCL) - www.pointclouds.org
  *  Copyright (c) 2010-2011, Willow Garage, Inc.
  *
- *  All rights reserved. 
+ *  All rights reserved.
  *
  *  Redistribution and use in source and binary forms, with or without
  *  modification, are permitted provided that the following conditions
 namespace pcl
 {
 
-  /** \brief Represents a distance map obtained from a distance transformation. 
+  /** \brief Represents a distance map obtained from a distance transformation.
     * \author Stefan Holzer
     */
   class DistanceMap
   {
     public:
       /** \brief Constructor. */
-      DistanceMap () : data_ (0), width_ (0), height_ (0) {}
+      DistanceMap () : data_ (0) {}
       /** \brief Destructor. */
       virtual ~DistanceMap () = default;
 
       /** \brief Returns the width of the map. */
-      inline std::size_t 
+      inline std::size_t
       getWidth () const
       {
-        return (width_); 
+        return (width_);
       }
 
       /** \brief Returns the height of the map. */
-      inline std::size_t 
+      inline std::size_t
       getHeight () const
-      { 
-        return (height_); 
+      {
+        return (height_);
       }
-    
+
       /** \brief Returns a pointer to the beginning of map. */
-      inline float * 
-      getData () 
-      { 
-        return (&data_[0]); 
+      inline float *
+      getData ()
+      {
+        return (data_.data());
       }
 
       /** \brief Resizes the map to the specified size.
         * \param[in] width the new width of the map.
         * \param[in] height the new height of the map.
         */
-      void 
+      void
       resize (const std::size_t width, const std::size_t height)
       {
         data_.resize (width*height);
@@ -88,7 +88,7 @@ namespace pcl
         * \param[in] col_index the column index of the element to access.
         * \param[in] row_index the row index of the element to access.
         */
-      inline float & 
+      inline float &
       operator() (const std::size_t col_index, const std::size_t row_index)
       {
         return (data_[row_index*width_ + col_index]);
@@ -98,7 +98,7 @@ namespace pcl
         * \param[in] col_index the column index of the element to access.
         * \param[in] row_index the row index of the element to access.
         */
-      inline const float & 
+      inline const float &
       operator() (const std::size_t col_index, const std::size_t row_index) const
       {
         return (data_[row_index*width_ + col_index]);
@@ -108,9 +108,9 @@ namespace pcl
       /** \brief The storage for the distance map data. */
       std::vector<float> data_;
       /** \brief The width of the map. */
-      std::size_t width_;
+      std::size_t width_{0};
       /** \brief The height of the map. */
-      std::size_t height_;
+      std::size_t height_{0};
   };
 
 }
index 2fb4d80408be8e550cc34adb83754e36644a54b6..f8dd642da076e22a55d6e100acb70d2538dd75a6 100644 (file)
@@ -16,70 +16,50 @@ namespace pcl
   class PCL_EXPORTS RFFaceDetectorTrainer
   {
     private:
-      int w_size_;
-      int max_patch_size_;
-      int stride_sw_;
-      int ntrees_;
-      std::string forest_filename_;
-      int nfeatures_;
-      float thres_face_;
-      int num_images_;
-      float trans_max_variance_;
+      int w_size_ {80};
+      int max_patch_size_ {40};
+      int stride_sw_ {4};
+      int ntrees_ {10};
+      std::string forest_filename_ {"forest.txt"};
+      int nfeatures_ {10000};
+      float thres_face_ {1.f};
+      int num_images_ {1000};
+      float trans_max_variance_ {1600.f};
       std::size_t min_votes_size_;
-      int used_for_pose_;
-      bool use_normals_;
+      int used_for_pose_ {std::numeric_limits<int>::max ()};
+      bool use_normals_ {false};
       std::string directory_;
-      float HEAD_ST_DIAMETER_;
-      float larger_radius_ratio_;
-      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > head_center_votes_;
-      std::vector<std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > > head_center_votes_clustered_;
-      std::vector<std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > > head_center_original_votes_clustered_;
-      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > angle_votes_;
-      std::vector<float> uncertainties_;
-      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > head_clusters_centers_;
-      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > head_clusters_rotation_;
-
-      pcl::PointCloud<pcl::PointXYZ>::Ptr input_;
-      pcl::PointCloud<pcl::PointXYZI>::Ptr face_heat_map_;
+      float HEAD_ST_DIAMETER_ {0.2364f};
+      float larger_radius_ratio_ {1.5f};
+      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > head_center_votes_{};
+      std::vector<std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > > head_center_votes_clustered_{};
+      std::vector<std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > > head_center_original_votes_clustered_{};
+      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > angle_votes_{};
+      std::vector<float> uncertainties_{};
+      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > head_clusters_centers_{};
+      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > head_clusters_rotation_{};
+
+      pcl::PointCloud<pcl::PointXYZ>::Ptr input_{};
+      pcl::PointCloud<pcl::PointXYZI>::Ptr face_heat_map_{};
 
       using NodeType = face_detection::RFTreeNode<face_detection::FeatureType>;
-      pcl::DecisionForest<NodeType> forest_;
+      pcl::DecisionForest<NodeType> forest_{};
 
-      std::string model_path_;
-      bool pose_refinement_;
-      int icp_iterations_;
+      std::string model_path_ {"face_mesh.ply"};
+      bool pose_refinement_ {false};
+      int icp_iterations_{};
 
-      pcl::PointCloud<pcl::PointXYZ>::Ptr model_original_;
-      float res_;
+      pcl::PointCloud<pcl::PointXYZ>::Ptr model_original_{};
+      float res_ {0.005f};
 
     public:
 
-      RFFaceDetectorTrainer()
-      {
-        w_size_ = 80;
-        max_patch_size_ = 40;
-        stride_sw_ = 4;
-        ntrees_ = 10;
-        forest_filename_ = std::string ("forest.txt");
-        nfeatures_ = 10000;
-        thres_face_ = 1.f;
-        num_images_ = 1000;
-        trans_max_variance_ = 1600.f;
-        used_for_pose_ = std::numeric_limits<int>::max ();
-        use_normals_ = false;
-        directory_ = std::string ("");
-        HEAD_ST_DIAMETER_ = 0.2364f;
-        larger_radius_ratio_ = 1.5f;
-        face_heat_map_.reset ();
-        model_path_ = std::string ("face_mesh.ply");
-        pose_refinement_ = false;
-        res_ = 0.005f;
-      }
+      RFFaceDetectorTrainer() = default;
 
       virtual ~RFFaceDetectorTrainer() = default;
 
       /*
-       * Common parameters
+       * Set name of the file in which RFFaceDetectorTrainer will store the forest.
        */
       void setForestFilename(std::string & ff)
       {
@@ -156,6 +136,9 @@ namespace pcl
         used_for_pose_ = n;
       }
 
+      /*
+       * This forest is used to detect faces.
+       */
       void setForest(pcl::DecisionForest<NodeType> & forest)
       {
         forest_ = forest;
index 4fc967e484a33e2fd5c4bb1a4df2b0ab32fb7fa1..fb4acf6f48fcd63a991c57c3b4b5b172ae8e3a7c 100644 (file)
@@ -368,7 +368,6 @@ namespace pcl
             std::vector < std::vector<ExampleIndex> > positive_examples;
             positive_examples.resize (num_of_branches + 1);
 
-            std::size_t pos = 0;
             for (std::size_t example_index = 0; example_index < num_of_examples; ++example_index)
             {
               unsigned char branch_index;
@@ -383,11 +382,10 @@ namespace pcl
 
                 positive_examples[branch_index].push_back (examples[example_index]);
                 positive_examples[num_of_branches].push_back (examples[example_index]);
-                pos++;
               }
             }
 
-            //compute covariance from offsets and angles for all branchs
+            //compute covariance from offsets and angles for all branches
             std::vector < Eigen::Matrix3d > offset_covariances;
             std::vector < Eigen::Matrix3d > angle_covariances;
 
index bac7e9f9db33b4567af9d3241d40b768dfba2c71..bdfde3cd8364cbcc7d719cd47b1dcc0f4a7bd613 100644 (file)
@@ -366,7 +366,7 @@ pcl::Hough3DGrouping<PointModelT, PointSceneT, PointModelRfT, PointSceneRfT>::re
   //}
 
   this->deinitCompute ();
-  return (transformations.size ());
+  return (!transformations.empty());
 }
 
 
index 51cff240b59d4ba0d9b84284a08a61ac0c2e58b3..4783f7018d5e84dda21670035b866e6423c8e94d 100644 (file)
@@ -410,9 +410,9 @@ void pcl::GlobalHypothesesVerification<ModelT, SceneT>::SAOptimize(std::vector<i
   }
 
   int occupied_multiple = 0;
-  for(std::size_t i=0; i < complete_cloud_occupancy_by_RM_.size(); i++) {
-    if(complete_cloud_occupancy_by_RM_[i] > 1) {
-      occupied_multiple+=complete_cloud_occupancy_by_RM_[i];
+  for(const auto& i : complete_cloud_occupancy_by_RM_) {
+    if(i > 1) {
+      occupied_multiple+=i;
     }
   }
 
index 3efbae002cec79d903f836cca337a519a356a89a..62a50891c34f3f2f3b16d8f88232be57f9fd8395 100644 (file)
@@ -141,12 +141,12 @@ template<typename ModelT, typename SceneT>
       typename boost::graph_traits<Graph>::adjacency_iterator ai;
       typename boost::graph_traits<Graph>::adjacency_iterator ai_end;
 
-      auto current = std::static_pointer_cast<RecognitionModel> (graph_id_model_map_[int (v)]);
+      auto current = std::static_pointer_cast<RecognitionModel> (graph_id_model_map_[static_cast<int>(v)]);
 
       bool a_better_one = false;
       for (boost::tie (ai, ai_end) = boost::adjacent_vertices (v, conflict_graph_); (ai != ai_end) && !a_better_one; ++ai)
       {
-        auto neighbour = std::static_pointer_cast<RecognitionModel> (graph_id_model_map_[int (*ai)]);
+        auto neighbour = std::static_pointer_cast<RecognitionModel> (graph_id_model_map_[static_cast<int>(*ai)]);
         if ((neighbour->explained_.size () >= current->explained_.size ()) && mask_[neighbour->id_])
         {
           a_better_one = true;
@@ -169,7 +169,7 @@ template<typename ModelT, typename SceneT>
     for (std::size_t i = 0; i < (recognition_models_.size ()); i++)
     {
       const typename Graph::vertex_descriptor v = boost::add_vertex (recognition_models_[i], conflict_graph_);
-      graph_id_model_map_[int (v)] = std::static_pointer_cast<RecognitionModel> (recognition_models_[i]);
+      graph_id_model_map_[static_cast<int>(v)] = std::static_pointer_cast<RecognitionModel> (recognition_models_[i]);
     }
 
     // iterate over the remaining models and check for each one if there is a conflict with another one
index a0e8b490938ac4eaa00f552262396bf6f465ff26..c20314a8a966799723512e32d97dc4417701b2b7 100644 (file)
@@ -164,7 +164,7 @@ pcl::occlusion_reasoning::ZBuffering<ModelT, SceneT>::computeDepthMap (typename
   {
     //Dilate and smooth the depth map
     int ws = wsize;
-    int ws2 = int (std::floor (static_cast<float> (ws) / 2.f));
+    int ws2 = static_cast<int>(std::floor (static_cast<float> (ws) / 2.f));
     float * depth_smooth = new float[cx_ * cy_];
     for (int i = 0; i < (cx_ * cy_); i++)
       depth_smooth[i] = std::numeric_limits<float>::quiet_NaN ();
index c78f4f130ce54afe8f67cc2dfff575ec21182d3e..3830bdbe9b110fece484350712d40e14620cb75a 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-pcl::features::ISMVoteList<PointT>::ISMVoteList () :
-  votes_ (new pcl::PointCloud<pcl::InterestPoint> ()),
-  tree_is_valid_ (false),
-  votes_origins_ (new pcl::PointCloud<PointT> ()),
-  votes_class_ (0),
-  k_ind_ (0),
-  k_sqr_dist_ (0)
-{
-}
+pcl::features::ISMVoteList<PointT>::ISMVoteList() = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
@@ -140,7 +132,7 @@ pcl::features::ISMVoteList<PointT>::findStrongestPeaks (
 
   // heuristic: start from NUM_INIT_PTS different locations selected uniformly
   // on the votes. Intuitively, it is likely to get a good location in dense regions.
-  const int NUM_INIT_PTS = 100;
+  constexpr int NUM_INIT_PTS = 100;
   double SIGMA_DIST = in_sigma;// rule of thumb: 10% of the object radius
   const double FINAL_EPS = SIGMA_DIST / 100;// another heuristic
 
@@ -192,8 +184,8 @@ pcl::features::ISMVoteList<PointT>::findStrongestPeaks (
         best_density = peak_densities[i];
         strongest_peak = peaks[i];
         best_peak_ind = i;
+        ++peak_counter;
       }
-      ++peak_counter;
     }
 
     if( peak_counter == 0 )
@@ -297,18 +289,7 @@ pcl::features::ISMVoteList<PointT>::getNumberOfVotes ()
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-pcl::features::ISMModel::ISMModel () :
-  statistical_weights_ (0),
-  learned_weights_ (0),
-  classes_ (0),
-  sigmas_ (0),
-  clusters_ (0),
-  number_of_classes_ (0),
-  number_of_visual_words_ (0),
-  number_of_clusters_ (0),
-  descriptors_dimension_ (0)
-{
-}
+pcl::features::ISMModel::ISMModel () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 pcl::features::ISMModel::ISMModel (ISMModel const & copy)
@@ -546,17 +527,7 @@ pcl::features::ISMModel::operator = (const pcl::features::ISMModel& other)
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <int FeatureSize, typename PointT, typename NormalT>
-pcl::ism::ImplicitShapeModelEstimation<FeatureSize, PointT, NormalT>::ImplicitShapeModelEstimation () :
-  training_clouds_ (0),
-  training_classes_ (0),
-  training_normals_ (0),
-  training_sigmas_ (0),
-  sampling_size_ (0.1f),
-  feature_estimator_ (),
-  number_of_clusters_ (184),
-  n_vot_ON_ (true)
-{
-}
+pcl::ism::ImplicitShapeModelEstimation<FeatureSize, PointT, NormalT>::ImplicitShapeModelEstimation () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <int FeatureSize, typename PointT, typename NormalT>
@@ -1128,7 +1099,7 @@ pcl::ism::ImplicitShapeModelEstimation<FeatureSize, PointT, NormalT>::simplifyCl
   grid.filter (temp_cloud);
 
   //extract indices of points from source cloud which are closest to grid points
-  const float max_value = std::numeric_limits<float>::max ();
+  constexpr float max_value = std::numeric_limits<float>::max ();
 
   const auto num_source_points = in_point_cloud->size ();
   const auto num_sample_points = temp_cloud.size ();
@@ -1262,7 +1233,7 @@ pcl::ism::ImplicitShapeModelEstimation<FeatureSize, PointT, NormalT>::computeKMe
   int flags,
   Eigen::MatrixXf& cluster_centers)
 {
-  const int spp_trials = 3;
+  constexpr int spp_trials = 3;
   std::size_t number_of_points = points_to_cluster.rows () > 1 ? points_to_cluster.rows () : points_to_cluster.cols ();
   int feature_dimension = points_to_cluster.rows () > 1 ? FeatureSize : 1;
 
@@ -1280,7 +1251,7 @@ pcl::ism::ImplicitShapeModelEstimation<FeatureSize, PointT, NormalT>::computeKMe
   Eigen::MatrixXf old_centers (number_of_clusters, feature_dimension);
   std::vector<int> counters (number_of_clusters);
   std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > boxes (feature_dimension);
-  Eigen::Vector2f* box = &boxes[0];
+  Eigen::Vector2f* box = boxes.data();
 
   double best_compactness = std::numeric_limits<double>::max ();
   double compactness = 0.0;
@@ -1428,7 +1399,7 @@ pcl::ism::ImplicitShapeModelEstimation<FeatureSize, PointT, NormalT>::generateCe
   std::size_t dimension = data.cols ();
   auto number_of_points = static_cast<unsigned int> (data.rows ());
   std::vector<int> centers_vec (number_of_clusters);
-  int* centers = &centers_vec[0];
+  int* centers = centers_vec.data();
   std::vector<double> dist (number_of_points);
   std::vector<double> tdist (number_of_points);
   std::vector<double> tdist2 (number_of_points);
index 7069437e2fc113b0a769ac197bf4cd90ed016ba2..5fdd7028f53b8ed026b987cc55f590ece99c3d45 100644 (file)
@@ -167,10 +167,8 @@ LineRGBD<PointXYZT, PointRGBT>::loadTemplates (const std::string &file_name, con
     float max_y = -std::numeric_limits<float>::max ();
     float max_z = -std::numeric_limits<float>::max ();
     std::size_t counter = 0;
-    for (std::size_t j = 0; j < template_point_cloud.size (); ++j)
+    for (const auto & p : template_point_cloud)
     {
-      const PointXYZRGBA & p = template_point_cloud[j];
-
       if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z))
         continue;
 
@@ -200,9 +198,9 @@ LineRGBD<PointXYZT, PointRGBT>::loadTemplates (const std::string &file_name, con
     bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f;
     bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f;
 
-    for (std::size_t j = 0; j < template_point_cloud.size (); ++j)
+    for (auto & j : template_point_cloud)
     {
-      PointXYZRGBA p = template_point_cloud[j];
+      PointXYZRGBA p = j;
 
       if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z))
         continue;
@@ -211,7 +209,7 @@ LineRGBD<PointXYZT, PointRGBT>::loadTemplates (const std::string &file_name, con
       p.y -= center_y;
       p.z -= center_z;
 
-      template_point_cloud[j] = p;
+      j = p;
     }
   }
 
@@ -254,10 +252,8 @@ LineRGBD<PointXYZT, PointRGBT>::createAndAddTemplate (
     float max_y = -std::numeric_limits<float>::max ();
     float max_z = -std::numeric_limits<float>::max ();
     std::size_t counter = 0;
-    for (std::size_t j = 0; j < template_point_cloud.size (); ++j)
+    for (const auto & p : template_point_cloud)
     {
-      const PointXYZRGBA & p = template_point_cloud[j];
-
       if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z))
         continue;
 
@@ -287,9 +283,9 @@ LineRGBD<PointXYZT, PointRGBT>::createAndAddTemplate (
     bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f;
     bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f;
 
-    for (std::size_t j = 0; j < template_point_cloud.size (); ++j)
+    for (auto & j : template_point_cloud)
     {
-      PointXYZRGBA p = template_point_cloud[j];
+      PointXYZRGBA p = j;
 
       if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z))
         continue;
@@ -298,7 +294,7 @@ LineRGBD<PointXYZT, PointRGBT>::createAndAddTemplate (
       p.y -= center_y;
       p.z -= center_z;
 
-      template_point_cloud[j] = p;
+      j = p;
     }
   }
 
@@ -345,10 +341,8 @@ LineRGBD<PointXYZT, PointRGBT>::addTemplate (const SparseQuantizedMultiModTempla
     float max_y = -std::numeric_limits<float>::max ();
     float max_z = -std::numeric_limits<float>::max ();
     std::size_t counter = 0;
-    for (std::size_t j = 0; j < template_point_cloud.size (); ++j)
+    for (const auto & p : template_point_cloud)
     {
-      const PointXYZRGBA & p = template_point_cloud[j];
-
       if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z))
         continue;
 
@@ -378,9 +372,9 @@ LineRGBD<PointXYZT, PointRGBT>::addTemplate (const SparseQuantizedMultiModTempla
     bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f;
     bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f;
 
-    for (std::size_t j = 0; j < template_point_cloud.size (); ++j)
+    for (auto & j : template_point_cloud)
     {
-      PointXYZRGBA p = template_point_cloud[j];
+      PointXYZRGBA p = j;
 
       if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z))
         continue;
@@ -389,7 +383,7 @@ LineRGBD<PointXYZT, PointRGBT>::addTemplate (const SparseQuantizedMultiModTempla
       p.y -= center_y;
       p.z -= center_z;
 
-      template_point_cloud[j] = p;
+      j = p;
     }
   }
 
@@ -676,7 +670,7 @@ LineRGBD<PointXYZT, PointRGBT>::refineDetectionsAlongDepth ()
       }
     }
 
-    const std::size_t nr_bins = 1000;
+    constexpr std::size_t nr_bins = 1000;
     const float step_size = (max_depth - min_depth) / static_cast<float> (nr_bins-1);
     std::vector<std::size_t> depth_bins (nr_bins, 0);
     for (std::size_t row_index = start_y; row_index < end_y; ++row_index)
@@ -904,8 +898,8 @@ LineRGBD<PointXYZT, PointRGBT>::removeOverlappingDetections ()
       average_center_z += p_center_z * weight;
       weight_sum += weight;
 
-      average_region_x += float (detections_[detection_id].region.x) * weight;
-      average_region_y += float (detections_[detection_id].region.y) * weight;
+      average_region_x += static_cast<float>(detections_[detection_id].region.x) * weight;
+      average_region_y += static_cast<float>(detections_[detection_id].region.y) * weight;
     }
 
     typename LineRGBD<PointXYZT, PointRGBT>::Detection detection;
@@ -926,8 +920,8 @@ LineRGBD<PointXYZT, PointRGBT>::removeOverlappingDetections ()
     detection.bounding_box.height = best_detection_bb_height;
     detection.bounding_box.depth  = best_detection_bb_depth;
 
-    detection.region.x = int (average_region_x * inv_weight_sum);
-    detection.region.y = int (average_region_y * inv_weight_sum);
+    detection.region.x = static_cast<int>(average_region_x * inv_weight_sum);
+    detection.region.y = static_cast<int>(average_region_y * inv_weight_sum);
     detection.region.width = detections_[best_detection_id].region.width;
     detection.region.height = detections_[best_detection_id].region.height;
 
index bd2e6436010b24694654d89a04273c6690cd7a16..9e7f2103e0f37f9c89539a681a27b6683dbadf1a 100644 (file)
@@ -180,11 +180,7 @@ SimpleOctree<NodeData, NodeDataCreator, Scalar>::Node::makeNeighbors (Node* node
 
 
 template<typename NodeData, typename NodeDataCreator, typename Scalar> inline
-SimpleOctree<NodeData, NodeDataCreator, Scalar>::SimpleOctree ()
-: tree_levels_ (0),
-  root_ (nullptr)
-{
-}
+SimpleOctree<NodeData, NodeDataCreator, Scalar>::SimpleOctree () = default;
 
 
 template<typename NodeData, typename NodeDataCreator, typename Scalar> inline
index 5d57ab7f631e92d502d14162c2cf4160b036e4ef..0347eff922af06fe47d2703af9f6be7a06eb31c9 100644 (file)
@@ -96,10 +96,10 @@ namespace pcl
         getColoredCloud (typename pcl::PointCloud<PointT>::Ptr cloud = 0);
 
         /** \brief This method finds the strongest peaks (points were density has most higher values).
-          * It is based on the non maxima supression principles.
+          * It is based on the non maxima suppression principles.
           * \param[out] out_peaks it will contain the strongest peaks
           * \param[in] in_class_id class of interest for which peaks are evaluated
-          * \param[in] in_non_maxima_radius non maxima supression radius. The shapes radius is recommended for this value.
+          * \param[in] in_non_maxima_radius non maxima suppression radius. The shapes radius is recommended for this value.
           * \param in_sigma
           */
         void
@@ -128,29 +128,29 @@ namespace pcl
       protected:
 
         /** \brief Stores all votes. */
-        pcl::PointCloud<pcl::InterestPoint>::Ptr votes_;
+        pcl::PointCloud<pcl::InterestPoint>::Ptr votes_{new pcl::PointCloud<pcl::InterestPoint>};
 
         /** \brief Signalizes if the tree is valid. */
-        bool tree_is_valid_;
+        bool tree_is_valid_{false};
 
         /** \brief Stores the origins of the votes. */
-        typename pcl::PointCloud<PointT>::Ptr votes_origins_;
+        typename pcl::PointCloud<PointT>::Ptr votes_origins_{new pcl::PointCloud<PointT>};
 
         /** \brief Stores classes for which every single vote was cast. */
-        std::vector<int> votes_class_;
+        std::vector<int> votes_class_{};
 
         /** \brief Stores the search tree. */
-        pcl::KdTreeFLANN<pcl::InterestPoint>::Ptr tree_;
+        pcl::KdTreeFLANN<pcl::InterestPoint>::Ptr tree_{nullptr};
 
         /** \brief Stores neighbours indices. */
-        pcl::Indices k_ind_;
+        pcl::Indices k_ind_{};
 
         /** \brief Stores square distances to the corresponding neighbours. */
-        std::vector<float> k_sqr_dist_;
+        std::vector<float> k_sqr_dist_{};
     };
 
     /** \brief The assignment of this structure is to store the statistical/learned weights and other information
-      * of the trained Implict Shape Model algorithm.
+      * of the trained Implicit Shape Model algorithm.
       */
     struct PCL_EXPORTS ISMModel
     {
@@ -187,16 +187,16 @@ namespace pcl
       ISMModel & operator = (const ISMModel& other);
 
       /** \brief Stores statistical weights. */
-      std::vector<std::vector<float> > statistical_weights_;
+      std::vector<std::vector<float> > statistical_weights_{};
 
       /** \brief Stores learned weights. */
-      std::vector<float> learned_weights_;
+      std::vector<float> learned_weights_{};
 
       /** \brief Stores the class label for every direction. */
-      std::vector<unsigned int> classes_;
+      std::vector<unsigned int> classes_{};
 
       /** \brief Stores the sigma value for each class. This values were used to compute the learned weights. */
-      std::vector<float> sigmas_;
+      std::vector<float> sigmas_{};
 
       /** \brief Stores the directions to objects center for each visual word. */
       Eigen::MatrixXf directions_to_center_;
@@ -205,19 +205,19 @@ namespace pcl
       Eigen::MatrixXf clusters_centers_;
 
       /** \brief This is an array of clusters. Each cluster stores the indices of the visual words that it contains. */
-      std::vector<std::vector<unsigned int> > clusters_;
+      std::vector<std::vector<unsigned int> > clusters_{};
 
       /** \brief Stores the number of classes. */
-      unsigned int number_of_classes_;
+      unsigned int number_of_classes_{0};
 
       /** \brief Stores the number of visual words. */
-      unsigned int number_of_visual_words_;
+      unsigned int number_of_visual_words_{0};
 
       /** \brief Stores the number of clusters. */
-      unsigned int number_of_clusters_;
+      unsigned int number_of_clusters_{0};
 
       /** \brief Stores descriptors dimension. */
-      unsigned int descriptors_dimension_;
+      unsigned int descriptors_dimension_{0};
 
       PCL_MAKE_ALIGNED_OPERATOR_NEW
     };
@@ -227,7 +227,7 @@ namespace pcl
   {
     /** \brief This class implements Implicit Shape Model algorithm described in
       * "Hough Transforms and 3D SURF for robust three dimensional classication"
-      * by Jan Knopp1, Mukta Prasad, Geert Willems1, Radu Timofte, and Luc Van Gool.
+      * 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.
@@ -316,15 +316,14 @@ namespace pcl
         {
           /** \brief Empty constructor with member variables initialization. */
           VisualWordStat () :
-            class_ (-1),
-            learned_weight_ (0.0f),
+            
             dir_to_center_ (0.0f, 0.0f, 0.0f) {};
 
           /** \brief Which class this vote belongs. */
-          int class_;
+          int class_{-1};
 
           /** \brief Weight of the vote. */
-          float learned_weight_;
+          float learned_weight_{0.0f};
 
           /** \brief Expected direction to center. */
           pcl::PointXYZ dir_to_center_;
@@ -583,30 +582,30 @@ namespace pcl
       protected:
 
         /** \brief Stores the clouds used for training. */
-        std::vector<typename pcl::PointCloud<PointT>::Ptr> training_clouds_;
+        std::vector<typename pcl::PointCloud<PointT>::Ptr> training_clouds_{};
 
         /** \brief Stores the class number for each cloud from training_clouds_. */
-        std::vector<unsigned int> training_classes_;
+        std::vector<unsigned int> training_classes_{};
 
         /** \brief Stores the normals for each training cloud. */
-        std::vector<typename pcl::PointCloud<NormalT>::Ptr> training_normals_;
+        std::vector<typename pcl::PointCloud<NormalT>::Ptr> training_normals_{};
 
         /** \brief This array stores the sigma values for each training class. If this array has a size equals 0, then
           * sigma values will be calculated automatically.
           */
-        std::vector<float> training_sigmas_;
+        std::vector<float> training_sigmas_{};
 
         /** \brief This value is used for the simplification. It sets the size of grid bin. */
-        float sampling_size_;
+        float sampling_size_{0.1f};
 
         /** \brief Stores the feature estimator. */
         typename Feature::Ptr feature_estimator_;
 
         /** \brief Number of clusters, is used for clustering descriptors during the training. */
-        unsigned int number_of_clusters_;
+        unsigned int number_of_clusters_{184};
 
         /** \brief If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0. */
-        bool n_vot_ON_;
+        bool n_vot_ON_{true};
 
         /** \brief This const value is used for indicating that for k-means clustering centers must
           * be generated as described in
index fb771d75bb4154b7778ce9b99763ee20aff79f59..aac1e517b3fdc7bbf734c131264a015be47bf7e3 100644 (file)
@@ -55,10 +55,7 @@ namespace pcl
   {
     public:
       /** \brief Constructor. */
-      EnergyMaps () : width_ (0), height_ (0), nr_bins_ (0)
-      {
-      }
-
+      EnergyMaps () = default;
       /** \brief Destructor. */
       virtual ~EnergyMaps () = default;
 
@@ -182,11 +179,11 @@ namespace pcl
 
     private:
       /** \brief The width of the energy maps. */
-      std::size_t width_;
+      std::size_t width_{0};
       /** \brief The height of the energy maps. */
-      std::size_t height_;
+      std::size_t height_{0};
       /** \brief The number of quantization bins (== the number of internally stored energy maps). */
-      std::size_t nr_bins_;
+      std::size_t nr_bins_{0};
       /** \brief Storage for the energy maps. */
       std::vector<unsigned char*> maps_;
   };
@@ -198,9 +195,7 @@ namespace pcl
   {
     public:
       /** \brief Constructor. */
-      LinearizedMaps () : width_ (0), height_ (0), mem_width_ (0), mem_height_ (0), step_size_ (0)
-      {
-      }
+      LinearizedMaps () = default;
       
       /** \brief Destructor. */
       virtual ~LinearizedMaps () = default;
@@ -290,15 +285,15 @@ namespace pcl
 
     private:
       /** \brief the original width of the data represented by the map. */
-      std::size_t width_;
+      std::size_t width_{0};
       /** \brief the original height of the data represented by the map. */
-      std::size_t height_;
+      std::size_t height_{0};
       /** \brief the actual width of the linearized map. */
-      std::size_t mem_width_;
+      std::size_t mem_width_{0};
       /** \brief the actual height of the linearized map. */
-      std::size_t mem_height_;
+      std::size_t mem_height_{0};
       /** \brief the step-size used for sampling the original data. */
-      std::size_t step_size_;
+      std::size_t step_size_{0};
       /** \brief a vector containing all the linearized maps. */
       std::vector<unsigned char*> maps_;
   };
@@ -309,18 +304,18 @@ namespace pcl
   struct PCL_EXPORTS LINEMODDetection
   {
     /** \brief Constructor. */
-    LINEMODDetection () : x (0), y (0), template_id (0), score (0.0f), scale (1.0f) {}
+    LINEMODDetection () = default;
 
     /** \brief x-position of the detection. */
-    int x;
+    int x{0};
     /** \brief y-position of the detection. */
-    int y;
+    int y{0};
     /** \brief ID of the detected template. */
-    int template_id;
+    int template_id{0};
     /** \brief score of the detection. */
-    float score;
+    float score{0.0f};
     /** \brief scale at which the template was detected. */
-    float scale;
+    float scale{1.0f};
   };
 
   /**
@@ -461,13 +456,13 @@ namespace pcl
 
     private:
       /** template response threshold */
-      float template_threshold_;
+      float template_threshold_{0.75f};
       /** states whether non-max-suppression on detections is enabled or not */
-      bool use_non_max_suppression_;
+      bool use_non_max_suppression_{false};
       /** states whether to return an averaged detection */
-      bool average_detections_;
+      bool average_detections_{false};
       /** template storage */
-      std::vector<SparseQuantizedMultiModTemplate> templates_;
+      std::vector<SparseQuantizedMultiModTemplate> templates_{};
   };
 
 }
index 08f7292f3e9d26bdd62b4b8def6ecc71e0fb9c55..d9f9cd5dec82eeb95fb983cd407436004bbb5f0b 100644 (file)
@@ -48,21 +48,21 @@ namespace pcl
   struct BoundingBoxXYZ
   {
     /** \brief Constructor. */
-    BoundingBoxXYZ () : x (0.0f), y (0.0f), z (0.0f), width (0.0f), height (0.0f), depth (0.0f) {}
+    BoundingBoxXYZ () = default;
 
     /** \brief X-coordinate of the upper left front point */
-    float x;
+    float x{0.0f};
     /** \brief Y-coordinate of the upper left front point */
-    float y;
+    float y{0.0f};
     /** \brief Z-coordinate of the upper left front point */
-    float z;
+    float z{0.0f};
 
     /** \brief Width of the bounding box */
-    float width;
+    float width{0.0f};
     /** \brief Height of the bounding box */
-    float height;
+    float height{0.0f};
     /** \brief Depth of the bounding box */
-    float depth;
+    float depth{0.0f};
   };
 
   /** \brief High-level class for template matching using the LINEMOD approach based on RGB and Depth data.
@@ -77,16 +77,16 @@ namespace pcl
       struct Detection
       {
         /** \brief Constructor. */
-        Detection () : template_id (0), object_id (0), detection_id (0), response (0.0f) {}
+        Detection () = default;
 
         /** \brief The ID of the template. */
-        std::size_t template_id;
+        std::size_t template_id{0};
         /** \brief The ID of the object corresponding to the template. */
-        std::size_t object_id;
+        std::size_t object_id{0};
         /** \brief The ID of this detection. This is only valid for the last call of the method detect (...). */
-        std::size_t detection_id;
+        std::size_t detection_id{0};
         /** \brief The response of this detection. Responses are between 0 and 1, where 1 is best. */
-        float response;
+        float response{0.0f};
         /** \brief The 3D bounding box of the detection. */
         BoundingBoxXYZ bounding_box;
         /** \brief The 2D template region of the detection. */
@@ -95,8 +95,7 @@ namespace pcl
 
       /** \brief Constructor */
       LineRGBD ()
-        : intersection_volume_threshold_ (1.0f)
-        , color_gradient_mod_ ()
+        : color_gradient_mod_ ()
         , surface_normal_mod_ ()
         , cloud_xyz_ ()
         , cloud_rgb_ ()
@@ -281,7 +280,7 @@ namespace pcl
       readLTMHeader (int fd, pcl::io::TARHeader &header);
 
       /** \brief Intersection volume threshold. */
-      float intersection_volume_threshold_;
+      float intersection_volume_threshold_{1.0f};
 
       /** \brief LINEMOD instance. */
       public: pcl::LINEMOD linemod_;
index 756c4ba49f7bf8dea09e951116fa95511428f349..24f75f1585766f727b18f3b200da26c671f9882d 100644 (file)
@@ -59,10 +59,10 @@ namespace pcl
       getHeight () const { return (height_); }
       
       inline unsigned char*
-      getData () { return (&data_[0]); }
+      getData () { return (data_.data()); }
 
       inline const unsigned char*
-      getData () const { return (&data_[0]); }
+      getData () const { return (data_.data()); }
 
       inline QuantizedMap
       getSubMap (std::size_t x,
index dafdef9e6d2c8234b4d31f0661211d8da18367e6..a8a2a6814156f25ae26fc675567d38d1b06fa116 100644 (file)
@@ -74,17 +74,15 @@ namespace pcl
         }
 
       public:
-        float rigid_transform_[12];
-        const ModelLibrary::Model* obj_model_;
+        float rigid_transform_[12]{};
+        const ModelLibrary::Model* obj_model_{nullptr};
     };
 
     class Hypothesis: public HypothesisBase
     {
       public:
         Hypothesis (const ModelLibrary::Model* obj_model = nullptr)
-         : HypothesisBase (obj_model),
-           match_confidence_ (-1.0f),
-           linear_id_ (-1)
+         : HypothesisBase (obj_model)
         {
         }
 
@@ -149,9 +147,9 @@ namespace pcl
         }
 
       public:
-        float match_confidence_;
+        float match_confidence_{-1.0f};
         std::set<int> explained_pixels_;
-        int linear_id_;
+        int linear_id_{-1};
     };
   } // namespace recognition
 } // namespace pcl
index 71b083fffbaee9c174a1896cc46a7c7ef00fca80..a1c8ac673e5dfe60ca80e121727df30c07012040 100644 (file)
@@ -258,7 +258,7 @@ namespace pcl
         float pair_width_;
         float voxel_size_;
         float max_coplanarity_angle_;
-        bool ignore_coplanar_opps_;
+        bool ignore_coplanar_opps_{true};
 
         std::map<std::string,Model*> models_;
         HashTable hash_table_;
index a240aaa4997df207590d351f54a10abab9dd91da..c4d3723e0bf5a544faee685c956b0086ac8b5129 100644 (file)
@@ -329,9 +329,9 @@ namespace pcl
         {
           // 'p_obj' is the probability that given that the first sample point belongs to an object,
           // the second sample point will belong to the same object
-          const double p_obj = 0.25f;
+          constexpr double p_obj = 0.25f;
           // old version: p = p_obj*relative_obj_size_*fraction_of_pairs_in_hash_table_;
-          const double p = p_obj*relative_obj_size_;
+          const double p = p_obj * relative_obj_size_;
 
           if ( 1.0 - p <= 0.0 )
             return 1;
@@ -454,15 +454,15 @@ namespace pcl
         float position_discretization_;
         float rotation_discretization_;
         float abs_zdist_thresh_;
-        float relative_obj_size_;
-        float visibility_;
-        float relative_num_of_illegal_pts_;
-        float intersection_fraction_;
+        float relative_obj_size_{0.05f};
+        float visibility_{0.2f};
+        float relative_num_of_illegal_pts_{0.02f};
+        float intersection_fraction_{0.03f};
         float max_coplanarity_angle_;
-        float scene_bounds_enlargement_factor_;
-        bool ignore_coplanar_opps_;
-        float frac_of_points_for_icp_refinement_;
-        bool do_icp_hypotheses_refinement_;
+        float scene_bounds_enlargement_factor_{0.25f};
+        bool ignore_coplanar_opps_{true};
+        float frac_of_points_for_icp_refinement_{0.3f};
+        bool do_icp_hypotheses_refinement_{true};
 
         ModelLibrary model_library_;
         ORROctree scene_octree_;
@@ -473,7 +473,7 @@ namespace pcl
 
         std::list<OrientedPointPair> sampled_oriented_point_pairs_;
         std::vector<Hypothesis> accepted_hypotheses_;
-        Recognition_Mode rec_mode_;
+        Recognition_Mode rec_mode_{ObjRecRANSAC::FULL_RECOGNITION};
     };
   } // namespace recognition
 } // namespace pcl
index 8c8fd7e354af6bfa698de4343527809da75782b3..870624a228fd0cbc5f14de65d7642632f6ca041d 100644 (file)
@@ -83,7 +83,7 @@ namespace pcl
                   id_y_ (id_y),
                   id_z_ (id_z),
                   lin_id_ (lin_id),
-                  num_points_ (0),
+                  
                   user_data_ (user_data)
                 {
                   n_[0] = n_[1] = n_[2] = p_[0] = p_[1] = p_[2] = 0.0f;
@@ -156,17 +156,13 @@ namespace pcl
                 getNeighbors () const { return (neighbors_);}
 
               protected:
-                float n_[3], p_[3];
-                int id_x_, id_y_, id_z_, lin_id_, num_points_;
+                float n_[3]{}, p_[3]{};
+                int id_x_{0}, id_y_{0}, id_z_{0}, lin_id_{0}, num_points_{0};
                 std::set<Node*> neighbors_;
-                void *user_data_;
+                void *user_data_{nullptr};
             };
 
-            Node ()
-            : data_ (nullptr),
-              parent_ (nullptr),
-              children_(nullptr)
-            {}
+            Node () = default;
 
             virtual~ Node ()
             {
@@ -264,9 +260,9 @@ namespace pcl
             }
 
           protected:
-            Node::Data *data_;
-            float center_[3], bounds_[6], radius_;
-            Node *parent_, *children_;
+            Node::Data *data_{nullptr};
+            float center_[3]{}, bounds_[6]{}, radius_{0.0f};
+            Node *parent_{nullptr}, *children_{nullptr};
         };
 
         ORROctree ();
@@ -472,9 +468,9 @@ namespace pcl
         }
 
       protected:
-        float voxel_size_, bounds_[6];
-        int tree_levels_;
-        Node* root_;
+        float voxel_size_{-1.0}, bounds_[6];
+        int tree_levels_{-1};
+        Node* root_{nullptr};
         std::vector<Node*> full_leaves_;
     };
   } // namespace recognition
index d485fc65ceaf56a41c00f115737d494209f6f155..e05addd73fea216916df6d668a11a9267355a2d6 100644 (file)
@@ -113,10 +113,8 @@ namespace pcl
         };
 
       public:
-        ORROctreeZProjection ()
-        : pixels_(nullptr),
-          sets_(nullptr)
-        {}
+        ORROctreeZProjection () = default;
+
         virtual ~ORROctreeZProjection (){ this->clear();}
 
         void
@@ -200,8 +198,8 @@ namespace pcl
       protected:
         float pixel_size_, inv_pixel_size_, bounds_[4], extent_x_, extent_y_;
         int num_pixels_x_, num_pixels_y_, num_pixels_;
-        Pixel ***pixels_;
-        Set ***sets_;
+        Pixel ***pixels_{nullptr};
+        Set ***sets_{nullptr};
         std::list<Set*> full_sets_;
         std::list<Pixel*> full_pixels_;
     };
index 3e92dd984f8013bcc831de3cc20fd3aef6cd3310..a47a30748a52c82804ed672d55dfafba86cd48cc 100644 (file)
@@ -62,7 +62,6 @@ namespace pcl
         {
           public:
             Entry ()
-            : num_transforms_ (0)
             {
               aux::set3 (axis_angle_, 0.0f);
               aux::set3 (translation_, 0.0f);
@@ -134,7 +133,7 @@ namespace pcl
 
           protected:
             float axis_angle_[3], translation_[3];
-            int num_transforms_;
+            int num_transforms_{0};
         };// class Entry
 
       public:
@@ -293,9 +292,7 @@ namespace pcl
     class RotationSpaceCreator
     {
       public:
-        RotationSpaceCreator()
-        : counter_ (0)
-        {}
+        RotationSpaceCreator() = default;
 
         virtual ~RotationSpaceCreator() = default;
 
@@ -331,7 +328,7 @@ namespace pcl
 
       protected:
         float discretization_;
-        int counter_;
+        int counter_{0};
         std::list<RotationSpace*> rotation_spaces_;
     };
 
index 5084c7dbc51c8bf58007de76ac7c24d2675ba6af..fde0ff0e76ebd9ad6e092e08c6327bf2583ac0b6 100644 (file)
@@ -198,11 +198,11 @@ namespace pcl
         insertNeighbors (Node* node);
 
       protected:
-        Scalar voxel_size_, bounds_[6];
-        int tree_levels_;
-        Node* root_;
+        Scalar voxel_size_{0.0f}, bounds_[6]{};
+        int tree_levels_{0};
+        Node* root_{nullptr};
         std::vector<Node*> full_leaves_;
-        NodeDataCreator* node_data_creator_;
+        NodeDataCreator* node_data_creator_{nullptr};
     };
   } // namespace recognition
 } // namespace pcl
index a26bca5b5dbe469179e66a5c6e0740c86e254937..ee731eba1075f9c0f5fb12d9f6162a8f48144ab1 100644 (file)
@@ -68,9 +68,7 @@ namespace pcl
         using Matrix4 = typename Eigen::Matrix<Scalar, 4, 4>;
 
       public:
-        TrimmedICP ()
-        : new_to_old_energy_ratio_ (0.99f)
-        {}
+        TrimmedICP () = default;
 
         ~TrimmedICP () override = default;
 
@@ -177,7 +175,7 @@ namespace pcl
       protected:
         PointCloudConstPtr target_points_;
         pcl::KdTreeFLANN<PointT> kdtree_;
-        float new_to_old_energy_ratio_;
+        float new_to_old_energy_ratio_{0.99f};
     };
   } // namespace recognition
 } // namespace pcl
index 78d413cdeb076985805cbc3a34a562976cdf1fd2..38260f1dd5c8d682c94a9c4e3b18127e6c0a45dc 100644 (file)
@@ -4,7 +4,7 @@
  *  Point Cloud Library (PCL) - www.pointclouds.org
  *  Copyright (c) 2010-2011, Willow Garage, Inc.
  *
- *  All rights reserved. 
+ *  All rights reserved.
  *
  *  Redistribution and use in source and binary forms, with or without
  *  modification, are permitted provided that the following conditions
@@ -81,16 +81,16 @@ namespace pcl
   struct PCL_EXPORTS RegionXY
   {
     /** \brief Constructor. */
-    RegionXY () : x (0), y (0), width (0), height (0) {}
+    RegionXY () = default;
 
     /** \brief x-position of the region. */
-    int x;
+    int x{0};
     /** \brief y-position of the region. */
-    int y;
+    int y{0};
     /** \brief width of the region. */
-    int width;
+    int width{0};
     /** \brief height of the region. */
-    int height;
+    int height{0};
 
     /** \brief Serializes the object to the specified stream.
       * \param[out] stream the stream the object will be serialized to. */
@@ -105,7 +105,7 @@ namespace pcl
 
     /** \brief Deserializes the object from the specified stream.
       * \param[in] stream the stream the object will be deserialized from. */
-    void 
+    void
     deserialize (::std::istream & stream)
     {
       read (stream, x);
index a626933ce63a22b444d9dab4fe38512aef720ce3..70364c3a52181a71ccc79b31eaf4e87123ca012c 100644 (file)
@@ -4,7 +4,7 @@
  *  Point Cloud Library (PCL) - www.pointclouds.org
  *  Copyright (c) 2010-2011, Willow Garage, Inc.
  *
- *  All rights reserved. 
+ *  All rights reserved.
  *
  *  Redistribution and use in source and binary forms, with or without
  *  modification, are permitted provided that the following conditions
 namespace pcl
 {
 
-  /** \brief Feature that defines a position and quantized value in a specific modality. 
+  /** \brief Feature that defines a position and quantized value in a specific modality.
     * \author Stefan Holzer
     */
   struct QuantizedMultiModFeature
   {
     /** \brief Constructor. */
-    QuantizedMultiModFeature () : x (0), y (0), modality_index (0), quantized_value (0) {}
+    QuantizedMultiModFeature () = default;
 
     /** \brief x-position. */
-    int x;
+    int x{0};
     /** \brief y-position. */
-    int y;
+    int y{0};
     /** \brief the index of the corresponding modality. */
-    std::size_t modality_index;
+    std::size_t modality_index{0u};
     /** \brief the quantized value attached to the feature. */
-    unsigned char quantized_value;
+    unsigned char quantized_value{0u};
 
-    /** \brief Compares whether two features are the same. 
+    /** \brief Compares whether two features are the same.
       * \param[in] base the feature to compare to.
       */
     bool
@@ -81,7 +81,7 @@ namespace pcl
 
     /** \brief Serializes the object to the specified stream.
       * \param[out] stream the stream the object will be serialized to. */
-    void 
+    void
     serialize (std::ostream & stream) const
     {
       write (stream, x);
@@ -92,7 +92,7 @@ namespace pcl
 
     /** \brief Deserializes the object from the specified stream.
       * \param[in] stream the stream the object will be deserialized from. */
-    void 
+    void
     deserialize (std::istream & stream)
     {
       read (stream, x);
@@ -103,7 +103,7 @@ namespace pcl
   };
 
   /** \brief A multi-modality template constructed from a set of quantized multi-modality features.
-    * \author Stefan Holzer 
+    * \author Stefan Holzer
     */
   struct SparseQuantizedMultiModTemplate
   {
@@ -118,7 +118,7 @@ namespace pcl
 
     /** \brief Serializes the object to the specified stream.
       * \param[out] stream the stream the object will be serialized to. */
-    void 
+    void
     serialize (std::ostream & stream) const
     {
       const int num_of_features = static_cast<int> (features.size ());
@@ -133,7 +133,7 @@ namespace pcl
 
     /** \brief Deserializes the object from the specified stream.
       * \param[in] stream the stream the object will be deserialized from. */
-    void 
+    void
     deserialize (std::istream & stream)
     {
       features.clear ();
index 4651b501c8d91f63c23a54051f39a5b696395bd0..538e88c598db2a84ea6feeff25b43d273a7ff2d1 100644 (file)
@@ -63,7 +63,7 @@ namespace pcl
   {
     public:
       /** \brief Constructor. */
-      inline LINEMOD_OrientationMap () : width_ (0), height_ (0) {}
+      inline LINEMOD_OrientationMap () = default;
       /** \brief Destructor. */
       inline ~LINEMOD_OrientationMap () = default;
 
@@ -118,9 +118,9 @@ namespace pcl
 
     private:
       /** \brief The width of the map. */
-      std::size_t width_;
+      std::size_t width_{0};
       /** \brief The height of the map. */
-      std::size_t height_;
+      std::size_t height_{0};
       /** \brief Storage for the data of the map. */
       std::vector<float> map_;
   
@@ -132,35 +132,31 @@ namespace pcl
   struct QuantizedNormalLookUpTable
   {
     /** \brief The range of the LUT in x-direction. */
-    int range_x;
+    int range_x{-1};
     /** \brief The range of the LUT in y-direction. */
-    int range_y;
+    int range_y{-1};
     /** \brief The range of the LUT in z-direction. */
-    int range_z;
+    int range_z{-1};
 
     /** \brief The offset in x-direction. */
-    int offset_x;
+    int offset_x{-1};
     /** \brief The offset in y-direction. */
-    int offset_y;
+    int offset_y{-1};
     /** \brief The offset in z-direction. */
-    int offset_z;
+    int offset_z{-1};
 
     /** \brief The size of the LUT in x-direction. */
-    int size_x;
+    int size_x{-1};
     /** \brief The size of the LUT in y-direction. */
-    int size_y;
+    int size_y{-1};
     /** \brief The size of the LUT in z-direction. */
-    int size_z;
+    int size_z{-1};
 
     /** \brief The LUT data. */
-    unsigned char * lut;
+    unsigned char * lut{nullptr};
 
     /** \brief Constructor. */
-    QuantizedNormalLookUpTable () : 
-      range_x (-1), range_y (-1), range_z (-1), 
-      offset_x (-1), offset_y (-1), offset_z (-1), 
-      size_x (-1), size_y (-1), size_z (-1), lut (nullptr) 
-    {}
+    QuantizedNormalLookUpTable () = default;
 
     /** \brief Destructor. */
     ~QuantizedNormalLookUpTable () 
@@ -192,15 +188,15 @@ namespace pcl
       delete[] lut;
       lut = new unsigned char[size_x*size_y*size_z];
 
-      const int nr_normals = 8;
+      constexpr int nr_normals = 8;
            pcl::PointCloud<PointXYZ>::VectorType ref_normals (nr_normals);
       
-      const float normal0_angle = 40.0f * 3.14f / 180.0f;
+      constexpr float normal0_angle = 40.0f * 3.14f / 180.0f;
       ref_normals[0].x = std::cos (normal0_angle);
       ref_normals[0].y = 0.0f;
       ref_normals[0].z = -sinf (normal0_angle);
 
-      const float inv_nr_normals = 1.0f / static_cast<float> (nr_normals);
+      constexpr float inv_nr_normals = 1.0f / static_cast<float>(nr_normals);
       for (int normal_index = 1; normal_index < nr_normals; ++normal_index)
       {
         const float angle = 2.0f * static_cast<float> (M_PI * normal_index * inv_nr_normals);
@@ -306,20 +302,20 @@ namespace pcl
       struct Candidate
       {
         /** \brief Constructor. */
-        Candidate () : distance (0.0f), bin_index (0), x (0), y (0) {}
+        Candidate () = default;
 
         /** \brief Normal. */
         Normal normal;
         /** \brief Distance to the next different quantized value. */
-        float distance;
+        float distance{0.0f};
 
         /** \brief Quantized value. */
-        unsigned char bin_index;
+        unsigned char bin_index{0};
     
         /** \brief x-position of the feature. */
-        std::size_t x;
+        std::size_t x{0};
         /** \brief y-position of the feature. */
-        std::size_t y; 
+        std::size_t y{0};      
 
         /** \brief Compares two candidates based on their distance to the next different quantized value. 
           * \param[in] rhs the candidate to compare with. 
@@ -463,18 +459,18 @@ namespace pcl
     private:
 
       /** \brief Determines whether variable numbers of features are extracted or not. */
-      bool variable_feature_nr_;
+      bool variable_feature_nr_{false};
 
       /** \brief The feature distance threshold. */
-      float feature_distance_threshold_;
+      float feature_distance_threshold_{2.0f};
       /** \brief Minimum distance of a feature to a border. */
-      float min_distance_to_border_;
+      float min_distance_to_border_{2.0f};
 
       /** \brief Look-up-table for quantizing surface normals. */
       QuantizedNormalLookUpTable normal_lookup_;
 
       /** \brief The spreading size. */
-      std::size_t spreading_size_;
+      std::size_t spreading_size_{8};
 
       /** \brief Point cloud holding the computed surface normals. */
       pcl::PointCloud<pcl::Normal> surface_normals_;
@@ -495,13 +491,7 @@ namespace pcl
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointInT>
 pcl::SurfaceNormalModality<PointInT>::
-SurfaceNormalModality ()
-  : variable_feature_nr_ (false)
-  , feature_distance_threshold_ (2.0f)
-  , min_distance_to_border_ (2.0f)
-  , spreading_size_ (8)
-{
-}
+SurfaceNormalModality () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointInT>
@@ -749,7 +739,7 @@ pcl::SurfaceNormalModality<PointInT>::computeAndQuantizeSurfaceNormals2 ()
   const int l_W = width;
   const int l_H = height;
 
-  const int l_r = 5; // used to be 7
+  constexpr int l_r = 5; // used to be 7
   //const int l_offset0 = -l_r - l_r * l_W;
   //const int l_offset1 =    0 - l_r * l_W;
   //const int l_offset2 = +l_r - l_r * l_W;
@@ -774,8 +764,8 @@ pcl::SurfaceNormalModality<PointInT>::computeAndQuantizeSurfaceNormals2 ()
   //const int l_offsetx = GRANULARITY / 2;
   //const int l_offsety = GRANULARITY / 2;
 
-  const int difference_threshold = 50;
-  const int distance_threshold = 2000;
+  constexpr int difference_threshold = 50;
+  constexpr int distance_threshold = 2000;
 
   //const double scale = 1000.0;
   //const double difference_threshold = 0.05 * scale;
@@ -1027,7 +1017,7 @@ pcl::SurfaceNormalModality<PointInT>::extractFeatures (const MaskMap & mask,
 
   float weights[8] = {0,0,0,0,0,0,0,0};
 
-  const std::size_t off = 4;
+  constexpr std::size_t off = 4;
   for (std::size_t row_index = off; row_index < height-off; ++row_index)
   {
     for (std::size_t col_index = off; col_index < width-off; ++col_index)
@@ -1297,7 +1287,7 @@ pcl::SurfaceNormalModality<PointInT>::extractAllFeatures (
 
   float weights[8] = {0,0,0,0,0,0,0,0};
 
-  const std::size_t off = 4;
+  constexpr std::size_t off = 4;
   for (std::size_t row_index = off; row_index < height-off; ++row_index)
   {
     for (std::size_t col_index = off; col_index < width-off; ++col_index)
index 0e591a0ed18e0be1719baead9ede4072db3b7195..758046dbb559276e1a7a4711566c902502ef0e21 100644 (file)
@@ -48,10 +48,9 @@ PCL_INSTANTIATE_PRODUCT(Hough3DGrouping, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::P
 
 ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 pcl::recognition::HoughSpace3D::HoughSpace3D (const Eigen::Vector3d &min_coord, const Eigen::Vector3d &bin_size, const Eigen::Vector3d &max_coord)
+  : min_coord_ (min_coord)
+  , bin_size_ (bin_size)
 {
-  min_coord_ = min_coord;
-  bin_size_ = bin_size;
-
   for (int i = 0; i < 3; ++i)
   {
     bin_count_[i] = static_cast<int> (std::ceil ((max_coord[i] - min_coord_[i]) / bin_size_[i]));
index e11241537a60af8e4bf610cbb1e17854c5e13987..268324e0f70fac6d5058208f328ef59384b30915 100644 (file)
@@ -160,7 +160,7 @@ detectTemplates (const std::vector<DOTModality*> & modalities,
         const unsigned char * image_data = map.getData ();
         for (std::size_t template_index = 0; template_index < nr_templates; ++template_index)
         {
-          const unsigned char * template_data = &(templates_[template_index].modalities[modality_index].features[0]);
+          const unsigned char * template_data = templates_[template_index].modalities[modality_index].features.data();
           for (std::size_t data_index = 0; data_index < (nr_template_horizontal_bins*nr_template_vertical_bins); ++data_index)
           {
             if ((image_data[data_index] & template_data[data_index]) != 0)
@@ -170,7 +170,7 @@ detectTemplates (const std::vector<DOTModality*> & modalities,
       }
 
       // find templates with response over threshold
-      const float scaling_factor = 1.0f / float (nr_template_horizontal_bins * nr_template_vertical_bins);
+      const float scaling_factor = 1.0f / static_cast<float>(nr_template_horizontal_bins * nr_template_vertical_bins);
       for (std::size_t template_index = 0; template_index < nr_templates; ++template_index)
       {
         const float response = responses[template_index] * scaling_factor;
index d87db82709acc4d626d12175e4cc47ed453489d5..558c7f10773665f6f502aa14a4137f72f18b3aab 100644 (file)
@@ -254,7 +254,7 @@ void pcl::face_detection::FaceDetectorDataProvider<FeatureType, DataSet, LabelTy
 
     int element_stride = sizeof(pcl::PointXYZ) / sizeof(float);
     int row_stride = element_stride * cloud->width;
-    const float *data = reinterpret_cast<const float*> (&(*cloud)[0]);
+    const float *data = reinterpret_cast<const float*> (cloud->data());
     integral_image_depth->setInput (data + 2, cloud->width, cloud->height, element_stride, row_stride);
 
     //Compute normals and normal integral images
@@ -282,16 +282,14 @@ void pcl::face_detection::FaceDetectorDataProvider<FeatureType, DataSet, LabelTy
     if (USE_NORMALS_)
     {
       integral_image_normal_x.reset (new pcl::IntegralImage2D<float, 1> (false));
-      const float *data_nx = reinterpret_cast<const float*> (&(*normals)[0]);
-      integral_image_normal_x->setInput (data_nx, normals->width, normals->height, element_stride_normal, row_stride_normal);
+      const float *data = reinterpret_cast<const float*> (normals->data());
+      integral_image_normal_x->setInput (data + 0, normals->width, normals->height, element_stride_normal, row_stride_normal);
 
       integral_image_normal_y.reset (new pcl::IntegralImage2D<float, 1> (false));
-      const float *data_ny = reinterpret_cast<const float*> (&(*normals)[0]);
-      integral_image_normal_y->setInput (data_ny + 1, normals->width, normals->height, element_stride_normal, row_stride_normal);
+      integral_image_normal_y->setInput (data + 1, normals->width, normals->height, element_stride_normal, row_stride_normal);
 
       integral_image_normal_z.reset (new pcl::IntegralImage2D<float, 1> (false));
-      const float *data_nz = reinterpret_cast<const float*> (&(*normals)[0]);
-      integral_image_normal_z->setInput (data_nz + 2, normals->width, normals->height, element_stride_normal, row_stride_normal);
+      integral_image_normal_z->setInput (data + 2, normals->width, normals->height, element_stride_normal, row_stride_normal);
     }
 
     //Using cloud labels estimate a 2D window from where to extract positive samples
index 3387a8ed45723406e47b29e970256b22af1051b9..e4a447b4d81c98acd4029676178ce1a9ec89aeb1 100644 (file)
@@ -276,7 +276,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces()
 
   int element_stride = sizeof(pcl::PointXYZ) / sizeof(float);
   int row_stride = element_stride * cloud->width;
-  const float *data = reinterpret_cast<const float*> (&(*cloud)[0]);
+  const float *data = reinterpret_cast<const float*> (cloud->data());
   integral_image_depth->setInput (data + 2, cloud->width, cloud->height, element_stride, row_stride);
 
   //Compute normals and normal integral images
@@ -302,16 +302,14 @@ void pcl::RFFaceDetectorTrainer::detectFaces()
   if (use_normals_)
   {
     integral_image_normal_x.reset (new pcl::IntegralImage2D<float, 1> (false));
-    const float *data_nx = reinterpret_cast<const float*> (&(*normals)[0]);
-    integral_image_normal_x->setInput (data_nx, normals->width, normals->height, element_stride_normal, row_stride_normal);
+    const float *datum = reinterpret_cast<const float*> (normals->data());
+    integral_image_normal_x->setInput (datum + 0, normals->width, normals->height, element_stride_normal, row_stride_normal);
 
     integral_image_normal_y.reset (new pcl::IntegralImage2D<float, 1> (false));
-    const float *data_ny = reinterpret_cast<const float*> (&(*normals)[0]);
-    integral_image_normal_y->setInput (data_ny + 1, normals->width, normals->height, element_stride_normal, row_stride_normal);
+    integral_image_normal_y->setInput (datum + 1, normals->width, normals->height, element_stride_normal, row_stride_normal);
 
     integral_image_normal_z.reset (new pcl::IntegralImage2D<float, 1> (false));
-    const float *data_nz = reinterpret_cast<const float*> (&(*normals)[0]);
-    integral_image_normal_z->setInput (data_nz + 2, normals->width, normals->height, element_stride_normal, row_stride_normal);
+    integral_image_normal_z->setInput (datum + 2, normals->width, normals->height, element_stride_normal, row_stride_normal);
   }
 
   {
index fe61d04c532c9967fb5cb34c23e30c5372299628..8b47552e2b3e855a63afc94350c51948d7577ebf 100644 (file)
 //#define LINEMOD_USE_SEPARATE_ENERGY_MAPS
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-pcl::LINEMOD::LINEMOD () 
-  : template_threshold_ (0.75f)
-  , use_non_max_suppression_ (false)
-  , average_detections_ (false)
-{
-}
+pcl::LINEMOD::LINEMOD () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 pcl::LINEMOD::~LINEMOD() = default;
@@ -323,7 +318,7 @@ pcl::LINEMOD::matchTemplates (const std::vector<QuantizableModality*> & modaliti
     }
 #endif
 
-    const float inv_max_score = 1.0f / float (max_score);
+    const float inv_max_score = 1.0f / static_cast<float>(max_score);
     
     std::size_t max_value = 0;
     std::size_t max_index = 0;
@@ -662,14 +657,14 @@ pcl::LINEMOD::detectTemplates (const std::vector<QuantizableModality*> & modalit
     }
 #endif
 
-    const float inv_max_score = 1.0f / float (max_score);
+    const float inv_max_score = 1.0f / static_cast<float>(max_score);
 
     // we compute a new threshold based on the threshold supplied by the user;
     // this is due to the use of the cosine approx. in the response computation;
 #ifdef LINEMOD_USE_SEPARATE_ENERGY_MAPS
     const float raw_threshold = (4.0f * float (max_score) / 2.0f + template_threshold_ * (4.0f * float (max_score) / 2.0f));
 #else
-    const float raw_threshold = (float (max_score) / 2.0f + template_threshold_ * (float (max_score) / 2.0f));
+    const float raw_threshold = (static_cast<float>(max_score) / 2.0f + template_threshold_ * (static_cast<float>(max_score) / 2.0f));
 #endif
 
     //int max_value = 0;
@@ -1023,7 +1018,7 @@ pcl::LINEMOD::detectTemplatesSemiScaleInvariant (
             max_score += 4;
 
             unsigned char *data = modality_linearized_maps[feature.modality_index][bin_index].getOffsetMap (
-                std::size_t (float (feature.x) * scale), std::size_t (float (feature.y) * scale));
+                static_cast<std::size_t>(static_cast<float>(feature.x) * scale), static_cast<std::size_t>(static_cast<float>(feature.y) * scale));
             auto * data_m128i = reinterpret_cast<__m128i*> (data);
 
             for (std::size_t mem_index = 0; mem_index < mem_size_16; ++mem_index)
@@ -1129,14 +1124,14 @@ pcl::LINEMOD::detectTemplatesSemiScaleInvariant (
       }
 #endif
 
-      const float inv_max_score = 1.0f / float (max_score);
+      const float inv_max_score = 1.0f / static_cast<float>(max_score);
 
       // we compute a new threshold based on the threshold supplied by the user;
       // this is due to the use of the cosine approx. in the response computation;
 #ifdef LINEMOD_USE_SEPARATE_ENERGY_MAPS
       const float raw_threshold = (4.0f * float (max_score) / 2.0f + template_threshold_ * (4.0f * float (max_score) / 2.0f));
 #else
-      const float raw_threshold = (float (max_score) / 2.0f + template_threshold_ * (float (max_score) / 2.0f));
+      const float raw_threshold = (static_cast<float>(max_score) / 2.0f + template_threshold_ * (static_cast<float>(max_score) / 2.0f));
 #endif
 
       //int max_value = 0;
index 2f7bad0d9dd311a6518bf84859a46be9317bf222..dd3d3efdabcbfcdacf201e9bac8cb15ec932b1e2 100644 (file)
@@ -51,8 +51,7 @@ using namespace pcl::recognition;
 ModelLibrary::ModelLibrary (float pair_width, float voxel_size, float max_coplanarity_angle)
 : pair_width_ (pair_width),
   voxel_size_ (voxel_size),
-  max_coplanarity_angle_ (max_coplanarity_angle),
-  ignore_coplanar_opps_ (true)
+  max_coplanarity_angle_ (max_coplanarity_angle)
 {
   num_of_cells_[0] = 60;
   num_of_cells_[1] = 60;
index 7ba4c5137e869a006f5b1faeb428f3aad514e49e..a57b2d4bc6f9120fa6cce64c0e776a73e0f7ddf0 100644 (file)
@@ -48,17 +48,8 @@ pcl::recognition::ObjRecRANSAC::ObjRecRANSAC (float pair_width, float voxel_size
   position_discretization_ (5.0f*voxel_size_),
   rotation_discretization_ (5.0f*AUX_DEG_TO_RADIANS),
   abs_zdist_thresh_ (1.5f*voxel_size_),
-  relative_obj_size_ (0.05f),
-  visibility_ (0.2f),
-  relative_num_of_illegal_pts_ (0.02f),
-  intersection_fraction_ (0.03f),
   max_coplanarity_angle_ (3.0f*AUX_DEG_TO_RADIANS),
-  scene_bounds_enlargement_factor_ (0.25f), // 25% enlargement
-  ignore_coplanar_opps_ (true),
-  frac_of_points_for_icp_refinement_ (0.3f),
-  do_icp_hypotheses_refinement_ (true),
-  model_library_ (pair_width, voxel_size, max_coplanarity_angle_),
-  rec_mode_ (ObjRecRANSAC::FULL_RECOGNITION)
+  model_library_ (pair_width, voxel_size, max_coplanarity_angle_)
 {
 }
 
index e1b2fd48657d00676d4a7f4dda6dfb2562ea722c..07e2ea8819183f291b53490398d7935cef43da5a 100644 (file)
 
 using namespace pcl::recognition;
 
-pcl::recognition::ORROctree::ORROctree ()
-: voxel_size_ (-1.0),
-  tree_levels_ (-1),
-  root_ (nullptr)
-{
-}
+pcl::recognition::ORROctree::ORROctree () = default;
 
 //================================================================================================================================================================
 
index a8c137e9f3f5aae41c5d7477bf917a75fa4090be..7dce51a2f9117cc1bfee1cb3760e654e1ac9e7ab 100644 (file)
@@ -4,7 +4,7 @@ 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})
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
index dad1d542c4ad07dfb93dfe637cb2322ad7adb346..0d3dde6952838ebbc3414f24641ffaf3dfd74e02 100644 (file)
@@ -28,7 +28,7 @@ public:
   void
   compute(const OtherPolynomial& poly, bool& hasRealRoot)
   {
-    const Scalar ZERO(0);
+    constexpr Scalar ZERO(0);
     Scalar a2(2 * poly[2]);
     assert(ZERO != poly[poly.size() - 1]);
     Scalar discriminant((poly[1] * poly[1]) - (4 * poly[0] * poly[2]));
@@ -101,7 +101,7 @@ struct BFGSDummyFunctor {
   virtual void
   fdf(const VectorType& x, Scalar& f, VectorType& df) = 0;
   virtual BFGSSpace::Status
-  checkGradient(const VectorType& g)
+  checkGradient(const VectorType& /*g*/)
   {
     return BFGSSpace::NotStarted;
   };
@@ -110,7 +110,7 @@ struct BFGSDummyFunctor {
 /**
  * BFGS stands for Broyden–Fletcher–Goldfarb–Shanno (BFGS) method for solving
  * unconstrained nonlinear optimization problems.
- * For further details please visit: http://en.wikipedia.org/wiki/BFGS_method
+ * For further details please visit: https://en.wikipedia.org/wiki/BFGS_method
  * The method provided here is almost similar to the one provided by GSL.
  * It reproduces Fletcher's original algorithm in Practical Methods of Optimization
  * algorithms : 2.6.2 and 2.6.4 and uses the same politics in GSL with cubic
@@ -351,7 +351,7 @@ BFGS<FunctorType>::minimize(FVectorType& x)
   BFGSSpace::Status status = minimizeInit(x);
   do {
     status = minimizeOneStep(x);
-    iter++;
+    ++iter;
   } while (status == BFGSSpace::Success && iter < parameters.max_iters);
   return status;
 }
index de46b3e7b6721902eea384d6cd599c4df6af602a..bb1db6aab3ab871cbd1c7d9705597460882980d4 100644 (file)
@@ -72,9 +72,11 @@ public:
 
   using KdTree = pcl::search::KdTree<PointTarget>;
   using KdTreePtr = typename KdTree::Ptr;
+  using KdTreeConstPtr = typename KdTree::ConstPtr;
 
   using KdTreeReciprocal = pcl::search::KdTree<PointSource>;
-  using KdTreeReciprocalPtr = typename KdTree::Ptr;
+  using KdTreeReciprocalPtr = typename KdTreeReciprocal::Ptr;
+  using KdTreeReciprocalConstPtr = typename KdTreeReciprocal::ConstPtr;
 
   using PointCloudSource = pcl::PointCloud<PointSource>;
   using PointCloudSourcePtr = typename PointCloudSource::Ptr;
@@ -85,6 +87,8 @@ public:
   using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;
 
   using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr;
+  using PointRepresentationReciprocalConstPtr =
+      typename KdTreeReciprocal::PointRepresentationConstPtr;
 
   /** \brief Empty constructor. */
   CorrespondenceEstimationBase()
@@ -94,10 +98,6 @@ public:
   , target_()
   , point_representation_()
   , input_transformed_()
-  , target_cloud_updated_(true)
-  , source_cloud_updated_(true)
-  , force_no_recompute_(false)
-  , force_no_recompute_reciprocal_(false)
   {}
 
   /** \brief Empty destructor */
@@ -275,8 +275,8 @@ public:
       pcl::Correspondences& correspondences,
       double max_distance = std::numeric_limits<double>::max()) = 0;
 
-  /** \brief Provide a boost shared pointer to the PointRepresentation to be used
-   * when searching for nearest neighbors.
+  /** \brief Provide a boost shared pointer to the PointRepresentation for target cloud
+   * to be used when searching for nearest neighbors.
    *
    * \param[in] point_representation the PointRepresentation to be used by the
    * k-D tree for nearest neighbor search
@@ -287,6 +287,19 @@ public:
     point_representation_ = point_representation;
   }
 
+  /** \brief Provide a boost shared pointer to the PointRepresentation for source cloud
+   * to be used when searching for nearest neighbors.
+   *
+   * \param[in] point_representation the PointRepresentation to be used by the
+   * k-D tree for nearest neighbor search
+   */
+  inline void
+  setPointRepresentationReciprocal(
+      const PointRepresentationReciprocalConstPtr& point_representation_reciprocal)
+  {
+    point_representation_reciprocal_ = point_representation_reciprocal;
+  }
+
   /** \brief Clone and cast to CorrespondenceEstimationBase */
   virtual typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::Ptr
   clone() const = 0;
@@ -307,9 +320,12 @@ protected:
   /** \brief The target point cloud dataset indices. */
   IndicesPtr target_indices_;
 
-  /** \brief The point representation used (internal). */
+  /** \brief The target point representation used (internal). */
   PointRepresentationConstPtr point_representation_;
 
+  /** \brief The source point representation used (internal). */
+  PointRepresentationReciprocalConstPtr point_representation_reciprocal_;
+
   /** \brief The transformed input source point cloud dataset. */
   PointCloudTargetPtr input_transformed_;
 
@@ -334,18 +350,18 @@ protected:
   /** \brief Variable that stores whether we have a new target cloud, meaning we need to
    * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
    * cloud every time the determineCorrespondences () method is called. */
-  bool target_cloud_updated_;
+  bool target_cloud_updated_{true};
   /** \brief Variable that stores whether we have a new source cloud, meaning we need to
    * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
    * source cloud every time the determineCorrespondences () method is called. */
-  bool source_cloud_updated_;
+  bool source_cloud_updated_{true};
   /** \brief A flag which, if set, means the tree operating on the target cloud
    * will never be recomputed*/
-  bool force_no_recompute_;
+  bool force_no_recompute_{false};
 
   /** \brief A flag which, if set, means the tree operating on the source cloud
    * will never be recomputed*/
-  bool force_no_recompute_reciprocal_;
+  bool force_no_recompute_reciprocal_{false};
 };
 
 /** \brief @b CorrespondenceEstimation represents the base class for
@@ -396,8 +412,24 @@ public:
   using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_fields_;
   using PCLBase<PointSource>::deinitCompute;
 
-  using KdTree = pcl::search::KdTree<PointTarget>;
-  using KdTreePtr = typename KdTree::Ptr;
+  using KdTree =
+      typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::KdTree;
+  using KdTreePtr = typename CorrespondenceEstimationBase<PointSource,
+                                                          PointTarget,
+                                                          Scalar>::KdTreePtr;
+  using KdTreeConstPtr = typename CorrespondenceEstimationBase<PointSource,
+                                                               PointTarget,
+                                                               Scalar>::KdTreeConstPtr;
+  using KdTreeReciprocal =
+      typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+          KdTreeReciprocal;
+  using KdTreeReciprocalPtr =
+      typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+          KdTreeReciprocalPtr;
+
+  using KdTreeReciprocalConstPtr =
+      typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+          KdTreeReciprocalConstPtr;
 
   using PointCloudSource = pcl::PointCloud<PointSource>;
   using PointCloudSourcePtr = typename PointCloudSource::Ptr;
@@ -408,6 +440,8 @@ public:
   using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;
 
   using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr;
+  using PointRepresentationReciprocalConstPtr =
+      typename KdTreeReciprocal::PointRepresentationConstPtr;
 
   /** \brief Empty constructor. */
   CorrespondenceEstimation() { corr_name_ = "CorrespondenceEstimation"; }
index eb695201c931b1f28e98078f89b271836c439820..479b5a6038698e1d8b28860a8f851fc4579659a0 100644 (file)
@@ -99,7 +99,7 @@ public:
    * Sets the number of neighbors to be considered in the target point cloud (k_) to 10.
    */
   CorrespondenceEstimationBackProjection()
-  : source_normals_(), source_normals_transformed_(), target_normals_(), k_(10)
+  : source_normals_(), source_normals_transformed_(), target_normals_()
   {
     corr_name_ = "CorrespondenceEstimationBackProjection";
   }
@@ -250,7 +250,7 @@ private:
   NormalsConstPtr target_normals_;
 
   /** \brief The number of neighbours to be considered in the target point cloud */
-  unsigned int k_;
+  unsigned int k_{10};
 };
 } // namespace registration
 } // namespace pcl
index 0dc40ff11329edf44a7dd8626b1b6a1693c74733..cab09d4b43d9f21739257cd544a32a2d5f0c4b1f 100644 (file)
@@ -101,8 +101,18 @@ public:
       point_representation_;
   using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_indices_;
 
-  using KdTree = pcl::search::KdTree<PointTarget>;
-  using KdTreePtr = typename KdTree::Ptr;
+  using typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::KdTree;
+  using typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+      KdTreePtr;
+  using typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+      KdTreeConstPtr;
+
+  using typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+      KdTreeReciprocal;
+  using typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+      KdTreeReciprocalPtr;
+  using typename CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::
+      KdTreeReciprocalConstPtr;
 
   using PointCloudSource = pcl::PointCloud<PointSource>;
   using PointCloudSourcePtr = typename PointCloudSource::Ptr;
@@ -122,7 +132,7 @@ public:
    * Sets the number of neighbors to be considered in the target point cloud (k_) to 10.
    */
   CorrespondenceEstimationNormalShooting()
-  : source_normals_(), source_normals_transformed_(), k_(10)
+  : source_normals_(), source_normals_transformed_()
   {
     corr_name_ = "CorrespondenceEstimationNormalShooting";
   }
@@ -238,7 +248,7 @@ private:
   NormalsPtr source_normals_transformed_;
 
   /** \brief The number of neighbours to be considered in the target point cloud */
-  unsigned int k_;
+  unsigned int k_{10};
 };
 } // namespace registration
 } // namespace pcl
index 97bf14ab1886ee09756d36bd08eb04af6d62b996..e7e39e85cc03c202555a534a80ab9b09770c1fe1 100644 (file)
@@ -90,11 +90,7 @@ public:
   /** \brief Empty constructor that sets all the intrinsic calibration to the default
    * Kinect values. */
   CorrespondenceEstimationOrganizedProjection()
-  : fx_(525.f)
-  , fy_(525.f)
-  , cx_(319.5f)
-  , cy_(239.5f)
-  , src_to_tgt_transformation_(Eigen::Matrix4f::Identity())
+  : src_to_tgt_transformation_(Eigen::Matrix4f::Identity())
   , depth_threshold_(std::numeric_limits<float>::max())
   , projection_matrix_(Eigen::Matrix3f::Identity())
   {}
@@ -223,8 +219,8 @@ protected:
   bool
   initCompute();
 
-  float fx_, fy_;
-  float cx_, cy_;
+  float fx_{525.f}, fy_{525.f};
+  float cx_{319.5f}, cy_{239.5f};
   Eigen::Matrix4f src_to_tgt_transformation_;
   float depth_threshold_;
 
index 75e9957a74c9c377b6c51166c0f0bb0845f1fe70..f68882ab665d23e58ad860fb83696e86c01492fd 100644 (file)
@@ -198,7 +198,7 @@ public:
 
 protected:
   /** \brief The name of the rejection method. */
-  std::string rejection_name_;
+  std::string rejection_name_{};
 
   /** \brief The input correspondences. */
   CorrespondencesConstPtr input_correspondences_;
@@ -254,8 +254,6 @@ public:
   , tree_(new pcl::search::KdTree<PointT>)
   , class_name_("DataContainer")
   , needs_normals_(needs_normals)
-  , target_cloud_updated_(true)
-  , force_no_recompute_(false)
   {}
 
   /** \brief Empty destructor */
@@ -385,8 +383,9 @@ public:
            "Normals are not set for the input and target point clouds");
     const NormalT& src = (*input_normals_)[corr.index_query];
     const NormalT& tgt = (*target_normals_)[corr.index_match];
-    return (double((src.normal[0] * tgt.normal[0]) + (src.normal[1] * tgt.normal[1]) +
-                   (src.normal[2] * tgt.normal[2])));
+    return (static_cast<double>((src.normal[0] * tgt.normal[0]) +
+                                (src.normal[1] * tgt.normal[1]) +
+                                (src.normal[2] * tgt.normal[2])));
   }
 
 private:
@@ -396,7 +395,7 @@ private:
   /** \brief The input transformed point cloud dataset */
   PointCloudPtr input_transformed_;
 
-  /** \brief The target point cloud datase. */
+  /** \brief The target point cloud dataset. */
   PointCloudConstPtr target_;
 
   /** \brief Normals to the input point cloud */
@@ -419,11 +418,11 @@ private:
 
   /** \brief Variable that stores whether we have a new target cloud, meaning we need to
    * pre-process it again. This way, we avoid rebuilding the kd-tree */
-  bool target_cloud_updated_;
+  bool target_cloud_updated_{true};
 
   /** \brief A flag which, if set, means the tree operating on the target cloud
    * will never be recomputed*/
-  bool force_no_recompute_;
+  bool force_no_recompute_{false};
 
   /** \brief Get a string representation of the name of this class. */
   inline const std::string&
index 0d5f00c60bd28324b02882fa79616850204ef055..bf5715dbc87d95cf4a185d6a6a9968dfb69e23fc 100644 (file)
@@ -68,7 +68,7 @@ public:
   using ConstPtr = shared_ptr<const CorrespondenceRejectorMedianDistance>;
 
   /** \brief Empty constructor. */
-  CorrespondenceRejectorMedianDistance() : median_distance_(0), factor_(1.0)
+  CorrespondenceRejectorMedianDistance()
   {
     rejection_name_ = "CorrespondenceRejectorMedianDistance";
   }
@@ -193,12 +193,12 @@ protected:
   /** \brief The median distance threshold between two correspondent points in source
    * <-> target.
    */
-  double median_distance_;
+  double median_distance_{0.0};
 
   /** \brief The factor for correspondence rejection. Points with distance greater than
    * median times factor will be rejected
    */
-  double factor_;
+  double factor_{1.0};
 
   using DataContainerPtr = DataContainerInterface::Ptr;
 
index 25ec0d9581e6da4825d34108561b3d11c5afb922..23662a515a5571b81a1b494f6d1c639d0de06031 100644 (file)
@@ -59,9 +59,7 @@ class PCL_EXPORTS CorrespondenceRejectionOrganizedBoundary
 : public CorrespondenceRejector {
 public:
   /** @brief Empty constructor. */
-  CorrespondenceRejectionOrganizedBoundary()
-  : boundary_nans_threshold_(8), window_size_(5), depth_step_threshold_(0.025f)
-  {}
+  CorrespondenceRejectionOrganizedBoundary() = default;
 
   void
   getRemainingCorrespondences(const pcl::Correspondences& original_correspondences,
@@ -141,9 +139,9 @@ protected:
     getRemainingCorrespondences(*input_correspondences_, correspondences);
   }
 
-  int boundary_nans_threshold_;
-  int window_size_;
-  float depth_step_threshold_;
+  int boundary_nans_threshold_{8};
+  int window_size_{5};
+  float depth_step_threshold_{0.025f};
 
   using DataContainerPtr = DataContainerInterface::Ptr;
   DataContainerPtr data_container_;
index a5615118c9718fd710ad632d5d18a7274907f363..16ad6ca841bea2f4f2f80609e27af42ac7146c9b 100644 (file)
@@ -78,14 +78,7 @@ public:
   using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;
 
   /** \brief Empty constructor */
-  CorrespondenceRejectorPoly()
-  : iterations_(10000)
-  , cardinality_(3)
-  , similarity_threshold_(0.75f)
-  , similarity_threshold_squared_(0.75f * 0.75f)
-  {
-    rejection_name_ = "CorrespondenceRejectorPoly";
-  }
+  CorrespondenceRejectorPoly() { rejection_name_ = "CorrespondenceRejectorPoly"; }
 
   /** \brief Get a list of valid correspondences after rejection from the original set
    * of correspondences.
@@ -371,17 +364,17 @@ protected:
   PointCloudTargetConstPtr target_;
 
   /** \brief Number of iterations to run */
-  int iterations_;
+  int iterations_{10000};
 
   /** \brief The polygon cardinality used during rejection */
-  int cardinality_;
+  int cardinality_{3};
 
   /** \brief Lower edge length threshold in [0,1] used for verifying polygon
    * similarities, where 1 is a perfect match */
-  float similarity_threshold_;
+  float similarity_threshold_{0.75f};
 
   /** \brief Squared value if \ref similarity_threshold_, only for internal use */
-  float similarity_threshold_squared_;
+  float similarity_threshold_squared_{0.75f * 0.75f};
 };
 } // namespace registration
 } // namespace pcl
index 2920b3325c490153d1a7643e5db36b6c89e3a175..1b464c9bc87d0485366b5dd29486548861b0237c 100644 (file)
@@ -67,14 +67,7 @@ public:
   /** \brief Empty constructor. Sets the inlier threshold to 5cm (0.05m),
    * and the maximum number of iterations to 1000.
    */
-  CorrespondenceRejectorSampleConsensus()
-  : inlier_threshold_(0.05)
-  , max_iterations_(1000) // std::numeric_limits<int>::max ()
-  , input_()
-  , input_transformed_()
-  , target_()
-  , refine_(false)
-  , save_inliers_(false)
+  CorrespondenceRejectorSampleConsensus() : input_(), input_transformed_(), target_()
   {
     rejection_name_ = "CorrespondenceRejectorSampleConsensus";
   }
@@ -256,9 +249,9 @@ protected:
     getRemainingCorrespondences(*input_correspondences_, correspondences);
   }
 
-  double inlier_threshold_;
+  double inlier_threshold_{0.05};
 
-  int max_iterations_;
+  int max_iterations_{1000};
 
   PointCloudConstPtr input_;
   PointCloudPtr input_transformed_;
@@ -266,9 +259,9 @@ protected:
 
   Eigen::Matrix4f best_transformation_;
 
-  bool refine_;
+  bool refine_{false};
   pcl::Indices inlier_indices_;
-  bool save_inliers_;
+  bool save_inliers_{false};
 
 public:
   PCL_MAKE_ALIGNED_OPERATOR_NEW
index 520276105c120ca5ee2b9813b75609f7248a2b3d..d2795748e5f16b3c0a0b7b430d2216b4bfced24f 100644 (file)
@@ -67,7 +67,7 @@ public:
   using ConstPtr = shared_ptr<const CorrespondenceRejectorSurfaceNormal>;
 
   /** \brief Empty constructor. Sets the threshold to 1.0. */
-  CorrespondenceRejectorSurfaceNormal() : threshold_(1.0)
+  CorrespondenceRejectorSurfaceNormal()
   {
     rejection_name_ = "CorrespondenceRejectorSurfaceNormal";
   }
@@ -342,7 +342,7 @@ protected:
 
   /** \brief The median distance threshold between two correspondent points in source
    * <-> target. */
-  double threshold_;
+  double threshold_{1.0};
 
   using DataContainerPtr = DataContainerInterface::Ptr;
   /** \brief A pointer to the DataContainer object containing the input and target point
index 1b037bfe7dee76ec1a8032aefa9126a71a4d1b97..202ca9d566a0145bd37a822dcd9f11b643d162fe 100644 (file)
@@ -68,10 +68,7 @@ public:
   using ConstPtr = shared_ptr<const CorrespondenceRejectorTrimmed>;
 
   /** \brief Empty constructor. */
-  CorrespondenceRejectorTrimmed() : overlap_ratio_(0.5f), nr_min_correspondences_(0)
-  {
-    rejection_name_ = "CorrespondenceRejectorTrimmed";
-  }
+  CorrespondenceRejectorTrimmed() { rejection_name_ = "CorrespondenceRejectorTrimmed"; }
 
   /** \brief Destructor. */
   ~CorrespondenceRejectorTrimmed() override = default;
@@ -135,10 +132,10 @@ protected:
   }
 
   /** Overlap Ratio in [0..1] */
-  float overlap_ratio_;
+  float overlap_ratio_{0.5f};
 
   /** Minimum number of correspondences. */
-  unsigned int nr_min_correspondences_;
+  unsigned int nr_min_correspondences_{0};
 };
 
 } // namespace registration
index e5b5c7a7aa6a98be08c6eac1ef7961ccfe82d743..37485c9f6a1401d92d3ad3c4a4b41a3cb684d015 100644 (file)
@@ -73,7 +73,6 @@ public:
 
   /** \brief Empty constructor. */
   CorrespondenceRejectorVarTrimmed()
-  : trimmed_distance_(0), factor_(), min_ratio_(0.05), max_ratio_(0.95), lambda_(0.95)
   {
     rejection_name_ = "CorrespondenceRejectorVarTrimmed";
   }
@@ -224,26 +223,26 @@ protected:
   /** \brief The inlier distance threshold (based on the computed trim factor) between
    * two correspondent points in source <-> target.
    */
-  double trimmed_distance_;
+  double trimmed_distance_{0.0};
 
   /** \brief The factor for correspondence rejection. Only factor times the total points
    * sorted based on the correspondence distances will be considered as inliers.
    * Remaining points are rejected. This factor is computed internally
    */
-  double factor_;
+  double factor_{0.0};
 
   /** \brief The minimum overlap ratio between the input and target clouds
    */
-  double min_ratio_;
+  double min_ratio_{0.05};
 
   /** \brief The maximum overlap ratio between the input and target clouds
    */
-  double max_ratio_;
+  double max_ratio_{0.95};
 
   /** \brief part of the term that balances the root mean square difference. This is an
    * internal parameter
    */
-  double lambda_;
+  double lambda_{0.95};
 
   using DataContainerPtr = DataContainerInterface::Ptr;
 
index 7533cc6e27ff9e0e84fea9f3d68d5ec481199d45..b8cbd795ad64b04e4d5f0e98bac33d797eab4556 100644 (file)
@@ -97,17 +97,6 @@ public:
   : iterations_(iterations)
   , transformation_(transform)
   , correspondences_(correspondences)
-  , correspondences_prev_mse_(std::numeric_limits<double>::max())
-  , correspondences_cur_mse_(std::numeric_limits<double>::max())
-  , max_iterations_(100) // 100 iterations
-  , failure_after_max_iter_(false)
-  , rotation_threshold_(0.99999)        // 0.256 degrees
-  , translation_threshold_(3e-4 * 3e-4) // 0.0003 meters
-  , mse_threshold_relative_(0.00001)    // 0.001% of the previous MSE (relative error)
-  , mse_threshold_absolute_(1e-12)      // MSE (absolute error)
-  , iterations_similar_transforms_(0)
-  , max_iterations_similar_transforms_(0)
-  , convergence_state_(CONVERGENCE_CRITERIA_NOT_CONVERGED)
   {}
 
   /** \brief Empty destructor */
@@ -275,7 +264,7 @@ protected:
     double mse = 0;
     for (const auto& correspondence : correspondences)
       mse += correspondence.distance;
-    mse /= double(correspondences.size());
+    mse /= static_cast<double>(correspondences.size());
     return (mse);
   }
 
@@ -291,45 +280,45 @@ protected:
   const pcl::Correspondences& correspondences_;
 
   /** \brief The MSE for the previous set of correspondences. */
-  double correspondences_prev_mse_;
+  double correspondences_prev_mse_{std::numeric_limits<double>::max()};
 
   /** \brief The MSE for the current set of correspondences. */
-  double correspondences_cur_mse_;
+  double correspondences_cur_mse_{std::numeric_limits<double>::max()};
 
   /** \brief The maximum nuyyGmber of iterations that the registration loop is to be
    * executed. */
-  int max_iterations_;
+  int max_iterations_{100};
 
   /** \brief Specifys if the registration fails or converges when the maximum number of
    * iterations is reached. */
-  bool failure_after_max_iter_;
+  bool failure_after_max_iter_{false};
 
   /** \brief The rotation threshold is the relative rotation between two iterations (as
    * angle cosine). */
-  double rotation_threshold_;
+  double rotation_threshold_{0.99999};
 
   /** \brief The translation threshold is the relative translation between two
    * iterations (0 if no translation). */
-  double translation_threshold_;
+  double translation_threshold_{3e-4 * 3e-4}; // 0.0003 meters
 
   /** \brief The relative change from the previous MSE for the current set of
    * correspondences, e.g. .1 means 10% change. */
-  double mse_threshold_relative_;
+  double mse_threshold_relative_{0.00001};
 
   /** \brief The absolute change from the previous MSE for the current set of
    * correspondences. */
-  double mse_threshold_absolute_;
+  double mse_threshold_absolute_{1e-12};
 
   /** \brief Internal counter for the number of iterations that the internal
    * rotation, translation, and MSE differences are allowed to be similar. */
-  int iterations_similar_transforms_;
+  int iterations_similar_transforms_{0};
 
   /** \brief The maximum number of iterations that the internal rotation,
    * translation, and MSE differences are allowed to be similar. */
-  int max_iterations_similar_transforms_;
+  int max_iterations_similar_transforms_{0};
 
   /** \brief The state of the convergence (e.g., why did the registration converge). */
-  ConvergenceState convergence_state_;
+  ConvergenceState convergence_state_{CONVERGENCE_CRITERIA_NOT_CONVERGED};
 
 public:
   PCL_MAKE_ALIGNED_OPERATOR_NEW
index 5453b0c8ca948e48b8ae16b9deb553997caeb7f2..5e4a897512b5c60f6d4d443c77c8a31a63268432 100644 (file)
@@ -90,7 +90,6 @@ public:
   , loop_start_(0)
   , loop_end_(0)
   , reg_(new pcl::IterativeClosestPoint<PointT, PointT>)
-  , compute_loop_(true)
   , vd_(){};
 
   /** \brief Empty destructor */
@@ -239,7 +238,7 @@ private:
 
   /** \brief The transformation between that start and end of the loop. */
   Eigen::Matrix4f loop_transform_;
-  bool compute_loop_;
+  bool compute_loop_{true};
 
   /** \brief previously added node in the loop_graph_. */
   typename boost::graph_traits<LoopGraph>::vertex_descriptor vd_;
index d33e747c9a5df5706a2b6c8b8bb415d2d15019bc..4084c6444e02cca60a060e7d7f42d2f7ad909caf 100644 (file)
@@ -49,8 +49,9 @@ namespace pcl {
  * http://www.robots.ox.ac.uk/~avsegal/resources/papers/Generalized_ICP.pdf
  * The approach is based on using anisotropic cost functions to optimize the alignment
  * after closest point assignments have been made.
- * The original code uses GSL and ANN while in ours we use an eigen mapped BFGS and
- * FLANN.
+ * 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).
  * \author Nizar Sallem
  * \ingroup registration
  */
@@ -111,17 +112,13 @@ public:
   using Matrix3 = typename Eigen::Matrix<Scalar, 3, 3>;
   using Matrix4 =
       typename IterativeClosestPoint<PointSource, PointTarget, Scalar>::Matrix4;
+  using Matrix6d = Eigen::Matrix<double, 6, 6>;
   using AngleAxis = typename Eigen::AngleAxis<Scalar>;
 
+  PCL_MAKE_ALIGNED_OPERATOR_NEW
+
   /** \brief Empty constructor. */
-  GeneralizedIterativeClosestPoint()
-  : k_correspondences_(20)
-  , gicp_epsilon_(0.001)
-  , rotation_epsilon_(2e-3)
-  , mahalanobis_(0)
-  , max_inner_iterations_(20)
-  , translation_gradient_tolerance_(1e-2)
-  , rotation_gradient_tolerance_(1e-2)
+  GeneralizedIterativeClosestPoint() : mahalanobis_(0)
   {
     min_number_correspondences_ = 4;
     reg_name_ = "GeneralizedIterativeClosestPoint";
@@ -133,7 +130,7 @@ public:
                                               const PointCloudTarget& cloud_tgt,
                                               const pcl::Indices& indices_tgt,
                                               Matrix4& transformation_matrix) {
-      estimateRigidTransformationBFGS(
+      estimateRigidTransformationNewton(
           cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix);
     };
   }
@@ -212,6 +209,23 @@ public:
                                   const pcl::Indices& indices_tgt,
                                   Matrix4& transformation_matrix);
 
+  /** \brief Estimate a rigid rotation transformation between a source and a target
+   * point cloud using an iterative non-linear Newton approach.
+   * \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[in,out] transformation_matrix the resultant transformation matrix
+   */
+  void
+  estimateRigidTransformationNewton(const PointCloudSource& cloud_src,
+                                    const pcl::Indices& indices_src,
+                                    const PointCloudTarget& cloud_tgt,
+                                    const pcl::Indices& indices_tgt,
+                                    Matrix4& transformation_matrix);
+
   /** \brief \return Mahalanobis distance matrix for the given point index */
   inline const Eigen::Matrix3d&
   mahalanobis(std::size_t index) const
@@ -274,6 +288,21 @@ public:
     return k_correspondences_;
   }
 
+  /** \brief Use BFGS optimizer instead of default Newton optimizer
+   */
+  void
+  useBFGS()
+  {
+    rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src,
+                                              const pcl::Indices& indices_src,
+                                              const PointCloudTarget& cloud_tgt,
+                                              const pcl::Indices& indices_tgt,
+                                              Matrix4& transformation_matrix) {
+      estimateRigidTransformationBFGS(
+          cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix);
+    };
+  }
+
   /** \brief Set maximum number of iterations at the optimization step
    * \param[in] max maximum number of iterations for the optimizer
    */
@@ -330,19 +359,19 @@ protected:
   /** \brief The number of neighbors used for covariances computation.
    * default: 20
    */
-  int k_correspondences_;
+  int k_correspondences_{20};
 
   /** \brief The epsilon constant for gicp paper; this is NOT the convergence
    * tolerance
    * default: 0.001
    */
-  double gicp_epsilon_;
+  double gicp_epsilon_{0.001};
 
   /** The epsilon constant for rotation error. (In GICP the transformation epsilon
    * is split in rotation part and translation part).
    * default: 2e-3
    */
-  double rotation_epsilon_;
+  double rotation_epsilon_{2e-3};
 
   /** \brief base transformation */
   Matrix4 base_transformation_;
@@ -369,18 +398,18 @@ protected:
   std::vector<Eigen::Matrix3d> mahalanobis_;
 
   /** \brief maximum number of optimizations */
-  int max_inner_iterations_;
+  int max_inner_iterations_{20};
 
   /** \brief minimal translation gradient for early optimization stop */
-  double translation_gradient_tolerance_;
+  double translation_gradient_tolerance_{1e-2};
 
   /** \brief minimal rotation gradient for early optimization stop */
-  double rotation_gradient_tolerance_;
+  double rotation_gradient_tolerance_{1e-2};
 
   /** \brief compute points covariances matrices according to the K nearest
    * neighbors. K is set via setCorrespondenceRandomness() method.
-   * \param cloud pointer to point cloud
-   * \param tree KD tree performer for nearest neighbors search
+   * \param[in] cloud pointer to point cloud
+   * \param[in] tree KD tree performer for nearest neighbors search
    * \param[out] cloud_covariances covariances matrices for each point in the cloud
    */
   template <typename PointT>
@@ -445,6 +474,8 @@ protected:
     df(const Vector6d& x, Vector6d& df) override;
     void
     fdf(const Vector6d& x, double& f, Vector6d& df) override;
+    void
+    dfddf(const Vector6d& x, Vector6d& df, Matrix6d& ddf);
     BFGSSpace::Status
     checkGradient(const Vector6d& g) override;
 
@@ -457,6 +488,26 @@ protected:
                      const pcl::Indices& tgt_indices,
                      Matrix4& transformation_matrix)>
       rigid_transformation_estimation_;
+
+private:
+  void
+  getRDerivatives(double phi,
+                  double theta,
+                  double psi,
+                  Eigen::Matrix3d& dR_dPhi,
+                  Eigen::Matrix3d& dR_dTheta,
+                  Eigen::Matrix3d& dR_dPsi) const;
+
+  void
+  getR2ndDerivatives(double phi,
+                     double theta,
+                     double psi,
+                     Eigen::Matrix3d& ddR_dPhi_dPhi,
+                     Eigen::Matrix3d& ddR_dPhi_dTheta,
+                     Eigen::Matrix3d& ddR_dPhi_dPsi,
+                     Eigen::Matrix3d& ddR_dTheta_dTheta,
+                     Eigen::Matrix3d& ddR_dTheta_dPsi,
+                     Eigen::Matrix3d& ddR_dPsi_dPsi) const;
 };
 } // namespace pcl
 
index 788dfd0d9e372244692eb02a45e5e676797ec57a..abff434f52711113725b3045c993f6d2119536c0 100644 (file)
@@ -327,7 +327,7 @@ protected:
    * \param[out] base_indices indices of base B
    * \return
    * * < 0 no triangle with large enough base lines could be selected
-   * * = 0 base triangle succesully selected
+   * * = 0 base triangle successfully selected
    */
   int
   selectBaseTriangle(pcl::Indices& base_indices);
@@ -470,10 +470,10 @@ protected:
   /** \brief Number of threads for parallelization (standard = 1).
    * \note Only used if run compiled with OpenMP.
    */
-  int nr_threads_;
+  int nr_threads_{1};
 
   /** \brief Estimated overlap between source and target (standard = 0.5). */
-  float approx_overlap_;
+  float approx_overlap_{0.5f};
 
   /** \brief Delta value of 4pcs algorithm (standard = 1.0).
    * It can be used as:
@@ -482,7 +482,7 @@ protected:
    * * relative value (normalization = true), to adjust the internally calculated point
    * accuracy (= point density)
    */
-  float delta_;
+  float delta_{1.f};
 
   /** \brief Score threshold to stop calculation with success.
    * If not set by the user it depends on the size of the approximated overlap
@@ -491,34 +491,34 @@ protected:
 
   /** \brief The number of points to uniformly sample the source point cloud. (standard
    * = 0 => full cloud). */
-  int nr_samples_;
+  int nr_samples_{0};
 
   /** \brief Maximum normal difference of corresponding point pairs in degrees (standard
    * = 90). */
-  float max_norm_diff_;
+  float max_norm_diff_{90.f};
 
   /** \brief Maximum allowed computation time in seconds (standard = 0 => ~unlimited).
    */
-  int max_runtime_;
+  int max_runtime_{0};
 
   /** \brief Resulting fitness score of the best match. */
   float fitness_score_;
 
-  /** \brief Estimated diamter of the target point cloud. */
-  float diameter_;
+  /** \brief Estimated diameter of the target point cloud. */
+  float diameter_{0.0f};
 
   /** \brief Estimated squared metric overlap between source and target.
    * \note Internally calculated using the estimated overlap and the extent of the
    * source cloud. It is used to derive the minimum sampling distance of the base points
    * as well as to calculated the number of tries to reliably find a correct match.
    */
-  float max_base_diameter_sqr_;
+  float max_base_diameter_sqr_{0.0f};
 
   /** \brief Use normals flag. */
-  bool use_normals_;
+  bool use_normals_{false};
 
   /** \brief Normalize delta flag. */
-  bool normalize_delta_;
+  bool normalize_delta_{true};
 
   /** \brief A pointer to the vector of source point indices to use after sampling. */
   pcl::IndicesPtr source_indices_;
@@ -529,30 +529,30 @@ protected:
   /** \brief Maximal difference between corresponding point pairs in source and target.
    * \note Internally calculated using an estimation of the point density.
    */
-  float max_pair_diff_;
+  float max_pair_diff_{0.0f};
 
   /** \brief Maximal difference between the length of the base edges and valid match
    * edges. \note Internally calculated using an estimation of the point density.
    */
-  float max_edge_diff_;
+  float max_edge_diff_{0.0f};
 
   /** \brief Maximal distance between coinciding intersection points to find valid
    * matches. \note Internally calculated using an estimation of the point density.
    */
-  float coincidation_limit_;
+  float coincidation_limit_{0.0f};
 
   /** \brief Maximal mean squared errors of a transformation calculated from a candidate
    * match. \note Internally calculated using an estimation of the point density.
    */
-  float max_mse_;
+  float max_mse_{0.0f};
 
   /** \brief Maximal squared point distance between source and target points to count as
    * inlier. \note Internally calculated using an estimation of the point density.
    */
-  float max_inlier_dist_sqr_;
+  float max_inlier_dist_sqr_{0.0f};
 
   /** \brief Definition of a small error. */
-  const float small_error_;
+  const float small_error_{0.00001f};
 };
 }; // namespace registration
 }; // namespace pcl
index abfba231dd7c03b91629f19e8946cb5a6013be60..ac32c58b4807197ee717959c0d7b397162722a47 100644 (file)
@@ -235,23 +235,23 @@ protected:
   /** \brief Lower boundary for translation costs calculation.
    * \note If not set by the user, the translation costs are not used during evaluation.
    */
-  float lower_trl_boundary_;
+  float lower_trl_boundary_{-1.f};
 
   /** \brief Upper boundary for translation costs calculation.
    * \note If not set by the user, it is calculated from the estimated overlap and the
    * diameter of the point cloud.
    */
-  float upper_trl_boundary_;
+  float upper_trl_boundary_{-1.f};
 
   /** \brief Weighting factor for translation costs (standard = 0.5). */
-  float lambda_;
+  float lambda_{0.5f};
 
   /** \brief Container for resulting vector of registration candidates. */
   MatchingCandidates candidates_;
 
   /** \brief Flag if translation score should be used in validation (internal
    * calculation). */
-  bool use_trl_score_;
+  bool use_trl_score_{false};
 
   /** \brief Subset of input indices on which we evaluate candidates.
    * To speed up the evaluation, we only use a fix number of indices defined during
index 1d23a1889b1515ec8ec57d00cae21d96801007db..10fc7ec8b43caefb111a95d8c3207ed7b15785d8 100644 (file)
@@ -112,7 +112,7 @@ public:
     }
 
   protected:
-    float threshold_;
+    float threshold_{0.0f};
   };
 
   class TruncatedError : public ErrorFunctor {
@@ -132,7 +132,7 @@ public:
     }
 
   protected:
-    float threshold_;
+    float threshold_{0.0f};
   };
 
   using ErrorFunctorPtr = typename ErrorFunctor::Ptr;
@@ -142,9 +142,6 @@ public:
   SampleConsensusInitialAlignment()
   : input_features_()
   , target_features_()
-  , nr_samples_(3)
-  , min_sample_distance_(0.0f)
-  , k_correspondences_(10)
   , feature_tree_(new pcl::KdTreeFLANN<FeatureT>)
   , error_functor_()
   {
@@ -313,14 +310,14 @@ protected:
   FeatureCloudConstPtr target_features_;
 
   /** \brief The number of samples to use during each iteration. */
-  int nr_samples_;
+  int nr_samples_{3};
 
   /** \brief The minimum distances between samples. */
-  float min_sample_distance_;
+  float min_sample_distance_{0.0f};
 
   /** \brief The number of neighbors to use when selecting a random feature
    * correspondence. */
-  int k_correspondences_;
+  int k_correspondences_{10};
 
   /** \brief The KdTree used to compare feature descriptors. */
   FeatureKdTreePtr feature_tree_;
index 65b2ec9784f490a108891c3932d825b01eece059..8127b10d0293ae8e07a35d1d587ca0eb3c960456 100644 (file)
@@ -47,7 +47,8 @@
 #include <pcl/registration/transformation_estimation_point_to_plane_lls.h>
 #include <pcl/registration/transformation_estimation_svd.h>
 #include <pcl/registration/transformation_estimation_symmetric_point_to_plane_lls.h>
-#include <pcl/memory.h> // for dynamic_pointer_cast, pcl::make_shared, shared_ptr
+#include <pcl/memory.h>     // for dynamic_pointer_cast, pcl::make_shared, shared_ptr
+#include <pcl/pcl_config.h> // for PCL_NO_PRECOMPILE
 
 namespace pcl {
 /** \brief @b IterativeClosestPoint provides a base implementation of the Iterative
@@ -143,15 +144,6 @@ public:
 
   /** \brief Empty constructor. */
   IterativeClosestPoint()
-  : x_idx_offset_(0)
-  , y_idx_offset_(0)
-  , z_idx_offset_(0)
-  , nx_idx_offset_(0)
-  , ny_idx_offset_(0)
-  , nz_idx_offset_(0)
-  , use_reciprocal_correspondence_(false)
-  , source_has_normals_(false)
-  , target_has_normals_(false)
   {
     reg_name_ = "IterativeClosestPoint";
     transformation_estimation_.reset(
@@ -296,18 +288,18 @@ protected:
   determineRequiredBlobData();
 
   /** \brief XYZ fields offset. */
-  std::size_t x_idx_offset_, y_idx_offset_, z_idx_offset_;
+  std::size_t x_idx_offset_{0}, y_idx_offset_{0}, z_idx_offset_{0};
 
   /** \brief Normal fields offset. */
-  std::size_t nx_idx_offset_, ny_idx_offset_, nz_idx_offset_;
+  std::size_t nx_idx_offset_{0}, ny_idx_offset_{0}, nz_idx_offset_{0};
 
   /** \brief The correspondence type used for correspondence estimation. */
-  bool use_reciprocal_correspondence_;
+  bool use_reciprocal_correspondence_{false};
 
   /** \brief Internal check whether source dataset has normals or not. */
-  bool source_has_normals_;
+  bool source_has_normals_{false};
   /** \brief Internal check whether target dataset has normals or not. */
-  bool target_has_normals_;
+  bool target_has_normals_{false};
 
   /** \brief Checks for whether estimators and rejectors need various data */
   bool need_source_blob_, need_target_blob_;
@@ -456,3 +448,9 @@ protected:
 } // namespace pcl
 
 #include <pcl/registration/impl/icp.hpp>
+
+#if !defined(PCL_NO_PRECOMPILE) && !defined(PCL_REGISTRATION_ICP_CPP_)
+extern template class pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ>;
+extern template class pcl::IterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>;
+extern template class pcl::IterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB>;
+#endif // PCL_NO_PRECOMPILE
index 19cded5369aa2bdab1ee01c3df268a0605c7361d..50eb5b0fc66076fa740590e4121b8612b0c67110 100644 (file)
@@ -98,8 +98,8 @@ CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initComputeRecip
 {
   // Only update source kd-tree if a new target cloud was set
   if (source_cloud_updated_ && !force_no_recompute_reciprocal_) {
-    if (point_representation_)
-      tree_reciprocal_->setPointRepresentation(point_representation_);
+    if (point_representation_reciprocal_)
+      tree_reciprocal_->setPointRepresentation(point_representation_reciprocal_);
     // If the target indices have been given via setIndicesTarget
     if (indices_)
       tree_reciprocal_->setInputCloud(getInputSource(), getIndicesSource());
@@ -112,6 +112,35 @@ CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initComputeRecip
   return (true);
 }
 
+namespace detail {
+
+template <
+    typename PointTarget,
+    typename PointSource,
+    typename Index,
+    typename std::enable_if_t<isSamePointType<PointSource, PointTarget>()>* = nullptr>
+const PointSource&
+pointCopyOrRef(typename pcl::PointCloud<PointSource>::ConstPtr& input, const Index& idx)
+{
+  return (*input)[idx];
+}
+
+template <
+    typename PointTarget,
+    typename PointSource,
+    typename Index,
+    typename std::enable_if_t<!isSamePointType<PointSource, PointTarget>()>* = nullptr>
+PointTarget
+pointCopyOrRef(typename pcl::PointCloud<PointSource>::ConstPtr& input, const Index& idx)
+{
+  // Copy the source data to a target PointTarget format so we can search in the tree
+  PointTarget pt;
+  copyPoint((*input)[idx], pt);
+  return pt;
+}
+
+} // namespace detail
+
 template <typename PointSource, typename PointTarget, typename Scalar>
 void
 CorrespondenceEstimation<PointSource, PointTarget, Scalar>::determineCorrespondences(
@@ -120,50 +149,30 @@ CorrespondenceEstimation<PointSource, PointTarget, Scalar>::determineCorresponde
   if (!initCompute())
     return;
 
-  double max_dist_sqr = max_distance * max_distance;
-
   correspondences.resize(indices_->size());
 
   pcl::Indices index(1);
   std::vector<float> distance(1);
   pcl::Correspondence corr;
   unsigned int nr_valid_correspondences = 0;
+  double max_dist_sqr = max_distance * max_distance;
 
-  // 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!
-  if (isSamePointType<PointSource, PointTarget>()) {
-    // Iterate over the input set of source indices
-    for (const auto& idx : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx], 1, index, distance);
-      if (distance[0] > max_dist_sqr)
-        continue;
-
-      corr.index_query = idx;
-      corr.index_match = index[0];
-      corr.distance = distance[0];
-      correspondences[nr_valid_correspondences++] = corr;
-    }
-  }
-  else {
-    PointTarget pt;
-
-    // Iterate over the input set of source indices
-    for (const auto& idx : (*indices_)) {
-      // Copy the source data to a target PointTarget format so we can search in the
-      // tree
-      copyPoint((*input_)[idx], pt);
-
-      tree_->nearestKSearch(pt, 1, index, distance);
-      if (distance[0] > max_dist_sqr)
-        continue;
-
-      corr.index_query = idx;
-      corr.index_match = index[0];
-      corr.distance = distance[0];
-      correspondences[nr_valid_correspondences++] = corr;
-    }
+  // Iterate over the input set of source indices
+  for (const auto& idx : (*indices_)) {
+    // 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);
+    tree_->nearestKSearch(pt, 1, index, distance);
+    if (distance[0] > max_dist_sqr)
+      continue;
+
+    corr.index_query = idx;
+    corr.index_match = index[0];
+    corr.distance = distance[0];
+    correspondences[nr_valid_correspondences++] = corr;
   }
+
   correspondences.resize(nr_valid_correspondences);
   deinitCompute();
 }
@@ -192,59 +201,30 @@ CorrespondenceEstimation<PointSource, PointTarget, Scalar>::
   unsigned int nr_valid_correspondences = 0;
   int target_idx = 0;
 
-  // 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!
-  if (isSamePointType<PointSource, PointTarget>()) {
-    // Iterate over the input set of source indices
-    for (const auto& idx : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx], 1, index, distance);
-      if (distance[0] > max_dist_sqr)
-        continue;
-
-      target_idx = index[0];
-
-      tree_reciprocal_->nearestKSearch(
-          (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal);
-      if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0])
-        continue;
-
-      corr.index_query = idx;
-      corr.index_match = index[0];
-      corr.distance = distance[0];
-      correspondences[nr_valid_correspondences++] = corr;
-    }
-  }
-  else {
-    PointTarget pt_src;
-    PointSource pt_tgt;
-
-    // Iterate over the input set of source indices
-    for (const auto& idx : (*indices_)) {
-      // Copy the source data to a target PointTarget format so we can search in the
-      // tree
-      copyPoint((*input_)[idx], pt_src);
-
-      tree_->nearestKSearch(pt_src, 1, index, distance);
-      if (distance[0] > max_dist_sqr)
-        continue;
-
-      target_idx = index[0];
-
-      // Copy the target data to a target PointSource format so we can search in the
-      // tree_reciprocal
-      copyPoint((*target_)[target_idx], pt_tgt);
-
-      tree_reciprocal_->nearestKSearch(
-          pt_tgt, 1, index_reciprocal, distance_reciprocal);
-      if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0])
-        continue;
-
-      corr.index_query = idx;
-      corr.index_match = index[0];
-      corr.distance = distance[0];
-      correspondences[nr_valid_correspondences++] = corr;
-    }
+  // Iterate over the input set of source indices
+  for (const auto& idx : (*indices_)) {
+    // 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);
+
+    tree_->nearestKSearch(pt_src, 1, index, distance);
+    if (distance[0] > max_dist_sqr)
+      continue;
+
+    target_idx = index[0];
+    const auto& pt_tgt =
+        detail::pointCopyOrRef<PointSource, PointTarget>(target_, target_idx);
+
+    tree_reciprocal_->nearestKSearch(pt_tgt, 1, index_reciprocal, distance_reciprocal);
+    if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0])
+      continue;
+
+    corr.index_query = idx;
+    corr.index_match = index[0];
+    corr.distance = distance[0];
+    correspondences[nr_valid_correspondences++] = corr;
   }
   correspondences.resize(nr_valid_correspondences);
   deinitCompute();
index 1970ed6cc26d492ef9bbbd5aa9ae7db61f1194a5..66a33d957a1cd15e589a7d0985f11a63076212af 100644 (file)
@@ -81,82 +81,37 @@ CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar
   pcl::Correspondence corr;
   unsigned int nr_valid_correspondences = 0;
 
-  // 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!
-  if (isSamePointType<PointSource, PointTarget>()) {
-    PointTarget pt;
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      float min_dist = std::numeric_limits<float>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        float cos_angle = (*source_normals_)[idx_i].normal_x *
-                              (*target_normals_)[nn_indices[j]].normal_x +
-                          (*source_normals_)[idx_i].normal_y *
-                              (*target_normals_)[nn_indices[j]].normal_y +
-                          (*source_normals_)[idx_i].normal_z *
-                              (*target_normals_)[nn_indices[j]].normal_z;
-        float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle);
-
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
+  // Iterate over the input set of source indices
+  for (const auto& idx_i : (*indices_)) {
+    const auto& pt = detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx_i);
+    tree_->nearestKSearch(pt, k_, nn_indices, nn_dists);
+
+    // Among the K nearest neighbours find the one with minimum perpendicular distance
+    // to the normal
+    float min_dist = std::numeric_limits<float>::max();
+
+    // Find the best correspondence
+    for (std::size_t j = 0; j < nn_indices.size(); j++) {
+      float cos_angle = (*source_normals_)[idx_i].normal_x *
+                            (*target_normals_)[nn_indices[j]].normal_x +
+                        (*source_normals_)[idx_i].normal_y *
+                            (*target_normals_)[nn_indices[j]].normal_y +
+                        (*source_normals_)[idx_i].normal_z *
+                            (*target_normals_)[nn_indices[j]].normal_z;
+      float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle);
+
+      if (dist < min_dist) {
+        min_dist = dist;
+        min_index = static_cast<int>(j);
       }
-      if (min_dist > max_distance)
-        continue;
-
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
     }
-  }
-  else {
-    PointTarget pt;
-
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      float min_dist = std::numeric_limits<float>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        PointSource pt_src;
-        // Copy the source data to a target PointTarget format so we can search in the
-        // tree
-        copyPoint((*input_)[idx_i], pt_src);
+    if (min_dist > max_distance)
+      continue;
 
-        float cos_angle = (*source_normals_)[idx_i].normal_x *
-                              (*target_normals_)[nn_indices[j]].normal_x +
-                          (*source_normals_)[idx_i].normal_y *
-                              (*target_normals_)[nn_indices[j]].normal_y +
-                          (*source_normals_)[idx_i].normal_z *
-                              (*target_normals_)[nn_indices[j]].normal_z;
-        float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle);
-
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
-      }
-      if (min_dist > max_distance)
-        continue;
-
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
-    }
+    corr.index_query = idx_i;
+    corr.index_match = nn_indices[min_index];
+    corr.distance = nn_dists[min_index]; // min_dist;
+    correspondences[nr_valid_correspondences++] = corr;
   }
   correspondences.resize(nr_valid_correspondences);
   deinitCompute();
@@ -188,98 +143,54 @@ CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar
   unsigned int nr_valid_correspondences = 0;
   int target_idx = 0;
 
-  // 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!
-  if (isSamePointType<PointSource, PointTarget>()) {
-    PointTarget pt;
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      float min_dist = std::numeric_limits<float>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        float cos_angle = (*source_normals_)[idx_i].normal_x *
-                              (*target_normals_)[nn_indices[j]].normal_x +
-                          (*source_normals_)[idx_i].normal_y *
-                              (*target_normals_)[nn_indices[j]].normal_y +
-                          (*source_normals_)[idx_i].normal_z *
-                              (*target_normals_)[nn_indices[j]].normal_z;
-        float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle);
-
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
+  // Iterate over the input set of source indices
+  for (const auto& idx_i : (*indices_)) {
+    // 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!
+    tree_->nearestKSearch(
+        detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx_i),
+        k_,
+        nn_indices,
+        nn_dists);
+
+    // Among the K nearest neighbours find the one with minimum perpendicular distance
+    // to the normal
+    float min_dist = std::numeric_limits<float>::max();
+
+    // Find the best correspondence
+    for (std::size_t j = 0; j < nn_indices.size(); j++) {
+      float cos_angle = (*source_normals_)[idx_i].normal_x *
+                            (*target_normals_)[nn_indices[j]].normal_x +
+                        (*source_normals_)[idx_i].normal_y *
+                            (*target_normals_)[nn_indices[j]].normal_y +
+                        (*source_normals_)[idx_i].normal_z *
+                            (*target_normals_)[nn_indices[j]].normal_z;
+      float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle);
+
+      if (dist < min_dist) {
+        min_dist = dist;
+        min_index = static_cast<int>(j);
       }
-      if (min_dist > max_distance)
-        continue;
-
-      // Check if the correspondence is reciprocal
-      target_idx = nn_indices[min_index];
-      tree_reciprocal_->nearestKSearch(
-          (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal);
-
-      if (idx_i != index_reciprocal[0])
-        continue;
-
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
-    }
-  }
-  else {
-    PointTarget pt;
-
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      float min_dist = std::numeric_limits<float>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        PointSource pt_src;
-        // Copy the source data to a target PointTarget format so we can search in the
-        // tree
-        copyPoint((*input_)[idx_i], pt_src);
-
-        float cos_angle = (*source_normals_)[idx_i].normal_x *
-                              (*target_normals_)[nn_indices[j]].normal_x +
-                          (*source_normals_)[idx_i].normal_y *
-                              (*target_normals_)[nn_indices[j]].normal_y +
-                          (*source_normals_)[idx_i].normal_z *
-                              (*target_normals_)[nn_indices[j]].normal_z;
-        float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle);
-
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
-      }
-      if (min_dist > max_distance)
-        continue;
-
-      // Check if the correspondence is reciprocal
-      target_idx = nn_indices[min_index];
-      tree_reciprocal_->nearestKSearch(
-          (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal);
-
-      if (idx_i != index_reciprocal[0])
-        continue;
-
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
     }
+    if (min_dist > max_distance)
+      continue;
+
+    // Check if the correspondence is reciprocal
+    target_idx = nn_indices[min_index];
+    tree_reciprocal_->nearestKSearch(
+        detail::pointCopyOrRef<PointSource, PointTarget>(target_, target_idx),
+        1,
+        index_reciprocal,
+        distance_reciprocal);
+
+    if (idx_i != index_reciprocal[0])
+      continue;
+
+    corr.index_query = idx_i;
+    corr.index_match = nn_indices[min_index];
+    corr.distance = nn_dists[min_index]; // min_dist;
+    correspondences[nr_valid_correspondences++] = corr;
   }
   correspondences.resize(nr_valid_correspondences);
   deinitCompute();
index 16f9daf0060b399d1cbcc4af14efc8f01ee45b60..8668e4bd0eb835628c4dead5ad4f322198e3e5a0 100644 (file)
@@ -81,92 +81,49 @@ CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar
   pcl::Correspondence corr;
   unsigned int nr_valid_correspondences = 0;
 
-  // 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!
-  if (isSamePointType<PointSource, PointTarget>()) {
-    PointTarget pt;
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      double min_dist = std::numeric_limits<double>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        // computing the distance between a point and a line in 3d.
-        // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html
-        pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x;
-        pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y;
-        pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z;
-
-        const NormalT& normal = (*source_normals_)[idx_i];
-        Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z);
-        Eigen::Vector3d V(pt.x, pt.y, pt.z);
-        Eigen::Vector3d C = N.cross(V);
-
-        // Check if we have a better correspondence
-        double dist = C.dot(C);
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
+  PointTarget pt;
+  // Iterate over the input set of source indices
+  for (const auto& idx_i : (*indices_)) {
+    // 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!
+    tree_->nearestKSearch(
+        detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx_i),
+        k_,
+        nn_indices,
+        nn_dists);
+
+    // Among the K nearest neighbours find the one with minimum perpendicular distance
+    // to the normal
+    double min_dist = std::numeric_limits<double>::max();
+
+    // Find the best correspondence
+    for (std::size_t j = 0; j < nn_indices.size(); j++) {
+      // computing the distance between a point and a line in 3d.
+      // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html
+      pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x;
+      pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y;
+      pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z;
+
+      const NormalT& normal = (*source_normals_)[idx_i];
+      Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z);
+      Eigen::Vector3d V(pt.x, pt.y, pt.z);
+      Eigen::Vector3d C = N.cross(V);
+
+      // Check if we have a better correspondence
+      double dist = C.dot(C);
+      if (dist < min_dist) {
+        min_dist = dist;
+        min_index = static_cast<int>(j);
       }
-      if (min_dist > max_distance)
-        continue;
-
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
     }
-  }
-  else {
-    PointTarget pt;
-
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      double min_dist = std::numeric_limits<double>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        PointSource pt_src;
-        // Copy the source data to a target PointTarget format so we can search in the
-        // tree
-        copyPoint((*input_)[idx_i], pt_src);
-
-        // computing the distance between a point and a line in 3d.
-        // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html
-        pt.x = (*target_)[nn_indices[j]].x - pt_src.x;
-        pt.y = (*target_)[nn_indices[j]].y - pt_src.y;
-        pt.z = (*target_)[nn_indices[j]].z - pt_src.z;
-
-        const NormalT& normal = (*source_normals_)[idx_i];
-        Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z);
-        Eigen::Vector3d V(pt.x, pt.y, pt.z);
-        Eigen::Vector3d C = N.cross(V);
-
-        // Check if we have a better correspondence
-        double dist = C.dot(C);
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
-      }
-      if (min_dist > max_distance)
-        continue;
+    if (min_dist > max_distance)
+      continue;
 
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
-    }
+    corr.index_query = idx_i;
+    corr.index_match = nn_indices[min_index];
+    corr.distance = nn_dists[min_index]; // min_dist;
+    correspondences[nr_valid_correspondences++] = corr;
   }
   correspondences.resize(nr_valid_correspondences);
   deinitCompute();
@@ -199,110 +156,61 @@ CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar
   unsigned int nr_valid_correspondences = 0;
   int target_idx = 0;
 
-  // 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!
-  if (isSamePointType<PointSource, PointTarget>()) {
-    PointTarget pt;
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      double min_dist = std::numeric_limits<double>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        // computing the distance between a point and a line in 3d.
-        // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html
-        pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x;
-        pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y;
-        pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z;
-
-        const NormalT& normal = (*source_normals_)[idx_i];
-        Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z);
-        Eigen::Vector3d V(pt.x, pt.y, pt.z);
-        Eigen::Vector3d C = N.cross(V);
-
-        // Check if we have a better correspondence
-        double dist = C.dot(C);
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
-      }
-      if (min_dist > max_distance)
-        continue;
-
-      // Check if the correspondence is reciprocal
-      target_idx = nn_indices[min_index];
-      tree_reciprocal_->nearestKSearch(
-          (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal);
-
-      if (idx_i != index_reciprocal[0])
-        continue;
-
-      // Correspondence IS reciprocal, save it and continue
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
-    }
-  }
-  else {
-    PointTarget pt;
-
-    // Iterate over the input set of source indices
-    for (const auto& idx_i : (*indices_)) {
-      tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists);
-
-      // Among the K nearest neighbours find the one with minimum perpendicular distance
-      // to the normal
-      double min_dist = std::numeric_limits<double>::max();
-
-      // Find the best correspondence
-      for (std::size_t j = 0; j < nn_indices.size(); j++) {
-        PointSource pt_src;
-        // Copy the source data to a target PointTarget format so we can search in the
-        // tree
-        copyPoint((*input_)[idx_i], pt_src);
-
-        // computing the distance between a point and a line in 3d.
-        // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html
-        pt.x = (*target_)[nn_indices[j]].x - pt_src.x;
-        pt.y = (*target_)[nn_indices[j]].y - pt_src.y;
-        pt.z = (*target_)[nn_indices[j]].z - pt_src.z;
-
-        const NormalT& normal = (*source_normals_)[idx_i];
-        Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z);
-        Eigen::Vector3d V(pt.x, pt.y, pt.z);
-        Eigen::Vector3d C = N.cross(V);
-
-        // Check if we have a better correspondence
-        double dist = C.dot(C);
-        if (dist < min_dist) {
-          min_dist = dist;
-          min_index = static_cast<int>(j);
-        }
+  PointTarget pt;
+  // Iterate over the input set of source indices
+  for (const auto& idx_i : (*indices_)) {
+    // 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!
+    tree_->nearestKSearch(
+        detail::pointCopyOrRef<PointTarget, PointSource>(input_, idx_i),
+        k_,
+        nn_indices,
+        nn_dists);
+
+    // Among the K nearest neighbours find the one with minimum perpendicular distance
+    // to the normal
+    double min_dist = std::numeric_limits<double>::max();
+
+    // Find the best correspondence
+    for (std::size_t j = 0; j < nn_indices.size(); j++) {
+      // computing the distance between a point and a line in 3d.
+      // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html
+      pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x;
+      pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y;
+      pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z;
+
+      const NormalT& normal = (*source_normals_)[idx_i];
+      Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z);
+      Eigen::Vector3d V(pt.x, pt.y, pt.z);
+      Eigen::Vector3d C = N.cross(V);
+
+      // Check if we have a better correspondence
+      double dist = C.dot(C);
+      if (dist < min_dist) {
+        min_dist = dist;
+        min_index = static_cast<int>(j);
       }
-      if (min_dist > max_distance)
-        continue;
-
-      // Check if the correspondence is reciprocal
-      target_idx = nn_indices[min_index];
-      tree_reciprocal_->nearestKSearch(
-          (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal);
-
-      if (idx_i != index_reciprocal[0])
-        continue;
-
-      // Correspondence IS reciprocal, save it and continue
-      corr.index_query = idx_i;
-      corr.index_match = nn_indices[min_index];
-      corr.distance = nn_dists[min_index]; // min_dist;
-      correspondences[nr_valid_correspondences++] = corr;
     }
+    if (min_dist > max_distance)
+      continue;
+
+    // Check if the correspondence is reciprocal
+    target_idx = nn_indices[min_index];
+    tree_reciprocal_->nearestKSearch(
+        detail::pointCopyOrRef<PointSource, PointTarget>(target_, target_idx),
+        1,
+        index_reciprocal,
+        distance_reciprocal);
+
+    if (idx_i != index_reciprocal[0])
+      continue;
+
+    // Correspondence IS reciprocal, save it and continue
+    corr.index_query = idx_i;
+    corr.index_match = nn_indices[min_index];
+    corr.distance = nn_dists[min_index]; // min_dist;
+    correspondences[nr_valid_correspondences++] = corr;
   }
   correspondences.resize(nr_valid_correspondences);
   deinitCompute();
index 218834836177be68f68f284148befbc578a6f965..f9e3d7e178d91a95d1a33b44cc249f22b1d0f392 100644 (file)
@@ -167,7 +167,7 @@ CorrespondenceRejectorPoly<SourceT, TargetT>::computeHistogram(
 
   // Accumulate
   for (const float& value : data)
-    ++result[std::min(last_idx, int(value * idx_per_val))];
+    ++result[std::min(last_idx, static_cast<int>(value * idx_per_val))];
 
   return (result);
 }
@@ -178,7 +178,7 @@ CorrespondenceRejectorPoly<SourceT, TargetT>::findThresholdOtsu(
     const std::vector<int>& histogram)
 {
   // Precision
-  const double eps = std::numeric_limits<double>::epsilon();
+  constexpr double eps = std::numeric_limits<double>::epsilon();
 
   // Histogram dimension
   const int nbins = static_cast<int>(histogram.size());
index a8e9d17e1c07260f6d7d62369c47a7e924cca5ca..3e1bcb62ed6acd88aea00ce216b3e081683ccff8 100644 (file)
@@ -53,7 +53,7 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
     const typename pcl::search::KdTree<PointT>::Ptr kdtree,
     MatricesVector& cloud_covariances)
 {
-  if (k_correspondences_ > int(cloud->size())) {
+  if (k_correspondences_ > static_cast<int>(cloud->size())) {
     PCL_ERROR("[pcl::GeneralizedIterativeClosestPoint::computeCovariances] Number or "
               "points in cloud (%lu) is less than k_correspondences_ (%lu)!\n",
               cloud->size(),
@@ -62,10 +62,8 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
   }
 
   Eigen::Vector3d mean;
-  pcl::Indices nn_indices;
-  nn_indices.reserve(k_correspondences_);
-  std::vector<float> nn_dist_sq;
-  nn_dist_sq.reserve(k_correspondences_);
+  pcl::Indices nn_indices(k_correspondences_);
+  std::vector<float> nn_dist_sq(k_correspondences_);
 
   // We should never get there but who knows
   if (cloud_covariances.size() < cloud->size())
@@ -85,20 +83,23 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
 
     // Find the covariance matrix
     for (int j = 0; j < k_correspondences_; j++) {
-      const PointT& pt = (*cloud)[nn_indices[j]];
+      // de-mean neighbourhood to avoid inaccuracies when far away from origin
+      const double ptx = (*cloud)[nn_indices[j]].x - query_point.x,
+                   pty = (*cloud)[nn_indices[j]].y - query_point.y,
+                   ptz = (*cloud)[nn_indices[j]].z - query_point.z;
 
-      mean[0] += pt.x;
-      mean[1] += pt.y;
-      mean[2] += pt.z;
+      mean[0] += ptx;
+      mean[1] += pty;
+      mean[2] += ptz;
 
-      cov(0, 0) += pt.x * pt.x;
+      cov(0, 0) += ptx * ptx;
 
-      cov(1, 0) += pt.y * pt.x;
-      cov(1, 1) += pt.y * pt.y;
+      cov(1, 0) += pty * ptx;
+      cov(1, 1) += pty * pty;
 
-      cov(2, 0) += pt.z * pt.x;
-      cov(2, 1) += pt.z * pt.y;
-      cov(2, 2) += pt.z * pt.z;
+      cov(2, 0) += ptz * ptx;
+      cov(2, 1) += ptz * pty;
+      cov(2, 2) += ptz * ptz;
     }
 
     mean /= static_cast<double>(k_correspondences_);
@@ -128,19 +129,17 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
 
 template <typename PointSource, typename PointTarget, typename Scalar>
 void
-GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeRDerivative(
-    const Vector6d& x, const Eigen::Matrix3d& dCost_dR_T, Vector6d& g) const
+GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::getRDerivatives(
+    double phi,
+    double theta,
+    double psi,
+    Eigen::Matrix3d& dR_dPhi,
+    Eigen::Matrix3d& dR_dTheta,
+    Eigen::Matrix3d& dR_dPsi) const
 {
-  Eigen::Matrix3d dR_dPhi;
-  Eigen::Matrix3d dR_dTheta;
-  Eigen::Matrix3d dR_dPsi;
-
-  double phi = x[3], theta = x[4], psi = x[5];
-
-  double cphi = std::cos(phi), sphi = sin(phi);
-  double ctheta = std::cos(theta), stheta = sin(theta);
-  double cpsi = std::cos(psi), spsi = sin(psi);
-
+  const double cphi = std::cos(phi), sphi = std::sin(phi);
+  const double ctheta = std::cos(theta), stheta = std::sin(theta);
+  const double cpsi = std::cos(psi), spsi = std::sin(psi);
   dR_dPhi(0, 0) = 0.;
   dR_dPhi(1, 0) = 0.;
   dR_dPhi(2, 0) = 0.;
@@ -176,10 +175,97 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeRDeri
   dR_dPsi(0, 2) = cpsi * sphi - cphi * spsi * stheta;
   dR_dPsi(1, 2) = sphi * spsi + cphi * cpsi * stheta;
   dR_dPsi(2, 2) = 0.;
+}
+
+template <typename PointSource, typename PointTarget, typename Scalar>
+void
+GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeRDerivative(
+    const Vector6d& x, const Eigen::Matrix3d& dCost_dR_T, Vector6d& g) const
+{
+  Eigen::Matrix3d dR_dPhi;
+  Eigen::Matrix3d dR_dTheta;
+  Eigen::Matrix3d dR_dPsi;
+  getRDerivatives(x[3], x[4], x[5], dR_dPhi, dR_dTheta, dR_dPsi);
 
-  g[3] = matricesInnerProd(dR_dPhi, dCost_dR_T);
-  g[4] = matricesInnerProd(dR_dTheta, dCost_dR_T);
-  g[5] = matricesInnerProd(dR_dPsi, dCost_dR_T);
+  g[3] = (dR_dPhi * dCost_dR_T).trace();
+  g[4] = (dR_dTheta * dCost_dR_T).trace();
+  g[5] = (dR_dPsi * dCost_dR_T).trace();
+}
+
+template <typename PointSource, typename PointTarget, typename Scalar>
+void
+GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::getR2ndDerivatives(
+    double phi,
+    double theta,
+    double psi,
+    Eigen::Matrix3d& ddR_dPhi_dPhi,
+    Eigen::Matrix3d& ddR_dPhi_dTheta,
+    Eigen::Matrix3d& ddR_dPhi_dPsi,
+    Eigen::Matrix3d& ddR_dTheta_dTheta,
+    Eigen::Matrix3d& ddR_dTheta_dPsi,
+    Eigen::Matrix3d& ddR_dPsi_dPsi) const
+{
+  const double sphi = std::sin(phi), stheta = std::sin(theta), spsi = std::sin(psi);
+  const double cphi = std::cos(phi), ctheta = std::cos(theta), cpsi = std::cos(psi);
+  ddR_dPhi_dPhi(0, 0) = 0.0;
+  ddR_dPhi_dPhi(1, 0) = 0.0;
+  ddR_dPhi_dPhi(2, 0) = 0.0;
+  ddR_dPhi_dPhi(0, 1) = -cpsi * stheta * sphi + spsi * cphi;
+  ddR_dPhi_dPhi(1, 1) = -cpsi * cphi - spsi * stheta * sphi;
+  ddR_dPhi_dPhi(2, 1) = -ctheta * sphi;
+  ddR_dPhi_dPhi(0, 2) = -spsi * sphi - cpsi * stheta * cphi;
+  ddR_dPhi_dPhi(1, 2) = -spsi * stheta * cphi + cpsi * sphi;
+  ddR_dPhi_dPhi(2, 2) = -ctheta * cphi;
+
+  ddR_dPhi_dTheta(0, 0) = 0.0;
+  ddR_dPhi_dTheta(1, 0) = 0.0;
+  ddR_dPhi_dTheta(2, 0) = 0.0;
+  ddR_dPhi_dTheta(0, 1) = cpsi * ctheta * cphi;
+  ddR_dPhi_dTheta(1, 1) = spsi * ctheta * cphi;
+  ddR_dPhi_dTheta(2, 1) = -stheta * cphi;
+  ddR_dPhi_dTheta(0, 2) = -cpsi * ctheta * sphi;
+  ddR_dPhi_dTheta(1, 2) = -spsi * ctheta * sphi;
+  ddR_dPhi_dTheta(2, 2) = stheta * sphi;
+
+  ddR_dPhi_dPsi(0, 0) = 0.0;
+  ddR_dPhi_dPsi(1, 0) = 0.0;
+  ddR_dPhi_dPsi(2, 0) = 0.0;
+  ddR_dPhi_dPsi(0, 1) = -spsi * stheta * cphi + cpsi * sphi;
+  ddR_dPhi_dPsi(1, 1) = spsi * sphi + cpsi * stheta * cphi;
+  ddR_dPhi_dPsi(2, 1) = 0.0;
+  ddR_dPhi_dPsi(0, 2) = cpsi * cphi + spsi * stheta * sphi;
+  ddR_dPhi_dPsi(1, 2) = -cpsi * stheta * sphi + spsi * cphi;
+  ddR_dPhi_dPsi(2, 2) = 0.0;
+
+  ddR_dTheta_dTheta(0, 0) = -cpsi * ctheta;
+  ddR_dTheta_dTheta(1, 0) = -spsi * ctheta;
+  ddR_dTheta_dTheta(2, 0) = stheta;
+  ddR_dTheta_dTheta(0, 1) = -cpsi * stheta * sphi;
+  ddR_dTheta_dTheta(1, 1) = -spsi * stheta * sphi;
+  ddR_dTheta_dTheta(2, 1) = -ctheta * sphi;
+  ddR_dTheta_dTheta(0, 2) = -cpsi * stheta * cphi;
+  ddR_dTheta_dTheta(1, 2) = -spsi * stheta * cphi;
+  ddR_dTheta_dTheta(2, 2) = -ctheta * cphi;
+
+  ddR_dTheta_dPsi(0, 0) = spsi * stheta;
+  ddR_dTheta_dPsi(1, 0) = -cpsi * stheta;
+  ddR_dTheta_dPsi(2, 0) = 0.0;
+  ddR_dTheta_dPsi(0, 1) = -spsi * ctheta * sphi;
+  ddR_dTheta_dPsi(1, 1) = cpsi * ctheta * sphi;
+  ddR_dTheta_dPsi(2, 1) = 0.0;
+  ddR_dTheta_dPsi(0, 2) = -spsi * ctheta * cphi;
+  ddR_dTheta_dPsi(1, 2) = cpsi * ctheta * cphi;
+  ddR_dTheta_dPsi(2, 2) = 0.0;
+
+  ddR_dPsi_dPsi(0, 0) = -cpsi * ctheta;
+  ddR_dPsi_dPsi(1, 0) = -spsi * ctheta;
+  ddR_dPsi_dPsi(2, 0) = 0.0;
+  ddR_dPsi_dPsi(0, 1) = -cpsi * stheta * sphi + spsi * cphi;
+  ddR_dPsi_dPsi(1, 1) = -cpsi * cphi - spsi * stheta * sphi;
+  ddR_dPsi_dPsi(2, 1) = 0.0;
+  ddR_dPsi_dPsi(0, 2) = -spsi * sphi - cpsi * stheta * cphi;
+  ddR_dPsi_dPsi(1, 2) = -spsi * stheta * cphi + cpsi * sphi;
+  ddR_dPsi_dPsi(2, 2) = 0.0;
 }
 
 template <typename PointSource, typename PointTarget, typename Scalar>
@@ -258,6 +344,116 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
                     "solver didn't converge!");
 }
 
+template <typename PointSource, typename PointTarget, typename Scalar>
+void
+GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
+    estimateRigidTransformationNewton(const PointCloudSource& cloud_src,
+                                      const pcl::Indices& indices_src,
+                                      const PointCloudTarget& cloud_tgt,
+                                      const pcl::Indices& indices_tgt,
+                                      Matrix4& transformation_matrix)
+{
+  //  need at least min_number_correspondences_ samples
+  if (indices_src.size() < min_number_correspondences_) {
+    PCL_THROW_EXCEPTION(NotEnoughPointsException,
+                        "[pcl::GeneralizedIterativeClosestPoint::"
+                        "estimateRigidTransformationNewton] Need "
+                        "at least "
+                            << min_number_correspondences_
+                            << " points to estimate a transform! "
+                               "Source and target have "
+                            << indices_src.size() << " points!");
+    return;
+  }
+  // Set the initial solution
+  Vector6d x = Vector6d::Zero();
+  // translation part
+  x[0] = transformation_matrix(0, 3);
+  x[1] = transformation_matrix(1, 3);
+  x[2] = transformation_matrix(2, 3);
+  // rotation part (Z Y X euler angles convention)
+  // see: https://en.wikipedia.org/wiki/Rotation_matrix#General_rotations
+  x[3] = std::atan2(transformation_matrix(2, 1), transformation_matrix(2, 2));
+  x[4] = std::asin(
+      std::min<double>(1.0, std::max<double>(-1.0, -transformation_matrix(2, 0))));
+  x[5] = std::atan2(transformation_matrix(1, 0), transformation_matrix(0, 0));
+
+  // Set temporary pointers
+  tmp_src_ = &cloud_src;
+  tmp_tgt_ = &cloud_tgt;
+  tmp_idx_src_ = &indices_src;
+  tmp_idx_tgt_ = &indices_tgt;
+
+  // Optimize using Newton
+  OptimizationFunctorWithIndices functor(this);
+  Eigen::Matrix<double, 6, 6> hessian;
+  Eigen::Matrix<double, 6, 1> gradient;
+  double current_x_value = functor(x);
+  functor.dfddf(x, gradient, hessian);
+  Eigen::Matrix<double, 6, 1> delta;
+  int inner_iterations_ = 0;
+  do {
+    ++inner_iterations_;
+    // compute descent direction from hessian and gradient. Take special measures if
+    // hessian is not positive-definite (positive Eigenvalues)
+    Eigen::SelfAdjointEigenSolver<Eigen::Matrix<double, 6, 6>> eigensolver(hessian);
+    Eigen::Matrix<double, 6, 6> inverted_eigenvalues =
+        Eigen::Matrix<double, 6, 6>::Zero();
+    for (int i = 0; i < 6; ++i) {
+      const double ev = eigensolver.eigenvalues()[i];
+      if (ev < 0)
+        inverted_eigenvalues(i, i) = 1.0 / eigensolver.eigenvalues()[5];
+      else
+        inverted_eigenvalues(i, i) = 1.0 / ev;
+    }
+    delta = eigensolver.eigenvectors() * inverted_eigenvalues *
+            eigensolver.eigenvectors().transpose() * gradient;
+
+    // simple line search to guarantee a decrease in the function value
+    double alpha = 1.0;
+    double candidate_x_value;
+    bool improvement_found = false;
+    for (int i = 0; i < 10; ++i, alpha /= 2) {
+      Vector6d candidate_x = x - alpha * delta;
+      candidate_x_value = functor(candidate_x);
+      if (candidate_x_value < current_x_value) {
+        PCL_DEBUG("[estimateRigidTransformationNewton] Using stepsize=%g, function "
+                  "value previously: %g, now: %g, "
+                  "improvement: %g\n",
+                  alpha,
+                  current_x_value,
+                  candidate_x_value,
+                  current_x_value - candidate_x_value);
+        x = candidate_x;
+        current_x_value = candidate_x_value;
+        improvement_found = true;
+        break;
+      }
+    }
+    if (!improvement_found) {
+      PCL_DEBUG("[estimateRigidTransformationNewton] finishing because no progress\n");
+      break;
+    }
+    functor.dfddf(x, gradient, hessian);
+    if (gradient.head<3>().norm() < translation_gradient_tolerance_ &&
+        gradient.tail<3>().norm() < rotation_gradient_tolerance_) {
+      PCL_DEBUG("[estimateRigidTransformationNewton] finishing because gradient below "
+                "threshold: translation: %g<%g, rotation: %g<%g\n",
+                gradient.head<3>().norm(),
+                translation_gradient_tolerance_,
+                gradient.tail<3>().norm(),
+                rotation_gradient_tolerance_);
+      break;
+    }
+  } while (inner_iterations_ < max_inner_iterations_);
+  PCL_DEBUG("[estimateRigidTransformationNewton] solver finished after %i iterations "
+            "(of max %i)\n",
+            inner_iterations_,
+            max_inner_iterations_);
+  transformation_matrix.setIdentity();
+  applyState(transformation_matrix, x);
+}
+
 template <typename PointSource, typename PointTarget, typename Scalar>
 inline double
 GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
@@ -284,7 +480,7 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
     Eigen::Vector3d Md(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * d);
     // increment= d'*Md/num_matches = d'*M*d/num_matches (we postpone
     // 1/num_matches after the loop closes)
-    f += double(d.transpose() * Md);
+    f += static_cast<double>(d.transpose() * Md);
   }
   return f / m;
 }
@@ -360,7 +556,7 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
     // Md = M*d
     Eigen::Vector3d Md(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * d);
     // Increment total error
-    f += double(d.transpose() * Md);
+    f += static_cast<double>(d.transpose() * Md);
     // Increment translation gradient
     // g.head<3> ()+= 2*M*d/num_matches (we postpone 2/num_matches after the loop
     // closes)
@@ -370,12 +566,158 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
     // Increment rotation gradient
     dCost_dR_T += p_base_src * Md.transpose();
   }
-  f /= double(m);
-  g.head<3>() *= double(2.0 / m);
+  f /= static_cast<double>(m);
+  g.head<3>() *= (2.0 / m);
   dCost_dR_T *= 2.0 / m;
   gicp_->computeRDerivative(x, dCost_dR_T, g);
 }
 
+template <typename PointSource, typename PointTarget, typename Scalar>
+inline void
+GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
+    OptimizationFunctorWithIndices::dfddf(const Vector6d& x,
+                                          Vector6d& gradient,
+                                          Matrix6d& hessian)
+{
+  Matrix4 transformation_matrix = gicp_->base_transformation_;
+  gicp_->applyState(transformation_matrix, x);
+  const Eigen::Matrix4f transformation_matrix_float =
+      transformation_matrix.template cast<float>();
+  const Eigen::Matrix4f base_transformation_float =
+      gicp_->base_transformation_.template cast<float>();
+  // Zero out gradient and hessian
+  gradient.setZero();
+  hessian.setZero();
+  // Helper matrices
+  Eigen::Matrix3d dR_dPhi;
+  Eigen::Matrix3d dR_dTheta;
+  Eigen::Matrix3d dR_dPsi;
+  gicp_->getRDerivatives(x[3], x[4], x[5], dR_dPhi, dR_dTheta, dR_dPsi);
+  Eigen::Matrix3d ddR_dPhi_dPhi;
+  Eigen::Matrix3d ddR_dPhi_dTheta;
+  Eigen::Matrix3d ddR_dPhi_dPsi;
+  Eigen::Matrix3d ddR_dTheta_dTheta;
+  Eigen::Matrix3d ddR_dTheta_dPsi;
+  Eigen::Matrix3d ddR_dPsi_dPsi;
+  gicp_->getR2ndDerivatives(x[3],
+                            x[4],
+                            x[5],
+                            ddR_dPhi_dPhi,
+                            ddR_dPhi_dTheta,
+                            ddR_dPhi_dPsi,
+                            ddR_dTheta_dTheta,
+                            ddR_dTheta_dPsi,
+                            ddR_dPsi_dPsi);
+  Eigen::Matrix3d dCost_dR_T = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d dCost_dR_T1 = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d dCost_dR_T2 = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d dCost_dR_T3 = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d dCost_dR_T1b = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d dCost_dR_T2b = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d dCost_dR_T3b = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d hessian_rot_phi = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d hessian_rot_theta = Eigen::Matrix3d::Zero();
+  Eigen::Matrix3d hessian_rot_psi = Eigen::Matrix3d::Zero();
+  Eigen::Matrix<double, 9, 6> hessian_rot_tmp = Eigen::Matrix<double, 9, 6>::Zero();
+
+  int m = static_cast<int>(gicp_->tmp_idx_src_->size());
+  for (int i = 0; i < m; ++i) {
+    // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp
+    const auto& src_idx = (*gicp_->tmp_idx_src_)[i];
+    Vector4fMapConst p_src = (*gicp_->tmp_src_)[src_idx].getVector4fMap();
+    // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp
+    Vector4fMapConst p_tgt =
+        (*gicp_->tmp_tgt_)[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap();
+    Eigen::Vector4f p_trans_src(transformation_matrix_float * p_src);
+    // The last coordinate is still guaranteed to be set to 1.0
+    // The d here is the negative of the d in the paper
+    const Eigen::Vector3d d(p_trans_src[0] - p_tgt[0],
+                            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
+    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();
+    dCost_dR_T1b += p_base_src[0] * M;
+    dCost_dR_T2b += p_base_src[1] * M;
+    dCost_dR_T3b += p_base_src[2] * M;
+    hessian_rot_tmp.noalias() +=
+        Eigen::Map<const Eigen::Matrix<double, 9, 1>>{M.data()} *
+        (Eigen::Matrix<double, 1, 6>() << p_base_src[0] * p_base_src[0],
+         p_base_src[0] * p_base_src[1],
+         p_base_src[0] * p_base_src[2],
+         p_base_src[1] * p_base_src[1],
+         p_base_src[1] * p_base_src[2],
+         p_base_src[2] * p_base_src[2])
+            .finished();
+  }
+  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
+  // translation-rotation hessian
+  dCost_dR_T1.row(0) = dCost_dR_T1b.col(0);
+  dCost_dR_T1.row(1) = dCost_dR_T2b.col(0);
+  dCost_dR_T1.row(2) = dCost_dR_T3b.col(0);
+  dCost_dR_T2.row(0) = dCost_dR_T1b.col(1);
+  dCost_dR_T2.row(1) = dCost_dR_T2b.col(1);
+  dCost_dR_T2.row(2) = dCost_dR_T3b.col(1);
+  dCost_dR_T3.row(0) = dCost_dR_T1b.col(2);
+  dCost_dR_T3.row(1) = dCost_dR_T2b.col(2);
+  dCost_dR_T3.row(2) = dCost_dR_T3b.col(2);
+  dCost_dR_T1 *= 2.0 / m;
+  dCost_dR_T2 *= 2.0 / m;
+  dCost_dR_T3 *= 2.0 / m;
+  hessian(3, 0) = (dR_dPhi * dCost_dR_T1).trace();
+  hessian(4, 0) = (dR_dTheta * dCost_dR_T1).trace();
+  hessian(5, 0) = (dR_dPsi * dCost_dR_T1).trace();
+  hessian(3, 1) = (dR_dPhi * dCost_dR_T2).trace();
+  hessian(4, 1) = (dR_dTheta * dCost_dR_T2).trace();
+  hessian(5, 1) = (dR_dPsi * dCost_dR_T2).trace();
+  hessian(3, 2) = (dR_dPhi * dCost_dR_T3).trace();
+  hessian(4, 2) = (dR_dTheta * dCost_dR_T3).trace();
+  hessian(5, 2) = (dR_dPsi * dCost_dR_T3).trace();
+  hessian.block<3, 3>(0, 3) = hessian.block<3, 3>(3, 0).transpose();
+  // rotation-rotation hessian
+  int lookup[3][3] = {{0, 1, 2}, {1, 3, 4}, {2, 4, 5}};
+  for (int l = 0; l < 3; ++l) {
+    for (int i = 0; i < 3; ++i) {
+      double phi_tmp = 0.0, theta_tmp = 0.0, psi_tmp = 0.0;
+      for (int j = 0; j < 3; ++j) {
+        for (int k = 0; k < 3; ++k) {
+          phi_tmp += hessian_rot_tmp(3 * j + i, lookup[l][k]) * dR_dPhi(j, k);
+          theta_tmp += hessian_rot_tmp(3 * j + i, lookup[l][k]) * dR_dTheta(j, k);
+          psi_tmp += hessian_rot_tmp(3 * j + i, lookup[l][k]) * dR_dPsi(j, k);
+        }
+      }
+      hessian_rot_phi(i, l) = phi_tmp;
+      hessian_rot_theta(i, l) = theta_tmp;
+      hessian_rot_psi(i, l) = psi_tmp;
+    }
+  }
+  hessian_rot_phi *= 2.0 / m;
+  hessian_rot_theta *= 2.0 / m;
+  hessian_rot_psi *= 2.0 / m;
+  hessian(3, 3) = (dR_dPhi.transpose() * hessian_rot_phi).trace() +
+                  (ddR_dPhi_dPhi * dCost_dR_T).trace();
+  hessian(3, 4) = (dR_dPhi.transpose() * hessian_rot_theta).trace() +
+                  (ddR_dPhi_dTheta * dCost_dR_T).trace();
+  hessian(3, 5) = (dR_dPhi.transpose() * hessian_rot_psi).trace() +
+                  (ddR_dPhi_dPsi * dCost_dR_T).trace();
+  hessian(4, 4) = (dR_dTheta.transpose() * hessian_rot_theta).trace() +
+                  (ddR_dTheta_dTheta * dCost_dR_T).trace();
+  hessian(4, 5) = (dR_dTheta.transpose() * hessian_rot_psi).trace() +
+                  (ddR_dTheta_dPsi * dCost_dR_T).trace();
+  hessian(5, 5) = (dR_dPsi.transpose() * hessian_rot_psi).trace() +
+                  (ddR_dPsi_dPsi * dCost_dR_T).trace();
+  hessian(4, 3) = hessian(3, 4);
+  hessian(5, 3) = hessian(3, 5);
+  hessian(5, 4) = hessian(4, 5);
+}
+
 template <typename PointSource, typename PointTarget, typename Scalar>
 inline BFGSSpace::Status
 GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
@@ -441,7 +783,8 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
     for (std::size_t i = 0; i < 4; i++)
       for (std::size_t j = 0; j < 4; j++)
         for (std::size_t k = 0; k < 4; k++)
-          transform_R(i, j) += double(transformation_(i, k)) * double(guess(k, j));
+          transform_R(i, j) += static_cast<double>(transformation_(i, k)) *
+                               static_cast<double>(guess(k, j));
 
     Eigen::Matrix3d R = transform_R.topLeftCorner<3, 3>();
 
index c26a966f2665351af65143d27d954832720999e5..d73e56c3c3d1fbfa1d02fd24d79f2b413f002cc3 100644 (file)
@@ -66,13 +66,9 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud<PointT>::ConstPtr& cloud
   std::vector<float> dists_sqr(2);
 
   pcl::utils::ignore(nr_threads);
-#pragma omp parallel for \
-  default(none) \
-  shared(tree, cloud) \
-  firstprivate(ids, dists_sqr) \
-  reduction(+:mean_dist, num) \
-  firstprivate(s, max_dist_sqr) \
-  num_threads(nr_threads)
+#pragma omp parallel for default(none) shared(tree, cloud)                             \
+    firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num)                         \
+    firstprivate(s, max_dist_sqr) num_threads(nr_threads)
   for (int i = 0; i < 1000; i++) {
     tree.nearestKSearch((*cloud)[rand() % s], 2, ids, dists_sqr);
     if (dists_sqr[1] < max_dist_sqr) {
@@ -105,19 +101,11 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud<PointT>::ConstPtr& cloud
 
   pcl::utils::ignore(nr_threads);
 #if OPENMP_LEGACY_CONST_DATA_SHARING_RULE
-#pragma omp parallel for \
-  default(none) \
-  shared(tree, cloud, indices) \
-  firstprivate(ids, dists_sqr) \
-  reduction(+:mean_dist, num) \
-  num_threads(nr_threads)
+#pragma omp parallel for default(none) shared(tree, cloud, indices)                    \
+    firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) num_threads(nr_threads)
 #else
-#pragma omp parallel for \
-  default(none) \
-  shared(tree, cloud, indices, s, max_dist_sqr) \
-  firstprivate(ids, dists_sqr) \
-  reduction(+:mean_dist, num) \
-  num_threads(nr_threads)
+#pragma omp parallel for default(none) shared(tree, cloud, indices, s, max_dist_sqr)   \
+    firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) num_threads(nr_threads)
 #endif
   for (int i = 0; i < 1000; i++) {
     tree.nearestKSearch((*cloud)[indices[rand() % s]], 2, ids, dists_sqr);
@@ -136,24 +124,8 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
     FPCSInitialAlignment()
 : source_normals_()
 , target_normals_()
-, nr_threads_(1)
-, approx_overlap_(0.5f)
-, delta_(1.f)
 , score_threshold_(std::numeric_limits<float>::max())
-, nr_samples_(0)
-, max_norm_diff_(90.f)
-, max_runtime_(0)
 , fitness_score_(std::numeric_limits<float>::max())
-, diameter_()
-, max_base_diameter_sqr_()
-, use_normals_(false)
-, normalize_delta_(true)
-, max_pair_diff_()
-, max_edge_diff_()
-, coincidation_limit_()
-, max_mse_()
-, max_inlier_dist_sqr_()
-, small_error_(0.00001f)
 {
   reg_name_ = "pcl::registration::FPCSInitialAlignment";
   max_iterations_ = 0;
@@ -181,7 +153,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
   {
 #ifdef _OPENMP
     const unsigned int seed =
-        static_cast<unsigned int>(std::time(NULL)) ^ omp_get_thread_num();
+        static_cast<unsigned int>(std::time(nullptr)) ^ omp_get_thread_num();
     std::srand(seed);
     PCL_DEBUG("[%s::computeTransformation] Using seed=%u\n", reg_name_.c_str(), seed);
 #pragma omp for schedule(dynamic)
@@ -264,7 +236,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
     target_cloud_updated_ = true;
   }
 
-  // if a sample size for the point clouds is given; prefarably no sampling of target
+  // 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());
@@ -290,8 +262,8 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
   }
 
   // set predefined variables
-  const int min_iterations = 4;
-  const float diameter_fraction = 0.3f;
+  constexpr int min_iterations = 4;
+  constexpr float diameter_fraction = 0.3f;
 
   // get diameter of input cloud (distance between farthest points)
   Eigen::Vector4f pt_min, pt_max;
@@ -312,9 +284,9 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
   // heuristic determination of number of trials to have high probability of finding a
   // good solution
   if (max_iterations_ == 0) {
-    float first_est =
-        std::log(small_error_) /
-        std::log(1.0 - std::pow((double)approx_overlap_, (double)min_iterations));
+    float first_est = std::log(small_error_) /
+                      std::log(1.0 - std::pow(static_cast<double>(approx_overlap_),
+                                              static_cast<double>(min_iterations)));
     max_iterations_ =
         static_cast<int>(first_est / (diameter_fraction * approx_overlap_ * 2.f));
   }
@@ -397,7 +369,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
 
     // check if at least one point fulfilled the conditions
     if (nearest_to_plane != std::numeric_limits<float>::max()) {
-      // order points to build largest quadrangle and calcuate intersection ratios of
+      // order points to build largest quadrangle and calculate intersection ratios of
       // diagonals
       setupBase(base_indices, ratio);
       return (0);
@@ -419,7 +391,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
 
   // choose random first point
   base_indices[0] = (*target_indices_)[rand() % nr_points];
-  auto* index1 = &base_indices[0];
+  auto* index1 = base_indices.data();
 
   // random search for 2 other points (as far away as overlap allows)
   for (int i = 0; i < ransac_iterations_; i++) {
@@ -691,9 +663,9 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
         pcl::Indices match_indices(4);
 
         match_indices[0] =
-            pairs_a[static_cast<int>(std::floor((float)(id / 2.f)))].index_match;
+            pairs_a[static_cast<int>(std::floor((id / 2.f)))].index_match;
         match_indices[1] =
-            pairs_a[static_cast<int>(std::floor((float)(id / 2.f)))].index_query;
+            pairs_a[static_cast<int>(std::floor((id / 2.f)))].index_query;
         match_indices[2] = pair.index_match;
         match_indices[3] = pair.index_query;
 
@@ -834,7 +806,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
                   const pcl::Correspondences& correspondences,
                   Eigen::Matrix4f& transformation)
 {
-  // only use triplet of points to simlify process (possible due to planar case)
+  // only use triplet of points to simplify process (possible due to planar case)
   pcl::Correspondences correspondences_temp = correspondences;
   correspondences_temp.erase(correspondences_temp.end() - 1);
 
index 8977e873101099de963acbcb6fa7b86b17cf0126..93a9bc570eeb91f97f850de8fb80981db5264ec4 100644 (file)
@@ -46,11 +46,7 @@ namespace registration {
 template <typename PointSource, typename PointTarget, typename NormalT, typename Scalar>
 KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::
     KFPCSInitialAlignment()
-: lower_trl_boundary_(-1.f)
-, upper_trl_boundary_(-1.f)
-, lambda_(0.5f)
-, use_trl_score_(false)
-, indices_validation_(new pcl::Indices)
+: indices_validation_(new pcl::Indices)
 {
   reg_name_ = "pcl::registration::KFPCSInitialAlignment";
 }
@@ -71,7 +67,7 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::initCompute()
   pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::
       initCompute();
 
-  // set the threshold values with respect to keypoint charactersitics
+  // set the threshold values with respect to keypoint characteristics
   max_pair_diff_ = delta_ * 1.414f;      // diff between 2 points of delta_ accuracy
   coincidation_limit_ = delta_ * 2.828f; // diff between diff of 2 points
   max_edge_diff_ =
@@ -95,7 +91,7 @@ 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 < std::size_t(ransac_iterations_))
+  if (nr_indices < static_cast<std::size_t>(ransac_iterations_))
     indices_validation_ = indices_;
   else
     for (int i = 0; i < ransac_iterations_; i++)
index e4cbac64cd8718035b0c63f7619d4388b6478fa9..2b48169f1b21a7ea926ec61173e351995b088f6f 100644 (file)
@@ -44,6 +44,7 @@
 #include <pcl/correspondence.h>
 
 namespace pcl {
+// NOLINTBEGIN(readability-container-data-pointer)
 
 template <typename PointSource, typename PointTarget, typename Scalar>
 void
@@ -158,8 +159,6 @@ IterativeClosestPoint<PointSource, PointTarget, Scalar>::computeTransformation(
   convergence_criteria_->setTranslationThreshold(transformation_epsilon_);
   if (transformation_rotation_epsilon_ > 0)
     convergence_criteria_->setRotationThreshold(transformation_rotation_epsilon_);
-  else
-    convergence_criteria_->setRotationThreshold(1.0 - transformation_epsilon_);
 
   // Repeat until convergence
   do {
@@ -225,7 +224,7 @@ IterativeClosestPoint<PointSource, PointTarget, Scalar>::computeTransformation(
 
     ++nr_iterations_;
 
-    // Update the vizualization of icp convergence
+    // Update the visualization of icp convergence
     if (update_visualizer_ != nullptr) {
       pcl::Indices source_indices_good, target_indices_good;
       for (const Correspondence& corr : *correspondences_) {
@@ -317,6 +316,7 @@ IterativeClosestPointWithNormals<PointSource, PointTarget, Scalar>::transformClo
 {
   pcl::transformPointCloudWithNormals(input, output, transform);
 }
+// NOLINTEND(readability-container-data-pointer)
 
 } // namespace pcl
 
index 0ed47185f4c3977d410367243fac486f01954b86..b1ac2ceda1f5109f81d93dff36f2c1edc9fa71eb 100644 (file)
@@ -244,7 +244,7 @@ JointIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeTransformat
 
     ++nr_iterations_;
 
-    // Update the vizualization of icp convergence
+    // Update the visualization of icp convergence
     // if (update_visualizer_ != 0)
     //  update_visualizer_(output, source_indices_good, *target_, target_indices_good );
 
index 5bc532d802fde016bf6adabab2249c1e00c113ae..faa1d6f575de421593353535ca123795d56c5038 100644 (file)
@@ -203,7 +203,7 @@ LUM<PointT>::getCorrespondences(const Vertex& source_vertex,
   if (source_vertex >= getNumVertices() || target_vertex >= getNumVertices()) {
     PCL_ERROR("[pcl::registration::LUM::getCorrespondences] You are attempting to get "
               "a set of correspondences between non-existing graph vertices.\n");
-    return (pcl::CorrespondencesPtr());
+    return {};
   }
   Edge e;
   bool present;
@@ -211,7 +211,7 @@ LUM<PointT>::getCorrespondences(const Vertex& source_vertex,
   if (!present) {
     PCL_ERROR("[pcl::registration::LUM::getCorrespondences] You are attempting to get "
               "a set of correspondences from a non-existing graph edge.\n");
-    return (pcl::CorrespondencesPtr());
+    return {};
   }
   return ((*slam_graph_)[e].corrs_);
 }
index 67033c8f78be913dd9c6be21180e2027925e4ea0..15ac5d68e4bcc0cf098c35fb9c1c592674ae14e5 100644 (file)
@@ -47,12 +47,6 @@ template <typename PointSource, typename PointTarget, typename Scalar>
 NormalDistributionsTransform<PointSource, PointTarget, Scalar>::
     NormalDistributionsTransform()
 : target_cells_()
-, resolution_(1.0f)
-, step_size_(0.1)
-, outlier_ratio_(0.55)
-, gauss_d1_()
-, gauss_d2_()
-, trans_likelihood_()
 {
   reg_name_ = "NormalDistributionsTransform";
 
@@ -681,13 +675,13 @@ NormalDistributionsTransform<PointSource, PointTarget, Scalar>::computeStepLengt
 
   // The Search Algorithm for T(mu) [More, Thuente 1994]
 
-  const int max_step_iterations = 10;
+  constexpr int max_step_iterations = 10;
   int step_iterations = 0;
 
-  // Sufficient decreace constant, Equation 1.1 [More, Thuete 1994]
-  const double mu = 1.e-4;
+  // Sufficient decrease constant, Equation 1.1 [More, Thuete 1994]
+  constexpr double mu = 1.e-4;
   // Curvature condition constant, Equation 1.2 [More, Thuete 1994]
-  const double nu = 0.9;
+  constexpr double nu = 0.9;
 
   // Initial endpoints of Interval I,
   double a_l = 0, a_u = 0;
@@ -718,7 +712,7 @@ NormalDistributionsTransform<PointSource, PointTarget, Scalar>::computeStepLengt
 
   // Updates score, gradient and hessian.  Hessian calculation is unnecessary but
   // testing showed that most step calculations use the initial step suggestion and
-  // recalculation the reusable portions of the hessian would intail more computation
+  // recalculation the reusable portions of the hessian would entail more computation
   // time.
   score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, true);
 
@@ -732,7 +726,7 @@ NormalDistributionsTransform<PointSource, PointTarget, Scalar>::computeStepLengt
   // Calculate psi'(alpha_t)
   double d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu);
 
-  // Iterate until max number of iterations, interval convergance or a value satisfies
+  // Iterate until max number of iterations, interval convergence or a value satisfies
   // the sufficient decrease, Equation 1.1, and curvature condition, Equation 1.2 [More,
   // Thuente 1994]
   while (!interval_converged && step_iterations < max_step_iterations &&
index 0285757d7c8ac630444869b5d6018e26315dc527..a4b5dd42241dbd6f6d4eb6f503b9d3bdf2545823 100644 (file)
@@ -99,7 +99,7 @@ class NormalDist {
   using PointCloud = pcl::PointCloud<PointT>;
 
 public:
-  NormalDist() : min_n_(3), n_(0) {}
+  NormalDist() = default;
 
   /** \brief Store a point index to use later for estimating distribution parameters.
    * \param[in] i Point index to store
@@ -121,8 +121,8 @@ public:
     Eigen::Vector2d sx = Eigen::Vector2d::Zero();
     Eigen::Matrix2d sxx = Eigen::Matrix2d::Zero();
 
-    for (auto i = pt_indices_.cbegin(); i != pt_indices_.cend(); i++) {
-      Eigen::Vector2d p(cloud[*i].x, cloud[*i].y);
+    for (const auto& pt_index : pt_indices_) {
+      Eigen::Vector2d p(cloud[pt_index].x, cloud[pt_index].y);
       sx += p;
       sxx += p * p.transpose();
     }
@@ -176,7 +176,7 @@ public:
     const Eigen::Vector2d p_xy(transformed_pt.x, transformed_pt.y);
     const Eigen::Vector2d q = p_xy - mean_;
     const Eigen::RowVector2d qt_cvi(q.transpose() * covar_inv_);
-    const double exp_qt_cvi_q = std::exp(-0.5 * double(qt_cvi * q));
+    const double exp_qt_cvi_q = std::exp(-0.5 * static_cast<double>(qt_cvi * q));
     r.value = -exp_qt_cvi_q;
 
     Eigen::Matrix<double, 2, 3> jacobian;
@@ -184,7 +184,7 @@ public:
         x * cos_theta - y * sin_theta;
 
     for (std::size_t i = 0; i < 3; i++)
-      r.grad[i] = double(qt_cvi * jacobian.col(i)) * exp_qt_cvi_q;
+      r.grad[i] = static_cast<double>(qt_cvi * jacobian.col(i)) * exp_qt_cvi_q;
 
     // second derivative only for i == j == 2:
     const Eigen::Vector2d d2q_didj(y * sin_theta - x * cos_theta,
@@ -194,7 +194,8 @@ public:
       for (std::size_t j = 0; j < 3; j++)
         r.hessian(i, j) =
             -exp_qt_cvi_q *
-            (double(-qt_cvi * jacobian.col(i)) * double(-qt_cvi * jacobian.col(j)) +
+            (static_cast<double>(-qt_cvi * jacobian.col(i)) *
+                 static_cast<double>(-qt_cvi * jacobian.col(j)) +
              (-qt_cvi * ((i == 2 && j == 2) ? d2q_didj : Eigen::Vector2d::Zero())) +
              (-jacobian.col(j).transpose() * covar_inv_ * jacobian.col(i)));
 
@@ -202,9 +203,9 @@ public:
   }
 
 protected:
-  const std::size_t min_n_;
+  const std::size_t min_n_{3};
 
-  std::size_t n_;
+  std::size_t n_{0};
   std::vector<std::size_t> pt_indices_;
   Eigen::Vector2d mean_;
   Eigen::Matrix2d covar_inv_;
index 21cff70004cbed99900d75c676fb25db0efa15fb..685c4b827670e0e81b9a374ffb8411a8ace269ec 100644 (file)
@@ -78,14 +78,23 @@ pcl::PPFRegistration<PointSource, PointTarget>::computeTransformation(
   }
 
   const auto aux_size = static_cast<std::size_t>(
-      std::floor(2 * M_PI / search_method_->getAngleDiscretizationStep()));
+      std::ceil(2 * M_PI / search_method_->getAngleDiscretizationStep()));
+  if (std::abs(std::round(2 * M_PI / search_method_->getAngleDiscretizationStep()) -
+               2 * M_PI / search_method_->getAngleDiscretizationStep()) > 0.1) {
+    PCL_WARN("[pcl::PPFRegistration::computeTransformation] The chosen angle "
+             "discretization step (%g) does not result in a uniform discretization. "
+             "Consider using e.g. 2pi/%zu or 2pi/%zu\n",
+             search_method_->getAngleDiscretizationStep(),
+             aux_size - 1,
+             aux_size);
+  }
 
   const std::vector<unsigned int> tmp_vec(aux_size, 0);
   std::vector<std::vector<unsigned int>> accumulator_array(input_->size(), tmp_vec);
 
-  PCL_INFO("Accumulator array size: %u x %u.\n",
-           accumulator_array.size(),
-           accumulator_array.back().size());
+  PCL_DEBUG("[PPFRegistration] Accumulator array size: %u x %u.\n",
+            accumulator_array.size(),
+            accumulator_array.back().size());
 
   PoseWithVotesList voted_poses;
   // Consider every <scene_reference_point_sampling_rate>-th point as the reference
@@ -137,9 +146,10 @@ pcl::PPFRegistration<PointSource, PointTarget>::computeTransformation(
           search_method_->nearestNeighborSearch(f1, f2, f3, f4, nearest_indices);
 
           // Compute alpha_s angle
-          Eigen::Vector3f scene_point = (*target_)[scene_point_index].getVector3fMap();
+          const Eigen::Vector3f scene_point =
+              (*target_)[scene_point_index].getVector3fMap();
 
-          Eigen::Vector3f scene_point_transformed = transform_sg * scene_point;
+          const Eigen::Vector3f scene_point_transformed = transform_sg * scene_point;
           float alpha_s =
               std::atan2(-scene_point_transformed(2), scene_point_transformed(1));
           if (std::sin(alpha_s) * scene_point_transformed(2) < 0.0f)
@@ -173,55 +183,60 @@ pcl::PPFRegistration<PointSource, PointTarget>::computeTransformation(
       }
     }
 
-    std::size_t max_votes_i = 0, max_votes_j = 0;
+    // the paper says: "For stability reasons, all peaks that received a certain amount
+    // of votes relative to the maximum peak are used." No specific value is mentioned,
+    // but 90% seems good
     unsigned int max_votes = 0;
-
-    for (std::size_t i = 0; i < accumulator_array.size(); ++i)
-      for (std::size_t j = 0; j < accumulator_array.back().size(); ++j) {
-        if (accumulator_array[i][j] > max_votes) {
+    const std::size_t size_i = accumulator_array.size(),
+                      size_j = accumulator_array.back().size();
+    for (std::size_t i = 0; i < size_i; ++i)
+      for (std::size_t j = 0; j < size_j; ++j) {
+        if (accumulator_array[i][j] > max_votes)
           max_votes = accumulator_array[i][j];
-          max_votes_i = i;
-          max_votes_j = j;
+      }
+    max_votes *= 0.9;
+    for (std::size_t i = 0; i < size_i; ++i)
+      for (std::size_t j = 0; j < size_j; ++j) {
+        if (accumulator_array[i][j] >= max_votes) {
+          const Eigen::Vector3f model_reference_point = (*input_)[i].getVector3fMap(),
+                                model_reference_normal =
+                                    (*input_)[i].getNormalVector3fMap();
+          const float rotation_angle_mg =
+              std::acos(model_reference_normal.dot(Eigen::Vector3f::UnitX()));
+          const bool parallel_to_x_mg = (model_reference_normal.y() == 0.0f &&
+                                         model_reference_normal.z() == 0.0f);
+          const Eigen::Vector3f rotation_axis_mg =
+              (parallel_to_x_mg)
+                  ? (Eigen::Vector3f::UnitY())
+                  : (model_reference_normal.cross(Eigen::Vector3f::UnitX())
+                         .normalized());
+          const Eigen::AngleAxisf rotation_mg(rotation_angle_mg, rotation_axis_mg);
+          const Eigen::Affine3f transform_mg(
+              Eigen::Translation3f(rotation_mg * ((-1) * model_reference_point)) *
+              rotation_mg);
+          const Eigen::Affine3f max_transform =
+              transform_sg.inverse() *
+              Eigen::AngleAxisf((static_cast<float>(j + 0.5) *
+                                     search_method_->getAngleDiscretizationStep() -
+                                 M_PI),
+                                Eigen::Vector3f::UnitX()) *
+              transform_mg;
+
+          voted_poses.push_back(PoseWithVotes(max_transform, accumulator_array[i][j]));
         }
         // Reset accumulator_array for the next set of iterations with a new scene
         // reference point
         accumulator_array[i][j] = 0;
       }
-
-    Eigen::Vector3f model_reference_point = (*input_)[max_votes_i].getVector3fMap(),
-                    model_reference_normal =
-                        (*input_)[max_votes_i].getNormalVector3fMap();
-    float rotation_angle_mg =
-        std::acos(model_reference_normal.dot(Eigen::Vector3f::UnitX()));
-    bool parallel_to_x_mg =
-        (model_reference_normal.y() == 0.0f && model_reference_normal.z() == 0.0f);
-    Eigen::Vector3f rotation_axis_mg =
-        (parallel_to_x_mg)
-            ? (Eigen::Vector3f::UnitY())
-            : (model_reference_normal.cross(Eigen::Vector3f::UnitX()).normalized());
-    Eigen::AngleAxisf rotation_mg(rotation_angle_mg, rotation_axis_mg);
-    Eigen::Affine3f transform_mg(
-        Eigen::Translation3f(rotation_mg * ((-1) * model_reference_point)) *
-        rotation_mg);
-    Eigen::Affine3f max_transform =
-        transform_sg.inverse() *
-        Eigen::AngleAxisf((static_cast<float>(max_votes_j + 0.5) *
-                               search_method_->getAngleDiscretizationStep() -
-                           M_PI),
-                          Eigen::Vector3f::UnitX()) *
-        transform_mg;
-
-    voted_poses.push_back(PoseWithVotes(max_transform, max_votes));
   }
-  PCL_DEBUG("Done with the Hough Transform ...\n");
+  PCL_DEBUG("[PPFRegistration] Done with the Hough Transform ...\n");
 
   // Cluster poses for filtering out outliers and obtaining more precise results
-  PoseWithVotesList results;
-  clusterPoses(voted_poses, results);
+  clusterPoses(voted_poses, best_pose_candidates);
 
-  pcl::transformPointCloud(*input_, output, results.front().pose);
+  pcl::transformPointCloud(*input_, output, best_pose_candidates.front().pose);
 
-  transformation_ = final_transformation_ = results.front().pose.matrix();
+  transformation_ = final_transformation_ = best_pose_candidates.front().pose.matrix();
   converged_ = true;
 }
 
@@ -232,7 +247,8 @@ pcl::PPFRegistration<PointSource, PointTarget>::clusterPoses(
     typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotesList& poses,
     typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotesList& result)
 {
-  PCL_INFO("Clustering poses ...\n");
+  PCL_DEBUG("[PPFRegistration] Clustering poses (initially got %zu poses)\n",
+            poses.size());
   // Start off by sorting the poses by the number of votes
   sort(poses.begin(), poses.end(), poseWithVotesCompareFunction);
 
@@ -240,17 +256,37 @@ pcl::PPFRegistration<PointSource, PointTarget>::clusterPoses(
   std::vector<std::pair<std::size_t, unsigned int>> cluster_votes;
   for (std::size_t poses_i = 0; poses_i < poses.size(); ++poses_i) {
     bool found_cluster = false;
+    float lowest_position_diff = std::numeric_limits<float>::max(),
+          lowest_rotation_diff_angle = std::numeric_limits<float>::max();
+    std::size_t best_cluster = 0;
     for (std::size_t clusters_i = 0; clusters_i < clusters.size(); ++clusters_i) {
+      // if a pose can be added to more than one cluster (posesWithinErrorBounds returns
+      // true), then add it to the one where position and rotation difference are
+      // smallest
+      float position_diff, rotation_diff_angle;
       if (posesWithinErrorBounds(poses[poses_i].pose,
-                                 clusters[clusters_i].front().pose)) {
-        found_cluster = true;
-        clusters[clusters_i].push_back(poses[poses_i]);
-        cluster_votes[clusters_i].second += poses[poses_i].votes;
-        break;
+                                 clusters[clusters_i].front().pose,
+                                 position_diff,
+                                 rotation_diff_angle)) {
+        if (!found_cluster) {
+          found_cluster = true;
+          best_cluster = clusters_i;
+          lowest_position_diff = position_diff;
+          lowest_rotation_diff_angle = rotation_diff_angle;
+        }
+        else if (position_diff < lowest_position_diff &&
+                 rotation_diff_angle < lowest_rotation_diff_angle) {
+          best_cluster = clusters_i;
+          lowest_position_diff = position_diff;
+          lowest_rotation_diff_angle = rotation_diff_angle;
+        }
       }
     }
-
-    if (!found_cluster) {
+    if (found_cluster) {
+      clusters[best_cluster].push_back(poses[poses_i]);
+      cluster_votes[best_cluster].second += poses[poses_i].votes;
+    }
+    else {
       // Create a new cluster with the current pose
       PoseWithVotesList new_cluster;
       new_cluster.push_back(poses[poses_i]);
@@ -259,28 +295,30 @@ pcl::PPFRegistration<PointSource, PointTarget>::clusterPoses(
           clusters.size() - 1, poses[poses_i].votes));
     }
   }
+  PCL_DEBUG("[PPFRegistration] %zu poses remaining after clustering. Now averaging "
+            "each cluster and removing clusters with too few votes.\n",
+            clusters.size());
 
   // Sort clusters by total number of votes
   std::sort(cluster_votes.begin(), cluster_votes.end(), clusterVotesCompareFunction);
   // Compute pose average and put them in result vector
-  /// @todo some kind of threshold for determining whether a cluster has enough votes or
-  /// not... now just taking the first three clusters
   result.clear();
-  std::size_t max_clusters = (clusters.size() < 3) ? clusters.size() : 3;
-  for (std::size_t cluster_i = 0; cluster_i < max_clusters; ++cluster_i) {
-    PCL_INFO("Winning cluster has #votes: %d and #poses voted: %d.\n",
-             cluster_votes[cluster_i].second,
-             clusters[cluster_votes[cluster_i].first].size());
+  for (std::size_t cluster_i = 0; cluster_i < clusters.size(); ++cluster_i) {
+    // Remove all clusters that have less than 10% of the votes of the peak cluster.
+    // This way, if there is e.g. one cluster with far more votes than all other
+    // clusters, only that one is kept.
+    if (cluster_votes[cluster_i].second < 0.1 * cluster_votes[0].second)
+      continue;
+    PCL_DEBUG("Winning cluster has #votes: %d and #poses voted: %d.\n",
+              cluster_votes[cluster_i].second,
+              clusters[cluster_votes[cluster_i].first].size());
     Eigen::Vector3f translation_average(0.0, 0.0, 0.0);
     Eigen::Vector4f rotation_average(0.0, 0.0, 0.0, 0.0);
-    for (typename PoseWithVotesList::iterator v_it =
-             clusters[cluster_votes[cluster_i].first].begin();
-         v_it != clusters[cluster_votes[cluster_i].first].end();
-         ++v_it) {
-      translation_average += v_it->pose.translation();
+    for (const auto& vote : clusters[cluster_votes[cluster_i].first]) {
+      translation_average += vote.pose.translation();
       /// averaging rotations by just averaging the quaternions in 4D space - reference
       /// "On Averaging Rotations" by CLAUS GRAMKOW
-      rotation_average += Eigen::Quaternionf(v_it->pose.rotation()).coeffs();
+      rotation_average += Eigen::Quaternionf(vote.pose.rotation()).coeffs();
     }
 
     translation_average /=
@@ -301,13 +339,16 @@ pcl::PPFRegistration<PointSource, PointTarget>::clusterPoses(
 template <typename PointSource, typename PointTarget>
 bool
 pcl::PPFRegistration<PointSource, PointTarget>::posesWithinErrorBounds(
-    Eigen::Affine3f& pose1, Eigen::Affine3f& pose2)
+    Eigen::Affine3f& pose1,
+    Eigen::Affine3f& pose2,
+    float& position_diff,
+    float& rotation_diff_angle)
 {
-  float position_diff = (pose1.translation() - pose2.translation()).norm();
+  position_diff = (pose1.translation() - pose2.translation()).norm();
   Eigen::AngleAxisf rotation_diff_mat(
       (pose1.rotation().inverse().lazyProduct(pose2.rotation()).eval()));
 
-  float rotation_diff_angle = std::abs(rotation_diff_mat.angle());
+  rotation_diff_angle = std::abs(rotation_diff_mat.angle());
 
   return (position_diff < clustering_position_diff_threshold_ &&
           rotation_diff_angle < clustering_rotation_diff_threshold_);
index 0440178457a012ff2c478f52e7d657a5ae73beaf..ba7b4eebd0a7d8bcc105c4b86e1fbafc1f6ccaa2 100644 (file)
@@ -131,12 +131,7 @@ PyramidFeatureHistogram<PointFeature>::comparePyramidFeatureHistograms(
 
 template <typename PointFeature>
 PyramidFeatureHistogram<PointFeature>::PyramidFeatureHistogram()
-: nr_dimensions(0)
-, nr_levels(0)
-, nr_features(0)
-, feature_representation_(new DefaultPointRepresentation<PointFeature>)
-, is_computed_(false)
-, hist_levels()
+: feature_representation_(new DefaultPointRepresentation<PointFeature>), hist_levels()
 {}
 
 template <typename PointFeature>
index 1abc953f002f4c25b30733ed4afcadc3495bfd40..24a454efabd394958f01cafc342d987fa3e50d65 100644 (file)
@@ -124,8 +124,8 @@ Registration<PointSource, PointTarget, Scalar>::getFitnessScore(
 {
   unsigned int nr_elem =
       static_cast<unsigned int>(std::min(distances_a.size(), distances_b.size()));
-  Eigen::VectorXf map_a = Eigen::VectorXf::Map(&distances_a[0], nr_elem);
-  Eigen::VectorXf map_b = Eigen::VectorXf::Map(&distances_b[0], nr_elem);
+  Eigen::VectorXf map_a = Eigen::VectorXf::Map(distances_a.data(), nr_elem);
+  Eigen::VectorXf map_b = Eigen::VectorXf::Map(distances_b.data(), nr_elem);
   return (static_cast<double>((map_a - map_b).sum()) / static_cast<double>(nr_elem));
 }
 
index ddfc4be6a8773909a7738e7b1f6d5ddb9b43c636..a21327ba8904c7bf4aee548ca2cda1353f805c9c 100644 (file)
@@ -194,14 +194,15 @@ TransformationEstimationDualQuaternion<PointSource, PointTarget, Scalar>::
   C2 *= 2.0;
 
   const Eigen::Matrix<double, 4, 4> A =
-      (0.25 / double(npts)) * C2.transpose() * C2 - C1;
+      (0.25 / static_cast<double>(npts)) * C2.transpose() * C2 - C1;
 
   const Eigen::EigenSolver<Eigen::Matrix<double, 4, 4>> es(A);
 
   ptrdiff_t i;
   es.eigenvalues().real().maxCoeff(&i);
   const Eigen::Matrix<double, 4, 1> qmat = es.eigenvectors().col(i).real();
-  const Eigen::Matrix<double, 4, 1> smat = -(0.5 / double(npts)) * C2 * qmat;
+  const Eigen::Matrix<double, 4, 1> smat =
+      -(0.5 / static_cast<double>(npts)) * C2 * qmat;
 
   const Eigen::Quaternion<double> q(qmat(3), qmat(0), qmat(1), qmat(2));
   const Eigen::Quaternion<double> s(smat(3), smat(0), smat(1), smat(2));
index fe01a34a6339be5819c7874c18bca605b2646a15..21ccee1f76ac294cfc0390a3aac3b55c566e06ba 100644 (file)
@@ -50,8 +50,6 @@ pcl::registration::TransformationEstimationLM<PointSource, PointTarget, MatScala
     TransformationEstimationLM()
 : tmp_src_()
 , tmp_tgt_()
-, tmp_idx_src_()
-, tmp_idx_tgt_()
 , warp_point_(new WarpPointRigid6D<PointSource, PointTarget, MatScalar>){};
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -294,7 +292,7 @@ pcl::registration::TransformationEstimationLM<PointSource, PointTarget, MatScala
   return (0);
 }
 
-//#define PCL_INSTANTIATE_TransformationEstimationLM(T,U) template class PCL_EXPORTS
-// pcl::registration::TransformationEstimationLM<T,U>;
+// #define PCL_INSTANTIATE_TransformationEstimationLM(T,U) template class PCL_EXPORTS
+//  pcl::registration::TransformationEstimationLM<T,U>;
 
 #endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_HPP_ */
index ffa983dfd42c4171ac81cf9e6780aed3e139da39..a31b8ec010ff0d59612576b24abb26123d1a3d36 100644 (file)
@@ -53,10 +53,8 @@ pcl::registration::TransformationEstimationPointToPlaneWeighted<
     MatScalar>::TransformationEstimationPointToPlaneWeighted()
 : tmp_src_()
 , tmp_tgt_()
-, tmp_idx_src_()
-, tmp_idx_tgt_()
 , warp_point_(new WarpPointRigid6D<PointSource, PointTarget, MatScalar>)
-, use_correspondence_weights_(true){};
+{}
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointSource, typename PointTarget, typename MatScalar>
index 04489fde199a50337e6e8269dc2fabfe74ef3405..ad928d8729ffd9f8091e58b7f72c6f2c5eb0040a 100644 (file)
@@ -111,6 +111,8 @@ public:
   /** \brief Set registration instance used to align clouds */
   inline void setRegistration(RegistrationPtr);
 
+  PCL_MAKE_ALIGNED_OPERATOR_NEW
+
 protected:
   /** \brief last registered point cloud */
   PointCloudConstPtr last_cloud_;
index 97d2df644080be5e01c7545a10c3d303d19838e9..f6354ae047b30f24e0912749ddc2f50a6f5f600b 100644 (file)
@@ -139,7 +139,7 @@ public:
 
   /** \brief Empty constructor.
    */
-  LUM() : slam_graph_(new SLAMGraph), max_iterations_(5), convergence_threshold_(0.0) {}
+  LUM() : slam_graph_(new SLAMGraph) {}
 
   /** \brief Set the internal SLAM graph structure.
    * \details All data used and produced by LUM is stored in this boost::adjacency_list.
@@ -343,10 +343,10 @@ private:
   SLAMGraphPtr slam_graph_;
 
   /** \brief The maximum number of iterations for the compute() method. */
-  int max_iterations_;
+  int max_iterations_{5};
 
   /** \brief The convergence threshold for the summed vector lengths of all poses. */
-  float convergence_threshold_;
+  float convergence_threshold_{0.0};
 };
 } // namespace registration
 } // namespace pcl
index dad439e3d6c2981665578668c762b5147ec707fb..7fbb6403b32b69acd447610a1cdbba7764e225cc 100644 (file)
@@ -60,6 +60,7 @@ namespace pcl {
  * Optimization Theory and Methods: Nonlinear Programming. 89-100
  * \note Math refactored by Todor Stoyanov.
  * \author Brian Okorn (Space and Naval Warfare Systems Center Pacific)
+ * \ingroup registration
  */
 template <typename PointSource, typename PointTarget, typename Scalar = float>
 class NormalDistributionsTransform
@@ -228,9 +229,9 @@ public:
   convertTransform(const Eigen::Matrix<double, 6, 1>& x, Affine3& trans)
   {
     trans = Eigen::Translation<Scalar, 3>(x.head<3>().cast<Scalar>()) *
-            Eigen::AngleAxis<Scalar>(Scalar(x(3)), Vector3::UnitX()) *
-            Eigen::AngleAxis<Scalar>(Scalar(x(4)), Vector3::UnitY()) *
-            Eigen::AngleAxis<Scalar>(Scalar(x(5)), Vector3::UnitZ());
+            Eigen::AngleAxis<Scalar>(static_cast<Scalar>(x(3)), Vector3::UnitX()) *
+            Eigen::AngleAxis<Scalar>(static_cast<Scalar>(x(4)), Vector3::UnitY()) *
+            Eigen::AngleAxis<Scalar>(static_cast<Scalar>(x(5)), Vector3::UnitZ());
   }
 
   /** \brief Convert 6 element transformation vector to transformation matrix.
@@ -404,7 +405,7 @@ protected:
    * Thuente 1994) and \f$ \delta \vec{p} \f$ normalized in Algorithm 2
    * [Magnusson 2009]
    * \param[in] step_init initial step length estimate, \f$ \alpha_0 \f$ in
-   * Moore-Thuente (1994) and the noramal of \f$ \delta \vec{p} \f$ in Algorithm
+   * Moore-Thuente (1994) and the normal of \f$ \delta \vec{p} \f$ in Algorithm
    * 2 [Magnusson 2009]
    * \param[in] step_max maximum step length, \f$ \alpha_max \f$ in
    * Moore-Thuente (1994)
@@ -556,18 +557,18 @@ protected:
   TargetGrid target_cells_;
 
   /** \brief The side length of voxels. */
-  float resolution_;
+  float resolution_{1.0f};
 
   /** \brief The maximum step length. */
-  double step_size_;
+  double step_size_{0.1};
 
   /** \brief The ratio of outliers of points w.r.t. a normal distribution,
    * Equation 6.7 [Magnusson 2009]. */
-  double outlier_ratio_;
+  double outlier_ratio_{0.55};
 
   /** \brief The normalization constants used fit the point distribution to a
    * normal distribution, Equation 6.8 [Magnusson 2009]. */
-  double gauss_d1_, gauss_d2_;
+  double gauss_d1_{0.0}, gauss_d2_{0.0};
 
   /** \brief The likelihood score of the transform applied to the input cloud,
    * Equation 6.9 and 6.10 [Magnusson 2009]. */
@@ -576,7 +577,7 @@ protected:
                    16,
                    "`trans_probability_` has been renamed to `trans_likelihood_`.")
     double trans_probability_;
-    double trans_likelihood_;
+    double trans_likelihood_{0.0};
   };
 
   /** \brief Precomputed Angular Gradient
index 8b3a927a84b77b06d98ca735277bf798ad7bbd6e..e65af5ab192fd863fece2a9f4644ae5f4c616cba 100644 (file)
@@ -54,6 +54,7 @@ namespace pcl {
  * 2743–2748, Las Vegas, USA, October 2003.
  *
  * \author James Crosby
+ * \ingroup registration
  */
 template <typename PointSource, typename PointTarget>
 class NormalDistributionsTransform2D : public Registration<PointSource, PointTarget> {
index 602cce85ead1c15e96bef8b6f1fca8c566cb5ca1..fbb5ed39f93a23b8246b22d8926c324687ef4de6 100644 (file)
@@ -92,10 +92,8 @@ public:
                                                      static_cast<float>(M_PI),
                    float distance_discretization_step = 0.01f)
   : feature_hash_map_(new FeatureHashMapType)
-  , internals_initialized_(false)
   , angle_discretization_step_(angle_discretization_step)
   , distance_discretization_step_(distance_discretization_step)
-  , max_dist_(-1.0f)
   {}
 
   /** \brief Method that sets the feature cloud to be inserted in the hash map
@@ -155,10 +153,10 @@ public:
 
 private:
   FeatureHashMapTypePtr feature_hash_map_;
-  bool internals_initialized_;
+  bool internals_initialized_{false};
 
   float angle_discretization_step_, distance_discretization_step_;
-  float max_dist_;
+  float max_dist_{-1.0f};
 };
 
 /** \brief Class that registers two point clouds based on their sets of PPFSignatures.
@@ -169,6 +167,7 @@ private:
  *    13-18 June 2010, San Francisco, CA
  *
  * \note This class works in tandem with the PPFEstimation class
+ * \ingroup registration
  *
  * \author Alexandru-Eugen Ichim
  */
@@ -181,7 +180,7 @@ public:
    * - std::pair does not have a custom allocator
    */
   struct PoseWithVotes {
-    PoseWithVotes(Eigen::Affine3f& a_pose, unsigned int& a_votes)
+    PoseWithVotes(const Eigen::Affine3f& a_pose, unsigned int& a_votes)
     : pose(a_pose), votes(a_votes)
     {}
 
@@ -211,8 +210,6 @@ public:
    * default values */
   PPFRegistration()
   : Registration<PointSource, PointTarget>()
-  , scene_reference_point_sampling_rate_(5)
-  , clustering_position_diff_threshold_(0.01f)
   , clustering_rotation_diff_threshold_(20.0f / 180.0f * static_cast<float>(M_PI))
   {}
 
@@ -298,6 +295,18 @@ public:
   void
   setInputTarget(const PointCloudTargetConstPtr& cloud) override;
 
+  /** \brief Returns the most promising pose candidates, after clustering. The pose with
+   * the most votes is the result of the registration. It may make sense to check the
+   * next best pose candidates if the registration did not give the right result, or if
+   * there are more than one correct results. You need to call the align function before
+   * this one.
+   */
+  inline PoseWithVotesList
+  getBestPoseCandidates()
+  {
+    return best_pose_candidates;
+  }
+
 private:
   /** \brief Method that calculates the transformation between the input_ and target_
    * point clouds, based on the PPF features */
@@ -310,17 +319,21 @@ private:
   PPFHashMapSearch::Ptr search_method_;
 
   /** \brief parameter for the sampling rate of the scene reference points */
-  uindex_t scene_reference_point_sampling_rate_;
+  uindex_t scene_reference_point_sampling_rate_{5};
 
   /** \brief position and rotation difference thresholds below which two
    * poses are considered to be in the same cluster (for the clustering phase of the
    * algorithm) */
-  float clustering_position_diff_threshold_, clustering_rotation_diff_threshold_;
+  float clustering_position_diff_threshold_{0.01f}, clustering_rotation_diff_threshold_;
 
   /** \brief use a kd-tree with range searches of range max_dist to skip an O(N) pass
    * through the point cloud */
   typename pcl::KdTreeFLANN<PointTarget>::Ptr scene_search_tree_;
 
+  /** \brief List with the most promising pose candidates, after clustering. The pose
+   * with the most votes is returned as the registration result. */
+  PoseWithVotesList best_pose_candidates;
+
   /** \brief static method used for the std::sort function to order two PoseWithVotes
    * instances by their number of votes*/
   static bool
@@ -341,7 +354,10 @@ private:
   /** \brief Method that checks whether two poses are close together - based on the
    * clustering threshold parameters of the class */
   bool
-  posesWithinErrorBounds(Eigen::Affine3f& pose1, Eigen::Affine3f& pose2);
+  posesWithinErrorBounds(Eigen::Affine3f& pose1,
+                         Eigen::Affine3f& pose2,
+                         float& position_diff,
+                         float& rotation_diff_angle);
 };
 } // namespace pcl
 
index 8a243559d59771c6b4b31d3d5b031d9c1cdeb4a9..b16b9a9edd8b4fb536120c69ca13193a20baf4f4 100644 (file)
@@ -153,10 +153,10 @@ public:
                                   const PyramidFeatureHistogramPtr& pyramid_b);
 
 private:
-  std::size_t nr_dimensions, nr_levels, nr_features;
+  std::size_t nr_dimensions{0}, nr_levels{0}, nr_features{0};
   std::vector<std::pair<float, float>> dimension_range_input_, dimension_range_target_;
   FeatureRepresentationConstPtr feature_representation_;
-  bool is_computed_;
+  bool is_computed_{false};
 
   /** \brief Checks for input inconsistencies and initializes the underlying data
    * structures */
index e702b944c3c7bbbbcd425e252c48738574b25359..da80847ff7aa824a0c29ff3e327077298af6d4f9 100644 (file)
@@ -109,27 +109,15 @@ public:
   Registration()
   : tree_(new KdTree)
   , tree_reciprocal_(new KdTreeReciprocal)
-  , nr_iterations_(0)
-  , max_iterations_(10)
-  , ransac_iterations_(0)
   , target_()
   , final_transformation_(Matrix4::Identity())
   , transformation_(Matrix4::Identity())
   , previous_transformation_(Matrix4::Identity())
-  , transformation_epsilon_(0.0)
-  , transformation_rotation_epsilon_(0.0)
   , euclidean_fitness_epsilon_(-std::numeric_limits<double>::max())
   , corr_dist_threshold_(std::sqrt(std::numeric_limits<double>::max()))
-  , inlier_threshold_(0.05)
-  , converged_(false)
-  , min_number_correspondences_(3)
   , correspondences_(new Correspondences)
   , transformation_estimation_()
   , correspondence_estimation_()
-  , target_cloud_updated_(true)
-  , source_cloud_updated_(true)
-  , force_no_recompute_(false)
-  , force_no_recompute_reciprocal_(false)
   , point_representation_()
   {}
 
@@ -567,15 +555,15 @@ protected:
 
   /** \brief The number of iterations the internal optimization ran for (used
    * internally). */
-  int nr_iterations_;
+  int nr_iterations_{0};
 
   /** \brief The maximum number of iterations the internal optimization should run for.
    * The default value is 10.
    */
-  int max_iterations_;
+  int max_iterations_{10};
 
   /** \brief The number of iterations RANSAC should run for. */
-  int ransac_iterations_;
+  int ransac_iterations_{0};
 
   /** \brief The input point cloud dataset target. */
   PointCloudTargetConstPtr target_;
@@ -594,12 +582,12 @@ protected:
   /** \brief The maximum difference between two consecutive transformations in order to
    * consider convergence (user defined).
    */
-  double transformation_epsilon_;
+  double transformation_epsilon_{0.0};
 
   /** \brief The maximum rotation difference between two consecutive transformations in
    * order to consider convergence (user defined).
    */
-  double transformation_rotation_epsilon_;
+  double transformation_rotation_epsilon_{0.0};
 
   /** \brief The maximum allowed Euclidean error between two consecutive steps in the
    * ICP loop, before the algorithm is considered to have converged. The error is
@@ -619,15 +607,15 @@ protected:
    * target data index and the transformed source index is smaller than the given inlier
    * distance threshold. The default value is 0.05.
    */
-  double inlier_threshold_;
+  double inlier_threshold_{0.05};
 
   /** \brief Holds internal convergence state, given user parameters. */
-  bool converged_;
+  bool converged_{false};
 
   /** \brief The minimum number of correspondences that the algorithm needs before
    * attempting to estimate the transformation. The default value is 3.
    */
-  unsigned int min_number_correspondences_;
+  unsigned int min_number_correspondences_{3};
 
   /** \brief The set of correspondences determined at this ICP step. */
   CorrespondencesPtr correspondences_;
@@ -646,18 +634,18 @@ protected:
   /** \brief Variable that stores whether we have a new target cloud, meaning we need to
    * pre-process it again. This way, we avoid rebuilding the kd-tree for the target
    * cloud every time the determineCorrespondences () method is called. */
-  bool target_cloud_updated_;
+  bool target_cloud_updated_{true};
   /** \brief Variable that stores whether we have a new source cloud, meaning we need to
    * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the
    * source cloud every time the determineCorrespondences () method is called. */
-  bool source_cloud_updated_;
+  bool source_cloud_updated_{true};
   /** \brief A flag which, if set, means the tree operating on the target cloud
    * will never be recomputed*/
-  bool force_no_recompute_;
+  bool force_no_recompute_{false};
 
   /** \brief A flag which, if set, means the tree operating on the source cloud
    * will never be recomputed*/
-  bool force_no_recompute_reciprocal_;
+  bool force_no_recompute_reciprocal_{false};
 
   /** \brief Callback function to update intermediate source point cloud position during
    * it's registration to the target point cloud.
index f2b4e8cac6ed782a5b1867ca28c7b453cceafd9c..3d67b293092eb3723f5d82a90f47072f31cfb8a6 100644 (file)
@@ -121,11 +121,8 @@ public:
   SampleConsensusPrerejective()
   : input_features_()
   , target_features_()
-  , nr_samples_(3)
-  , k_correspondences_(2)
   , feature_tree_(new pcl::KdTreeFLANN<FeatureT>)
   , correspondence_rejector_poly_(new CorrespondenceRejectorPoly)
-  , inlier_fraction_(0.0f)
   {
     reg_name_ = "SampleConsensusPrerejective";
     correspondence_rejector_poly_->setSimilarityThreshold(0.6f);
@@ -305,11 +302,11 @@ protected:
   FeatureCloudConstPtr target_features_;
 
   /** \brief The number of samples to use during each iteration. */
-  int nr_samples_;
+  int nr_samples_{3};
 
   /** \brief The number of neighbors to use when selecting a random feature
    * correspondence. */
-  int k_correspondences_;
+  int k_correspondences_{2};
 
   /** \brief The KdTree used to compare feature descriptors. */
   FeatureKdTreePtr feature_tree_;
@@ -319,7 +316,7 @@ protected:
 
   /** \brief The fraction [0,1] of inlier points required for accepting a transformation
    */
-  float inlier_fraction_;
+  float inlier_fraction_{0.0f};
 
   /** \brief Inlier points of final transformation as indices into source */
   pcl::Indices inliers_;
index ff30f5556a79cada3e6159afe25ab7819ce6a0a7..3af43f5c9daf4d7d08bf6079f37b44f5c4677686 100644 (file)
@@ -202,16 +202,16 @@ protected:
   }
 
   /** \brief Temporary pointer to the source dataset. */
-  mutable const PointCloudSource* tmp_src_;
+  mutable const PointCloudSource* tmp_src_{nullptr};
 
   /** \brief Temporary pointer to the target dataset. */
-  mutable const PointCloudTarget* tmp_tgt_;
+  mutable const PointCloudTarget* tmp_tgt_{nullptr};
 
   /** \brief Temporary pointer to the source dataset indices. */
-  mutable const pcl::Indices* tmp_idx_src_;
+  mutable const pcl::Indices* tmp_idx_src_{nullptr};
 
   /** \brief Temporary pointer to the target dataset indices. */
-  mutable const pcl::Indices* tmp_idx_tgt_;
+  mutable const pcl::Indices* tmp_idx_tgt_{nullptr};
 
   /** \brief The parameterized function used to warp the source to the target. */
   typename pcl::registration::WarpPointRigid<PointSource, PointTarget, MatScalar>::Ptr
index 8d42452bdbb63b062d41e8b869a8cf27f40e00e9..6b4453f63b3d1cd60085ba07bb15dd159a3b8401 100644 (file)
@@ -198,20 +198,20 @@ public:
   }
 
 protected:
-  bool use_correspondence_weights_;
-  mutable std::vector<double> correspondence_weights_;
+  bool use_correspondence_weights_{true};
+  mutable std::vector<double> correspondence_weights_{};
 
   /** \brief Temporary pointer to the source dataset. */
-  mutable const PointCloudSource* tmp_src_;
+  mutable const PointCloudSource* tmp_src_{nullptr};
 
   /** \brief Temporary pointer to the target dataset. */
-  mutable const PointCloudTarget* tmp_tgt_;
+  mutable const PointCloudTarget* tmp_tgt_{nullptr};
 
   /** \brief Temporary pointer to the source dataset indices. */
-  mutable const pcl::Indices* tmp_idx_src_;
+  mutable const pcl::Indices* tmp_idx_src_{nullptr};
 
   /** \brief Temporary pointer to the target dataset indices. */
-  mutable const pcl::Indices* tmp_idx_tgt_;
+  mutable const pcl::Indices* tmp_idx_tgt_{nullptr};
 
   /** \brief The parameterized function used to warp the source to the target. */
   typename pcl::registration::WarpPointRigid<PointSource, PointTarget, MatScalar>::Ptr
index d91f7e367a0327075372324b97b3260237289504..f9c56ea59a2f00ab4ba7efead9acfdabd2b965db 100644 (file)
@@ -42,6 +42,7 @@
 
 #include <pcl/registration/transformation_estimation.h>
 #include <pcl/cloud_iterator.h>
+#include <pcl/pcl_config.h> // for PCL_NO_PRECOMPILE
 
 namespace pcl {
 namespace registration {
@@ -154,3 +155,13 @@ protected:
 } // namespace pcl
 
 #include <pcl/registration/impl/transformation_estimation_svd.hpp>
+
+#if !defined(PCL_NO_PRECOMPILE) &&                                                     \
+    !defined(PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_CPP_)
+extern template class pcl::registration::TransformationEstimationSVD<pcl::PointXYZ,
+                                                                     pcl::PointXYZ>;
+extern template class pcl::registration::TransformationEstimationSVD<pcl::PointXYZI,
+                                                                     pcl::PointXYZI>;
+extern template class pcl::registration::TransformationEstimationSVD<pcl::PointXYZRGB,
+                                                                     pcl::PointXYZRGB>;
+#endif // PCL_NO_PRECOMPILE
index 057fa2bb26fa1cf8e05b8adaaa1445f6a724e817..bb22c94aaddb7a77bce5911c48b2b9b3e68aacda 100644 (file)
@@ -71,8 +71,7 @@ public:
       typename TransformationEstimation<PointSource, PointTarget, Scalar>::Matrix4;
   using Vector6 = Eigen::Matrix<Scalar, 6, 1>;
 
-  TransformationEstimationSymmetricPointToPlaneLLS()
-  : enforce_same_direction_normals_(true){};
+  TransformationEstimationSymmetricPointToPlaneLLS() = default;
   ~TransformationEstimationSymmetricPointToPlaneLLS() override = default;
 
   /** \brief Estimate a rigid rotation transformation between a source and a target
@@ -161,7 +160,7 @@ protected:
 
   /** \brief Whether or not to negate source and/or target normals such that they point
    * in the same direction */
-  bool enforce_same_direction_normals_;
+  bool enforce_same_direction_normals_{true};
 };
 } // namespace registration
 } // namespace pcl
index b22ed68adafc1a6e7e3d8f2a98a3e9f72bb35c8e..83ffeb2657c6e8fd70414d864c11ad0bd608bf1a 100644 (file)
@@ -101,7 +101,6 @@ public:
   : max_range_(std::numeric_limits<double>::max())
   , threshold_(std::numeric_limits<double>::quiet_NaN())
   , tree_(new pcl::search::KdTree<PointTarget>)
-  , force_no_recompute_(false)
   {}
 
   virtual ~TransformationValidationEuclidean() = default;
@@ -229,7 +228,7 @@ protected:
 
   /** \brief A flag which, if set, means the tree operating on the target cloud
    * will never be recomputed*/
-  bool force_no_recompute_;
+  bool force_no_recompute_{false};
 
   /** \brief Internal point representation uses only 3D coordinates for L2 */
   class MyPointRepresentation : public pcl::PointRepresentation<PointTarget> {
index 4131cffd87d951816bee8c2f701ea2b852cf167c..7bdebcad606571a0bbdfba42459c822d1e241f4b 100644 (file)
@@ -65,7 +65,7 @@ struct PoseEstimate {
   : pose(p), cloud(c)
   {}
 
-  PCL_MAKE_ALIGNED_OPERATOR_NEW;
+  PCL_MAKE_ALIGNED_OPERATOR_NEW
 };
 } // namespace registration
 } // namespace pcl
index f305ee82e95aa433a3ebe8cc48d69be6ed8f98f1..8fcb8abd8dfaea46975a7dff23cf6d44d47828d1 100644 (file)
@@ -47,8 +47,8 @@ pcl::registration::CorrespondenceRejectorTrimmed::getRemainingCorrespondences(
 {
   // not really an efficient implementation
   remaining_correspondences = original_correspondences;
-  unsigned int number_valid_correspondences = (int(std::floor(
-      overlap_ratio_ * static_cast<float>(remaining_correspondences.size()))));
+  auto number_valid_correspondences = static_cast<unsigned int>(std::floor(
+      overlap_ratio_ * static_cast<float>(remaining_correspondences.size())));
   number_valid_correspondences =
       std::max(number_valid_correspondences, nr_min_correspondences_);
 
index 79ee3955e392ed9b3733c06ca57af71a09e3152b..62c1c70f4bc8038b539095fd13e7d45b96943d94 100644 (file)
@@ -57,9 +57,12 @@ pcl::registration::CorrespondenceRejectorVarTrimmed::getRemainingCorrespondences
     }
   }
   factor_ = optimizeInlierRatio(dists);
-  nth_element(
-      dists.begin(), dists.begin() + int(double(dists.size()) * factor_), dists.end());
-  trimmed_distance_ = dists[int(double(dists.size()) * factor_)];
+  nth_element(dists.begin(),
+              dists.begin() +
+                  static_cast<int>(static_cast<double>(dists.size()) * factor_),
+              dists.end());
+  trimmed_distance_ =
+      dists[static_cast<int>(static_cast<double>(dists.size()) * factor_)];
 
   unsigned int number_valid_correspondences = 0;
   remaining_correspondences.resize(original_correspondences.size());
@@ -82,11 +85,11 @@ pcl::registration::CorrespondenceRejectorVarTrimmed::optimizeInlierRatio(
   auto points_nbr = static_cast<unsigned int>(dists.size());
   std::sort(dists.begin(), dists.end());
 
-  const int min_el = int(std::floor(min_ratio_ * points_nbr));
-  const int max_el = int(std::floor(max_ratio_ * points_nbr));
+  const int min_el = static_cast<int>(std::floor(min_ratio_ * points_nbr));
+  const int max_el = static_cast<int>(std::floor(max_ratio_ * points_nbr));
 
   using LineArray = Eigen::Array<double, Eigen::Dynamic, 1>;
-  Eigen::Map<LineArray> sorted_dist(&dists[0], points_nbr);
+  Eigen::Map<LineArray> sorted_dist(dists.data(), points_nbr);
 
   const LineArray trunk_sorted_dist = sorted_dist.segment(min_el, max_el - min_el);
   const double lower_sum = sorted_dist.head(min_el).sum();
@@ -99,6 +102,7 @@ pcl::registration::CorrespondenceRejectorVarTrimmed::optimizeInlierRatio(
   int min_index(0);
   FRMS.minCoeff(&min_index);
 
-  const float opt_ratio = float(min_index + min_el) / float(points_nbr);
+  const float opt_ratio =
+      static_cast<float>(min_index + min_el) / static_cast<float>(points_nbr);
   return (opt_ratio);
 }
index 5c3fa82dc203adc826d05bfb59853c43117dc2eb..c06bc2c2664d8ed5fb8df616cb0f8d886c5cdf60 100644 (file)
@@ -141,7 +141,8 @@ GeneralizedIterativeClosestPoint6D::computeTransformation(PointCloudSource& outp
     for (std::size_t i = 0; i < 4; i++)
       for (std::size_t j = 0; j < 4; j++)
         for (std::size_t k = 0; k < 4; k++)
-          transform_R(i, j) += double(transformation_(i, k)) * double(guess(k, j));
+          transform_R(i, j) += static_cast<double>(transformation_(i, k)) *
+                               static_cast<double>(guess(k, j));
 
     Eigen::Matrix3d R = transform_R.topLeftCorner<3, 3>();
 
index 0b2f60b4183a2903dd2453592d56f53c9ad9b38b..0ca020475f8edcca5ac2860e9eb7e489309fcc17 100644 (file)
  *
  */
 
+#define PCL_REGISTRATION_ICP_CPP_
 #include <pcl/registration/icp.h>
+#include <pcl/pcl_config.h> // for PCL_NO_PRECOMPILE
+
+#ifndef PCL_NO_PRECOMPILE
+#include <pcl/pcl_exports.h> // for PCL_EXPORTS
+#include <pcl/point_types.h>
+template class PCL_EXPORTS pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ>;
+template class PCL_EXPORTS pcl::IterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>;
+template class PCL_EXPORTS
+    pcl::IterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB>;
+#endif // PCL_NO_PRECOMPILE
index 29895a6c3788729f207fa641385ef22ac26dbaf6..674c2da5f93b36ebccc63beba677b7d7c81251b8 100644 (file)
  *
  */
 
+#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_CPP_
 #include <pcl/registration/transformation_estimation_svd.h>
+#include <pcl/pcl_config.h> // for PCL_NO_PRECOMPILE
+
+#ifndef PCL_NO_PRECOMPILE
+#include <pcl/pcl_exports.h> // for PCL_EXPORTS
+#include <pcl/point_types.h>
+template class PCL_EXPORTS
+    pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ>;
+template class PCL_EXPORTS
+    pcl::registration::TransformationEstimationSVD<pcl::PointXYZI, pcl::PointXYZI>;
+template class PCL_EXPORTS
+    pcl::registration::TransformationEstimationSVD<pcl::PointXYZRGB, pcl::PointXYZRGB>;
+#endif // PCL_NO_PRECOMPILE
index 028fd3f7e18ac370d23ac9f529851e0953325d47..c1ce5deefb1d990725f53d0152d190cae15a579e 100644 (file)
@@ -90,8 +90,12 @@ pcl::MEstimatorSampleConsensus<PointT>::computeModel (int debug_verbosity_level)
     // Iterate through the 3d points and calculate the distances from them to the model
     sac_model_->getDistancesToModel (model_coefficients, distances);
     
-    if (distances.empty () && k > 1.0)
+    if (distances.empty ())
+    {
+      // skip invalid model suppress infinite loops 
+      ++ skipped_count;
       continue;
+    }
 
     for (const double &distance : distances)
       d_cur_penalty += (std::min) (distance, threshold_);
index f3879929b3615ba9cd8aeeda1370467dfccc721e..5f5cab7151cbe2201dc66c5ef409a6aeac5270ee 100644 (file)
@@ -108,8 +108,11 @@ pcl::RandomizedMEstimatorSampleConsensus<PointT>::computeModel (int debug_verbos
     // Iterate through the 3d points and calculate the distances from them to the model
     sac_model_->getDistancesToModel (model_coefficients, distances);
 
-    if (distances.empty () && k > 1.0)
+    if (distances.empty ())
+    {
+      ++ skipped_count;
       continue;
+    }
 
     for (const double &distance : distances)
       d_cur_penalty += std::min (distance, threshold_);
index 1003cd9686157c2c376a86e335716a726bf1977f..e0be7718f0d6613087b7c1c2e0fada8853d28e72 100644 (file)
@@ -39,7 +39,6 @@
 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_
 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_
 
-#include <unsupported/Eigen/NonLinearOptimization> // for LevenbergMarquardt
 #include <pcl/sample_consensus/sac_model_cone.h>
 #include <pcl/common/common.h> // for getAngle3D
 #include <pcl/common/concatenate.h>
@@ -70,7 +69,7 @@ pcl::SampleConsensusModelCone<PointT, PointNT>::computeModelCoefficients (
 
   if (!normals_)
   {
-    PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] No input dataset containing normals was given!\n");
+    PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] No input dataset containing normals was given! Use setInputNormals\n");
     return (false);
   }
 
@@ -344,14 +343,20 @@ pcl::SampleConsensusModelCone<PointT, PointNT>::optimizeModelCoefficients (
     return;
   }
 
-  OptimizationFunctor functor (this, inliers);
-  Eigen::NumericalDiff<OptimizationFunctor > num_diff (functor);
-  Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, float> lm (num_diff);
-  int info = lm.minimize (optimized_coefficients);
+  Eigen::ArrayXf pts_x(inliers.size());
+  Eigen::ArrayXf pts_y(inliers.size());
+  Eigen::ArrayXf pts_z(inliers.size());
+  std::size_t pos = 0;
+  for(const auto& index : inliers) {
+    pts_x[pos] = (*input_)[index].x;
+    pts_y[pos] = (*input_)[index].y;
+    pts_z[pos] = (*input_)[index].z;
+    ++pos;
+  }
+  pcl::internal::optimizeModelCoefficientsCone(optimized_coefficients, pts_x, pts_y, pts_z);
 
-  // Compute the L2 norm of the residuals
-  PCL_DEBUG ("[pcl::SampleConsensusModelCone::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n",
-             info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3],
+  PCL_DEBUG ("[pcl::SampleConsensusModelCone::optimizeModelCoefficients] Initial solution: %g %g %g %g %g %g %g \nFinal solution: %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], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]);
 
   Eigen::Vector3f line_dir (optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5]);
index 284e95c447bdfb41966c705bc374708e23e69850..6ae067ad3c4c475ad014bd8be688277127403ef3 100644 (file)
@@ -41,7 +41,6 @@
 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_
 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_
 
-#include <unsupported/Eigen/NonLinearOptimization> // for LevenbergMarquardt
 #include <pcl/sample_consensus/sac_model_cylinder.h>
 #include <pcl/common/common.h> // for getAngle3D
 #include <pcl/common/concatenate.h>
@@ -85,7 +84,7 @@ pcl::SampleConsensusModelCylinder<PointT, PointNT>::computeModelCoefficients (
 
   if (!normals_)
   {
-    PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given!\n");
+    PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given! Use setInputNormals\n");
     return (false);
   }
 
@@ -299,14 +298,20 @@ pcl::SampleConsensusModelCylinder<PointT, PointNT>::optimizeModelCoefficients (
     return;
   }
 
-  OptimizationFunctor functor (this, inliers);
-  Eigen::NumericalDiff<OptimizationFunctor > num_diff (functor);
-  Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, float> lm (num_diff);
-  int info = lm.minimize (optimized_coefficients);
+  Eigen::ArrayXf pts_x(inliers.size());
+  Eigen::ArrayXf pts_y(inliers.size());
+  Eigen::ArrayXf pts_z(inliers.size());
+  std::size_t pos = 0;
+  for(const auto& index : inliers) {
+    pts_x[pos] = (*input_)[index].x;
+    pts_y[pos] = (*input_)[index].y;
+    pts_z[pos] = (*input_)[index].z;
+    ++pos;
+  }
+  pcl::internal::optimizeModelCoefficientsCylinder(optimized_coefficients, pts_x, pts_y, pts_z);
   
-  // Compute the L2 norm of the residuals
-  PCL_DEBUG ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n",
-             info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3],
+  PCL_DEBUG ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] Initial solution: %g %g %g %g %g %g %g \nFinal solution: %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], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]);
     
   Eigen::Vector3f line_dir (optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5]);
@@ -447,7 +452,7 @@ pcl::SampleConsensusModelCylinder<PointT, PointNT>::projectPointToCylinder (
   Eigen::Vector4f line_pt  (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f);
   Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0.0f);
 
-  float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) * line_dir.dot (line_dir);
+  float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir);
   pt_proj = line_pt + k * line_dir;
 
   Eigen::Vector4f dir = pt - pt_proj;
index a85b9bb3add7f7b35316364636a4e668f19b39de..247a58e3d1f0b0f752a61f2052b62449035d19eb 100644 (file)
@@ -223,7 +223,7 @@ pcl::SampleConsensusModelEllipse3D<PointT>::computeModelCoefficients (const Indi
   model_coefficients[6] = static_cast<float>(ellipse_normal[1]);
   model_coefficients[7] = static_cast<float>(ellipse_normal[2]);
 
-  // Retrive the ellipse point at the tilt angle t (par_t), along the local x-axis
+  // Retrieve the ellipse point at the tilt angle t (par_t), along the local x-axis
   const Eigen::VectorXf params = (Eigen::VectorXf(5) << par_a, par_b, par_h, par_k, par_t).finished();
   Eigen::Vector3f p_th_(0.0, 0.0, 0.0);
   get_ellipse_point(params, par_t, p_th_(0), p_th_(1));
@@ -551,7 +551,7 @@ pcl::SampleConsensusModelEllipse3D<PointT>::projectPoints (
       float th_opt;
       dvec2ellipse(params, p_(0), p_(1), th_opt);
 
-      // Retrive the ellipse point at the tilt angle t, along the local x-axis
+      // Retrieve the ellipse point at the tilt angle t, along the local x-axis
       Eigen::Vector3f k_(0.0, 0.0, 0.0);
       get_ellipse_point(params, th_opt, k_[0], k_[1]);
 
@@ -613,7 +613,7 @@ pcl::SampleConsensusModelEllipse3D<PointT>::projectPoints (
       float th_opt;
       dvec2ellipse(params, p_(0), p_(1), th_opt);
 
-      // Retrive the ellipse point at the tilt angle t, along the local x-axis
+      // Retrieve the ellipse point at the tilt angle t, along the local x-axis
       //// model_coefficients[5] = static_cast<float>(par_t);
       Eigen::Vector3f k_(0.0, 0.0, 0.0);
       get_ellipse_point(params, th_opt, k_[0], k_[1]);
index 0e718f100720ccc63022baad34e9601b4158359e..94de2e7af8ddbd3f3a41e7f1d69994b5e35f0117 100644 (file)
@@ -251,7 +251,10 @@ pcl::SampleConsensusModelLine<PointT>::projectPoints (
 {
   // Needs a valid model coefficients
   if (!isModelValid (model_coefficients))
+  {
+    PCL_ERROR ("[pcl::SampleConsensusModelLine::projectPoints] Given model is invalid!\n");
     return;
+  }
 
   // Obtain the line point and direction
   Eigen::Vector4f line_pt  (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f);
index b83d0f70ec412856350a5eb9545ff5eb051dd848..a29a7067baf651fa3239e248e25623489760e2cd 100644 (file)
@@ -51,7 +51,7 @@ pcl::SampleConsensusModelNormalSphere<PointT, PointNT>::selectWithinDistance (
 {
   if (!normals_)
   {
-    PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given!\n");
+    PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given! Use setInputNormals\n");
     inliers.clear ();
     return;
   }
@@ -112,7 +112,7 @@ pcl::SampleConsensusModelNormalSphere<PointT, PointNT>::countWithinDistance (
 {
   if (!normals_)
   {
-    PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n");
+    PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given! Use setInputNormals\n");
     return (0);
   }
 
@@ -163,7 +163,7 @@ pcl::SampleConsensusModelNormalSphere<PointT, PointNT>::getDistancesToModel (
 {
   if (!normals_)
   {
-    PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n");
+    PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given! Use setInputNormals\n");
     return;
   }
 
index 3b77afdb75be54587db3a823121bec241a11aa5a..2ff3e55210fb8a4bd9c1e6d8b627bafa02c795b3 100644 (file)
@@ -41,7 +41,6 @@
 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_
 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_
 
-#include <unsupported/Eigen/NonLinearOptimization> // for LevenbergMarquardt
 #include <pcl/sample_consensus/sac_model_sphere.h>
 
 //////////////////////////////////////////////////////////////////////////
@@ -354,14 +353,20 @@ pcl::SampleConsensusModelSphere<PointT>::optimizeModelCoefficients (
     return;
   }
 
-  OptimizationFunctor functor (this, inliers);
-  Eigen::NumericalDiff<OptimizationFunctor> num_diff (functor);
-  Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, float> lm (num_diff);
-  int info = lm.minimize (optimized_coefficients);
+  Eigen::ArrayXf pts_x(inliers.size());
+  Eigen::ArrayXf pts_y(inliers.size());
+  Eigen::ArrayXf pts_z(inliers.size());
+  std::size_t pos = 0;
+  for(const auto& index : inliers) {
+    pts_x[pos] = (*input_)[index].x;
+    pts_y[pos] = (*input_)[index].y;
+    pts_z[pos] = (*input_)[index].z;
+    ++pos;
+  }
+  pcl::internal::optimizeModelCoefficientsSphere(optimized_coefficients, pts_x, pts_y, pts_z);
 
-  // Compute the L2 norm of the residuals
-  PCL_DEBUG ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g \nFinal solution: %g %g %g %g\n",
-             info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3]);
+  PCL_DEBUG ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Initial solution: %g %g %g %g \nFinal solution: %g %g %g %g\n",
+             model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3]);
 }
 
 //////////////////////////////////////////////////////////////////////////
@@ -399,20 +404,20 @@ pcl::SampleConsensusModelSphere<PointT>::projectPoints (
       pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[i], projected_points.points[i]));
 
     // Iterate through the 3d points and calculate the distances from them to the sphere
-    for (std::size_t i = 0; i < inliers.size (); ++i)
+    for (const auto& inlier : inliers)
     {
       // what i have:
       // P : Sample Point
-      const Eigen::Vector3d P (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z);
+      const Eigen::Vector3d P (input_->points[inlier].x, input_->points[inlier].y, input_->points[inlier].z);
 
       const Eigen::Vector3d direction = (P - C).normalized();
 
       // K : Point on Sphere
       const Eigen::Vector3d K = C + r * direction;
 
-      projected_points.points[inliers[i]].x = static_cast<float> (K[0]);
-      projected_points.points[inliers[i]].y = static_cast<float> (K[1]);
-      projected_points.points[inliers[i]].z = static_cast<float> (K[2]);
+      projected_points.points[inlier].x = static_cast<float> (K[0]);
+      projected_points.points[inlier].y = static_cast<float> (K[1]);
+      projected_points.points[inlier].z = static_cast<float> (K[2]);
     }
   }
   else
index 0eb0e4724781eb2beb8c09a598548c180e1c8a25..568deb36dedcbca00b957d413f04263827f0c617 100644 (file)
 
 namespace pcl
 {
-  const static int SAC_RANSAC  = 0;
-  const static int SAC_LMEDS   = 1;
-  const static int SAC_MSAC    = 2;
-  const static int SAC_RRANSAC = 3;
-  const static int SAC_RMSAC   = 4;
-  const static int SAC_MLESAC  = 5;
-  const static int SAC_PROSAC  = 6;
+  constexpr int SAC_RANSAC  = 0;
+  constexpr int SAC_LMEDS   = 1;
+  constexpr int SAC_MSAC    = 2;
+  constexpr int SAC_RRANSAC = 3;
+  constexpr int SAC_RMSAC   = 4;
+  constexpr int SAC_MLESAC  = 5;
+  constexpr int SAC_PROSAC  = 6;
 }
index 88fa2e9b98a29358a07cb588a39870391696e8e6..39f066a725474ef4ad392808bb0e13511f3c9dc6 100644 (file)
@@ -47,6 +47,7 @@
 #include <boost/random/mersenne_twister.hpp> // for mt19937
 #include <boost/random/uniform_int.hpp> // for uniform_int
 #include <boost/random/variate_generator.hpp> // for variate_generator
+#include <random>
 
 #include <pcl/memory.h>
 #include <pcl/console/print.h>
@@ -92,7 +93,7 @@ namespace pcl
       {
         // Create a random number generator object
         if (random)
-          rng_alg_.seed (static_cast<unsigned> (std::time(nullptr)));
+          rng_alg_.seed (std::random_device()());
         else
           rng_alg_.seed (12345u);
 
@@ -114,7 +115,7 @@ namespace pcl
         , custom_model_constraints_ ([](auto){return true;})
       {
         if (random)
-          rng_alg_.seed (static_cast<unsigned> (std::time (nullptr)));
+          rng_alg_.seed (std::random_device()());
         else
           rng_alg_.seed (12345u);
 
@@ -143,7 +144,7 @@ namespace pcl
         , custom_model_constraints_ ([](auto){return true;})
       {
         if (random)
-          rng_alg_.seed (static_cast<unsigned> (std::time(nullptr)));
+          rng_alg_.seed (std::random_device()());
         else
           rng_alg_.seed (12345u);
 
@@ -618,7 +619,7 @@ namespace pcl
       using ConstPtr = shared_ptr<const SampleConsensusModelFromNormals<PointT, PointNT> >;
 
       /** \brief Empty constructor for base SampleConsensusModelFromNormals. */
-      SampleConsensusModelFromNormals () : normal_distance_weight_ (0.0), normals_ () {};
+      SampleConsensusModelFromNormals () :  normals_ () {};
 
       /** \brief Destructor. */
       virtual ~SampleConsensusModelFromNormals () = default;
@@ -662,7 +663,7 @@ namespace pcl
       /** \brief The relative weight (between 0 and 1) to give to the angular
         * distance (0 to pi/2) between point normals and the plane normal. 
         */
-      double normal_distance_weight_;
+      double normal_distance_weight_{0.0};
 
       /** \brief A pointer to the input dataset that contains the point normals
         * of the XYZ dataset. 
index d96a0d764b8d652c9e9b99dcb6e47356c948db71..6137c26126c99495d0f0a94afe0ec709340bb236 100644 (file)
 
 namespace pcl
 {
+  namespace internal {
+    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.
     * The model coefficients are defined as:
     * <ul>
@@ -299,54 +303,6 @@ namespace pcl
       /** \brief The minimum and maximum allowed opening angles of valid cone model. */
       double min_angle_;
       double max_angle_;
-
-      /** \brief Functor for the optimization function */
-      struct OptimizationFunctor : pcl::Functor<float>
-      {
-        /** Functor constructor
-          * \param[in] indices the indices of data points to evaluate
-          * \param[in] estimator pointer to the estimator object
-          */
-        OptimizationFunctor (const pcl::SampleConsensusModelCone<PointT, PointNT> *model, const Indices& indices) :
-          pcl::Functor<float> (indices.size ()), model_ (model), indices_ (indices) {}
-
-        /** Cost function to be minimized
-          * \param[in] x variables array
-          * \param[out] fvec resultant functions evaluations
-          * \return 0
-          */
-        int 
-        operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const
-        {
-          Eigen::Vector4f apex  (x[0], x[1], x[2], 0);
-          Eigen::Vector4f axis_dir (x[3], x[4], x[5], 0);
-          float opening_angle = x[6];
-
-          float apexdotdir = apex.dot (axis_dir);
-          float dirdotdir = 1.0f / axis_dir.dot (axis_dir);
-
-          for (int i = 0; i < values (); ++i)
-          {
-            // dist = f - r
-            Eigen::Vector4f pt = (*model_->input_)[indices_[i]].getVector4fMap();
-            pt[3] = 0;
-
-            // Calculate the point's projection on the cone axis
-            float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir;
-            Eigen::Vector4f pt_proj = apex + k * axis_dir;
-
-            // Calculate the actual radius of the cone at the level of the projected point
-            Eigen::Vector4f height = apex-pt_proj;
-            float actual_cone_radius = tanf (opening_angle) * height.norm ();
-
-            fvec[i] = static_cast<float> (pcl::sqrPointToLineDistance (pt, apex, axis_dir) - actual_cone_radius * actual_cone_radius);
-          }
-          return (0);
-        }
-
-        const pcl::SampleConsensusModelCone<PointT, PointNT> *model_;
-        const Indices &indices_;
-      };
   };
 }
 
index 7a45f26ff666e604327444e917cd197026b8af7d..95a6e80873befdebb2056346ba7382d3f086cd74 100644 (file)
 
 namespace pcl
 {
+  namespace internal {
+    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.
     * The model coefficients are defined as:
     *   - \b point_on_axis.x  : the X coordinate of a point located on the cylinder axis
@@ -295,42 +299,6 @@ namespace pcl
     
       /** \brief The maximum allowed difference between the cylinder direction and the given axis. */
       double eps_angle_;
-
-      /** \brief Functor for the optimization function */
-      struct OptimizationFunctor : pcl::Functor<float>
-      {
-        /** Functor constructor
-          * \param[in] indices the indices of data points to evaluate
-          * \param[in] estimator pointer to the estimator object
-          */
-        OptimizationFunctor (const pcl::SampleConsensusModelCylinder<PointT, PointNT> *model, const Indices& indices) :
-          pcl::Functor<float> (indices.size ()), model_ (model), indices_ (indices) {}
-
-        /** Cost function to be minimized
-          * \param[in] x variables array
-          * \param[out] fvec resultant functions evaluations
-          * \return 0
-          */
-        int 
-        operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const
-        {
-          Eigen::Vector4f line_pt  (x[0], x[1], x[2], 0);
-          Eigen::Vector4f line_dir (x[3], x[4], x[5], 0);
-          
-          for (int i = 0; i < values (); ++i)
-          {
-            // dist = f - r
-            Eigen::Vector4f pt = (*model_->input_)[indices_[i]].getVector4fMap();
-            pt[3] = 0;
-
-            fvec[i] = static_cast<float> (pcl::sqrPointToLineDistance (pt, line_pt, line_dir) - x[6]*x[6]);
-          }
-          return (0);
-        }
-
-        const pcl::SampleConsensusModelCylinder<PointT, PointNT> *model_;
-        const Indices &indices_;
-      };
   };
 }
 
index 44dca3591af2ae9c2ea19e7f35a5163393ab0595..537fcb3d0dd8c2c78ae7562c20152c091ff878a9 100644 (file)
 
 namespace pcl
 {
+  namespace internal {
+    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.
     * The model coefficients are defined as:
     *   - \b center.x : the X coordinate of the sphere's center
@@ -219,10 +223,14 @@ namespace pcl
         if (!SampleConsensusModel<PointT>::isModelValid (model_coefficients))
           return (false);
 
-        if (radius_min_ != -std::numeric_limits<double>::max() && model_coefficients[3] < radius_min_)
+        if (radius_min_ != -std::numeric_limits<double>::max() && model_coefficients[3] < radius_min_) {
+          PCL_DEBUG("[SampleConsensusModelSphere::isModelValid] Model radius %g is smaller than user specified minimum radius %g\n", model_coefficients[3], radius_min_);
           return (false);
-        if (radius_max_ != std::numeric_limits<double>::max() && model_coefficients[3] > radius_max_)
+        }
+        if (radius_max_ != std::numeric_limits<double>::max() && model_coefficients[3] > radius_max_) {
+          PCL_DEBUG("[SampleConsensusModelSphere::isModelValid] Model radius %g is bigger than user specified maximum radius %g\n", model_coefficients[3], radius_max_);
           return (false);
+        }
 
         return (true);
       }
@@ -263,40 +271,6 @@ namespace pcl
 #endif
 
     private:
-      struct OptimizationFunctor : pcl::Functor<float>
-      {
-        /** Functor constructor
-          * \param[in] indices the indices of data points to evaluate
-          * \param[in] estimator pointer to the estimator object
-          */
-        OptimizationFunctor (const pcl::SampleConsensusModelSphere<PointT> *model, const Indices& indices) :
-          pcl::Functor<float> (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::VectorXf &x, Eigen::VectorXf &fvec) const
-        {
-          Eigen::Vector4f cen_t;
-          cen_t[3] = 0;
-          for (int i = 0; i < values (); ++i)
-          {
-            // Compute the difference between the center of the sphere and the datapoint X_i
-            cen_t.head<3>() = (*model_->input_)[indices_[i]].getVector3fMap() - x.head<3>();
-
-            // g = sqrt ((x-a)^2 + (y-b)^2 + (z-c)^2) - R
-            fvec[i] = std::sqrt (cen_t.dot (cen_t)) - x[3];
-          }
-          return (0);
-        }
-
-        const pcl::SampleConsensusModelSphere<PointT> *model_;
-        const Indices &indices_;
-      };
-
 #ifdef __AVX__
       inline __m256 sqr_dist8 (const std::size_t i, const __m256 a_vec, const __m256 b_vec, const __m256 c_vec) const;
 #endif
index 14805c67e94e42d1052568b026c5714c5c71f58f..3d8babdff429deb8d6d5ffffabf97706197fd8c1 100644 (file)
@@ -56,11 +56,16 @@ namespace pcl
     *   - \b line_direction.z : the Z coordinate of a line's direction
     *   - \b line_width       : the width of the line
     *
+    * \warning This model is considered deprecated. The coefficients are used inconsistently in the methods, and the last coefficient (line width) is unused. We recommend to use the line or cylinder model instead.
     * \author Radu B. Rusu
     * \ingroup sample_consensus
     */
   template <typename PointT>
+#ifdef SAC_MODEL_STICK_DONT_WARN_DEPRECATED
   class SampleConsensusModelStick : public SampleConsensusModel<PointT>
+#else
+  class PCL_DEPRECATED(1, 17, "Use line or cylinder model instead") SampleConsensusModelStick : public SampleConsensusModel<PointT>
+#endif
   {
     public:
       using SampleConsensusModel<PointT>::model_name_;
index 28b06caedee0685b7c89663523a7dcab9a4e8429..914722bb28b167eee250a6d113d1eafa5cd05d59 100644 (file)
@@ -4,7 +4,7 @@
   \section secSampleConsensusPresentation Overview
 
   The <b>pcl_sample_consensus</b> library holds SAmple Consensus (SAC) methods like 
-  <a href="http://en.wikipedia.org/wiki/RANSAC">RANSAC</a> and models like planes and cylinders.  These can be
+  <a href="https://en.wikipedia.org/wiki/RANSAC">RANSAC</a> and models like planes and cylinders.  These can be
   combined freely in order to detect specific models and their parameters in point clouds.
 
   Some of the models implemented in this library include: lines, planes, cylinders, and spheres.  Plane fitting
@@ -37,7 +37,7 @@
 
   The following list describes the robust sample consensus estimators implemented:
   <ul>
-    <li><a href="http://en.wikipedia.org/wiki/RANSAC">SAC_RANSAC</a> - RANdom SAmple Consensus</li>
+    <li><a href="https://en.wikipedia.org/wiki/RANSAC">SAC_RANSAC</a> - RANdom SAmple Consensus</li>
     <li><a href="https://www-sop.inria.fr/odyssee/software/old_robotvis/Tutorial-Estim/node25.html">SAC_LMEDS</a> - Least Median of Squares</li>
     <li><a href="https://www.robots.ox.ac.uk/~vgg/publications/2000/Torr00/torr00.pdf">SAC_MSAC</a> - M-Estimator SAmple Consensus</li>
     <li><a href="https://web.archive.org/web/20170811194151/http://www.bmva.org/bmvc/2002/papers/50/full_50.pdf">SAC_RRANSAC</a> - Randomized RANSAC</li>
index a321c33bbc0b0e545ed8e15edece3b7854dc6cef..e2db0c337313550fda0955da70beb78f28b16faf 100644 (file)
  */
 
 #include <pcl/sample_consensus/impl/sac_model_cone.hpp>
+#include <unsupported/Eigen/NonLinearOptimization> // for LevenbergMarquardt
+
+int pcl::internal::optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z)
+{
+  if(pts_x.size() != pts_y.size() || pts_y.size() != pts_z.size()) {
+    PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCone] Sizes not equal!\n");
+    return Eigen::LevenbergMarquardtSpace::ImproperInputParameters;
+  }
+  if(coeff.size() != 7) {
+    PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCone] Coefficients have wrong size\n");
+    return Eigen::LevenbergMarquardtSpace::ImproperInputParameters;
+  }
+  struct ConeOptimizationFunctor : pcl::Functor<float>
+  {
+    ConeOptimizationFunctor (const Eigen::ArrayXf& x, const Eigen::ArrayXf& y, const Eigen::ArrayXf& z) :
+      pcl::Functor<float>(x.size()), pts_x(x), pts_y(y), pts_z(z)
+      {}
+
+    int
+    operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const
+    {
+      Eigen::Vector3f axis_dir(x[3], x[4], x[5]);
+      axis_dir.normalize();
+      const Eigen::ArrayXf axis_dir_x = Eigen::ArrayXf::Constant(pts_x.size(), axis_dir.x());
+      const Eigen::ArrayXf axis_dir_y = Eigen::ArrayXf::Constant(pts_x.size(), axis_dir.y());
+      const Eigen::ArrayXf axis_dir_z = Eigen::ArrayXf::Constant(pts_x.size(), axis_dir.z());
+      const Eigen::ArrayXf bx = Eigen::ArrayXf::Constant(pts_x.size(), x[0]) - pts_x;
+      const Eigen::ArrayXf by = Eigen::ArrayXf::Constant(pts_x.size(), x[1]) - pts_y;
+      const Eigen::ArrayXf bz = Eigen::ArrayXf::Constant(pts_x.size(), x[2]) - pts_z;
+      const Eigen::ArrayXf actual_cone_radius = std::tan(x[6]) *
+          (bx*axis_dir_x+by*axis_dir_y+bz*axis_dir_z);
+      // compute the squared distance of point b to the line (cross product), then subtract the actual cone radius (squared)
+      fvec = ((axis_dir_y * bz - axis_dir_z * by).square()
+             +(axis_dir_z * bx - axis_dir_x * bz).square()
+             +(axis_dir_x * by - axis_dir_y * bx).square())
+             -actual_cone_radius.square();
+      return (0);
+    }
+
+    const Eigen::ArrayXf& pts_x, pts_y, pts_z;
+  };
+
+  ConeOptimizationFunctor functor (pts_x, pts_y, pts_z);
+  Eigen::NumericalDiff<ConeOptimizationFunctor> num_diff (functor);
+  Eigen::LevenbergMarquardt<Eigen::NumericalDiff<ConeOptimizationFunctor>, float> lm (num_diff);
+  const int info = lm.minimize (coeff);
+  PCL_DEBUG ("[pcl::internal::optimizeModelCoefficientsCone] LM solver finished with exit code %i, having a residual norm of %g.\n",
+             info, lm.fvec.norm ());
+  return info;
+}
 
 #ifndef PCL_NO_PRECOMPILE
 #include <pcl/impl/instantiate.hpp>
index 54929fab8cb45daf7ed748fa5a4bb1cb01392d69..aae33d91c7e6c77dc1b95ace9bd593c0b0706420 100644 (file)
  */
 
 #include <pcl/sample_consensus/impl/sac_model_cylinder.hpp>
+#include <unsupported/Eigen/NonLinearOptimization> // for LevenbergMarquardt
+
+int pcl::internal::optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z)
+{
+  if(pts_x.size() != pts_y.size() || pts_y.size() != pts_z.size()) {
+    PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCylinder] Sizes not equal!\n");
+    return Eigen::LevenbergMarquardtSpace::ImproperInputParameters;
+  }
+  if(coeff.size() != 7) {
+    PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCylinder] Coefficients have wrong size\n");
+    return Eigen::LevenbergMarquardtSpace::ImproperInputParameters;
+  }
+  struct CylinderOptimizationFunctor : pcl::Functor<float>
+  {
+    CylinderOptimizationFunctor (const Eigen::ArrayXf& x, const Eigen::ArrayXf& y, const Eigen::ArrayXf& z) :
+      pcl::Functor<float>(x.size()), pts_x(x), pts_y(y), pts_z(z)
+      {}
+
+    int
+    operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const
+    {
+      Eigen::Vector3f line_dir(x[3], x[4], x[5]);
+      line_dir.normalize();
+      const Eigen::ArrayXf line_dir_x = Eigen::ArrayXf::Constant(pts_x.size(), line_dir.x());
+      const Eigen::ArrayXf line_dir_y = Eigen::ArrayXf::Constant(pts_x.size(), line_dir.y());
+      const Eigen::ArrayXf line_dir_z = Eigen::ArrayXf::Constant(pts_x.size(), line_dir.z());
+      const Eigen::ArrayXf bx = Eigen::ArrayXf::Constant(pts_x.size(), x[0]) - pts_x;
+      const Eigen::ArrayXf by = Eigen::ArrayXf::Constant(pts_x.size(), x[1]) - pts_y;
+      const Eigen::ArrayXf bz = Eigen::ArrayXf::Constant(pts_x.size(), x[2]) - pts_z;
+      // compute the squared distance of point b to the line (cross product), then subtract the squared model radius
+      fvec = ((line_dir_y * bz - line_dir_z * by).square()
+             +(line_dir_z * bx - line_dir_x * bz).square()
+             +(line_dir_x * by - line_dir_y * bx).square())
+             -Eigen::ArrayXf::Constant(pts_x.size(), x[6]*x[6]);
+      return (0);
+    }
+
+    const Eigen::ArrayXf& pts_x, pts_y, pts_z;
+  };
+
+  CylinderOptimizationFunctor functor (pts_x, pts_y, pts_z);
+  Eigen::NumericalDiff<CylinderOptimizationFunctor> num_diff (functor);
+  Eigen::LevenbergMarquardt<Eigen::NumericalDiff<CylinderOptimizationFunctor>, float> lm (num_diff);
+  const int info = lm.minimize (coeff);
+  coeff[6] = std::abs(coeff[6]);
+  PCL_DEBUG ("[pcl::internal::optimizeModelCoefficientsCylinder] LM solver finished with exit code %i, having a residual norm of %g.\n",
+             info, lm.fvec.norm ());
+  return info;
+}
 
 #ifndef PCL_NO_PRECOMPILE
 #include <pcl/impl/instantiate.hpp>
index 03d84652715d7857eb1138cafa176dca940ebd49..27fbf325760dca06e13423357aa96e1be8daa857 100644 (file)
  */
 
 #include <pcl/sample_consensus/impl/sac_model_sphere.hpp>
+#include <unsupported/Eigen/NonLinearOptimization> // for LevenbergMarquardt
+
+int pcl::internal::optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z)
+{
+  if(pts_x.size() != pts_y.size() || pts_y.size() != pts_z.size()) {
+    PCL_ERROR("[pcl::internal::optimizeModelCoefficientsSphere] Sizes not equal!\n");
+    return Eigen::LevenbergMarquardtSpace::ImproperInputParameters;
+  }
+  if(coeff.size() != 4) {
+    PCL_ERROR("[pcl::internal::optimizeModelCoefficientsSphere] Coefficients have wrong size\n");
+    return Eigen::LevenbergMarquardtSpace::ImproperInputParameters;
+  }
+  struct SphereOptimizationFunctor : pcl::Functor<float>
+  {
+    SphereOptimizationFunctor (const Eigen::ArrayXf& x, const Eigen::ArrayXf& y, const Eigen::ArrayXf& z) :
+      pcl::Functor<float>(x.size()), pts_x(x), pts_y(y), pts_z(z)
+      {}
+
+    int
+    operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const
+    {
+      // Compute distance of all points to center, then subtract radius
+      fvec = ((Eigen::ArrayXf::Constant(pts_x.size(), x[0])-pts_x).square()
+             +(Eigen::ArrayXf::Constant(pts_x.size(), x[1])-pts_y).square()
+             +(Eigen::ArrayXf::Constant(pts_x.size(), x[2])-pts_z).square()).sqrt()
+             -Eigen::ArrayXf::Constant(pts_x.size(), x[3]);
+      return (0);
+    }
+
+    const Eigen::ArrayXf& pts_x, pts_y, pts_z;
+  };
+
+  SphereOptimizationFunctor functor (pts_x, pts_y, pts_z);
+  Eigen::NumericalDiff<SphereOptimizationFunctor> num_diff (functor);
+  Eigen::LevenbergMarquardt<Eigen::NumericalDiff<SphereOptimizationFunctor>, float> lm (num_diff);
+  const int info = lm.minimize (coeff);
+  PCL_DEBUG ("[pcl::internal::optimizeModelCoefficientsSphere] LM solver finished with exit code %i, having a residual norm of %g.\n",
+             info, lm.fvec.norm ());
+  return info;
+}
 
 #ifndef PCL_NO_PRECOMPILE
 #include <pcl/impl/instantiate.hpp>
index 0b00fba0dddbbf3a2ce1bd3409534f636c0f5b6e..db48a7f0ea487ad02490f9c46ee6a89514062109 100644 (file)
@@ -37,6 +37,7 @@
  */
 
 #include <pcl/pcl_config.h>
+#define SAC_MODEL_STICK_DONT_WARN_DEPRECATED
 #include <pcl/sample_consensus/impl/sac_model_stick.hpp>
 
 #ifndef PCL_NO_PRECOMPILE
index e3461988feb05673fcff95561efc8da5a0c0b17c..f093a572809c159f3ec9712969dc9542e6b11624 100644 (file)
@@ -254,7 +254,7 @@ namespace pcl
           * \param[in] cloud the const boost shared pointer to a PointCloud message
           * \param[in] indices the point indices subset that is to be used from \a cloud
           */
-        void
+        bool
         setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices = IndicesConstPtr ()) override;
 
         using Search<PointT>::nearestKSearch;
@@ -348,20 +348,22 @@ namespace pcl
 
         /** Epsilon for approximate NN search.
           */
-        float eps_;
+        float eps_{0.0f};
         
         /** Number of checks to perform for approximate NN search using the multiple randomized tree index
          */
-        int checks_;
+        int checks_{32};
         
-        bool input_copied_for_flann_;
+        bool input_copied_for_flann_{false};
 
-        PointRepresentationConstPtr point_representation_;
+        PointRepresentationConstPtr point_representation_{nullptr};
 
-        int dim_;
+        int dim_{0};
 
         Indices index_mapping_;
-        bool identity_mapping_;
+        bool identity_mapping_{false};
+
+        std::size_t total_nr_points_{0};
 
     };
   }
index f54098ffb2a103ecc919c84fcad90c0e799813cd..2026db79e9be5da732e872fb7cb79888b6036727 100644 (file)
@@ -54,7 +54,7 @@ template <typename PointT, typename FlannDistance>
 typename pcl::search::FlannSearch<PointT, FlannDistance>::IndexPtr
 pcl::search::FlannSearch<PointT, FlannDistance>::KdTreeIndexCreator::createIndex (MatrixConstPtr data)
 {
-  return (IndexPtr (new flann::KDTreeSingleIndex<FlannDistance> (*data,flann::KDTreeSingleIndexParams (max_leaf_size_))));
+  return (static_cast<IndexPtr> (new flann::KDTreeSingleIndex<FlannDistance> (*data,static_cast<flann::KDTreeSingleIndexParams> (max_leaf_size_))));
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -62,7 +62,7 @@ template <typename PointT, typename FlannDistance>
 typename pcl::search::FlannSearch<PointT, FlannDistance>::IndexPtr
 pcl::search::FlannSearch<PointT, FlannDistance>::KMeansIndexCreator::createIndex (MatrixConstPtr data)
 {
-  return (IndexPtr (new flann::KMeansIndex<FlannDistance> (*data,flann::KMeansIndexParams ())));
+  return (static_cast<IndexPtr> (new flann::KMeansIndex<FlannDistance> (*data,flann::KMeansIndexParams ())));
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -70,14 +70,13 @@ template <typename PointT, typename FlannDistance>
 typename pcl::search::FlannSearch<PointT, FlannDistance>::IndexPtr
 pcl::search::FlannSearch<PointT, FlannDistance>::KdTreeMultiIndexCreator::createIndex (MatrixConstPtr data)
 {
-  return (IndexPtr (new flann::KDTreeIndex<FlannDistance> (*data, flann::KDTreeIndexParams (trees_))));
+  return (static_cast<IndexPtr> (new flann::KDTreeIndex<FlannDistance> (*data, static_cast<flann::KDTreeIndexParams> (trees_))));
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT, typename FlannDistance>
 pcl::search::FlannSearch<PointT, FlannDistance>::FlannSearch(bool sorted, FlannIndexCreatorPtr creator) : pcl::search::Search<PointT> ("FlannSearch",sorted),
-  index_(), creator_ (creator), eps_ (0), checks_ (32), input_copied_for_flann_ (false), point_representation_ (new DefaultPointRepresentation<PointT>),
-  dim_ (0), identity_mapping_()
+  index_(), creator_ (creator),  point_representation_ (new DefaultPointRepresentation<PointT>)
 {
   dim_ = point_representation_->getNumberOfDimensions ();
 }
@@ -91,7 +90,7 @@ pcl::search::FlannSearch<PointT, FlannDistance>::~FlannSearch()
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-template <typename PointT, typename FlannDistance> void
+template <typename PointT, typename FlannDistance> bool
 pcl::search::FlannSearch<PointT, FlannDistance>::setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices)
 {
   input_ = cloud;
@@ -99,6 +98,7 @@ pcl::search::FlannSearch<PointT, FlannDistance>::setInputCloud (const PointCloud
   convertInputToFlannMatrix ();
   index_ = creator_->createIndex (input_flann_);
   index_->buildIndex ();
+  return true;
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
@@ -118,6 +118,9 @@ pcl::search::FlannSearch<PointT, FlannDistance>::nearestKSearch (const PointT &p
   float* cdata = can_cast ? const_cast<float*> (reinterpret_cast<const float*> (&point)): data;
   const flann::Matrix<float> m (cdata ,1, point_representation_->getNumberOfDimensions ());
 
+  if (static_cast<unsigned int>(k) > total_nr_points_)
+    k = total_nr_points_;
+
   flann::SearchParams p;
   p.eps = eps_;
   p.sorted = sorted_results_;
@@ -126,7 +129,7 @@ pcl::search::FlannSearch<PointT, FlannDistance>::nearestKSearch (const PointT &p
     indices.resize (k,-1);
   if (dists.size() != static_cast<unsigned int> (k))
     dists.resize (k);
-  flann::Matrix<float> d (&dists[0],1,k);
+  flann::Matrix<float> d (dists.data(),1,k);
   int result = knn_search(*index_, m, indices, d, k, p);
 
   delete [] data;
@@ -180,6 +183,9 @@ pcl::search::FlannSearch<PointT, FlannDistance>::nearestKSearch (
     float* cdata = can_cast ? const_cast<float*> (reinterpret_cast<const float*> (&cloud[0])): data;
     const flann::Matrix<float> m (cdata ,cloud.size (), dim_, can_cast ? sizeof (PointT) : dim_ * sizeof (float) );
 
+    if (static_cast<unsigned int>(k) > total_nr_points_)
+      k = total_nr_points_;
+
     flann::SearchParams p;
     p.sorted = sorted_results_;
     p.eps = eps_;
@@ -383,12 +389,13 @@ pcl::search::FlannSearch<PointT, FlannDistance>::convertInputToFlannMatrix ()
     if (input_->is_dense && point_representation_->isTrivial ())
     {
       // const cast is evil, but flann won't change the data
-      input_flann_ = MatrixPtr (new flann::Matrix<float> (const_cast<float*>(reinterpret_cast<const float*>(&(*input_) [0])), original_no_of_points, point_representation_->getNumberOfDimensions (),sizeof (PointT)));
+      input_flann_ = static_cast<MatrixPtr> (new flann::Matrix<float> (const_cast<float*>(reinterpret_cast<const float*>(&(*input_) [0])), original_no_of_points, point_representation_->getNumberOfDimensions (),sizeof (PointT)));
       input_copied_for_flann_ = false;
+      total_nr_points_ = input_->points.size();
     }
     else
     {
-      input_flann_ = MatrixPtr (new flann::Matrix<float> (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ()));
+      input_flann_ = static_cast<MatrixPtr> (new flann::Matrix<float> (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ()));
       float* cloud_ptr = input_flann_->ptr();
       for (std::size_t i = 0; i < original_no_of_points; ++i)
       {
@@ -400,18 +407,20 @@ pcl::search::FlannSearch<PointT, FlannDistance>::convertInputToFlannMatrix ()
           continue;
         }
 
-        index_mapping_.push_back (static_cast<index_t> (i));  // If the returned index should be for the indices vector
+        index_mapping_.push_back (static_cast<index_t> (i));  
 
         point_representation_->vectorize (point, cloud_ptr);
         cloud_ptr += dim_;
       }
+      total_nr_points_ = index_mapping_.size();
     }
 
   }
   else
   {
-    input_flann_ = MatrixPtr (new flann::Matrix<float> (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ()));
+    input_flann_ = static_cast<MatrixPtr> (new flann::Matrix<float> (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ()));
     float* cloud_ptr = input_flann_->ptr();
+    identity_mapping_ = false;
     for (std::size_t indices_index = 0; indices_index < original_no_of_points; ++indices_index)
     {
       index_t cloud_index = (*indices_)[indices_index];
@@ -419,15 +428,15 @@ pcl::search::FlannSearch<PointT, FlannDistance>::convertInputToFlannMatrix ()
       // Check if the point is invalid
       if (!point_representation_->isValid (point))
       {
-        identity_mapping_ = false;
         continue;
       }
 
-      index_mapping_.push_back (static_cast<index_t> (indices_index));  // If the returned index should be for the indices vector
+      index_mapping_.push_back (static_cast<index_t> (cloud_index));  
 
       point_representation_->vectorize (point, cloud_ptr);
       cloud_ptr += dim_;
     }
+    total_nr_points_ = index_mapping_.size();
   }
   if (input_copied_for_flann_)
     input_flann_->rows = index_mapping_.size ();
index b3eff66740f4d18e096cae97d1dcd17cd61e7017..281b1cda360f19d74875742c2d2327ce97cb893e 100644 (file)
@@ -72,7 +72,7 @@ pcl::search::KdTree<PointT,Tree>::setEpsilon (float eps)
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////
-template <typename PointT, class Tree> void
+template <typename PointT, class Tree> bool
 pcl::search::KdTree<PointT,Tree>::setInputCloud (
     const PointCloudConstPtr& cloud, 
     const IndicesConstPtr& indices)
@@ -80,6 +80,7 @@ pcl::search::KdTree<PointT,Tree>::setInputCloud (
   tree_->setInputCloud (cloud, indices);
   input_ = cloud;
   indices_ = indices;
+  return true;
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////
index 45b493a376a4f7d7a9c5cbab753b7de7b9c72696..12e6da32962d0c2322e51f792058820854a3b0b0 100644 (file)
@@ -128,8 +128,8 @@ pcl::search::OrganizedNeighbor<PointT>::nearestKSearch (const PointT &query,
   // project query point on the image plane
   //Eigen::Vector3f q = KR_ * query.getVector3fMap () + projection_matrix_.block <3, 1> (0, 3);
   Eigen::Vector3f q (KR_ * queryvec + projection_matrix_.block <3, 1> (0, 3));
-  int xBegin = int(q [0] / q [2] + 0.5f);
-  int yBegin = int(q [1] / q [2] + 0.5f);
+  int xBegin = static_cast<int>(q [0] / q [2] + 0.5f);
+  int yBegin = static_cast<int>(q [1] / q [2] + 0.5f);
   int xEnd   = xBegin + 1; // end is the pixel that is not used anymore, like in iterators
   int yEnd   = yBegin + 1;
 
@@ -329,7 +329,7 @@ pcl::search::OrganizedNeighbor<PointT>::computeCameraMatrix (Eigen::Matrix3f& ca
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-template<typename PointT> void
+template<typename PointT> bool
 pcl::search::OrganizedNeighbor<PointT>::estimateProjectionMatrix ()
 {
   // internally we calculate with double but store the result into float matrices.
@@ -337,11 +337,11 @@ pcl::search::OrganizedNeighbor<PointT>::estimateProjectionMatrix ()
   if (input_->height == 1 || input_->width == 1)
   {
     PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not organized!\n", this->getName ().c_str ());
-    return;
+    return false;
   }
   
-  const unsigned ySkip = (std::max) (input_->height >> pyramid_level_, unsigned (1));
-  const unsigned xSkip = (std::max) (input_->width >> pyramid_level_, unsigned (1));
+  const unsigned ySkip = (std::max) (input_->height >> pyramid_level_, static_cast<unsigned>(1));
+  const unsigned xSkip = (std::max) (input_->width >> pyramid_level_, static_cast<unsigned>(1));
 
   Indices indices;
   indices.reserve (input_->size () >> (pyramid_level_ << 1));
@@ -358,11 +358,12 @@ pcl::search::OrganizedNeighbor<PointT>::estimateProjectionMatrix ()
   }
 
   double residual_sqr = pcl::estimateProjectionMatrix<PointT> (input_, projection_matrix_, indices);
+  PCL_DEBUG_STREAM("[pcl::" << this->getName () << "::estimateProjectionMatrix] projection matrix=" << std::endl << projection_matrix_ << std::endl << "residual_sqr=" << residual_sqr << std::endl);
   
-  if (std::abs (residual_sqr) > eps_ * float (indices.size ()))
+  if (std::abs (residual_sqr) > eps_ * static_cast<float>(indices.size ()))
   {
-    PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not from a projective device!\nResidual (MSE) %f, using %d valid points\n", this->getName ().c_str (), residual_sqr / double (indices.size()), indices.size ());
-    return;
+    PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not from a projective device!\nResidual (MSE) %g, using %d valid points\n", this->getName ().c_str (), residual_sqr / double (indices.size()), indices.size ());
+    return false;
   }
 
   // get left 3x3 sub matrix, which contains K * R, with K = camera matrix = [[fx s cx] [0 fy cy] [0 0 1]]
@@ -371,6 +372,21 @@ pcl::search::OrganizedNeighbor<PointT>::estimateProjectionMatrix ()
 
   // precalculate KR * KR^T needed by calculations during nn-search
   KR_KRT_ = KR_ * KR_.transpose ();
+
+  // final test: project a few points at known image coordinates and test if the projected coordinates are close
+  for(std::size_t i=0; i<11; ++i) {
+    const std::size_t test_index = input_->size()*i/11u;
+    if (!mask_[test_index])
+      continue;
+    const auto& test_point = (*input_)[test_index];
+    pcl::PointXY q;
+    if (!projectPoint(test_point, q) || std::abs(q.x-test_index%input_->width)>1 || std::abs(q.y-test_index/input_->width)>1) {
+      PCL_WARN ("[pcl::%s::estimateProjectionMatrix] Input dataset does not seem to be from a projective device! (point %zu (%g,%g,%g) projected to pixel coordinates (%g,%g), but actual pixel coordinates are (%zu,%zu))\n",
+                this->getName ().c_str (), test_index, test_point.x, test_point.y, test_point.z, q.x, q.y, static_cast<std::size_t>(test_index%input_->width), static_cast<std::size_t>(test_index/input_->width));
+      return false;
+    }
+  }
+  return true;
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
index aa8d229fd893bc15b33f365b2f9d84bbdfa2a802..9f24d244acd4f31dfbc0b3a269a61bb611f4825a 100644 (file)
@@ -71,12 +71,13 @@ pcl::search::Search<PointT>::getSortedResults ()
 }
  
 ///////////////////////////////////////////////////////////////////////////////////////////
-template <typename PointT> void
+template <typename PointT> bool
 pcl::search::Search<PointT>::setInputCloud (
     const PointCloudConstPtr& cloud, const IndicesConstPtr &indices)
 {
   input_ = cloud;
   indices_ = indices;
+  return true;
 }
 
 
index c0503a12588139dc778497a82f73bdef8bf0d031..59018eac220cc55f8e2413f32907a98241985078 100644 (file)
@@ -128,7 +128,7 @@ namespace pcl
           * \param[in] cloud the const boost shared pointer to a PointCloud message
           * \param[in] indices the point indices subset that is to be used from \a cloud 
           */
-        void
+        bool
         setInputCloud (const PointCloudConstPtr& cloud, 
                        const IndicesConstPtr& indices = IndicesConstPtr ()) override;
 
index 283a02600e1004dcb5b6b2610d5c276a7218ebe2..827667cb7235f96a7bb4cca5308599cbc7d5832d 100644 (file)
@@ -114,7 +114,7 @@ namespace pcl
           * \param[in] cloud the const boost shared pointer to a PointCloud message
           * \param[in] indices the point indices subset that is to be used from \a cloud 
           */
-        inline void
+        inline bool
         setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr& indices) override
         {
           tree_->deleteTree ();
@@ -122,6 +122,7 @@ namespace pcl
           tree_->addPointsFromInputCloud ();
           input_ = cloud;
           indices_ = indices;
+          return true;
         }
 
         /** \brief Search for the k-nearest neighbors for the given query point.
index 138759f0bfdf54fbb4757c732de68b448ba1f1a0..fe07756ef4495453fb8af9ca651e01741ba2e97e 100644 (file)
@@ -52,10 +52,14 @@ namespace pcl
 {
   namespace search
   {
-    /** \brief OrganizedNeighbor is a class for optimized nearest neigbhor search in organized point clouds.
-      * \author Radu B. Rusu, Julius Kammerl, Suat Gedikli, Koen Buys
-      * \ingroup search
-      */
+    /** \brief OrganizedNeighbor is a class for optimized nearest neighbor search in
+     * organized projectable point clouds, for instance from Time-Of-Flight cameras or
+     * stereo cameras. Note that rotating LIDARs may output organized clouds, but are
+     * not projectable via a pinhole camera model into two dimensions and thus will
+     * generally not work with this class.
+     * \author Radu B. Rusu, Julius Kammerl, Suat Gedikli, Koen Buys
+     * \ingroup search
+     */
     template<typename PointT>
     class OrganizedNeighbor : public pcl::search::Search<PointT>
     {
@@ -121,7 +125,7 @@ namespace pcl
           * \param[in] cloud the const boost shared pointer to a PointCloud message
           * \param[in] indices the const boost shared pointer to PointIndices
           */
-        void
+        bool
         setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr &indices = IndicesConstPtr ()) override
         {
           input_ = cloud;
@@ -139,7 +143,7 @@ namespace pcl
           else
             mask_.assign (input_->size (), 1);
 
-          estimateProjectionMatrix ();
+          return estimateProjectionMatrix () && isValid ();
         }
 
         /** \brief Search for all neighbors of query point that are within a given radius.
@@ -160,7 +164,7 @@ namespace pcl
                       unsigned int max_nn = 0) const override;
 
         /** \brief estimated the projection matrix from the input cloud. */
-        void 
+        bool
         estimateProjectionMatrix ();
 
          /** \brief Search for the k-nearest neighbors for a given query point.
index 396e1829d10321be51065a8525b4be31219abbe1..0991c98a967fd5a0b541f68f40a71eb815c5ac7f 100644 (file)
@@ -113,8 +113,9 @@ namespace pcl
         /** \brief Pass the input dataset that the search will be performed on.
           * \param[in] cloud a const pointer to the PointCloud data
           * \param[in] indices the point indices subset that is to be used from the cloud
+          * \return True if successful, false if an error occurred, for example because the point cloud is unsuited for the search method.
           */
-        virtual void
+        virtual bool
         setInputCloud (const PointCloudConstPtr& cloud, 
                        const IndicesConstPtr &indices = IndicesConstPtr ());
 
index 89bea126d82dcb972ee9d77f24adec91abc71cdd..f6cdf291a5ace5f5b49234f023b11a6414613273 100644 (file)
@@ -4,7 +4,7 @@ set(SUBSYS_DEPS common geometry search sample_consensus kdtree octree features f
 
 set(build TRUE)
 PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON)
-PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS})
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
@@ -25,7 +25,6 @@ set(srcs
   src/organized_multi_plane_segmentation.cpp
   src/planar_polygon_fusion.cpp
   src/crf_segmentation.cpp
-  src/crf_normal_segmentation.cpp
   src/unary_classifier.cpp
   src/conditional_euclidean_clustering.cpp
   src/supervoxel_clustering.cpp
index bc99e831d480354bf15cf11189a51873f9f3c46e..77bf58926f58269dd4958d7adc3dd4da7a20fa8a 100644 (file)
@@ -144,28 +144,28 @@ namespace pcl
     protected:
 
       /** \brief Maximum window size to be used in filtering ground returns. */
-      int max_window_size_;
+      int max_window_size_{33};
 
       /** \brief Slope value to be used in computing the height threshold. */
-      float slope_;
+      float slope_{0.7f};
 
       /** \brief Maximum height above the parameterized ground surface to be considered a ground return. */
-      float max_distance_;
+      float max_distance_{10.0f};
 
       /** \brief Initial height above the parameterized ground surface to be considered a ground return. */
-      float initial_distance_;
+      float initial_distance_{0.15f};
 
       /** \brief Cell size. */
-      float cell_size_;
+      float cell_size_{1.0f};
 
       /** \brief Base to be used in computing progressive window sizes. */
-      float base_;
+      float base_{2.0f};
 
       /** \brief Exponentially grow window sizes? */
-      bool exponential_;
+      bool exponential_{true};
 
       /** \brief Number of threads to be used. */
-      unsigned int threads_;      
+      unsigned int threads_{0};      
   };
 }
 
index dd7157867f30913da2a522b8ac628fb534b95d6f..a922e1b74c695ac65ecb2a923b4d081291e56293 100644 (file)
@@ -99,9 +99,6 @@ namespace pcl
       ConditionalEuclideanClustering (bool extract_removed_clusters = false) :
           searcher_ (),
           condition_function_ (),
-          cluster_tolerance_ (0.0f),
-          min_cluster_size_ (1),
-          max_cluster_size_ (std::numeric_limits<int>::max ()),
           extract_removed_clusters_ (extract_removed_clusters),
           small_clusters_ (new pcl::IndicesClusters),
           large_clusters_ (new pcl::IndicesClusters)
@@ -237,28 +234,28 @@ namespace pcl
 
     private:
       /** \brief A pointer to the spatial search object */
-      SearcherPtr searcher_;
+      SearcherPtr searcher_{nullptr};
 
       /** \brief The condition function that needs to hold for clustering */
       std::function<bool (const PointT&, const PointT&, float)> condition_function_;
 
       /** \brief The distance to scan for cluster candidates (default = 0.0) */
-      float cluster_tolerance_;
+      float cluster_tolerance_{0.0f};
 
       /** \brief The minimum cluster size (default = 1) */
-      int min_cluster_size_;
+      int min_cluster_size_{1};
 
       /** \brief The maximum cluster size (default = unlimited) */
-      int max_cluster_size_;
+      int max_cluster_size_{std::numeric_limits<int>::max ()};
 
       /** \brief Set to true if you want to be able to extract the clusters that are too large or too small (default = false) */
       bool extract_removed_clusters_;
 
       /** \brief The resultant clusters that contain less than min_cluster_size points */
-      pcl::IndicesClustersPtr small_clusters_;
+      pcl::IndicesClustersPtr small_clusters_{nullptr};
 
       /** \brief The resultant clusters that contain more than max_cluster_size points */
-      pcl::IndicesClustersPtr large_clusters_;
+      pcl::IndicesClustersPtr large_clusters_{nullptr};
 
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
index cb665b0b7f4781b67e567f170ed58e10591d9be1..897070e3522d1bc795f14ac6ad29b0b76880018b 100644 (file)
@@ -138,25 +138,25 @@ namespace pcl
       ///  *** Parameters *** ///
 
       /** \brief Maximum number of cuts */
-      std::uint32_t max_cuts_;
+      std::uint32_t max_cuts_{20};
 
       /** \brief Minimum segment size for cutting */
-      std::uint32_t min_segment_size_for_cutting_;
+      std::uint32_t min_segment_size_for_cutting_{400};
 
       /** \brief Cut_score threshold */
-      float min_cut_score_;
+      float min_cut_score_{0.16};
 
       /** \brief Use local constrains for cutting */
-      bool use_local_constrains_;
+      bool use_local_constrains_{true};
 
       /** \brief Use directed weights for the cutting */
-      bool use_directed_weights_;
+      bool use_directed_weights_{true};
 
       /** \brief Use clean cutting */
-      bool use_clean_cutting_;
+      bool use_clean_cutting_{false};
 
       /** \brief Iterations for RANSAC */
-      std::uint32_t ransac_itrs_;
+      std::uint32_t ransac_itrs_{10000};
 
 
 /******************************************* Directional weighted RANSAC declarations ******************************************************************/
index 6eb2663c1ba5acfa926aa9c8b8bd65462b4714b8..14a5d97c51fe9fc3d4c69d76ac184371d9081ce1 100644 (file)
@@ -47,7 +47,7 @@ namespace pcl
    * \author Christian Potthast
    */
   template <typename PointT>
-  class PCL_EXPORTS CrfNormalSegmentation
+  class PCL_DEPRECATED(1, 17, "CrfNormalSegmentation is not implemented and does not do anything useful") CrfNormalSegmentation
   {
     public:
       /** \brief Constructor that sets default values for member variables. */
@@ -71,6 +71,4 @@ namespace pcl
   };
 }
 
-#ifdef PCL_NO_PRECOMPILE
 #include <pcl/segmentation/impl/crf_normal_segmentation.hpp>
-#endif
index 300fb20f073fbc8fa2f012cf906c39e70648ea2d..67592875996e3a349bb7181d8d6b4e5c96efe6dd 100644 (file)
@@ -48,7 +48,7 @@
 
 namespace pcl
 {
-  /** \brief EuclideanClusterComparator is a comparator used for finding clusters based on euclidian distance.
+  /** \brief EuclideanClusterComparator is a comparator used for finding clusters based on euclidean distance.
   *
   * \author Alex Trevor
   */
@@ -126,7 +126,7 @@ namespace pcl
         return labels_;
       }
 
-      /** \brief Get exlude labels */
+      /** \brief Get exclude labels */
       const ExcludeLabelSetConstPtr&
       getExcludeLabels () const
       {
index d7234ade46fed090d4e3d25ccb6848e936d93202..cbda2cdf9523cca82d21a80336fa59e115a356ee 100644 (file)
@@ -179,9 +179,8 @@ namespace pcl
         for (std::size_t j = 0; j < seed_queue.size (); ++j)
           r.indices[j] = seed_queue[j];
 
-        // These two lines should not be needed: (can anyone confirm?) -FF
+        // After clustering, indices are out of order, so sort them
         std::sort (r.indices.begin (), r.indices.end ());
-        r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
 
         r.header = cloud.header;
         clusters.push_back (r);   // We could avoid a copy by working directly in the vector
@@ -299,9 +298,8 @@ namespace pcl
         for (std::size_t j = 0; j < seed_queue.size (); ++j)
           r.indices[j] = seed_queue[j];
 
-        // These two lines should not be needed: (can anyone confirm?) -FF
+        // After clustering, indices are out of order, so sort them
         std::sort (r.indices.begin (), r.indices.end ());
-        r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
 
         r.header = cloud.header;
         clusters.push_back (r);
@@ -339,11 +337,7 @@ namespace pcl
 
       //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
       /** \brief Empty constructor. */
-      EuclideanClusterExtraction () : tree_ (), 
-                                      cluster_tolerance_ (0),
-                                      min_pts_per_cluster_ (1), 
-                                      max_pts_per_cluster_ (std::numeric_limits<pcl::uindex_t>::max ())
-      {};
+      EuclideanClusterExtraction () = default;
 
       /** \brief Provide a pointer to the search object.
         * \param[in] tree a pointer to the spatial search object.
@@ -425,16 +419,16 @@ namespace pcl
       using BasePCLBase::deinitCompute;
 
       /** \brief A pointer to the spatial search object. */
-      KdTreePtr tree_;
+      KdTreePtr tree_{nullptr};
 
       /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
-      double cluster_tolerance_;
+      double cluster_tolerance_{0.0};
 
       /** \brief The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). */
-      pcl::uindex_t min_pts_per_cluster_;
+      pcl::uindex_t min_pts_per_cluster_{1};
 
       /** \brief The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). */
-      pcl::uindex_t max_pts_per_cluster_;
+      pcl::uindex_t max_pts_per_cluster_{std::numeric_limits<pcl::uindex_t>::max()};
 
       /** \brief Class getName method. */
       virtual std::string getClassName () const { return ("EuclideanClusterExtraction"); }
index d65beacad7dc4a2c4dc07cc774441cd74bd1a0b6..39aab83b0fd62b4750b7709d0289893b5b7604fe 100644 (file)
 
 namespace pcl {
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-/** \brief Decompose a region of space into clusters based on the Euclidean distance
- * between points
- * \param[in] cloud the point cloud message
- * \param[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors
- * searching
- * \note the tree has to be created as a spatial locator on \a cloud
- * \param[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
- * \param[out] labeled_clusters the resultant clusters containing point indices (as a
- * vector of PointIndices)
- * \param[in] min_pts_per_cluster minimum number of points that a cluster may contain
- * (default: 1)
- * \param[in] max_pts_per_cluster maximum number of points that a cluster may contain
- * (default: max int)
- * \param[in] max_label
- * \ingroup segmentation
- */
-template <typename PointT>
-PCL_DEPRECATED(1, 14, "Use of max_label is deprecated")
-void extractLabeledEuclideanClusters(
-    const PointCloud<PointT>& cloud,
-    const typename search::Search<PointT>::Ptr& tree,
-    float tolerance,
-    std::vector<std::vector<PointIndices>>& labeled_clusters,
-    unsigned int min_pts_per_cluster,
-    unsigned int max_pts_per_cluster,
-    unsigned int max_label);
-
 /** \brief Decompose a region of space into clusters based on the Euclidean distance
  * between points
  * \param[in] cloud the point cloud message
@@ -115,12 +88,7 @@ public:
 
   //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
   /** \brief Empty constructor. */
-  LabeledEuclideanClusterExtraction()
-  : tree_()
-  , cluster_tolerance_(0)
-  , min_pts_per_cluster_(1)
-  , max_pts_per_cluster_(std::numeric_limits<int>::max())
-  , max_label_(std::numeric_limits<int>::max()){};
+  LabeledEuclideanClusterExtraction() = default;
 
   /** \brief Provide a pointer to the search object.
    * \param[in] tree a pointer to the spatial search object.
@@ -190,24 +158,6 @@ public:
     return (max_pts_per_cluster_);
   }
 
-  /** \brief Set the maximum number of labels in the cloud.
-   * \param[in] max_label the maximum
-   */
-  PCL_DEPRECATED(1, 14, "Max label is being deprecated")
-  inline void
-  setMaxLabels(unsigned int max_label)
-  {
-    max_label_ = max_label;
-  }
-
-  /** \brief Get the maximum number of labels */
-  PCL_DEPRECATED(1, 14, "Max label is being deprecated")
-  inline unsigned int
-  getMaxLabels() const
-  {
-    return (max_label_);
-  }
-
   /** \brief Cluster extraction in a PointCloud given by <setInputCloud (), setIndices
    * ()> \param[out] labeled_clusters the resultant point clusters
    */
@@ -222,22 +172,22 @@ protected:
   using BasePCLBase::input_;
 
   /** \brief A pointer to the spatial search object. */
-  KdTreePtr tree_;
+  KdTreePtr tree_{nullptr};
 
   /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
-  double cluster_tolerance_;
+  double cluster_tolerance_{0.0};
 
   /** \brief The minimum number of points that a cluster needs to contain in order to be
    * considered valid (default = 1). */
-  int min_pts_per_cluster_;
+  int min_pts_per_cluster_{1};
 
   /** \brief The maximum number of points that a cluster needs to contain in order to be
    * considered valid (default = MAXINT). */
-  int max_pts_per_cluster_;
+  int max_pts_per_cluster_{std::numeric_limits<int>::max()};
 
   /** \brief The maximum number of labels we can find in this pointcloud (default =
    * MAXINT)*/
-  unsigned int max_label_;
+  unsigned int max_label_{std::numeric_limits<int>::max()};
 
   /** \brief Class getName method. */
   virtual std::string
index c35e28dbe943f7c9dbde6063a04fb46fa53f4d6c..0739726c53eaa820005b84fcf54f83c762efc770 100644 (file)
@@ -115,11 +115,7 @@ namespace pcl
       using PointIndicesConstPtr = PointIndices::ConstPtr;
 
       /** \brief Empty constructor. */
-      ExtractPolygonalPrismData () : planar_hull_ (), min_pts_hull_ (3), 
-                                     height_limit_min_ (0),
-                                     height_limit_max_(std::numeric_limits<float>::max()),
-                                     vpx_ (0), vpy_ (0), vpz_ (0)
-      {};
+      ExtractPolygonalPrismData () = default;
 
       /** \brief Provide a pointer to the input planar hull dataset.
         * \note Please see the example in the class description for how to obtain this.
@@ -187,23 +183,23 @@ namespace pcl
 
     protected:
       /** \brief A pointer to the input planar hull dataset. */
-      PointCloudConstPtr planar_hull_;
+      PointCloudConstPtr planar_hull_{nullptr};
 
       /** \brief The minimum number of points needed on the convex hull. */
-      int min_pts_hull_;
+      int min_pts_hull_{3};
 
       /** \brief The minimum allowed height (distance to the model) a point
         * will be considered from. 
         */
-      double height_limit_min_;
+      double height_limit_min_{0.0};
 
       /** \brief The maximum allowed height (distance to the model) a point
         * will be considered from. 
         */
-      double height_limit_max_;
+      double height_limit_max_{std::numeric_limits<float>::max()};
 
       /** \brief Values describing the data acquisition viewpoint. Default: 0,0,0. */
-      float vpx_, vpy_, vpz_;
+      float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};
 
       /** \brief Class getName method. */
       virtual std::string 
index 6734b46b12e934dff5c407d8ef9c73abf91f4426..0788cd690508ab96d22d4f14e521da4a3cef2507 100644 (file)
@@ -157,7 +157,7 @@ namespace pcl
           /// nodes and their outgoing internal edges
           std::vector<capacitated_edge> nodes_;
           /// current flow value (includes constant)
-          double flow_value_;
+          double flow_value_{0.0};
           /// identifies which side of the cut a node falls
           std::vector<unsigned char> cut_;
 
@@ -256,12 +256,9 @@ namespace pcl
       class GaussianFitter
       {
         public:
-        GaussianFitter (float epsilon = 0.0001)
-          : sum_ (Eigen::Vector3f::Zero ())
-          , accumulator_ (Eigen::Matrix3f::Zero ())
-          , count_ (0)
-          , epsilon_ (epsilon)
-        { }
+        GaussianFitter (float epsilon = 0.0001f)
+          : epsilon_ (epsilon)
+        {}
 
         /// Add a color sample
         void
@@ -281,11 +278,11 @@ namespace pcl
 
         private:
         /// sum of r,g, and b
-        Eigen::Vector3f sum_;
+        Eigen::Vector3f sum_{Eigen::Vector3f::Zero ()};
         /// matrix of products (i.e. r*r, r*g, r*b), some values are duplicated.
-        Eigen::Matrix3f accumulator_;
+        Eigen::Matrix3f accumulator_{Eigen::Matrix3f::Zero ()};
         /// count of color samples added to the gaussian
-        std::uint32_t count_;
+        std::uint32_t count_{0};
         /// small value to add to covariance matrix diagonal to avoid singular values
         float epsilon_;
         PCL_MAKE_ALIGNED_OPERATOR_NEW
@@ -329,12 +326,8 @@ namespace pcl
       using PCLBase<PointT>::fake_indices_;
 
       /// Constructor
-      GrabCut (std::uint32_t K = 5, float lambda = 50.f)
-        : K_ (K)
-        , lambda_ (lambda)
-        , nb_neighbours_ (9)
-        , initialized_ (false)
-      {}
+      GrabCut(std::uint32_t K = 5, float lambda = 50.f) : K_(K), lambda_(lambda) {}
+
       /// Destructor
       ~GrabCut () override = default;
       // /// Set input cloud
@@ -399,12 +392,12 @@ namespace pcl
       // Storage for N-link weights, each pixel stores links to nb_neighbours
       struct NLinks
       {
-        NLinks () : nb_links (0), indices (0), dists (0), weights (0) {}
+        NLinks () = default;
 
-        int nb_links;
-        Indices indices;
-        std::vector<float> dists;
-        std::vector<float> weights;
+        int nb_links{0};
+        Indices indices{};
+        std::vector<float> dists{};
+        std::vector<float> weights{};
       };
       bool
       initCompute ();
@@ -445,39 +438,39 @@ namespace pcl
       inline bool
       isSource (vertex_descriptor v) { return (graph_.inSourceTree (v)); }
       /// image width
-      std::uint32_t width_;
+      std::uint32_t width_{0};
       /// image height
-      std::uint32_t height_;
+      std::uint32_t height_{0};
       // Variables used in formulas from the paper.
       /// Number of GMM components
       std::uint32_t K_;
       /// lambda = 50. This value was suggested the GrabCut paper.
       float lambda_;
       /// beta = 1/2 * average of the squared color distances between all pairs of 8-neighboring pixels.
-      float beta_;
+      float beta_{0.0f};
       /// L = a large value to force a pixel to be foreground or background
-      float L_;
+      float L_{0.0f};
       /// Pointer to the spatial search object.
-      KdTreePtr tree_;
+      KdTreePtr tree_{nullptr};
       /// Number of neighbours
-      int nb_neighbours_;
+      int nb_neighbours_{9};
       /// is segmentation initialized
-      bool initialized_;
+      bool initialized_{false};
       /// Precomputed N-link weights
-      std::vector<NLinks> n_links_;
+      std::vector<NLinks> n_links_{};
       /// Converted input
       segmentation::grabcut::Image::Ptr image_;
-      std::vector<segmentation::grabcut::TrimapValue> trimap_;
-      std::vector<std::size_t> GMM_component_;
-      std::vector<segmentation::grabcut::SegmentationValue> hard_segmentation_;
+      std::vector<segmentation::grabcut::TrimapValue> trimap_{};
+      std::vector<std::size_t> GMM_component_{};
+      std::vector<segmentation::grabcut::SegmentationValue> hard_segmentation_{};
       // Not yet implemented (this would be interpreted as alpha)
-      std::vector<float> soft_segmentation_;
+      std::vector<float> soft_segmentation_{};
       segmentation::grabcut::GMM background_GMM_, foreground_GMM_;
       // Graph part
       /// Graph for Graphcut
       pcl::segmentation::grabcut::BoykovKolmogorov graph_;
       /// Graph nodes
-      std::vector<vertex_descriptor> graph_nodes_;
+      std::vector<vertex_descriptor> graph_nodes_{};
   };
 }
 
index 9e67b261f69a2f34634d41213a45f7fd6ad86512..8a054c54c1dcf6229d8001ae7f6e3616e66b2f00 100644 (file)
@@ -41,6 +41,7 @@
 
 #include <pcl/common/common.h>
 #include <pcl/common/io.h>
+#include <pcl/common/point_tests.h> // for isFinite
 #include <pcl/filters/morphological_filter.h>
 #include <pcl/segmentation/approximate_progressive_morphological_filter.h>
 #include <pcl/point_cloud.h>
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-pcl::ApproximateProgressiveMorphologicalFilter<PointT>::ApproximateProgressiveMorphologicalFilter () :
-  max_window_size_ (33),
-  slope_ (0.7f),
-  max_distance_ (10.0f),
-  initial_distance_ (0.15f),
-  cell_size_ (1.0f),
-  base_ (2.0f),
-  exponential_ (true),
-  threads_ (0)
-{
-}
+pcl::ApproximateProgressiveMorphologicalFilter<PointT>::ApproximateProgressiveMorphologicalFilter () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
@@ -122,26 +113,51 @@ pcl::ApproximateProgressiveMorphologicalFilter<PointT>::extract (Indices& ground
   Eigen::MatrixXf Zf (rows, cols);
   Zf.setConstant (std::numeric_limits<float>::quiet_NaN ());
 
+  if (input_->is_dense) {
 #pragma omp parallel for \
   default(none) \
   shared(A, global_min) \
   num_threads(threads_)
-  for (int i = 0; i < (int)input_->size (); ++i)
-  {
-    // ...then test for lower points within the cell
-    PointT p = (*input_)[i];
-    int row = std::floor((p.y - global_min.y ()) / cell_size_);
-    int col = std::floor((p.x - global_min.x ()) / cell_size_);
-
-    if (p.z < A (row, col) || std::isnan (A (row, col)))
-    {
-      A (row, col) = p.z;
+    for (int i = 0; i < static_cast<int>(input_->size ()); ++i) {
+      // ...then test for lower points within the cell
+      const PointT& p = (*input_)[i];
+      int row = std::floor((p.y - global_min.y ()) / cell_size_);
+      int col = std::floor((p.x - global_min.x ()) / cell_size_);
+
+      if (p.z < A (row, col) || std::isnan (A (row, col)))
+        A (row, col) = p.z;
+    }
+  }
+  else {
+#pragma omp parallel for \
+  default(none) \
+  shared(A, global_min) \
+  num_threads(threads_)
+    for (int i = 0; i < static_cast<int>(input_->size ()); ++i) {
+      // ...then test for lower points within the cell
+      const PointT& p = (*input_)[i];
+      if (!pcl::isFinite(p))
+        continue;
+      int row = std::floor((p.y - global_min.y ()) / cell_size_);
+      int col = std::floor((p.x - global_min.x ()) / cell_size_);
+
+      if (p.z < A (row, col) || std::isnan (A (row, col)))
+        A (row, col) = p.z;
     }
   }
 
   // Ground indices are initially limited to those points in the input cloud we
   // wish to process
-  ground = *indices_;
+  if (input_->is_dense) {
+    ground = *indices_;
+  }
+  else {
+    ground.clear();
+    ground.reserve(indices_->size());
+    for (const auto& index: *indices_)
+      if (pcl::isFinite((*input_)[index]))
+        ground.push_back(index);
+  }
 
   // Progressively filter ground returns using morphological open
   for (std::size_t i = 0; i < window_sizes.size (); ++i)
@@ -229,7 +245,7 @@ pcl::ApproximateProgressiveMorphologicalFilter<PointT>::extract (Indices& ground
     Indices pt_indices;
     for (std::size_t p_idx = 0; p_idx < ground.size (); ++p_idx)
     {
-      PointT p = (*cloud)[p_idx];
+      const PointT& p = (*cloud)[p_idx];
       int erow = static_cast<int> (std::floor ((p.y - global_min.y ()) / cell_size_));
       int ecol = static_cast<int> (std::floor ((p.x - global_min.x ()) / cell_size_));
 
index 2f0f5a57a0aea4e5e359add7d2e44ce993312816..f1aca882ecae4c4308b84e4b61029eb92c9a4035 100644 (file)
 #include <pcl/segmentation/cpc_segmentation.h>
 
 template <typename PointT>
-pcl::CPCSegmentation<PointT>::CPCSegmentation () :
-    max_cuts_ (20),
-    min_segment_size_for_cutting_ (400),
-    min_cut_score_ (0.16),
-    use_local_constrains_ (true),
-    use_directed_weights_ (true),
-    ransac_itrs_ (10000)
-{
-}
+pcl::CPCSegmentation<PointT>::CPCSegmentation () = default;
 
 template <typename PointT>
 pcl::CPCSegmentation<PointT>::~CPCSegmentation () = default;
@@ -199,7 +191,6 @@ pcl::CPCSegmentation<PointT>::applyCuttingPlane (std::uint32_t depth_levels_left
       for (const auto &cluster_index : cluster_indices)
       {
         // get centroids of vertices        
-        int cluster_concave_pts = 0;
         float cluster_score = 0;
 //         std::cout << "Cluster has " << cluster_indices[cc].indices.size () << " points" << std::endl;
         for (const auto &current_index : cluster_index.indices)
@@ -208,8 +199,6 @@ pcl::CPCSegmentation<PointT>::applyCuttingPlane (std::uint32_t depth_levels_left
           if (use_directed_weights_)
             index_score *= 1.414 * (std::abs (plane_normal.dot (edge_cloud_cluster->at (current_index).getNormalVector3fMap ())));
           cluster_score += index_score;
-          if (weights[current_index] > 0)
-            ++cluster_concave_pts;
         }
         // check if the score is below the threshold. If that is the case this segment should not be split
         cluster_score /= cluster_index.indices.size ();
index 57213cf3e2935f50a572a2da3be6238cf3bbeba5..2c2f9f5bac05d0564fc3ab3187b5017c36d81f8d 100644 (file)
@@ -349,7 +349,7 @@ pcl::CrfSegmentation<PointT>::createUnaryPotentials (std::vector<float> &unary,
       }
     }
   
-    // set the engeries for the labels
+    // set the energies for the labels
     std::size_t u_idx = k * n_labels;
     if (label > 0)
     {
index f5ec59ad88d22f531c350bf22dbf05212c42f7c4..8c1fb79aa1ed855d5fddc4fd28e523e0595adab4 100644 (file)
@@ -106,9 +106,8 @@ pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
       for (std::size_t j = 0; j < seed_queue.size (); ++j)
         r.indices[j] = seed_queue[j];
 
-      // These two lines should not be needed: (can anyone confirm?) -FF
+      // After clustering, indices are out of order, so sort them
       std::sort (r.indices.begin (), r.indices.end ());
-      r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
 
       r.header = cloud.header;
       clusters.push_back (r);   // We could avoid a copy by working directly in the vector
@@ -122,7 +121,6 @@ pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-/** @todo: fix the return value, make sure the exit is not needed anymore*/
 template <typename PointT> void
 pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
                                const Indices &indices,
@@ -174,7 +172,7 @@ pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
       if( ret == -1)
       {
         PCL_ERROR("[pcl::extractEuclideanClusters] Received error code -1 from radiusSearch\n");
-        exit(0);
+        return;
       }
       if (!ret)
       {
@@ -204,10 +202,8 @@ pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud,
         // This is the only place where indices come into play
         r.indices[j] = seed_queue[j];
 
-      // These two lines should not be needed: (can anyone confirm?) -FF
-      //r.indices.assign(seed_queue.begin(), seed_queue.end());
+      // After clustering, indices are out of order, so sort them
       std::sort (r.indices.begin (), r.indices.end ());
-      r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
 
       r.header = cloud.header;
       clusters.push_back (r);   // We could avoid a copy by working directly in the vector
index cbaa75aaf3dd78d8329ff22cc2a554127979422c..1f6ea1d88d1c941daf330374451c6ac356437756 100644 (file)
 #include <pcl/segmentation/extract_labeled_clusters.h>
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-template <typename PointT>
-void
-pcl::extractLabeledEuclideanClusters(
-    const PointCloud<PointT>& cloud,
-    const typename search::Search<PointT>::Ptr& tree,
-    float tolerance,
-    std::vector<std::vector<PointIndices>>& labeled_clusters,
-    unsigned int min_pts_per_cluster,
-    unsigned int max_pts_per_cluster,
-    unsigned int)
-{
-  pcl::extractLabeledEuclideanClusters<PointT>(cloud,
-                                               tree,
-                                               tolerance,
-                                               labeled_clusters,
-                                               min_pts_per_cluster,
-                                               max_pts_per_cluster);
-}
-
 template <typename PointT>
 void
 pcl::extractLabeledEuclideanClusters(
@@ -129,9 +110,8 @@ pcl::extractLabeledEuclideanClusters(
       r.indices.resize(seed_queue.size());
       for (std::size_t j = 0; j < seed_queue.size(); ++j)
         r.indices[j] = seed_queue[j];
-
+      // After clustering, indices are out of order, so sort them
       std::sort(r.indices.begin(), r.indices.end());
-      r.indices.erase(std::unique(r.indices.begin(), r.indices.end()), r.indices.end());
 
       r.header = cloud.header;
       labeled_clusters[cloud[i].label].push_back(
@@ -180,15 +160,6 @@ pcl::LabeledEuclideanClusterExtraction<PointT>::extract(
 
 #define PCL_INSTANTIATE_LabeledEuclideanClusterExtraction(T)                           \
   template class PCL_EXPORTS pcl::LabeledEuclideanClusterExtraction<T>;
-#define PCL_INSTANTIATE_extractLabeledEuclideanClusters_deprecated(T)                  \
-  template void PCL_EXPORTS pcl::extractLabeledEuclideanClusters<T>(                   \
-      const pcl::PointCloud<T>&,                                                       \
-      const typename pcl::search::Search<T>::Ptr&,                                     \
-      float,                                                                           \
-      std::vector<std::vector<pcl::PointIndices>>&,                                    \
-      unsigned int,                                                                    \
-      unsigned int,                                                                    \
-      unsigned int);
 #define PCL_INSTANTIATE_extractLabeledEuclideanClusters(T)                             \
   template void PCL_EXPORTS pcl::extractLabeledEuclideanClusters<T>(                   \
       const pcl::PointCloud<T>&,                                                       \
index 280d3c3ff8c6379264da5f1c81735164c7e4bf8c..8f1f6033670fa873a4144d71bca8bdb4618955a5 100644 (file)
 
 
 template <typename PointT>
-pcl::LCCPSegmentation<PointT>::LCCPSegmentation () :
-  concavity_tolerance_threshold_ (10),
-  grouping_data_valid_ (false),
-  supervoxels_set_ (false),
-  use_smoothness_check_ (false),
-  smoothness_threshold_ (0.1),
-  use_sanity_check_ (false),  
-  seed_resolution_ (0),
-  voxel_resolution_ (0),
-  k_factor_ (0),
-  min_segment_size_ (0)
-{
-}
+pcl::LCCPSegmentation<PointT>::LCCPSegmentation () = default;
 
 template <typename PointT>
 pcl::LCCPSegmentation<PointT>::~LCCPSegmentation () = default;
@@ -177,7 +165,6 @@ pcl::LCCPSegmentation<PointT>::mergeSmallSegments ()
   while (continue_filtering)
   {
     continue_filtering = false;
-    unsigned int nr_filtered = 0;
 
     VertexIterator sv_itr, sv_itr_end;
     // Iterate through all supervoxels, check if they are in a "small" segment -> change label to largest neighborID
@@ -195,7 +182,6 @@ pcl::LCCPSegmentation<PointT>::mergeSmallSegments ()
       if (seg_label_to_sv_list_map_[current_seg_label].size () <= min_segment_size_)
       {
         continue_filtering = true;
-        nr_filtered++;
 
         // Find largest neighbor
         for (auto neighbors_itr = seg_label_to_neighbor_set_map_[current_seg_label].cbegin (); neighbors_itr != seg_label_to_neighbor_set_map_[current_seg_label].cend (); ++neighbors_itr)
index 0b390c3b892d134d8ee3136e1cd1d9c18cbea74f..0ec614a8e53639ee5fe1899b92adc1b9a9ef2489 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-pcl::MinCutSegmentation<PointT>::MinCutSegmentation () :
-  inverse_sigma_ (16.0),
-  binary_potentials_are_valid_ (false),
-  epsilon_ (0.0001),
-  radius_ (16.0),
-  unary_potentials_are_valid_ (false),
-  source_weight_ (0.8),
-  search_ (),
-  number_of_neighbours_ (14),
-  graph_is_valid_ (false),
-  foreground_points_ (0),
-  background_points_ (0),
-  clusters_ (0),
-  vertices_ (0),
-  edge_marker_ (0),
-  source_ (),/////////////////////////////////
-  sink_ (),///////////////////////////////////
-  max_flow_ (0.0)
-{
-}
+pcl::MinCutSegmentation<PointT>::MinCutSegmentation () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
@@ -496,7 +477,7 @@ pcl::MinCutSegmentation<PointT>::recalculateBinaryPotentials ()
   std::vector< std::set<VertexDescriptor> > edge_marker;
   std::set<VertexDescriptor> out_edges_marker;
   edge_marker.clear ();
-  edge_marker.resize (indices_->size () + 2, out_edges_marker);
+  edge_marker.resize (input_->size () + 2, out_edges_marker);
 
   for (boost::tie (vertex_iter, vertex_end) = boost::vertices (*graph_); vertex_iter != vertex_end; ++vertex_iter)
   {
index cdba4b46ac500edb6f4def9614fccf2a52132583..d9792e0fa4ea653917f2eadf200784de17a8ad6e 100644 (file)
@@ -78,7 +78,7 @@ pcl::OrganizedConnectedComponentSegmentation<PointT, PointLT>::findLabeledRegion
     x = curr_x + directions [dIdx].d_x;
     y = curr_y + directions [dIdx].d_y;
     index = curr_idx + directions [dIdx].d_index;
-    if (x >= 0 && x < int(labels->width) && y >= 0 && y < int(labels->height) && (*labels)[index].label != label)
+    if (x >= 0 && x < static_cast<int>(labels->width) && y >= 0 && y < static_cast<int>(labels->height) && (*labels)[index].label != label)
     {
       direction = dIdx;
       break;
@@ -100,7 +100,7 @@ pcl::OrganizedConnectedComponentSegmentation<PointT, PointLT>::findLabeledRegion
       x = curr_x + directions [nIdx].d_x;
       y = curr_y + directions [nIdx].d_y;
       index = curr_idx + directions [nIdx].d_index;
-      if (x >= 0 && x < int(labels->width) && y >= 0 && y < int(labels->height) && (*labels)[index].label == label)
+      if (x >= 0 && x < static_cast<int>(labels->width) && y >= 0 && y < static_cast<int>(labels->height) && (*labels)[index].label == label)
         break;
     }
     
index 1c1ee2e01484c9e8f3480adfffd5d3af4fb7a447..68a3d3cd240d8cbae74fea2cfd71d286612a9183 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-pcl::ProgressiveMorphologicalFilter<PointT>::ProgressiveMorphologicalFilter () :
-  max_window_size_ (33),
-  slope_ (0.7f),
-  max_distance_ (10.0f),
-  initial_distance_ (0.15f),
-  cell_size_ (1.0f),
-  base_ (2.0f),
-  exponential_ (true)
-{
-}
+pcl::ProgressiveMorphologicalFilter<PointT>::ProgressiveMorphologicalFilter () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
index 2b8653e4f541dc21a270986c39a54d142e3f944d..0677cfbe17e655ba74acb31e6f9c5ec87352727a 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT, typename NormalT>
-pcl::RegionGrowing<PointT, NormalT>::RegionGrowing () :
-  min_pts_per_cluster_ (1),
-  max_pts_per_cluster_ (std::numeric_limits<pcl::uindex_t>::max ()),
-  smooth_mode_flag_ (true),
-  curvature_flag_ (true),
-  residual_flag_ (false),
-  theta_threshold_ (30.0f / 180.0f * static_cast<float> (M_PI)),
-  residual_threshold_ (0.05f),
-  curvature_threshold_ (0.05f),
-  neighbour_number_ (30),
-  search_ (),
-  normals_ (),
-  point_neighbours_ (0),
-  point_labels_ (0),
-  normal_flag_ (true),
-  num_pts_in_segment_ (0),
-  clusters_ (0),
-  number_of_segments_ (0)
-{
-}
+pcl::RegionGrowing<PointT, NormalT>::RegionGrowing() = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT, typename NormalT>
@@ -140,7 +121,7 @@ pcl::RegionGrowing<PointT, NormalT>::setCurvatureTestFlag (bool value)
 {
   curvature_flag_ = value;
 
-  if (curvature_flag_ == false && residual_flag_ == false)
+  if (!curvature_flag_ && !residual_flag_)
     residual_flag_ = true;
 }
 
@@ -157,7 +138,7 @@ pcl::RegionGrowing<PointT, NormalT>::setResidualTestFlag (bool value)
 {
   residual_flag_ = value;
 
-  if (curvature_flag_ == false && residual_flag_ == false)
+  if (!curvature_flag_ && !residual_flag_)
     curvature_flag_ = true;
 }
 
@@ -342,30 +323,27 @@ pcl::RegionGrowing<PointT, NormalT>::prepareForSegmentation ()
 template <typename PointT, typename NormalT> void
 pcl::RegionGrowing<PointT, NormalT>::findPointNeighbours ()
 {
-  int point_number = static_cast<int> (indices_->size ());
   pcl::Indices neighbours;
   std::vector<float> distances;
 
   point_neighbours_.resize (input_->size (), neighbours);
   if (input_->is_dense)
   {
-    for (int i_point = 0; i_point < point_number; i_point++)
+    for (const auto& point_index: (*indices_))
     {
-      int point_index = (*indices_)[i_point];
       neighbours.clear ();
-      search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances);
+      search_->nearestKSearch (point_index, neighbour_number_, neighbours, distances);
       point_neighbours_[point_index].swap (neighbours);
     }
   }
   else
   {
-    for (int i_point = 0; i_point < point_number; i_point++)
+    for (const auto& point_index: (*indices_))
     {
-      neighbours.clear ();
-      int point_index = (*indices_)[i_point];
       if (!pcl::isFinite ((*input_)[point_index]))
         continue;
-      search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances);
+      neighbours.clear ();
+      search_->nearestKSearch (point_index, neighbour_number_, neighbours, distances);
       point_neighbours_[point_index].swap (neighbours);
     }
   }
@@ -382,11 +360,11 @@ pcl::RegionGrowing<PointT, NormalT>::applySmoothRegionGrowingAlgorithm ()
   std::pair<float, int> pair;
   point_residual.resize (num_of_pts, pair);
 
-  if (normal_flag_ == true)
+  if (normal_flag_)
   {
     for (int i_point = 0; i_point < num_of_pts; i_point++)
     {
-      int point_index = (*indices_)[i_point];
+      const auto point_index = (*indices_)[i_point];
       point_residual[i_point].first = (*normals_)[point_index].curvature;
       point_residual[i_point].second = point_index;
     }
@@ -396,7 +374,7 @@ pcl::RegionGrowing<PointT, NormalT>::applySmoothRegionGrowingAlgorithm ()
   {
     for (int i_point = 0; i_point < num_of_pts; i_point++)
     {
-      int point_index = (*indices_)[i_point];
+      const auto point_index = (*indices_)[i_point];
       point_residual[i_point].first = 0;
       point_residual[i_point].second = point_index;
     }
@@ -495,7 +473,7 @@ pcl::RegionGrowing<PointT, NormalT>::validatePoint (pcl::index_t initial_seed, p
   Eigen::Map<Eigen::Vector3f> initial_normal (static_cast<float*> ((*normals_)[point].normal));
 
   //check the angle between normals
-  if (smooth_mode_flag_ == true)
+  if (smooth_mode_flag_)
   {
     Eigen::Map<Eigen::Vector3f> nghbr_normal (static_cast<float*> ((*normals_)[nghbr].normal));
     float dot_product = std::abs (nghbr_normal.dot (initial_normal));
index 1bce66b94b9a23402dde68e3be2a313d1869bd64..2c240d37c46246a43c0cbcb1e3ace7b251c13dd6 100644 (file)
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT, typename NormalT>
 pcl::RegionGrowingRGB<PointT, NormalT>::RegionGrowingRGB () :
-  color_p2p_threshold_ (1225.0f),
-  color_r2r_threshold_ (10.0f),
-  distance_threshold_ (0.05f),
-  region_neighbour_number_ (100),
   point_distances_ (0),
   segment_neighbours_ (0),
   segment_distances_ (0),
@@ -272,19 +268,17 @@ pcl::RegionGrowingRGB<PointT, NormalT>::prepareForSegmentation ()
 template <typename PointT, typename NormalT> void
 pcl::RegionGrowingRGB<PointT, NormalT>::findPointNeighbours ()
 {
-  int point_number = static_cast<int> (indices_->size ());
   pcl::Indices neighbours;
   std::vector<float> distances;
 
   point_neighbours_.resize (input_->size (), neighbours);
   point_distances_.resize (input_->size (), distances);
 
-  for (int i_point = 0; i_point < point_number; i_point++)
+  for (const auto& point_index: (*indices_))
   {
-    int point_index = (*indices_)[i_point];
     neighbours.clear ();
     distances.clear ();
-    search_->nearestKSearch (i_point, region_neighbour_number_, neighbours, distances);
+    search_->nearestKSearch (point_index, region_neighbour_number_, neighbours, distances);
     point_neighbours_[point_index].swap (neighbours);
     point_distances_[point_index].swap (distances);
   }
@@ -511,9 +505,9 @@ template <typename PointT, typename NormalT> float
 pcl::RegionGrowingRGB<PointT, NormalT>::calculateColorimetricalDifference (std::vector<unsigned int>& first_color, std::vector<unsigned int>& second_color) const
 {
   float difference = 0.0f;
-  difference += float ((first_color[0] - second_color[0]) * (first_color[0] - second_color[0]));
-  difference += float ((first_color[1] - second_color[1]) * (first_color[1] - second_color[1]));
-  difference += float ((first_color[2] - second_color[2]) * (first_color[2] - second_color[2]));
+  difference += static_cast<float>((first_color[0] - second_color[0]) * (first_color[0] - second_color[0]));
+  difference += static_cast<float>((first_color[1] - second_color[1]) * (first_color[1] - second_color[1]));
+  difference += static_cast<float>((first_color[2] - second_color[2]) * (first_color[2] - second_color[2]));
   return (difference);
 }
 
index d02c08712814b968f1b206ca1a3871d47ef410f6..e701b5ef75272234d4bb5801faafed5362da71e3 100644 (file)
@@ -68,7 +68,9 @@
 #include <pcl/sample_consensus/sac_model_plane.h>
 #include <pcl/sample_consensus/sac_model_sphere.h>
 #include <pcl/sample_consensus/sac_model_normal_sphere.h>
+#define SAC_MODEL_STICK_DONT_WARN_DEPRECATED
 #include <pcl/sample_consensus/sac_model_stick.h>
+#undef SAC_MODEL_STICK_DONT_WARN_DEPRECATED
 #include <pcl/sample_consensus/sac_model_ellipse3d.h>
 
 #include <pcl/memory.h>  // for static_pointer_cast
@@ -118,14 +120,14 @@ pcl::SACSegmentation<PointT>::segment (PointIndices &inliers, ModelCoefficients
     Eigen::VectorXf coeff_refined (model_->getModelSize ());
     model_->optimizeModelCoefficients (inliers.indices, coeff, coeff_refined);
     model_coefficients.values.resize (coeff_refined.size ());
-    memcpy (&model_coefficients.values[0], &coeff_refined[0], coeff_refined.size () * sizeof (float));
+    memcpy (model_coefficients.values.data(), coeff_refined.data(), coeff_refined.size () * sizeof (float));
     // Refine inliers
     model_->selectWithinDistance (coeff_refined, threshold_, inliers.indices);
   }
   else
   {
     model_coefficients.values.resize (coeff.size ());
-    memcpy (&model_coefficients.values[0], &coeff[0], coeff.size () * sizeof (float));
+    memcpy (model_coefficients.values.data(), coeff.data(), coeff.size () * sizeof (float));
   }
 
   deinitCompute ();
@@ -155,6 +157,7 @@ pcl::SACSegmentation<PointT>::initSACModel (const int model_type)
     }
     case SACMODEL_STICK:
     {
+      PCL_WARN ("[pcl::%s::initSACModel] SACMODEL_STICK is deprecated: Use SACMODEL_LINE instead (It will be removed in PCL 1.17)\n", getClassName ().c_str ());
       PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_STICK\n", getClassName ().c_str ());
       model_.reset (new SampleConsensusModelStick<PointT> (input_, *indices_));
       double min_radius, max_radius;
index ad4de5e943f4fa0044e71a1cd652027c2810c9f2..dc3611639eca4d63e51cdd4b00615b5b9a81f59f 100755 (executable)
@@ -63,7 +63,7 @@ pcl::getPointCloudDifference (
   // Iterate through the source data set
   for (index_t i = 0; i < static_cast<index_t> (src.size ()); ++i)
   {
-    // Ignore invalid points in the inpout cloud
+    // Ignore invalid points in the input cloud
     if (!isFinite (src[i]))
       continue;
     // Search for the closest point in the target data set (number of neighbors to find = 1)
index 2af3e32e9b53b14c0035f070b6596daa1d501d08..9d627c600ff5e07c201ef998606f0d502e05a7ba 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-pcl::SupervoxelClustering<PointT>::SupervoxelClustering (float voxel_resolution, float seed_resolution) :
-  resolution_ (voxel_resolution),
-  seed_resolution_ (seed_resolution),
-  adjacency_octree_ (),
-  voxel_centroid_cloud_ (),
-  color_importance_ (0.1f),
-  spatial_importance_ (0.4f),
-  normal_importance_ (1.0f),
-  use_default_transform_behaviour_ (true)
+pcl::SupervoxelClustering<PointT>::SupervoxelClustering(float voxel_resolution,
+                                                        float seed_resolution)
+: resolution_(voxel_resolution)
+, seed_resolution_(seed_resolution)
+, adjacency_octree_()
+, voxel_centroid_cloud_()
 {
-  adjacency_octree_.reset (new OctreeAdjacencyT (resolution_));
+  adjacency_octree_.reset(new OctreeAdjacencyT(resolution_));
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -505,7 +502,7 @@ pcl::SupervoxelClustering<PointT>::getSupervoxelAdjacencyList (VoxelAdjacencyLis
       if (edge_added)
       {
         VoxelData centroid_data = (sv_itr)->getCentroid ();
-        //Find the neighbhor with this label
+        //Find the neighbor with this label
         VoxelData neighb_centroid_data;
         
         for (typename HelperListT::const_iterator neighb_itr = supervoxel_helpers_.cbegin (); neighb_itr != supervoxel_helpers_.cend (); ++neighb_itr)
index 38f2cd59cda228b1e8269d9784e0dc5ae17a078a..dc4ef677a38b3484139b942f80f11f997f21b516 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
-pcl::UnaryClassifier<PointT>::UnaryClassifier () :
-  input_cloud_ (new pcl::PointCloud<PointT>),
-  label_field_ (false),
-  normal_radius_search_ (0.01f),
-  fpfh_radius_search_ (0.05f),
-  feature_threshold_ (5.0)
-{
-}
+pcl::UnaryClassifier<PointT>::UnaryClassifier() = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointT>
index ed04968159c51e2dcc76489cf5b014b0a329986b..c3c3508ad8b870a8433f68a8106098ff41bba458 100644 (file)
@@ -60,21 +60,18 @@ namespace pcl
     struct EdgeProperties
     {
       /** \brief Describes the difference of normals of the two supervoxels being connected*/
-      float normal_difference;
+      float normal_difference{0.0f};
 
       /** \brief Describes if a connection is convex or concave*/
-      bool is_convex;
+      bool is_convex{false};
 
       /** \brief Describes if a connection is valid for the segment growing. Usually convex connections are and concave connection are not. Due to k-concavity a convex connection can be invalidated*/
-      bool is_valid;
+      bool is_valid{false};
 
       /** \brief Additional member used for the CPC algorithm. If edge has already induced a cut, it should be ignored for further cutting.*/
-      bool used_for_cutting;
+      bool used_for_cutting{false};
 
-      EdgeProperties () :
-      normal_difference (0), is_convex (false), is_valid (false), used_for_cutting (false)
-      {
-      }
+      EdgeProperties () = default;
     };
 
     public:
@@ -297,34 +294,34 @@ namespace pcl
       ///  *** Parameters *** ///
 
       /** \brief Normal Threshold in degrees [0,180] used for merging */
-      float concavity_tolerance_threshold_;
+      float concavity_tolerance_threshold_{10};
 
       /** \brief Marks if valid grouping data (\ref sv_adjacency_list_, \ref sv_label_to_seg_label_map_, \ref processed_) is available */
-      bool grouping_data_valid_;
+      bool grouping_data_valid_{false};
 
       /** \brief Marks if supervoxels have been set by calling \ref setInputSupervoxels */
-      bool supervoxels_set_;
+      bool supervoxels_set_{false};
 
       /** \brief Determines if the smoothness check is used during segmentation*/
-      bool use_smoothness_check_;
+      bool use_smoothness_check_{false};
 
       /** \brief Two supervoxels are unsmooth if their plane-to-plane distance DIST >  (expected_distance + smoothness_threshold_*voxel_resolution_). For parallel supervoxels, the expected_distance is zero. */
-      float smoothness_threshold_;
+      float smoothness_threshold_{0.1};
 
       /** \brief Determines if we use the sanity check which tries to find and invalidate singular connected patches*/
-      bool use_sanity_check_;
+      bool use_sanity_check_{false};
 
       /** \brief Seed resolution of the supervoxels (used only for smoothness check) */
-      float seed_resolution_;
+      float seed_resolution_{0.0f};
 
       /** \brief Voxel resolution used to build the supervoxels (used only for smoothness check)*/
-      float voxel_resolution_;
+      float voxel_resolution_{0.0f};
 
       /** \brief Factor used for k-convexity */
-      std::uint32_t k_factor_;
+      std::uint32_t k_factor_{0};
 
       /** \brief Minimum segment size */
-      std::uint32_t min_segment_size_;
+      std::uint32_t min_segment_size_{0};
 
       /** \brief Stores which supervoxel labels were already visited during recursive grouping.
        *  \note processed_[sv_Label] = false (default)/true (already processed) */
index 888cdc13f4209e927659c2bf13db0446b04f64af..0e56705ff52b0d34e81a78228a4de94ecb650aba 100644 (file)
@@ -54,6 +54,7 @@ namespace pcl
     * The description can be found in the article:
     * "Min-Cut Based Segmentation of Point Clouds"
     * \author: Aleksey Golovinskiy and Thomas Funkhouser.
+    * \ingroup segmentation
     */
   template <typename PointT>
   class PCL_EXPORTS MinCutSegmentation : public pcl::PCLBase<PointT>
@@ -260,64 +261,64 @@ namespace pcl
     protected:
 
       /** \brief Stores the sigma coefficient. It is used for finding smooth costs. More information can be found in the article. */
-      double inverse_sigma_;
+      double inverse_sigma_{16.0};
 
       /** \brief Signalizes if the binary potentials are valid. */
-      bool binary_potentials_are_valid_;
+      bool binary_potentials_are_valid_{false};
 
       /** \brief Used for comparison of the floating point numbers. */
-      double epsilon_;
+      double epsilon_{0.0001};
 
       /** \brief Stores the distance to the background. */
-      double radius_;
+      double radius_{16.0};
 
       /** \brief Signalizes if the unary potentials are valid. */
-      bool unary_potentials_are_valid_;
+      bool unary_potentials_are_valid_{false};
 
       /** \brief Stores the weight for every edge that comes from source point. */
-      double source_weight_;
+      double source_weight_{0.8};
 
       /** \brief Stores the search method that will be used for finding K nearest neighbors. Neighbours are used for building the graph. */
-      KdTreePtr search_;
+      KdTreePtr search_{nullptr};
 
       /** \brief Stores the number of neighbors to find. */
-      unsigned int number_of_neighbours_;
+      unsigned int number_of_neighbours_{14};
 
       /** \brief Signalizes if the graph is valid. */
-      bool graph_is_valid_;
+      bool graph_is_valid_{false};
 
       /** \brief Stores the points that are known to be in the foreground. */
-      std::vector<PointT, Eigen::aligned_allocator<PointT> > foreground_points_;
+      std::vector<PointT, Eigen::aligned_allocator<PointT> > foreground_points_{};
 
       /** \brief Stores the points that are known to be in the background. */
-      std::vector<PointT, Eigen::aligned_allocator<PointT> > background_points_;
+      std::vector<PointT, Eigen::aligned_allocator<PointT> > background_points_{};
 
       /** \brief After the segmentation it will contain the segments. */
-      std::vector <pcl::PointIndices> clusters_;
+      std::vector <pcl::PointIndices> clusters_{};
 
       /** \brief Stores the graph for finding the maximum flow. */
-      mGraphPtr graph_;
+      mGraphPtr graph_{nullptr};
 
       /** \brief Stores the capacity of every edge in the graph. */
-      std::shared_ptr<CapacityMap> capacity_;
+      std::shared_ptr<CapacityMap> capacity_{nullptr};
 
       /** \brief Stores reverse edges for every edge in the graph. */
-      std::shared_ptr<ReverseEdgeMap> reverse_edges_;
+      std::shared_ptr<ReverseEdgeMap> reverse_edges_{nullptr};
 
       /** \brief Stores the vertices of the graph. */
-      std::vector< VertexDescriptor > vertices_;
+      std::vector< VertexDescriptor > vertices_{};
 
       /** \brief Stores the information about the edges that were added to the graph. It is used to avoid the duplicate edges. */
-      std::vector< std::set<int> > edge_marker_;
+      std::vector< std::set<int> > edge_marker_{};
 
       /** \brief Stores the vertex that serves as source. */
-      VertexDescriptor source_;
+      VertexDescriptor source_{};
 
       /** \brief Stores the vertex that serves as sink. */
-      VertexDescriptor sink_;
+      VertexDescriptor sink_{};
 
       /** \brief Stores the maximum flow value that was calculated during the segmentation. */
-      double max_flow_;
+      double max_flow_{0.0};
 
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
index 30890706c57e5e9001a458a3cf1478fd33ab17c4..8bf5c5ffe7e307e299cd571fa86aee5f6cc486d0 100644 (file)
@@ -53,6 +53,7 @@ namespace pcl
     * See OrganizedMultiPlaneSegmentation for an example application.
     *
     * \author Alex Trevor, Suat Gedikli
+    * \ingroup segmentation
     */
   template <typename PointT, typename PointLT>
   class OrganizedConnectedComponentSegmentation : public PCLBase<PointT>
index 462e5e1fa957619fc030a07113a510423abac98b..79a872a25f311004ed657b43aa823f0f3dac84a3 100644 (file)
@@ -89,16 +89,7 @@ namespace pcl
       using PlaneRefinementComparatorConstPtr = typename PlaneRefinementComparator::ConstPtr;
 
       /** \brief Constructor for OrganizedMultiPlaneSegmentation. */
-      OrganizedMultiPlaneSegmentation () :
-        normals_ (), 
-        min_inliers_ (1000), 
-        angular_threshold_ (pcl::deg2rad (3.0)), 
-        distance_threshold_ (0.02),
-        maximum_curvature_ (0.001),
-        project_points_ (false), 
-        compare_ (new PlaneComparator ()), refinement_compare_ (new PlaneRefinementComparator ())
-      {
-      }
+      OrganizedMultiPlaneSegmentation() = default;
 
       /** \brief Destructor for OrganizedMultiPlaneSegmentation. */
       
@@ -279,28 +270,28 @@ namespace pcl
     protected:
 
       /** \brief A pointer to the input normals */
-      PointCloudNConstPtr normals_;
+      PointCloudNConstPtr normals_{nullptr};
 
       /** \brief The minimum number of inliers required for each plane. */
-      unsigned min_inliers_;
+      unsigned min_inliers_{1000};
 
       /** \brief The tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */
-      double angular_threshold_;
+      double angular_threshold_{pcl::deg2rad (3.0)};
 
       /** \brief The tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. */
-      double distance_threshold_;
+      double distance_threshold_{0.02};
 
       /** \brief The tolerance for maximum curvature after fitting a plane.  Used to remove smooth, but non-planar regions. */
-      double maximum_curvature_;
+      double maximum_curvature_{0.001};
 
       /** \brief Whether or not points should be projected to the plane, or left in the original 3D space. */
-      bool project_points_;
+      bool project_points_{false};
 
       /** \brief A comparator for comparing neighboring pixels' plane equations. */
-      PlaneComparatorPtr compare_;
+      PlaneComparatorPtr compare_{new PlaneComparator};
 
       /** \brief A comparator for use on the refinement step.  Compares points to regions segmented in the first pass. */
-      PlaneRefinementComparatorPtr refinement_compare_;
+      PlaneRefinementComparatorPtr refinement_compare_{new PlaneRefinementComparator};
 
       /** \brief Class getName method. */
       virtual std::string
index acdd7e3c77c3b53f4d4bcb7315df7d1ca1cd9271..f9b9b99e4db346e6998fde996395b84e9852fc2c 100644 (file)
@@ -81,7 +81,7 @@ namespace pcl
         * \param[in] centroid the centroid of the region.
         * \param[in] covariance the covariance of the region.
         * \param[in] count the number of points in the region.
-        * \param[in] contour the contour / boudnary for the region
+        * \param[in] contour the contour / boundary for the region
         * \param[in] coefficients the model coefficients (a,b,c,d) for the plane
         */
       PlanarRegion (const Eigen::Vector3f& centroid, const Eigen::Matrix3f& covariance, unsigned count,
index f48f25a1282a2370ccc22bfc75384f0a410d8045..894412fb03a7d9060cc6f721655a56f403310fe1 100644 (file)
@@ -137,25 +137,25 @@ namespace pcl
     protected:
 
       /** \brief Maximum window size to be used in filtering ground returns. */
-      int max_window_size_;
+      int max_window_size_{33};
 
       /** \brief Slope value to be used in computing the height threshold. */
-      float slope_;
+      float slope_{0.7f};
 
       /** \brief Maximum height above the parameterized ground surface to be considered a ground return. */
-      float max_distance_;
+      float max_distance_{10.0f};
 
       /** \brief Initial height above the parameterized ground surface to be considered a ground return. */
-      float initial_distance_;
+      float initial_distance_{0.15f};
 
       /** \brief Cell size. */
-      float cell_size_;
+      float cell_size_{1.0f};
 
       /** \brief Base to be used in computing progressive window sizes. */
-      float base_;
+      float base_{2.0f};
 
       /** \brief Exponentially grow window sizes? */
-      bool exponential_;
+      bool exponential_{true};
   };
 }
 
index 30e6876637d6343bdd23cac8fcc9cd788c8ae1f3..6db56268b20b78e88af162ab659f20d0ba1fbe73 100644 (file)
@@ -279,57 +279,57 @@ namespace pcl
     protected:
 
       /** \brief Stores the minimum number of points that a cluster needs to contain in order to be considered valid. */
-      pcl::uindex_t min_pts_per_cluster_;
+      pcl::uindex_t min_pts_per_cluster_{1};
 
       /** \brief Stores the maximum number of points that a cluster needs to contain in order to be considered valid. */
-      pcl::uindex_t max_pts_per_cluster_;
+      pcl::uindex_t max_pts_per_cluster_{std::numeric_limits<pcl::uindex_t>::max()};
 
       /** \brief Flag that signalizes if the smoothness constraint will be used. */
-      bool smooth_mode_flag_;
+      bool smooth_mode_flag_{true};
 
       /** \brief If set to true then curvature test will be done during segmentation. */
-      bool curvature_flag_;
+      bool curvature_flag_{true};
 
       /** \brief If set to true then residual test will be done during segmentation. */
-      bool residual_flag_;
+      bool residual_flag_{false};
 
       /** \brief Threshold used for testing the smoothness between points. */
-      float theta_threshold_;
+      float theta_threshold_{30.0f / 180.0f * static_cast<float>(M_PI)};
 
       /** \brief Threshold used in residual test. */
-      float residual_threshold_;
+      float residual_threshold_{0.05f};
 
       /** \brief Threshold used in curvature test. */
-      float curvature_threshold_;
+      float curvature_threshold_{0.05f};
 
       /** \brief Number of neighbours to find. */
-      unsigned int neighbour_number_;
+      unsigned int neighbour_number_{30};
 
       /** \brief Search method that will be used for KNN. */
-      KdTreePtr search_;
+      KdTreePtr search_{nullptr};
 
       /** \brief Contains normals of the points that will be segmented. */
-      NormalPtr normals_;
+      NormalPtr normals_{nullptr};
 
       /** \brief Contains neighbours of each point. */
-      std::vector<pcl::Indices> point_neighbours_;
+      std::vector<pcl::Indices> point_neighbours_{};
 
       /** \brief Point labels that tells to which segment each point belongs. */
-      std::vector<int> point_labels_;
+      std::vector<int> point_labels_{};
 
       /** \brief If set to true then normal/smoothness test will be done during segmentation.
         * It is always set to true for the usual region growing algorithm. It is used for turning on/off the test
         * for smoothness in the child class RegionGrowingRGB.*/
-      bool normal_flag_;
+      bool normal_flag_{true};
 
       /** \brief Tells how much points each segment contains. Used for reserving memory. */
-      std::vector<pcl::uindex_t> num_pts_in_segment_;
+      std::vector<pcl::uindex_t> num_pts_in_segment_{};
 
       /** \brief After the segmentation it will contain the segments. */
-      std::vector <pcl::PointIndices> clusters_;
+      std::vector <pcl::PointIndices> clusters_{};
 
       /** \brief Stores the number of segments. */
-      int number_of_segments_;
+      int number_of_segments_{0};
 
     public:
       PCL_MAKE_ALIGNED_OPERATOR_NEW
index e409d80d69a62f98a76a6871850298e028436ba5..68670d379a88ff5770fde5e28a10a81f3801086a 100644 (file)
@@ -252,16 +252,16 @@ namespace pcl
     protected:
 
       /** \brief Thershold used in color test for points. */
-      float color_p2p_threshold_;
+      float color_p2p_threshold_{1225.0f};
 
       /** \brief Thershold used in color test for regions. */
-      float color_r2r_threshold_;
+      float color_r2r_threshold_{10.0f};
 
       /** \brief Threshold that tells which points we need to assume neighbouring. */
-      float distance_threshold_;
+      float distance_threshold_{0.05f};
 
       /** \brief Number of neighbouring segments to find. */
-      unsigned int region_neighbour_number_;
+      unsigned int region_neighbour_number_{100};
 
       /** \brief Stores distances for the point neighbours from point_neighbours_ */
       std::vector< std::vector<float> > point_distances_;
index aa3bdbf146d542bc5fa3b1f3cd9c017bdcdf6e01..a43832cdd831237bb0c76574d8129d20152a8ad4 100644 (file)
@@ -81,25 +81,9 @@ namespace pcl
       /** \brief Empty constructor. 
         * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false)
         */
-      SACSegmentation (bool random = false) 
-        : model_ ()
-        , sac_ ()
-        , model_type_ (-1)
-        , method_type_ (0)
-        , threshold_ (0)
-        , optimize_coefficients_ (true)
-        , radius_min_ (-std::numeric_limits<double>::max ())
-        , radius_max_ (std::numeric_limits<double>::max ())
-        , samples_radius_ (0.0)
-        , samples_radius_search_ ()
-        , eps_angle_ (0.0)
-        , axis_ (Eigen::Vector3f::Zero ())
-        , max_iterations_ (50)
-        , threads_ (-1)
-        , probability_ (0.99)
-        , random_ (random)
-      {
-      }
+      SACSegmentation(bool random = false)
+      : random_(random)
+      {}
 
       /** \brief Empty destructor. */
       ~SACSegmentation () override = default;
@@ -264,46 +248,46 @@ namespace pcl
       initSAC (const int method_type);
 
       /** \brief The model that needs to be segmented. */
-      SampleConsensusModelPtr model_;
+      SampleConsensusModelPtr model_{nullptr};
 
       /** \brief The sample consensus segmentation method. */
-      SampleConsensusPtr sac_;
+      SampleConsensusPtr sac_{nullptr};
 
       /** \brief The type of model to use (user given parameter). */
-      int model_type_;
+      int model_type_{-1};
 
       /** \brief The type of sample consensus method to use (user given parameter). */
-      int method_type_;
+      int method_type_{0};
 
       /** \brief Distance to the model threshold (user given parameter). */
-      double threshold_;
+      double threshold_{0.0};
 
       /** \brief Set to true if a coefficient refinement is required. */
-      bool optimize_coefficients_;
+      bool optimize_coefficients_{true};
 
       /** \brief The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius. */
-      double radius_min_, radius_max_;
+      double radius_min_{-std::numeric_limits<double>::max()}, radius_max_{std::numeric_limits<double>::max()};
 
       /** \brief The maximum distance of subsequent samples from the first (radius search) */
-      double samples_radius_;
+      double samples_radius_{0.0};
 
       /** \brief The search object for picking subsequent samples using radius search */
-      SearchPtr samples_radius_search_;
+      SearchPtr samples_radius_search_{nullptr};
 
       /** \brief The maximum allowed difference between the model normal and the given axis. */
-      double eps_angle_;
+      double eps_angle_{0.0};
 
       /** \brief The axis along which we need to search for a model perpendicular to. */
-      Eigen::Vector3f axis_;
+      Eigen::Vector3f axis_{Eigen::Vector3f::Zero()};
 
       /** \brief Maximum number of iterations before giving up (user given parameter). */
-      int max_iterations_;
+      int max_iterations_{50};
 
       /** \brief The number of threads the scheduler should use, or a negative number if no parallelization is wanted. */
-      int threads_;
+      int threads_{-1};
 
       /** \brief Desired probability of choosing at least one sample free from outliers (user given parameter). */
-      double probability_;
+      double probability_{0.99};
 
       /** \brief Set to true if we need a random seed. */
       bool random_;
@@ -349,11 +333,6 @@ namespace pcl
         */
       SACSegmentationFromNormals (bool random = false) 
         : SACSegmentation<PointT> (random)
-        , normals_ ()
-        , distance_weight_ (0.1)
-        , distance_from_origin_ (0)
-        , min_angle_ (0.0)
-        , max_angle_ (M_PI_2)
       {};
 
       /** \brief Provide a pointer to the input dataset that contains the point normals of 
@@ -410,19 +389,19 @@ namespace pcl
 
     protected:
       /** \brief A pointer to the input dataset that contains the point normals of the XYZ dataset. */
-      PointCloudNConstPtr normals_;
+      PointCloudNConstPtr normals_{nullptr};
 
       /** \brief The relative weight (between 0 and 1) to give to the angular
         * distance (0 to pi/2) between point normals and the plane normal. 
         */
-      double distance_weight_;
+      double distance_weight_{0.1};
 
       /** \brief The distance from the template plane to the origin. */
-      double distance_from_origin_;
+      double distance_from_origin_{0.0};
 
       /** \brief The minimum and maximum allowed opening angle of valid cone model. */
-      double min_angle_;
-      double max_angle_;
+      double min_angle_{0.0};
+      double max_angle_{M_PI_2};
 
       /** \brief Initialize the Sample Consensus model and set its parameters.
         * \param[in] model_type the type of SAC model that is to be used
index 286bc92a5814ee1233a5e44d77bba4cf230c4063..e740a7fc483acca24c9b13ed7355d61a297793e6 100644 (file)
@@ -107,8 +107,7 @@ namespace pcl
 
       //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
       /** \brief Empty constructor. */
-      SeededHueSegmentation () : cluster_tolerance_ (0), delta_hue_ (0.0)
-      {};
+      SeededHueSegmentation () = default;
 
       /** \brief Provide a pointer to the search object.
         * \param[in] tree a pointer to the spatial search object.
@@ -130,7 +129,7 @@ namespace pcl
       inline double 
       getClusterTolerance () const { return (cluster_tolerance_); }
 
-      /** \brief Set the tollerance on the hue
+      /** \brief Set the tolerance on the hue
         * \param[in] delta_hue the new delta hue
         */
       inline void 
@@ -155,13 +154,13 @@ namespace pcl
       using BasePCLBase::deinitCompute;
 
       /** \brief A pointer to the spatial search object. */
-      KdTreePtr tree_;
+      KdTreePtr tree_{nullptr};
 
       /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
-      double cluster_tolerance_;
+      double cluster_tolerance_{0.0};
 
       /** \brief The allowed difference on the hue*/
-      float delta_hue_;
+      float delta_hue_{0.0f};
 
       /** \brief Class getName method. */
       virtual std::string getClassName () const { return ("seededHueSegmentation"); }
index 9b89cd2a0332b5e59721a401640434fb2c3ae96b..6cc2d90a547210b8c2ffcfa645f8cc78d488e02f 100755 (executable)
@@ -85,9 +85,7 @@ namespace pcl
       using PointIndicesConstPtr = PointIndices::ConstPtr;
 
       /** \brief Empty constructor. */
-      SegmentDifferences () : 
-        tree_ (), target_ (), distance_threshold_ (0)
-      {};
+      SegmentDifferences () = default;
 
       /** \brief Provide a pointer to the target dataset against which we
         * compare the input cloud given in setInputCloud
@@ -139,15 +137,15 @@ namespace pcl
       using BasePCLBase::deinitCompute;
 
       /** \brief A pointer to the spatial search object. */
-      KdTreePtr tree_;
+      KdTreePtr tree_{nullptr};
 
       /** \brief The input target point cloud dataset. */
-      PointCloudConstPtr target_;
+      PointCloudConstPtr target_{nullptr};
 
       /** \brief The distance tolerance (squared) as a measure in the L2
         * Euclidean space between corresponding points. 
         */
-      double distance_threshold_;
+      double distance_threshold_{0.0};
 
       /** \brief Class getName method. */
       virtual std::string 
index ff5aae70dcc4b8ac6abe56cf18cf1258529aa4c2..e9e8018bf55f4d75459f1290edafd0e2678afa0c 100644 (file)
@@ -139,9 +139,7 @@ namespace pcl
             xyz_ (0.0f, 0.0f, 0.0f),
             rgb_ (0.0f, 0.0f, 0.0f),
             normal_ (0.0f, 0.0f, 0.0f, 0.0f),
-            curvature_ (0.0f),
-            distance_(0),
-            idx_(0),
+            
             owner_ (nullptr)
             {}
 
@@ -160,9 +158,9 @@ namespace pcl
           Eigen::Vector3f xyz_;
           Eigen::Vector3f rgb_;
           Eigen::Vector4f normal_;
-          float curvature_;
-          float distance_;
-          int idx_;
+          float curvature_{0.0f};
+          float distance_{0.0f};
+          int idx_{0};
           SupervoxelHelper* owner_;
 
         public:
@@ -275,14 +273,14 @@ namespace pcl
 
       /** \brief Returns labeled cloud
         * Points that belong to the same supervoxel have the same label.
-        * Labels for segments start from 1, unlabled points have label 0
+        * Labels for segments start from 1, unlabeled points have label 0
         */
       typename pcl::PointCloud<PointXYZL>::Ptr
       getLabeledCloud () const;
 
       /** \brief Returns labeled voxelized cloud
        * Points that belong to the same supervoxel have the same label.
-       * Labels for segments start from 1, unlabled points have label 0
+       * Labels for segments start from 1, unlabeled points have label 0
        */
       pcl::PointCloud<pcl::PointXYZL>::Ptr
       getLabeledVoxelCloud () const;
@@ -373,11 +371,11 @@ namespace pcl
       typename NormalCloudT::ConstPtr input_normals_;
 
       /** \brief Importance of color in clustering */
-      float color_importance_;
+      float color_importance_{0.1f};
       /** \brief Importance of distance from seed center in clustering */
-      float spatial_importance_;
+      float spatial_importance_{0.4f};
       /** \brief Importance of similarity in normals for clustering */
-      float normal_importance_;
+      float normal_importance_{1.0f};
 
       /** \brief Whether or not to use the transform compressing depth in Z
        *  This is only checked if it has been manually set by the user.
@@ -385,7 +383,7 @@ namespace pcl
        */
       bool use_single_camera_transform_;
       /** \brief Whether to use default transform behavior or not */
-      bool use_default_transform_behaviour_;
+      bool use_default_transform_behaviour_{true};
 
       /** \brief Internal storage class for supervoxels
        * \note Stores pointers to leaves of clustering internal octree,
index 52ed89e90d58233c2b5699facfc8a047b20b03fb..f6025c6a171b226776c5f76f6797498bdefa9762 100644 (file)
@@ -145,18 +145,18 @@ namespace pcl
 
 
       /** \brief Contains the input cloud */
-      typename pcl::PointCloud<PointT>::Ptr input_cloud_;
+      typename pcl::PointCloud<PointT>::Ptr input_cloud_{new pcl::PointCloud<PointT>};
       
-      bool label_field_;
+      bool label_field_{false};
       
-      unsigned int cluster_size_;
+      unsigned int cluster_size_{0};
 
-      float normal_radius_search_;
-      float fpfh_radius_search_;
-      float feature_threshold_;
+      float normal_radius_search_{0.01f};
+      float fpfh_radius_search_{0.05f};
+      float feature_threshold_{5.0};
       
       
-      std::vector<pcl::PointCloud<pcl::FPFHSignature33>::Ptr> trained_features_;
+      std::vector<pcl::PointCloud<pcl::FPFHSignature33>::Ptr> trained_features_{};
 
       /** \brief Contains normals of the points that will be segmented. */
       //typename pcl::PointCloud<pcl::Normal>::Ptr normals_;
diff --git a/segmentation/src/crf_normal_segmentation.cpp b/segmentation/src/crf_normal_segmentation.cpp
deleted file mode 100644 (file)
index 70a378f..0000000
+++ /dev/null
@@ -1,46 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Point Cloud Library (PCL) - www.pointclouds.org
- *
- *  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.
- *
- * Author : Christian Potthast
- * Email  : potthast@usc.edu
- *
- */
-
-#include <pcl/point_types.h>
-#include <pcl/impl/instantiate.hpp>
-#include <pcl/segmentation/crf_normal_segmentation.h>
-#include <pcl/segmentation/impl/crf_normal_segmentation.hpp>
-
-// Instantiations of specific point types
-template class pcl::CrfNormalSegmentation<pcl::PointXYZRGBNormal>;
index 85560542911845aaade2f7ea572da0612e1e2546..21bef03184659f8022c67963e524746e91106e57 100644 (file)
@@ -56,6 +56,5 @@ PCL_INSTANTIATE(extractEuclideanClusters, PCL_XYZ_POINT_TYPES)
 PCL_INSTANTIATE(extractEuclideanClusters_indices, PCL_XYZ_POINT_TYPES)
 #endif
 PCL_INSTANTIATE(LabeledEuclideanClusterExtraction, PCL_XYZL_POINT_TYPES)
-PCL_INSTANTIATE(extractLabeledEuclideanClusters_deprecated, PCL_XYZL_POINT_TYPES)
 PCL_INSTANTIATE(extractLabeledEuclideanClusters, PCL_XYZL_POINT_TYPES)
 
index 6b9e5b99bd7317e0a2b915d8f610e4c61284d16a..ea2b75c7704aa5cfac47fefabed13cbb7627be35 100644 (file)
@@ -47,7 +47,6 @@
 const int pcl::segmentation::grabcut::BoykovKolmogorov::TERMINAL = -1;
 
 pcl::segmentation::grabcut::BoykovKolmogorov::BoykovKolmogorov (std::size_t max_nodes)
-  : flow_value_(0.0)
 {
   if (max_nodes > 0)
   {
@@ -83,7 +82,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::getTargetEdgeCapacity (int u) cons
 void
 pcl::segmentation::grabcut::BoykovKolmogorov::preAugmentPaths ()
 {
-  for (int u = 0; u < (int)nodes_.size (); u++)
+  for (int u = 0; u < static_cast<int>(nodes_.size ()); u++)
   {
     // augment s-u-t paths
     if ((source_edges_[u] > 0.0) && (target_edges_[u] > 0.0))
@@ -115,7 +114,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::preAugmentPaths ()
 int
 pcl::segmentation::grabcut::BoykovKolmogorov::addNodes (std::size_t n)
 {
-  int node_id = (int)nodes_.size ();
+  int node_id = static_cast<int>(nodes_.size ());
   nodes_.resize (nodes_.size () + n);
   source_edges_.resize (nodes_.size (), 0.0);
   target_edges_.resize (nodes_.size (), 0.0);
@@ -283,7 +282,7 @@ void
 pcl::segmentation::grabcut::BoykovKolmogorov::initializeTrees ()
 {
   // initialize search tree
-  for (int u = 0; u < (int)nodes_.size (); u++)
+  for (int u = 0; u < static_cast<int>(nodes_.size ()); u++)
   {
     if (source_edges_[u] > 0.0)
     {
index 9c0ef990c5dba3548da247c38404510a9de40ce2..1785e47143536f47c0338b02b151b0bbbbe3faf6 100644 (file)
@@ -140,7 +140,7 @@ public:
   Eigen::Vector3d
   getYPR() const
   {
-    return Eigen::Vector3d(yaw_, pitch_, roll_);
+    return {yaw_, pitch_, roll_};
   }
 
 private:
index 829915c6f0dc9e5a7a33173bedb4a09d6ae7a549..5514de5223846bc1ad84f03b074f9d8b528d5a3d 100644 (file)
@@ -1,12 +1,12 @@
 #pragma once
 
 #include <pcl/simulation/glsl_shader.h>
-#include <pcl/PolygonMesh.h>
 #include <pcl/memory.h>
 #include <pcl/pcl_config.h>
 #include <pcl/pcl_macros.h>
 #include <pcl/point_cloud.h> // for PointCloud
 #include <pcl/point_types.h>
+#include <pcl/PolygonMesh.h>
 
 #if defined(_WIN32) && !defined(APIENTRY) && !defined(__CYGWIN__)
 #define WIN32_LEAN_AND_MEAN 1
index aab4bbb424923b1f45e2ddb3b3adcfd5d9cb0690..0bd2b8a851b476b0cd2c454e2ee9be03cda15295 100644 (file)
@@ -276,31 +276,31 @@ private:
   float z_far_;
 
   // For caching only, not part of observable state.
-  mutable bool depth_buffer_dirty_;
-  mutable bool color_buffer_dirty_;
-  mutable bool score_buffer_dirty_;
+  mutable bool depth_buffer_dirty_{true};
+  mutable bool color_buffer_dirty_{true};
+  mutable bool score_buffer_dirty_{true};
 
   int which_cost_function_;
   double floor_proportion_;
   double sigma_;
 
-  GLuint fbo_;
+  GLuint fbo_{0};
   GLuint score_fbo_;
 
-  GLuint depth_render_buffer_;
-  GLuint color_render_buffer_;
+  GLuint depth_render_buffer_{0};
+  GLuint color_render_buffer_{0};
   GLuint color_texture_;
-  GLuint depth_texture_;
-  GLuint score_texture_;
-  GLuint score_summarized_texture_;
-  GLuint sensor_texture_;
-  GLuint likelihood_texture_;
-
-  bool compute_likelihood_on_cpu_;
-  bool aggregate_on_cpu_;
-  bool use_instancing_;
+  GLuint depth_texture_{0};
+  GLuint score_texture_{0};
+  GLuint score_summarized_texture_{0};
+  GLuint sensor_texture_{0};
+  GLuint likelihood_texture_{0};
+
+  bool compute_likelihood_on_cpu_{false};
+  bool aggregate_on_cpu_{false};
+  bool use_instancing_{false};
   bool generate_color_image_;
-  bool use_color_;
+  bool use_color_{true};
 
   gllib::Program::Ptr likelihood_program_;
   GLuint quad_vbo_;
index ca6443a0fa75a8a1b1fd38d02e6e4309ee38ff49..4eed218b3afa9ee0ce039aff232338f9e69a233f 100644 (file)
@@ -30,7 +30,7 @@ readTextFile(const char* filename)
   return buf;
 }
 
-pcl::simulation::gllib::Program::Program() { program_id_ = glCreateProgram(); }
+pcl::simulation::gllib::Program::Program() : program_id_(glCreateProgram()) {}
 
 pcl::simulation::gllib::Program::~Program() = default;
 
index f114666de61355c3b723ca2ef2141b8f2232a7ad..99ec4d45fc3b5f24e2bfbe865c3baafddddead2e 100644 (file)
@@ -53,7 +53,7 @@ pcl::simulation::TriangleMeshModel::TriangleMeshModel(pcl::PolygonMesh::Ptr plg)
   glBindBuffer(GL_ARRAY_BUFFER, vbo_);
   glBufferData(GL_ARRAY_BUFFER,
                vertices.size() * sizeof(vertices[0]),
-               &(vertices[0]),
+               vertices.data(),
                GL_STATIC_DRAW);
   glBindBuffer(GL_ARRAY_BUFFER, 0);
 
@@ -61,7 +61,7 @@ pcl::simulation::TriangleMeshModel::TriangleMeshModel(pcl::PolygonMesh::Ptr plg)
   glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, ibo_);
   glBufferData(GL_ELEMENT_ARRAY_BUFFER,
                indices.size() * sizeof(indices[0]),
-               &(indices[0]),
+               indices.data(),
                GL_STATIC_DRAW);
   glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
 
@@ -289,10 +289,11 @@ pcl::simulation::Quad::render() const
 }
 
 pcl::simulation::TexturedQuad::TexturedQuad(int width, int height)
-: width_(width), height_(height)
+: width_(width)
+, height_(height)
+, program_(
+      gllib::Program::loadProgramFromFile("single_texture.vert", "single_texture.frag"))
 {
-  program_ =
-      gllib::Program::loadProgramFromFile("single_texture.vert", "single_texture.frag");
   program_->use();
   Eigen::Matrix<float, 4, 4> MVP;
   MVP.setIdentity();
index e40aeaa25af1bfaffe708d51834c3ecc1ab53da9..34961f9f58dc39e5519b4d61209f2acbd9dc6f0b 100644 (file)
@@ -279,21 +279,6 @@ pcl::simulation::RangeLikelihood::RangeLikelihood(
 , cols_(cols)
 , row_height_(row_height)
 , col_width_(col_width)
-, depth_buffer_dirty_(true)
-, color_buffer_dirty_(true)
-, score_buffer_dirty_(true)
-, fbo_(0)
-, depth_render_buffer_(0)
-, color_render_buffer_(0)
-, depth_texture_(0)
-, score_texture_(0)
-, score_summarized_texture_(0)
-, sensor_texture_(0)
-, likelihood_texture_(0)
-, compute_likelihood_on_cpu_(false)
-, aggregate_on_cpu_(false)
-, use_instancing_(false)
-, use_color_(true)
 , sum_reduce_(cols * col_width, rows * row_height, max_level(col_width, row_height))
 {
   height_ = rows_ * row_height;
@@ -470,7 +455,7 @@ pcl::simulation::RangeLikelihood::RangeLikelihood(
   glBindBuffer(GL_ARRAY_BUFFER, quad_vbo_);
   glBufferData(GL_ARRAY_BUFFER,
                sizeof(Eigen::Vector3f) * vertices_.size(),
-               &(vertices_[0]),
+               vertices_.data(),
                GL_STATIC_DRAW);
   glBindBuffer(GL_ARRAY_BUFFER, 0);
 
index 20105624cbe93e7c8c3879b4c1fbe4d1f07d5769..f6a4b0c7bf5bfb0404f92cdea0001bafea43791e 100644 (file)
@@ -3,12 +3,10 @@
 using namespace pcl::simulation;
 
 pcl::simulation::SumReduce::SumReduce(int width, int height, int levels)
-: levels_(levels), width_(width), height_(height)
+: levels_(levels), width_(width), height_(height), sum_program_(new gllib::Program())
 {
   std::cout << "SumReduce: levels: " << levels_ << std::endl;
 
-  // Load shader
-  sum_program_ = gllib::Program::Ptr(new gllib::Program());
   // TODO: to remove file dependency include the shader source in the binary
   if (!sum_program_->addShaderFile("sum_score.vert", gllib::VERTEX)) {
     std::cout << "Failed loading vertex shader" << std::endl;
@@ -93,8 +91,8 @@ pcl::simulation::SumReduce::sum(GLuint input_array, float* output_array)
 
     glViewport(0, 0, width / 2, height / 2);
 
-    float step_x = 1.0f / float(width);
-    float step_y = 1.0f / float(height);
+    float step_x = 1.0f / static_cast<float>(width);
+    float step_y = 1.0f / static_cast<float>(height);
     sum_program_->setUniform("step_x", step_x);
     sum_program_->setUniform("step_y", step_y);
     // float step_x = 1.0f / static_cast<float> (width);
index 5c4d778cf14ed749d3351b5bad4bed8eb1da1564..36e60b73786c44a388e8445eb0b6ea12698f4249 100644 (file)
@@ -18,6 +18,6 @@ status : reads obj, creates window, use keyboard to drive around environment
 was    : range_performance_test.cpp
 
 4. sim_test_simple
-purpose: similar code to #3 but has a 2x2 grid each containing 640x480 windows, but operates as #1. press 'v' to capture a cloud to file (only works properly if 2x2 canged to 1x1)
+purpose: similar code to #3 but has a 2x2 grid each containing 640x480 windows, but operates as #1. press 'v' to capture a cloud to file (only works properly if 2x2 changed to 1x1)
 status : reads obj, creates window, use keyboard to drive around environment
 was    : range_test_v2.cpp
index 5b5de285bbe9420283dafe7a1c3890c5625b0c7d..0347761875f004b671c9fbb2fbdbb91c82c292f1 100644 (file)
@@ -100,7 +100,8 @@ generate_halo(
     int n_poses)
 {
 
-  for (double t = 0; t < (2 * M_PI); t = t + (2 * M_PI) / ((double)n_poses)) {
+  for (double t = 0; t < (2 * M_PI);
+       t = t + (2 * M_PI) / (static_cast<double>(n_poses))) {
     double x = halo_r * std::cos(t);
     double y = halo_r * sin(t);
     double z = halo_dz;
@@ -189,7 +190,7 @@ main(int argc, char** argv)
     pose2.rotate(rot2);
 
     int n_poses = 20;
-    for (double i = 0; i <= 1; i += 1 / ((double)n_poses - 1)) {
+    for (double i = 0; i <= 1; i += 1 / (static_cast<double>(n_poses) - 1)) {
       Eigen::Quaterniond rot3;
       Eigen::Quaterniond r1(pose1.rotation());
       Eigen::Quaterniond r2(pose2.rotation());
index a0547df862aa94618f924052a0ba12624bb0d026..10e2b832e16116f9b1d323f6ca71f776f8503a76 100644 (file)
@@ -516,8 +516,8 @@ on_passive_motion(int x, int y)
     return;
 
   // in window coordinates positive y-axis is down
-  double pitch = -(0.5 - (double)y / window_height_) * M_PI * 4;
-  double yaw = (0.5 - (double)x / window_width_) * M_PI * 2 * 4;
+  double pitch = -(0.5 - static_cast<double>(y) / window_height_) * M_PI * 4;
+  double yaw = (0.5 - static_cast<double>(x) / window_width_) * M_PI * 2 * 4;
 
   camera_->setPitch(pitch);
   camera_->setYaw(yaw);
index f80f0dd5bd2491dd8d870f0ae69d6fd0d6c1de0f..02bf5745b13caedd07dc2586785c6417a2316a21 100644 (file)
@@ -638,7 +638,7 @@ main(int argc, char** argv)
     // Create the PCLVisualizer object here on the first encountered XYZ file
     if (!p) {
       p.reset(new pcl::visualization::PCLVisualizer(argc, argv, "PCD viewer"));
-      p->registerPointPickingCallback(&pp_callback, (void*)&cloud);
+      p->registerPointPickingCallback(&pp_callback, reinterpret_cast<void*>(&cloud));
       Eigen::Matrix3f rotation;
       rotation = orientation;
       p->setCameraPosition(origin[0],
@@ -670,7 +670,7 @@ main(int argc, char** argv)
     print_info("[done, ");
     print_value("%g", tt.toc());
     print_info(" ms : ");
-    print_value("%d", (int)cloud->width * cloud->height);
+    print_value("%d", static_cast<int>(cloud->width * cloud->height));
     print_info(" points]\n");
     print_info("Available dimensions: ");
     print_value("%s\n", pcl::getFieldsList(*cloud).c_str());
@@ -827,7 +827,7 @@ main(int argc, char** argv)
   ////////////////////////////////////////////////////////////////
   // Key binding for saving simulated point cloud:
   if (p)
-    p->registerKeyboardCallback(simulate_callback, (void*)&p);
+    p->registerKeyboardCallback(simulate_callback, reinterpret_cast<void*>(&p));
 
   int width = 640;
   int height = 480;
index 9a4cd8c0afaa4080a5b5d30654b775163671fe17..53df19b34d45e9bd5230fe9cc592be92a8fa4ed0 100644 (file)
@@ -129,11 +129,11 @@ public:
 
 protected:
   /** \brief Column resolution of the DEM. */
-  std::size_t resolution_column_;
+  std::size_t resolution_column_{64};
   /** \brief disparity resolution of the DEM. */
-  std::size_t resolution_disparity_;
+  std::size_t resolution_disparity_{32};
   /** \brief Minimum amount of points in a DEM's cell. */
-  std::size_t min_points_in_cell_;
+  std::size_t min_points_in_cell_{1};
 };
 
 } // namespace pcl
index 0fb59953241d0f84293b859649c03b3a8ee30d63..ece97c4cc4f2fd76def1b9c51d30df7d5d1fc0f0 100644 (file)
@@ -221,35 +221,35 @@ protected:
    * \param[in] row
    * \param[in] column
    * \param[in] disparity
-   * \return the 3D point, that corresponds to the input parametres and the camera
+   * \return the 3D point, that corresponds to the input parameters and the camera
    * calibration.
    */
   PointXYZ
   translateCoordinates(std::size_t row, std::size_t column, float disparity) const;
 
   /** \brief X-coordinate of the image center. */
-  float center_x_;
+  float center_x_{0.0f};
   /** \brief Y-coordinate of the image center. */
-  float center_y_;
+  float center_y_{0.0f};
   /** \brief Focal length. */
-  float focal_length_;
+  float focal_length_{0.0f};
   /** \brief Baseline. */
-  float baseline_;
+  float baseline_{0.0f};
 
   /** \brief Is color image is set. */
-  bool is_color_;
+  bool is_color_{false};
   /** \brief Color image of the scene. */
   pcl::PointCloud<pcl::RGB>::ConstPtr image_;
 
   /** \brief Vector for the disparity map. */
   std::vector<float> disparity_map_;
   /** \brief X-size of the disparity map. */
-  std::size_t disparity_map_width_;
+  std::size_t disparity_map_width_{640};
   /** \brief Y-size of the disparity map. */
-  std::size_t disparity_map_height_;
+  std::size_t disparity_map_height_{480};
 
   /** \brief Thresholds of the disparity. */
-  float disparity_threshold_min_;
+  float disparity_threshold_min_{0.0f};
   float disparity_threshold_max_;
 };
 
index 773a28704119804773c367d8893205028f6bf996..ce7db93ef84dc664f1822a1d79ff0f662e88f3fa 100644 (file)
 
 template <typename PointT>
 pcl::DisparityMapConverter<PointT>::DisparityMapConverter()
-: center_x_(0.0f)
-, center_y_(0.0f)
-, focal_length_(0.0f)
-, baseline_(0.0f)
-, is_color_(false)
-, disparity_map_width_(640)
-, disparity_map_height_(480)
-, disparity_threshold_min_(0.0f)
-, disparity_threshold_max_(std::numeric_limits<float>::max())
+: disparity_threshold_max_(std::numeric_limits<float>::max())
 {}
 
 template <typename PointT>
index 7dd966adc18551a216ceb4f9b6da071f299013f2..df7106476f0fee6d34e9b07d4e9e0ea50aefd824 100644 (file)
@@ -452,7 +452,7 @@ private:
  * This class implements an adaptive-cost stereo matching algorithm based on 2-pass
  * Scanline Optimization. The algorithm is inspired by the paper: [1] L. Wang et al.,
  * "High Quality Real-time Stereo using Adaptive Cost Aggregation and Dynamic
- * Programming", 3DPVT 2006 Cost aggregation is performed using adaptive weigths
+ * Programming", 3DPVT 2006 Cost aggregation is performed using adaptive weights
  * computed on a single column as proposed in [1]. Instead of using Dynamic Programming
  * as in [1], the optimization is performed via 2-pass Scanline Optimization. The
  * algorithm is based on the Sum of Absolute Differences (SAD) matching function Only
index f5406942ccfdfad096b583092250d21cb220a9f6..ef312c76e12b6086b8859d4742cedfe480b83f2d 100644 (file)
@@ -38,9 +38,7 @@
 #include <pcl/console/print.h>
 #include <pcl/stereo/digital_elevation_map.h>
 
-pcl::DigitalElevationMapBuilder::DigitalElevationMapBuilder()
-: resolution_column_(64), resolution_disparity_(32), min_points_in_cell_(1)
-{}
+pcl::DigitalElevationMapBuilder::DigitalElevationMapBuilder() = default;
 
 pcl::DigitalElevationMapBuilder::~DigitalElevationMapBuilder() = default;
 
index 353195bf384509bdb5eb653c6b486167d0678be7..335bebb7d04cd4fc33923ce8b735f317d3931f7a 100644 (file)
@@ -79,7 +79,7 @@ pcl::AdaptiveCostSOStereoMatching::compute_impl(unsigned char* ref_img,
   // LUT for color distance weight computation
   float lut[256];
   for (int j = 0; j < 256; j++)
-    lut[j] = float(std::exp(-j / gamma_c_));
+    lut[j] = static_cast<float>(std::exp(-j / gamma_c_));
 
   // left weight array alloc
   float* wl = new float[2 * radius_ + 1];
index 2be9bf1699df4f428159754085a6c3e0adb3d12c..0cdcab10a815c478460d6c44c603fdb936f7be58 100644 (file)
@@ -78,11 +78,11 @@ pcl::StereoGrabberBase::StereoGrabberImpl::StereoGrabberImpl(
 , frames_per_second_(frames_per_second)
 , repeat_(repeat)
 , running_(false)
+, pair_files_({pair_files})
 , time_trigger_(1.0 / static_cast<double>(std::max(frames_per_second, 0.001f)),
                 [this] { trigger(); })
 , valid_(false)
 {
-  pair_files_.push_back(pair_files);
   pair_iterator_ = pair_files_.begin();
 }
 
@@ -96,11 +96,11 @@ pcl::StereoGrabberBase::StereoGrabberImpl::StereoGrabberImpl(
 , frames_per_second_(frames_per_second)
 , repeat_(repeat)
 , running_(false)
+, pair_files_(files)
 , time_trigger_(1.0 / static_cast<double>(std::max(frames_per_second, 0.001f)),
                 [this] { trigger(); })
 , valid_(false)
 {
-  pair_files_ = files;
   pair_iterator_ = pair_files_.begin();
 }
 
index c29105e6a67f7749da6e66770aefbdcb8aa9b3b6..b86614fe471edfe670d20409cb4176627afb6172 100644 (file)
@@ -1,10 +1,11 @@
 set(SUBSYS_NAME surface)
 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)
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS qhull vtk OpenMP)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
@@ -66,6 +67,16 @@ if(BUILD_surface_on_nurbs)
   
   include(src/3rdparty/opennurbs/openNURBS.cmake)
   include(src/on_nurbs/on_nurbs.cmake)
+  
+  if(WITH_SYSTEM_ZLIB)
+    find_package(ZLIB REQUIRED)
+    list(APPEND ON_NURBS_LIBRARIES ${ZLIB_LIBRARIES})
+    list(APPEND SUBSYS_EXT_DEPS zlib)
+  else()
+    include(src/3rdparty/opennurbs/zlib.cmake)
+    list(APPEND OPENNURBS_INCLUDES ${ZLIB_INCLUDES})
+    list(APPEND OPENNURBS_SOURCES ${ZLIB_SOURCES})
+  endif()
 endif()
 
 set(POISSON_INCLUDES
@@ -196,7 +207,7 @@ if(QHULL_FOUND)
   target_link_libraries("${LIB_NAME}" QHULL::QHULL)
 endif()
 
-PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS})
+PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${SUBSYS_EXT_DEPS})
 
 # Install include files
 PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs})
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/crc32.h b/surface/include/pcl/surface/3rdparty/opennurbs/crc32.h
deleted file mode 100644 (file)
index afe4b28..0000000
+++ /dev/null
@@ -1,441 +0,0 @@
-/* crc32.h -- tables for rapid CRC calculation
- * Generated automatically by crc32.c
- */
-
-local const unsigned int FAR crc_table[TBLS][256] =
-{
-  {
-    0x00000000UL, 0x77073096UL, 0xee0e612cUL, 0x990951baUL, 0x076dc419UL,
-    0x706af48fUL, 0xe963a535UL, 0x9e6495a3UL, 0x0edb8832UL, 0x79dcb8a4UL,
-    0xe0d5e91eUL, 0x97d2d988UL, 0x09b64c2bUL, 0x7eb17cbdUL, 0xe7b82d07UL,
-    0x90bf1d91UL, 0x1db71064UL, 0x6ab020f2UL, 0xf3b97148UL, 0x84be41deUL,
-    0x1adad47dUL, 0x6ddde4ebUL, 0xf4d4b551UL, 0x83d385c7UL, 0x136c9856UL,
-    0x646ba8c0UL, 0xfd62f97aUL, 0x8a65c9ecUL, 0x14015c4fUL, 0x63066cd9UL,
-    0xfa0f3d63UL, 0x8d080df5UL, 0x3b6e20c8UL, 0x4c69105eUL, 0xd56041e4UL,
-    0xa2677172UL, 0x3c03e4d1UL, 0x4b04d447UL, 0xd20d85fdUL, 0xa50ab56bUL,
-    0x35b5a8faUL, 0x42b2986cUL, 0xdbbbc9d6UL, 0xacbcf940UL, 0x32d86ce3UL,
-    0x45df5c75UL, 0xdcd60dcfUL, 0xabd13d59UL, 0x26d930acUL, 0x51de003aUL,
-    0xc8d75180UL, 0xbfd06116UL, 0x21b4f4b5UL, 0x56b3c423UL, 0xcfba9599UL,
-    0xb8bda50fUL, 0x2802b89eUL, 0x5f058808UL, 0xc60cd9b2UL, 0xb10be924UL,
-    0x2f6f7c87UL, 0x58684c11UL, 0xc1611dabUL, 0xb6662d3dUL, 0x76dc4190UL,
-    0x01db7106UL, 0x98d220bcUL, 0xefd5102aUL, 0x71b18589UL, 0x06b6b51fUL,
-    0x9fbfe4a5UL, 0xe8b8d433UL, 0x7807c9a2UL, 0x0f00f934UL, 0x9609a88eUL,
-    0xe10e9818UL, 0x7f6a0dbbUL, 0x086d3d2dUL, 0x91646c97UL, 0xe6635c01UL,
-    0x6b6b51f4UL, 0x1c6c6162UL, 0x856530d8UL, 0xf262004eUL, 0x6c0695edUL,
-    0x1b01a57bUL, 0x8208f4c1UL, 0xf50fc457UL, 0x65b0d9c6UL, 0x12b7e950UL,
-    0x8bbeb8eaUL, 0xfcb9887cUL, 0x62dd1ddfUL, 0x15da2d49UL, 0x8cd37cf3UL,
-    0xfbd44c65UL, 0x4db26158UL, 0x3ab551ceUL, 0xa3bc0074UL, 0xd4bb30e2UL,
-    0x4adfa541UL, 0x3dd895d7UL, 0xa4d1c46dUL, 0xd3d6f4fbUL, 0x4369e96aUL,
-    0x346ed9fcUL, 0xad678846UL, 0xda60b8d0UL, 0x44042d73UL, 0x33031de5UL,
-    0xaa0a4c5fUL, 0xdd0d7cc9UL, 0x5005713cUL, 0x270241aaUL, 0xbe0b1010UL,
-    0xc90c2086UL, 0x5768b525UL, 0x206f85b3UL, 0xb966d409UL, 0xce61e49fUL,
-    0x5edef90eUL, 0x29d9c998UL, 0xb0d09822UL, 0xc7d7a8b4UL, 0x59b33d17UL,
-    0x2eb40d81UL, 0xb7bd5c3bUL, 0xc0ba6cadUL, 0xedb88320UL, 0x9abfb3b6UL,
-    0x03b6e20cUL, 0x74b1d29aUL, 0xead54739UL, 0x9dd277afUL, 0x04db2615UL,
-    0x73dc1683UL, 0xe3630b12UL, 0x94643b84UL, 0x0d6d6a3eUL, 0x7a6a5aa8UL,
-    0xe40ecf0bUL, 0x9309ff9dUL, 0x0a00ae27UL, 0x7d079eb1UL, 0xf00f9344UL,
-    0x8708a3d2UL, 0x1e01f268UL, 0x6906c2feUL, 0xf762575dUL, 0x806567cbUL,
-    0x196c3671UL, 0x6e6b06e7UL, 0xfed41b76UL, 0x89d32be0UL, 0x10da7a5aUL,
-    0x67dd4accUL, 0xf9b9df6fUL, 0x8ebeeff9UL, 0x17b7be43UL, 0x60b08ed5UL,
-    0xd6d6a3e8UL, 0xa1d1937eUL, 0x38d8c2c4UL, 0x4fdff252UL, 0xd1bb67f1UL,
-    0xa6bc5767UL, 0x3fb506ddUL, 0x48b2364bUL, 0xd80d2bdaUL, 0xaf0a1b4cUL,
-    0x36034af6UL, 0x41047a60UL, 0xdf60efc3UL, 0xa867df55UL, 0x316e8eefUL,
-    0x4669be79UL, 0xcb61b38cUL, 0xbc66831aUL, 0x256fd2a0UL, 0x5268e236UL,
-    0xcc0c7795UL, 0xbb0b4703UL, 0x220216b9UL, 0x5505262fUL, 0xc5ba3bbeUL,
-    0xb2bd0b28UL, 0x2bb45a92UL, 0x5cb36a04UL, 0xc2d7ffa7UL, 0xb5d0cf31UL,
-    0x2cd99e8bUL, 0x5bdeae1dUL, 0x9b64c2b0UL, 0xec63f226UL, 0x756aa39cUL,
-    0x026d930aUL, 0x9c0906a9UL, 0xeb0e363fUL, 0x72076785UL, 0x05005713UL,
-    0x95bf4a82UL, 0xe2b87a14UL, 0x7bb12baeUL, 0x0cb61b38UL, 0x92d28e9bUL,
-    0xe5d5be0dUL, 0x7cdcefb7UL, 0x0bdbdf21UL, 0x86d3d2d4UL, 0xf1d4e242UL,
-    0x68ddb3f8UL, 0x1fda836eUL, 0x81be16cdUL, 0xf6b9265bUL, 0x6fb077e1UL,
-    0x18b74777UL, 0x88085ae6UL, 0xff0f6a70UL, 0x66063bcaUL, 0x11010b5cUL,
-    0x8f659effUL, 0xf862ae69UL, 0x616bffd3UL, 0x166ccf45UL, 0xa00ae278UL,
-    0xd70dd2eeUL, 0x4e048354UL, 0x3903b3c2UL, 0xa7672661UL, 0xd06016f7UL,
-    0x4969474dUL, 0x3e6e77dbUL, 0xaed16a4aUL, 0xd9d65adcUL, 0x40df0b66UL,
-    0x37d83bf0UL, 0xa9bcae53UL, 0xdebb9ec5UL, 0x47b2cf7fUL, 0x30b5ffe9UL,
-    0xbdbdf21cUL, 0xcabac28aUL, 0x53b39330UL, 0x24b4a3a6UL, 0xbad03605UL,
-    0xcdd70693UL, 0x54de5729UL, 0x23d967bfUL, 0xb3667a2eUL, 0xc4614ab8UL,
-    0x5d681b02UL, 0x2a6f2b94UL, 0xb40bbe37UL, 0xc30c8ea1UL, 0x5a05df1bUL,
-    0x2d02ef8dUL
-#ifdef BYFOUR
-  },
-  {
-    0x00000000UL, 0x191b3141UL, 0x32366282UL, 0x2b2d53c3UL, 0x646cc504UL,
-    0x7d77f445UL, 0x565aa786UL, 0x4f4196c7UL, 0xc8d98a08UL, 0xd1c2bb49UL,
-    0xfaefe88aUL, 0xe3f4d9cbUL, 0xacb54f0cUL, 0xb5ae7e4dUL, 0x9e832d8eUL,
-    0x87981ccfUL, 0x4ac21251UL, 0x53d92310UL, 0x78f470d3UL, 0x61ef4192UL,
-    0x2eaed755UL, 0x37b5e614UL, 0x1c98b5d7UL, 0x05838496UL, 0x821b9859UL,
-    0x9b00a918UL, 0xb02dfadbUL, 0xa936cb9aUL, 0xe6775d5dUL, 0xff6c6c1cUL,
-    0xd4413fdfUL, 0xcd5a0e9eUL, 0x958424a2UL, 0x8c9f15e3UL, 0xa7b24620UL,
-    0xbea97761UL, 0xf1e8e1a6UL, 0xe8f3d0e7UL, 0xc3de8324UL, 0xdac5b265UL,
-    0x5d5daeaaUL, 0x44469febUL, 0x6f6bcc28UL, 0x7670fd69UL, 0x39316baeUL,
-    0x202a5aefUL, 0x0b07092cUL, 0x121c386dUL, 0xdf4636f3UL, 0xc65d07b2UL,
-    0xed705471UL, 0xf46b6530UL, 0xbb2af3f7UL, 0xa231c2b6UL, 0x891c9175UL,
-    0x9007a034UL, 0x179fbcfbUL, 0x0e848dbaUL, 0x25a9de79UL, 0x3cb2ef38UL,
-    0x73f379ffUL, 0x6ae848beUL, 0x41c51b7dUL, 0x58de2a3cUL, 0xf0794f05UL,
-    0xe9627e44UL, 0xc24f2d87UL, 0xdb541cc6UL, 0x94158a01UL, 0x8d0ebb40UL,
-    0xa623e883UL, 0xbf38d9c2UL, 0x38a0c50dUL, 0x21bbf44cUL, 0x0a96a78fUL,
-    0x138d96ceUL, 0x5ccc0009UL, 0x45d73148UL, 0x6efa628bUL, 0x77e153caUL,
-    0xbabb5d54UL, 0xa3a06c15UL, 0x888d3fd6UL, 0x91960e97UL, 0xded79850UL,
-    0xc7cca911UL, 0xece1fad2UL, 0xf5facb93UL, 0x7262d75cUL, 0x6b79e61dUL,
-    0x4054b5deUL, 0x594f849fUL, 0x160e1258UL, 0x0f152319UL, 0x243870daUL,
-    0x3d23419bUL, 0x65fd6ba7UL, 0x7ce65ae6UL, 0x57cb0925UL, 0x4ed03864UL,
-    0x0191aea3UL, 0x188a9fe2UL, 0x33a7cc21UL, 0x2abcfd60UL, 0xad24e1afUL,
-    0xb43fd0eeUL, 0x9f12832dUL, 0x8609b26cUL, 0xc94824abUL, 0xd05315eaUL,
-    0xfb7e4629UL, 0xe2657768UL, 0x2f3f79f6UL, 0x362448b7UL, 0x1d091b74UL,
-    0x04122a35UL, 0x4b53bcf2UL, 0x52488db3UL, 0x7965de70UL, 0x607eef31UL,
-    0xe7e6f3feUL, 0xfefdc2bfUL, 0xd5d0917cUL, 0xcccba03dUL, 0x838a36faUL,
-    0x9a9107bbUL, 0xb1bc5478UL, 0xa8a76539UL, 0x3b83984bUL, 0x2298a90aUL,
-    0x09b5fac9UL, 0x10aecb88UL, 0x5fef5d4fUL, 0x46f46c0eUL, 0x6dd93fcdUL,
-    0x74c20e8cUL, 0xf35a1243UL, 0xea412302UL, 0xc16c70c1UL, 0xd8774180UL,
-    0x9736d747UL, 0x8e2de606UL, 0xa500b5c5UL, 0xbc1b8484UL, 0x71418a1aUL,
-    0x685abb5bUL, 0x4377e898UL, 0x5a6cd9d9UL, 0x152d4f1eUL, 0x0c367e5fUL,
-    0x271b2d9cUL, 0x3e001cddUL, 0xb9980012UL, 0xa0833153UL, 0x8bae6290UL,
-    0x92b553d1UL, 0xddf4c516UL, 0xc4eff457UL, 0xefc2a794UL, 0xf6d996d5UL,
-    0xae07bce9UL, 0xb71c8da8UL, 0x9c31de6bUL, 0x852aef2aUL, 0xca6b79edUL,
-    0xd37048acUL, 0xf85d1b6fUL, 0xe1462a2eUL, 0x66de36e1UL, 0x7fc507a0UL,
-    0x54e85463UL, 0x4df36522UL, 0x02b2f3e5UL, 0x1ba9c2a4UL, 0x30849167UL,
-    0x299fa026UL, 0xe4c5aeb8UL, 0xfdde9ff9UL, 0xd6f3cc3aUL, 0xcfe8fd7bUL,
-    0x80a96bbcUL, 0x99b25afdUL, 0xb29f093eUL, 0xab84387fUL, 0x2c1c24b0UL,
-    0x350715f1UL, 0x1e2a4632UL, 0x07317773UL, 0x4870e1b4UL, 0x516bd0f5UL,
-    0x7a468336UL, 0x635db277UL, 0xcbfad74eUL, 0xd2e1e60fUL, 0xf9ccb5ccUL,
-    0xe0d7848dUL, 0xaf96124aUL, 0xb68d230bUL, 0x9da070c8UL, 0x84bb4189UL,
-    0x03235d46UL, 0x1a386c07UL, 0x31153fc4UL, 0x280e0e85UL, 0x674f9842UL,
-    0x7e54a903UL, 0x5579fac0UL, 0x4c62cb81UL, 0x8138c51fUL, 0x9823f45eUL,
-    0xb30ea79dUL, 0xaa1596dcUL, 0xe554001bUL, 0xfc4f315aUL, 0xd7626299UL,
-    0xce7953d8UL, 0x49e14f17UL, 0x50fa7e56UL, 0x7bd72d95UL, 0x62cc1cd4UL,
-    0x2d8d8a13UL, 0x3496bb52UL, 0x1fbbe891UL, 0x06a0d9d0UL, 0x5e7ef3ecUL,
-    0x4765c2adUL, 0x6c48916eUL, 0x7553a02fUL, 0x3a1236e8UL, 0x230907a9UL,
-    0x0824546aUL, 0x113f652bUL, 0x96a779e4UL, 0x8fbc48a5UL, 0xa4911b66UL,
-    0xbd8a2a27UL, 0xf2cbbce0UL, 0xebd08da1UL, 0xc0fdde62UL, 0xd9e6ef23UL,
-    0x14bce1bdUL, 0x0da7d0fcUL, 0x268a833fUL, 0x3f91b27eUL, 0x70d024b9UL,
-    0x69cb15f8UL, 0x42e6463bUL, 0x5bfd777aUL, 0xdc656bb5UL, 0xc57e5af4UL,
-    0xee530937UL, 0xf7483876UL, 0xb809aeb1UL, 0xa1129ff0UL, 0x8a3fcc33UL,
-    0x9324fd72UL
-  },
-  {
-    0x00000000UL, 0x01c26a37UL, 0x0384d46eUL, 0x0246be59UL, 0x0709a8dcUL,
-    0x06cbc2ebUL, 0x048d7cb2UL, 0x054f1685UL, 0x0e1351b8UL, 0x0fd13b8fUL,
-    0x0d9785d6UL, 0x0c55efe1UL, 0x091af964UL, 0x08d89353UL, 0x0a9e2d0aUL,
-    0x0b5c473dUL, 0x1c26a370UL, 0x1de4c947UL, 0x1fa2771eUL, 0x1e601d29UL,
-    0x1b2f0bacUL, 0x1aed619bUL, 0x18abdfc2UL, 0x1969b5f5UL, 0x1235f2c8UL,
-    0x13f798ffUL, 0x11b126a6UL, 0x10734c91UL, 0x153c5a14UL, 0x14fe3023UL,
-    0x16b88e7aUL, 0x177ae44dUL, 0x384d46e0UL, 0x398f2cd7UL, 0x3bc9928eUL,
-    0x3a0bf8b9UL, 0x3f44ee3cUL, 0x3e86840bUL, 0x3cc03a52UL, 0x3d025065UL,
-    0x365e1758UL, 0x379c7d6fUL, 0x35dac336UL, 0x3418a901UL, 0x3157bf84UL,
-    0x3095d5b3UL, 0x32d36beaUL, 0x331101ddUL, 0x246be590UL, 0x25a98fa7UL,
-    0x27ef31feUL, 0x262d5bc9UL, 0x23624d4cUL, 0x22a0277bUL, 0x20e69922UL,
-    0x2124f315UL, 0x2a78b428UL, 0x2bbade1fUL, 0x29fc6046UL, 0x283e0a71UL,
-    0x2d711cf4UL, 0x2cb376c3UL, 0x2ef5c89aUL, 0x2f37a2adUL, 0x709a8dc0UL,
-    0x7158e7f7UL, 0x731e59aeUL, 0x72dc3399UL, 0x7793251cUL, 0x76514f2bUL,
-    0x7417f172UL, 0x75d59b45UL, 0x7e89dc78UL, 0x7f4bb64fUL, 0x7d0d0816UL,
-    0x7ccf6221UL, 0x798074a4UL, 0x78421e93UL, 0x7a04a0caUL, 0x7bc6cafdUL,
-    0x6cbc2eb0UL, 0x6d7e4487UL, 0x6f38fadeUL, 0x6efa90e9UL, 0x6bb5866cUL,
-    0x6a77ec5bUL, 0x68315202UL, 0x69f33835UL, 0x62af7f08UL, 0x636d153fUL,
-    0x612bab66UL, 0x60e9c151UL, 0x65a6d7d4UL, 0x6464bde3UL, 0x662203baUL,
-    0x67e0698dUL, 0x48d7cb20UL, 0x4915a117UL, 0x4b531f4eUL, 0x4a917579UL,
-    0x4fde63fcUL, 0x4e1c09cbUL, 0x4c5ab792UL, 0x4d98dda5UL, 0x46c49a98UL,
-    0x4706f0afUL, 0x45404ef6UL, 0x448224c1UL, 0x41cd3244UL, 0x400f5873UL,
-    0x4249e62aUL, 0x438b8c1dUL, 0x54f16850UL, 0x55330267UL, 0x5775bc3eUL,
-    0x56b7d609UL, 0x53f8c08cUL, 0x523aaabbUL, 0x507c14e2UL, 0x51be7ed5UL,
-    0x5ae239e8UL, 0x5b2053dfUL, 0x5966ed86UL, 0x58a487b1UL, 0x5deb9134UL,
-    0x5c29fb03UL, 0x5e6f455aUL, 0x5fad2f6dUL, 0xe1351b80UL, 0xe0f771b7UL,
-    0xe2b1cfeeUL, 0xe373a5d9UL, 0xe63cb35cUL, 0xe7fed96bUL, 0xe5b86732UL,
-    0xe47a0d05UL, 0xef264a38UL, 0xeee4200fUL, 0xeca29e56UL, 0xed60f461UL,
-    0xe82fe2e4UL, 0xe9ed88d3UL, 0xebab368aUL, 0xea695cbdUL, 0xfd13b8f0UL,
-    0xfcd1d2c7UL, 0xfe976c9eUL, 0xff5506a9UL, 0xfa1a102cUL, 0xfbd87a1bUL,
-    0xf99ec442UL, 0xf85cae75UL, 0xf300e948UL, 0xf2c2837fUL, 0xf0843d26UL,
-    0xf1465711UL, 0xf4094194UL, 0xf5cb2ba3UL, 0xf78d95faUL, 0xf64fffcdUL,
-    0xd9785d60UL, 0xd8ba3757UL, 0xdafc890eUL, 0xdb3ee339UL, 0xde71f5bcUL,
-    0xdfb39f8bUL, 0xddf521d2UL, 0xdc374be5UL, 0xd76b0cd8UL, 0xd6a966efUL,
-    0xd4efd8b6UL, 0xd52db281UL, 0xd062a404UL, 0xd1a0ce33UL, 0xd3e6706aUL,
-    0xd2241a5dUL, 0xc55efe10UL, 0xc49c9427UL, 0xc6da2a7eUL, 0xc7184049UL,
-    0xc25756ccUL, 0xc3953cfbUL, 0xc1d382a2UL, 0xc011e895UL, 0xcb4dafa8UL,
-    0xca8fc59fUL, 0xc8c97bc6UL, 0xc90b11f1UL, 0xcc440774UL, 0xcd866d43UL,
-    0xcfc0d31aUL, 0xce02b92dUL, 0x91af9640UL, 0x906dfc77UL, 0x922b422eUL,
-    0x93e92819UL, 0x96a63e9cUL, 0x976454abUL, 0x9522eaf2UL, 0x94e080c5UL,
-    0x9fbcc7f8UL, 0x9e7eadcfUL, 0x9c381396UL, 0x9dfa79a1UL, 0x98b56f24UL,
-    0x99770513UL, 0x9b31bb4aUL, 0x9af3d17dUL, 0x8d893530UL, 0x8c4b5f07UL,
-    0x8e0de15eUL, 0x8fcf8b69UL, 0x8a809decUL, 0x8b42f7dbUL, 0x89044982UL,
-    0x88c623b5UL, 0x839a6488UL, 0x82580ebfUL, 0x801eb0e6UL, 0x81dcdad1UL,
-    0x8493cc54UL, 0x8551a663UL, 0x8717183aUL, 0x86d5720dUL, 0xa9e2d0a0UL,
-    0xa820ba97UL, 0xaa6604ceUL, 0xaba46ef9UL, 0xaeeb787cUL, 0xaf29124bUL,
-    0xad6fac12UL, 0xacadc625UL, 0xa7f18118UL, 0xa633eb2fUL, 0xa4755576UL,
-    0xa5b73f41UL, 0xa0f829c4UL, 0xa13a43f3UL, 0xa37cfdaaUL, 0xa2be979dUL,
-    0xb5c473d0UL, 0xb40619e7UL, 0xb640a7beUL, 0xb782cd89UL, 0xb2cddb0cUL,
-    0xb30fb13bUL, 0xb1490f62UL, 0xb08b6555UL, 0xbbd72268UL, 0xba15485fUL,
-    0xb853f606UL, 0xb9919c31UL, 0xbcde8ab4UL, 0xbd1ce083UL, 0xbf5a5edaUL,
-    0xbe9834edUL
-  },
-  {
-    0x00000000UL, 0xb8bc6765UL, 0xaa09c88bUL, 0x12b5afeeUL, 0x8f629757UL,
-    0x37def032UL, 0x256b5fdcUL, 0x9dd738b9UL, 0xc5b428efUL, 0x7d084f8aUL,
-    0x6fbde064UL, 0xd7018701UL, 0x4ad6bfb8UL, 0xf26ad8ddUL, 0xe0df7733UL,
-    0x58631056UL, 0x5019579fUL, 0xe8a530faUL, 0xfa109f14UL, 0x42acf871UL,
-    0xdf7bc0c8UL, 0x67c7a7adUL, 0x75720843UL, 0xcdce6f26UL, 0x95ad7f70UL,
-    0x2d111815UL, 0x3fa4b7fbUL, 0x8718d09eUL, 0x1acfe827UL, 0xa2738f42UL,
-    0xb0c620acUL, 0x087a47c9UL, 0xa032af3eUL, 0x188ec85bUL, 0x0a3b67b5UL,
-    0xb28700d0UL, 0x2f503869UL, 0x97ec5f0cUL, 0x8559f0e2UL, 0x3de59787UL,
-    0x658687d1UL, 0xdd3ae0b4UL, 0xcf8f4f5aUL, 0x7733283fUL, 0xeae41086UL,
-    0x525877e3UL, 0x40edd80dUL, 0xf851bf68UL, 0xf02bf8a1UL, 0x48979fc4UL,
-    0x5a22302aUL, 0xe29e574fUL, 0x7f496ff6UL, 0xc7f50893UL, 0xd540a77dUL,
-    0x6dfcc018UL, 0x359fd04eUL, 0x8d23b72bUL, 0x9f9618c5UL, 0x272a7fa0UL,
-    0xbafd4719UL, 0x0241207cUL, 0x10f48f92UL, 0xa848e8f7UL, 0x9b14583dUL,
-    0x23a83f58UL, 0x311d90b6UL, 0x89a1f7d3UL, 0x1476cf6aUL, 0xaccaa80fUL,
-    0xbe7f07e1UL, 0x06c36084UL, 0x5ea070d2UL, 0xe61c17b7UL, 0xf4a9b859UL,
-    0x4c15df3cUL, 0xd1c2e785UL, 0x697e80e0UL, 0x7bcb2f0eUL, 0xc377486bUL,
-    0xcb0d0fa2UL, 0x73b168c7UL, 0x6104c729UL, 0xd9b8a04cUL, 0x446f98f5UL,
-    0xfcd3ff90UL, 0xee66507eUL, 0x56da371bUL, 0x0eb9274dUL, 0xb6054028UL,
-    0xa4b0efc6UL, 0x1c0c88a3UL, 0x81dbb01aUL, 0x3967d77fUL, 0x2bd27891UL,
-    0x936e1ff4UL, 0x3b26f703UL, 0x839a9066UL, 0x912f3f88UL, 0x299358edUL,
-    0xb4446054UL, 0x0cf80731UL, 0x1e4da8dfUL, 0xa6f1cfbaUL, 0xfe92dfecUL,
-    0x462eb889UL, 0x549b1767UL, 0xec277002UL, 0x71f048bbUL, 0xc94c2fdeUL,
-    0xdbf98030UL, 0x6345e755UL, 0x6b3fa09cUL, 0xd383c7f9UL, 0xc1366817UL,
-    0x798a0f72UL, 0xe45d37cbUL, 0x5ce150aeUL, 0x4e54ff40UL, 0xf6e89825UL,
-    0xae8b8873UL, 0x1637ef16UL, 0x048240f8UL, 0xbc3e279dUL, 0x21e91f24UL,
-    0x99557841UL, 0x8be0d7afUL, 0x335cb0caUL, 0xed59b63bUL, 0x55e5d15eUL,
-    0x47507eb0UL, 0xffec19d5UL, 0x623b216cUL, 0xda874609UL, 0xc832e9e7UL,
-    0x708e8e82UL, 0x28ed9ed4UL, 0x9051f9b1UL, 0x82e4565fUL, 0x3a58313aUL,
-    0xa78f0983UL, 0x1f336ee6UL, 0x0d86c108UL, 0xb53aa66dUL, 0xbd40e1a4UL,
-    0x05fc86c1UL, 0x1749292fUL, 0xaff54e4aUL, 0x322276f3UL, 0x8a9e1196UL,
-    0x982bbe78UL, 0x2097d91dUL, 0x78f4c94bUL, 0xc048ae2eUL, 0xd2fd01c0UL,
-    0x6a4166a5UL, 0xf7965e1cUL, 0x4f2a3979UL, 0x5d9f9697UL, 0xe523f1f2UL,
-    0x4d6b1905UL, 0xf5d77e60UL, 0xe762d18eUL, 0x5fdeb6ebUL, 0xc2098e52UL,
-    0x7ab5e937UL, 0x680046d9UL, 0xd0bc21bcUL, 0x88df31eaUL, 0x3063568fUL,
-    0x22d6f961UL, 0x9a6a9e04UL, 0x07bda6bdUL, 0xbf01c1d8UL, 0xadb46e36UL,
-    0x15080953UL, 0x1d724e9aUL, 0xa5ce29ffUL, 0xb77b8611UL, 0x0fc7e174UL,
-    0x9210d9cdUL, 0x2aacbea8UL, 0x38191146UL, 0x80a57623UL, 0xd8c66675UL,
-    0x607a0110UL, 0x72cfaefeUL, 0xca73c99bUL, 0x57a4f122UL, 0xef189647UL,
-    0xfdad39a9UL, 0x45115eccUL, 0x764dee06UL, 0xcef18963UL, 0xdc44268dUL,
-    0x64f841e8UL, 0xf92f7951UL, 0x41931e34UL, 0x5326b1daUL, 0xeb9ad6bfUL,
-    0xb3f9c6e9UL, 0x0b45a18cUL, 0x19f00e62UL, 0xa14c6907UL, 0x3c9b51beUL,
-    0x842736dbUL, 0x96929935UL, 0x2e2efe50UL, 0x2654b999UL, 0x9ee8defcUL,
-    0x8c5d7112UL, 0x34e11677UL, 0xa9362eceUL, 0x118a49abUL, 0x033fe645UL,
-    0xbb838120UL, 0xe3e09176UL, 0x5b5cf613UL, 0x49e959fdUL, 0xf1553e98UL,
-    0x6c820621UL, 0xd43e6144UL, 0xc68bceaaUL, 0x7e37a9cfUL, 0xd67f4138UL,
-    0x6ec3265dUL, 0x7c7689b3UL, 0xc4caeed6UL, 0x591dd66fUL, 0xe1a1b10aUL,
-    0xf3141ee4UL, 0x4ba87981UL, 0x13cb69d7UL, 0xab770eb2UL, 0xb9c2a15cUL,
-    0x017ec639UL, 0x9ca9fe80UL, 0x241599e5UL, 0x36a0360bUL, 0x8e1c516eUL,
-    0x866616a7UL, 0x3eda71c2UL, 0x2c6fde2cUL, 0x94d3b949UL, 0x090481f0UL,
-    0xb1b8e695UL, 0xa30d497bUL, 0x1bb12e1eUL, 0x43d23e48UL, 0xfb6e592dUL,
-    0xe9dbf6c3UL, 0x516791a6UL, 0xccb0a91fUL, 0x740cce7aUL, 0x66b96194UL,
-    0xde0506f1UL
-  },
-  {
-    0x00000000UL, 0x96300777UL, 0x2c610eeeUL, 0xba510999UL, 0x19c46d07UL,
-    0x8ff46a70UL, 0x35a563e9UL, 0xa395649eUL, 0x3288db0eUL, 0xa4b8dc79UL,
-    0x1ee9d5e0UL, 0x88d9d297UL, 0x2b4cb609UL, 0xbd7cb17eUL, 0x072db8e7UL,
-    0x911dbf90UL, 0x6410b71dUL, 0xf220b06aUL, 0x4871b9f3UL, 0xde41be84UL,
-    0x7dd4da1aUL, 0xebe4dd6dUL, 0x51b5d4f4UL, 0xc785d383UL, 0x56986c13UL,
-    0xc0a86b64UL, 0x7af962fdUL, 0xecc9658aUL, 0x4f5c0114UL, 0xd96c0663UL,
-    0x633d0ffaUL, 0xf50d088dUL, 0xc8206e3bUL, 0x5e10694cUL, 0xe44160d5UL,
-    0x727167a2UL, 0xd1e4033cUL, 0x47d4044bUL, 0xfd850dd2UL, 0x6bb50aa5UL,
-    0xfaa8b535UL, 0x6c98b242UL, 0xd6c9bbdbUL, 0x40f9bcacUL, 0xe36cd832UL,
-    0x755cdf45UL, 0xcf0dd6dcUL, 0x593dd1abUL, 0xac30d926UL, 0x3a00de51UL,
-    0x8051d7c8UL, 0x1661d0bfUL, 0xb5f4b421UL, 0x23c4b356UL, 0x9995bacfUL,
-    0x0fa5bdb8UL, 0x9eb80228UL, 0x0888055fUL, 0xb2d90cc6UL, 0x24e90bb1UL,
-    0x877c6f2fUL, 0x114c6858UL, 0xab1d61c1UL, 0x3d2d66b6UL, 0x9041dc76UL,
-    0x0671db01UL, 0xbc20d298UL, 0x2a10d5efUL, 0x8985b171UL, 0x1fb5b606UL,
-    0xa5e4bf9fUL, 0x33d4b8e8UL, 0xa2c90778UL, 0x34f9000fUL, 0x8ea80996UL,
-    0x18980ee1UL, 0xbb0d6a7fUL, 0x2d3d6d08UL, 0x976c6491UL, 0x015c63e6UL,
-    0xf4516b6bUL, 0x62616c1cUL, 0xd8306585UL, 0x4e0062f2UL, 0xed95066cUL,
-    0x7ba5011bUL, 0xc1f40882UL, 0x57c40ff5UL, 0xc6d9b065UL, 0x50e9b712UL,
-    0xeab8be8bUL, 0x7c88b9fcUL, 0xdf1ddd62UL, 0x492dda15UL, 0xf37cd38cUL,
-    0x654cd4fbUL, 0x5861b24dUL, 0xce51b53aUL, 0x7400bca3UL, 0xe230bbd4UL,
-    0x41a5df4aUL, 0xd795d83dUL, 0x6dc4d1a4UL, 0xfbf4d6d3UL, 0x6ae96943UL,
-    0xfcd96e34UL, 0x468867adUL, 0xd0b860daUL, 0x732d0444UL, 0xe51d0333UL,
-    0x5f4c0aaaUL, 0xc97c0dddUL, 0x3c710550UL, 0xaa410227UL, 0x10100bbeUL,
-    0x86200cc9UL, 0x25b56857UL, 0xb3856f20UL, 0x09d466b9UL, 0x9fe461ceUL,
-    0x0ef9de5eUL, 0x98c9d929UL, 0x2298d0b0UL, 0xb4a8d7c7UL, 0x173db359UL,
-    0x810db42eUL, 0x3b5cbdb7UL, 0xad6cbac0UL, 0x2083b8edUL, 0xb6b3bf9aUL,
-    0x0ce2b603UL, 0x9ad2b174UL, 0x3947d5eaUL, 0xaf77d29dUL, 0x1526db04UL,
-    0x8316dc73UL, 0x120b63e3UL, 0x843b6494UL, 0x3e6a6d0dUL, 0xa85a6a7aUL,
-    0x0bcf0ee4UL, 0x9dff0993UL, 0x27ae000aUL, 0xb19e077dUL, 0x44930ff0UL,
-    0xd2a30887UL, 0x68f2011eUL, 0xfec20669UL, 0x5d5762f7UL, 0xcb676580UL,
-    0x71366c19UL, 0xe7066b6eUL, 0x761bd4feUL, 0xe02bd389UL, 0x5a7ada10UL,
-    0xcc4add67UL, 0x6fdfb9f9UL, 0xf9efbe8eUL, 0x43beb717UL, 0xd58eb060UL,
-    0xe8a3d6d6UL, 0x7e93d1a1UL, 0xc4c2d838UL, 0x52f2df4fUL, 0xf167bbd1UL,
-    0x6757bca6UL, 0xdd06b53fUL, 0x4b36b248UL, 0xda2b0dd8UL, 0x4c1b0aafUL,
-    0xf64a0336UL, 0x607a0441UL, 0xc3ef60dfUL, 0x55df67a8UL, 0xef8e6e31UL,
-    0x79be6946UL, 0x8cb361cbUL, 0x1a8366bcUL, 0xa0d26f25UL, 0x36e26852UL,
-    0x95770cccUL, 0x03470bbbUL, 0xb9160222UL, 0x2f260555UL, 0xbe3bbac5UL,
-    0x280bbdb2UL, 0x925ab42bUL, 0x046ab35cUL, 0xa7ffd7c2UL, 0x31cfd0b5UL,
-    0x8b9ed92cUL, 0x1daede5bUL, 0xb0c2649bUL, 0x26f263ecUL, 0x9ca36a75UL,
-    0x0a936d02UL, 0xa906099cUL, 0x3f360eebUL, 0x85670772UL, 0x13570005UL,
-    0x824abf95UL, 0x147ab8e2UL, 0xae2bb17bUL, 0x381bb60cUL, 0x9b8ed292UL,
-    0x0dbed5e5UL, 0xb7efdc7cUL, 0x21dfdb0bUL, 0xd4d2d386UL, 0x42e2d4f1UL,
-    0xf8b3dd68UL, 0x6e83da1fUL, 0xcd16be81UL, 0x5b26b9f6UL, 0xe177b06fUL,
-    0x7747b718UL, 0xe65a0888UL, 0x706a0fffUL, 0xca3b0666UL, 0x5c0b0111UL,
-    0xff9e658fUL, 0x69ae62f8UL, 0xd3ff6b61UL, 0x45cf6c16UL, 0x78e20aa0UL,
-    0xeed20dd7UL, 0x5483044eUL, 0xc2b30339UL, 0x612667a7UL, 0xf71660d0UL,
-    0x4d476949UL, 0xdb776e3eUL, 0x4a6ad1aeUL, 0xdc5ad6d9UL, 0x660bdf40UL,
-    0xf03bd837UL, 0x53aebca9UL, 0xc59ebbdeUL, 0x7fcfb247UL, 0xe9ffb530UL,
-    0x1cf2bdbdUL, 0x8ac2bacaUL, 0x3093b353UL, 0xa6a3b424UL, 0x0536d0baUL,
-    0x9306d7cdUL, 0x2957de54UL, 0xbf67d923UL, 0x2e7a66b3UL, 0xb84a61c4UL,
-    0x021b685dUL, 0x942b6f2aUL, 0x37be0bb4UL, 0xa18e0cc3UL, 0x1bdf055aUL,
-    0x8def022dUL
-  },
-  {
-    0x00000000UL, 0x41311b19UL, 0x82623632UL, 0xc3532d2bUL, 0x04c56c64UL,
-    0x45f4777dUL, 0x86a75a56UL, 0xc796414fUL, 0x088ad9c8UL, 0x49bbc2d1UL,
-    0x8ae8effaUL, 0xcbd9f4e3UL, 0x0c4fb5acUL, 0x4d7eaeb5UL, 0x8e2d839eUL,
-    0xcf1c9887UL, 0x5112c24aUL, 0x1023d953UL, 0xd370f478UL, 0x9241ef61UL,
-    0x55d7ae2eUL, 0x14e6b537UL, 0xd7b5981cUL, 0x96848305UL, 0x59981b82UL,
-    0x18a9009bUL, 0xdbfa2db0UL, 0x9acb36a9UL, 0x5d5d77e6UL, 0x1c6c6cffUL,
-    0xdf3f41d4UL, 0x9e0e5acdUL, 0xa2248495UL, 0xe3159f8cUL, 0x2046b2a7UL,
-    0x6177a9beUL, 0xa6e1e8f1UL, 0xe7d0f3e8UL, 0x2483dec3UL, 0x65b2c5daUL,
-    0xaaae5d5dUL, 0xeb9f4644UL, 0x28cc6b6fUL, 0x69fd7076UL, 0xae6b3139UL,
-    0xef5a2a20UL, 0x2c09070bUL, 0x6d381c12UL, 0xf33646dfUL, 0xb2075dc6UL,
-    0x715470edUL, 0x30656bf4UL, 0xf7f32abbUL, 0xb6c231a2UL, 0x75911c89UL,
-    0x34a00790UL, 0xfbbc9f17UL, 0xba8d840eUL, 0x79dea925UL, 0x38efb23cUL,
-    0xff79f373UL, 0xbe48e86aUL, 0x7d1bc541UL, 0x3c2ade58UL, 0x054f79f0UL,
-    0x447e62e9UL, 0x872d4fc2UL, 0xc61c54dbUL, 0x018a1594UL, 0x40bb0e8dUL,
-    0x83e823a6UL, 0xc2d938bfUL, 0x0dc5a038UL, 0x4cf4bb21UL, 0x8fa7960aUL,
-    0xce968d13UL, 0x0900cc5cUL, 0x4831d745UL, 0x8b62fa6eUL, 0xca53e177UL,
-    0x545dbbbaUL, 0x156ca0a3UL, 0xd63f8d88UL, 0x970e9691UL, 0x5098d7deUL,
-    0x11a9ccc7UL, 0xd2fae1ecUL, 0x93cbfaf5UL, 0x5cd76272UL, 0x1de6796bUL,
-    0xdeb55440UL, 0x9f844f59UL, 0x58120e16UL, 0x1923150fUL, 0xda703824UL,
-    0x9b41233dUL, 0xa76bfd65UL, 0xe65ae67cUL, 0x2509cb57UL, 0x6438d04eUL,
-    0xa3ae9101UL, 0xe29f8a18UL, 0x21cca733UL, 0x60fdbc2aUL, 0xafe124adUL,
-    0xeed03fb4UL, 0x2d83129fUL, 0x6cb20986UL, 0xab2448c9UL, 0xea1553d0UL,
-    0x29467efbUL, 0x687765e2UL, 0xf6793f2fUL, 0xb7482436UL, 0x741b091dUL,
-    0x352a1204UL, 0xf2bc534bUL, 0xb38d4852UL, 0x70de6579UL, 0x31ef7e60UL,
-    0xfef3e6e7UL, 0xbfc2fdfeUL, 0x7c91d0d5UL, 0x3da0cbccUL, 0xfa368a83UL,
-    0xbb07919aUL, 0x7854bcb1UL, 0x3965a7a8UL, 0x4b98833bUL, 0x0aa99822UL,
-    0xc9fab509UL, 0x88cbae10UL, 0x4f5def5fUL, 0x0e6cf446UL, 0xcd3fd96dUL,
-    0x8c0ec274UL, 0x43125af3UL, 0x022341eaUL, 0xc1706cc1UL, 0x804177d8UL,
-    0x47d73697UL, 0x06e62d8eUL, 0xc5b500a5UL, 0x84841bbcUL, 0x1a8a4171UL,
-    0x5bbb5a68UL, 0x98e87743UL, 0xd9d96c5aUL, 0x1e4f2d15UL, 0x5f7e360cUL,
-    0x9c2d1b27UL, 0xdd1c003eUL, 0x120098b9UL, 0x533183a0UL, 0x9062ae8bUL,
-    0xd153b592UL, 0x16c5f4ddUL, 0x57f4efc4UL, 0x94a7c2efUL, 0xd596d9f6UL,
-    0xe9bc07aeUL, 0xa88d1cb7UL, 0x6bde319cUL, 0x2aef2a85UL, 0xed796bcaUL,
-    0xac4870d3UL, 0x6f1b5df8UL, 0x2e2a46e1UL, 0xe136de66UL, 0xa007c57fUL,
-    0x6354e854UL, 0x2265f34dUL, 0xe5f3b202UL, 0xa4c2a91bUL, 0x67918430UL,
-    0x26a09f29UL, 0xb8aec5e4UL, 0xf99fdefdUL, 0x3accf3d6UL, 0x7bfde8cfUL,
-    0xbc6ba980UL, 0xfd5ab299UL, 0x3e099fb2UL, 0x7f3884abUL, 0xb0241c2cUL,
-    0xf1150735UL, 0x32462a1eUL, 0x73773107UL, 0xb4e17048UL, 0xf5d06b51UL,
-    0x3683467aUL, 0x77b25d63UL, 0x4ed7facbUL, 0x0fe6e1d2UL, 0xccb5ccf9UL,
-    0x8d84d7e0UL, 0x4a1296afUL, 0x0b238db6UL, 0xc870a09dUL, 0x8941bb84UL,
-    0x465d2303UL, 0x076c381aUL, 0xc43f1531UL, 0x850e0e28UL, 0x42984f67UL,
-    0x03a9547eUL, 0xc0fa7955UL, 0x81cb624cUL, 0x1fc53881UL, 0x5ef42398UL,
-    0x9da70eb3UL, 0xdc9615aaUL, 0x1b0054e5UL, 0x5a314ffcUL, 0x996262d7UL,
-    0xd85379ceUL, 0x174fe149UL, 0x567efa50UL, 0x952dd77bUL, 0xd41ccc62UL,
-    0x138a8d2dUL, 0x52bb9634UL, 0x91e8bb1fUL, 0xd0d9a006UL, 0xecf37e5eUL,
-    0xadc26547UL, 0x6e91486cUL, 0x2fa05375UL, 0xe836123aUL, 0xa9070923UL,
-    0x6a542408UL, 0x2b653f11UL, 0xe479a796UL, 0xa548bc8fUL, 0x661b91a4UL,
-    0x272a8abdUL, 0xe0bccbf2UL, 0xa18dd0ebUL, 0x62defdc0UL, 0x23efe6d9UL,
-    0xbde1bc14UL, 0xfcd0a70dUL, 0x3f838a26UL, 0x7eb2913fUL, 0xb924d070UL,
-    0xf815cb69UL, 0x3b46e642UL, 0x7a77fd5bUL, 0xb56b65dcUL, 0xf45a7ec5UL,
-    0x370953eeUL, 0x763848f7UL, 0xb1ae09b8UL, 0xf09f12a1UL, 0x33cc3f8aUL,
-    0x72fd2493UL
-  },
-  {
-    0x00000000UL, 0x376ac201UL, 0x6ed48403UL, 0x59be4602UL, 0xdca80907UL,
-    0xebc2cb06UL, 0xb27c8d04UL, 0x85164f05UL, 0xb851130eUL, 0x8f3bd10fUL,
-    0xd685970dUL, 0xe1ef550cUL, 0x64f91a09UL, 0x5393d808UL, 0x0a2d9e0aUL,
-    0x3d475c0bUL, 0x70a3261cUL, 0x47c9e41dUL, 0x1e77a21fUL, 0x291d601eUL,
-    0xac0b2f1bUL, 0x9b61ed1aUL, 0xc2dfab18UL, 0xf5b56919UL, 0xc8f23512UL,
-    0xff98f713UL, 0xa626b111UL, 0x914c7310UL, 0x145a3c15UL, 0x2330fe14UL,
-    0x7a8eb816UL, 0x4de47a17UL, 0xe0464d38UL, 0xd72c8f39UL, 0x8e92c93bUL,
-    0xb9f80b3aUL, 0x3cee443fUL, 0x0b84863eUL, 0x523ac03cUL, 0x6550023dUL,
-    0x58175e36UL, 0x6f7d9c37UL, 0x36c3da35UL, 0x01a91834UL, 0x84bf5731UL,
-    0xb3d59530UL, 0xea6bd332UL, 0xdd011133UL, 0x90e56b24UL, 0xa78fa925UL,
-    0xfe31ef27UL, 0xc95b2d26UL, 0x4c4d6223UL, 0x7b27a022UL, 0x2299e620UL,
-    0x15f32421UL, 0x28b4782aUL, 0x1fdeba2bUL, 0x4660fc29UL, 0x710a3e28UL,
-    0xf41c712dUL, 0xc376b32cUL, 0x9ac8f52eUL, 0xada2372fUL, 0xc08d9a70UL,
-    0xf7e75871UL, 0xae591e73UL, 0x9933dc72UL, 0x1c259377UL, 0x2b4f5176UL,
-    0x72f11774UL, 0x459bd575UL, 0x78dc897eUL, 0x4fb64b7fUL, 0x16080d7dUL,
-    0x2162cf7cUL, 0xa4748079UL, 0x931e4278UL, 0xcaa0047aUL, 0xfdcac67bUL,
-    0xb02ebc6cUL, 0x87447e6dUL, 0xdefa386fUL, 0xe990fa6eUL, 0x6c86b56bUL,
-    0x5bec776aUL, 0x02523168UL, 0x3538f369UL, 0x087faf62UL, 0x3f156d63UL,
-    0x66ab2b61UL, 0x51c1e960UL, 0xd4d7a665UL, 0xe3bd6464UL, 0xba032266UL,
-    0x8d69e067UL, 0x20cbd748UL, 0x17a11549UL, 0x4e1f534bUL, 0x7975914aUL,
-    0xfc63de4fUL, 0xcb091c4eUL, 0x92b75a4cUL, 0xa5dd984dUL, 0x989ac446UL,
-    0xaff00647UL, 0xf64e4045UL, 0xc1248244UL, 0x4432cd41UL, 0x73580f40UL,
-    0x2ae64942UL, 0x1d8c8b43UL, 0x5068f154UL, 0x67023355UL, 0x3ebc7557UL,
-    0x09d6b756UL, 0x8cc0f853UL, 0xbbaa3a52UL, 0xe2147c50UL, 0xd57ebe51UL,
-    0xe839e25aUL, 0xdf53205bUL, 0x86ed6659UL, 0xb187a458UL, 0x3491eb5dUL,
-    0x03fb295cUL, 0x5a456f5eUL, 0x6d2fad5fUL, 0x801b35e1UL, 0xb771f7e0UL,
-    0xeecfb1e2UL, 0xd9a573e3UL, 0x5cb33ce6UL, 0x6bd9fee7UL, 0x3267b8e5UL,
-    0x050d7ae4UL, 0x384a26efUL, 0x0f20e4eeUL, 0x569ea2ecUL, 0x61f460edUL,
-    0xe4e22fe8UL, 0xd388ede9UL, 0x8a36abebUL, 0xbd5c69eaUL, 0xf0b813fdUL,
-    0xc7d2d1fcUL, 0x9e6c97feUL, 0xa90655ffUL, 0x2c101afaUL, 0x1b7ad8fbUL,
-    0x42c49ef9UL, 0x75ae5cf8UL, 0x48e900f3UL, 0x7f83c2f2UL, 0x263d84f0UL,
-    0x115746f1UL, 0x944109f4UL, 0xa32bcbf5UL, 0xfa958df7UL, 0xcdff4ff6UL,
-    0x605d78d9UL, 0x5737bad8UL, 0x0e89fcdaUL, 0x39e33edbUL, 0xbcf571deUL,
-    0x8b9fb3dfUL, 0xd221f5ddUL, 0xe54b37dcUL, 0xd80c6bd7UL, 0xef66a9d6UL,
-    0xb6d8efd4UL, 0x81b22dd5UL, 0x04a462d0UL, 0x33cea0d1UL, 0x6a70e6d3UL,
-    0x5d1a24d2UL, 0x10fe5ec5UL, 0x27949cc4UL, 0x7e2adac6UL, 0x494018c7UL,
-    0xcc5657c2UL, 0xfb3c95c3UL, 0xa282d3c1UL, 0x95e811c0UL, 0xa8af4dcbUL,
-    0x9fc58fcaUL, 0xc67bc9c8UL, 0xf1110bc9UL, 0x740744ccUL, 0x436d86cdUL,
-    0x1ad3c0cfUL, 0x2db902ceUL, 0x4096af91UL, 0x77fc6d90UL, 0x2e422b92UL,
-    0x1928e993UL, 0x9c3ea696UL, 0xab546497UL, 0xf2ea2295UL, 0xc580e094UL,
-    0xf8c7bc9fUL, 0xcfad7e9eUL, 0x9613389cUL, 0xa179fa9dUL, 0x246fb598UL,
-    0x13057799UL, 0x4abb319bUL, 0x7dd1f39aUL, 0x3035898dUL, 0x075f4b8cUL,
-    0x5ee10d8eUL, 0x698bcf8fUL, 0xec9d808aUL, 0xdbf7428bUL, 0x82490489UL,
-    0xb523c688UL, 0x88649a83UL, 0xbf0e5882UL, 0xe6b01e80UL, 0xd1dadc81UL,
-    0x54cc9384UL, 0x63a65185UL, 0x3a181787UL, 0x0d72d586UL, 0xa0d0e2a9UL,
-    0x97ba20a8UL, 0xce0466aaUL, 0xf96ea4abUL, 0x7c78ebaeUL, 0x4b1229afUL,
-    0x12ac6fadUL, 0x25c6adacUL, 0x1881f1a7UL, 0x2feb33a6UL, 0x765575a4UL,
-    0x413fb7a5UL, 0xc429f8a0UL, 0xf3433aa1UL, 0xaafd7ca3UL, 0x9d97bea2UL,
-    0xd073c4b5UL, 0xe71906b4UL, 0xbea740b6UL, 0x89cd82b7UL, 0x0cdbcdb2UL,
-    0x3bb10fb3UL, 0x620f49b1UL, 0x55658bb0UL, 0x6822d7bbUL, 0x5f4815baUL,
-    0x06f653b8UL, 0x319c91b9UL, 0xb48adebcUL, 0x83e01cbdUL, 0xda5e5abfUL,
-    0xed3498beUL
-  },
-  {
-    0x00000000UL, 0x6567bcb8UL, 0x8bc809aaUL, 0xeeafb512UL, 0x5797628fUL,
-    0x32f0de37UL, 0xdc5f6b25UL, 0xb938d79dUL, 0xef28b4c5UL, 0x8a4f087dUL,
-    0x64e0bd6fUL, 0x018701d7UL, 0xb8bfd64aUL, 0xddd86af2UL, 0x3377dfe0UL,
-    0x56106358UL, 0x9f571950UL, 0xfa30a5e8UL, 0x149f10faUL, 0x71f8ac42UL,
-    0xc8c07bdfUL, 0xada7c767UL, 0x43087275UL, 0x266fcecdUL, 0x707fad95UL,
-    0x1518112dUL, 0xfbb7a43fUL, 0x9ed01887UL, 0x27e8cf1aUL, 0x428f73a2UL,
-    0xac20c6b0UL, 0xc9477a08UL, 0x3eaf32a0UL, 0x5bc88e18UL, 0xb5673b0aUL,
-    0xd00087b2UL, 0x6938502fUL, 0x0c5fec97UL, 0xe2f05985UL, 0x8797e53dUL,
-    0xd1878665UL, 0xb4e03addUL, 0x5a4f8fcfUL, 0x3f283377UL, 0x8610e4eaUL,
-    0xe3775852UL, 0x0dd8ed40UL, 0x68bf51f8UL, 0xa1f82bf0UL, 0xc49f9748UL,
-    0x2a30225aUL, 0x4f579ee2UL, 0xf66f497fUL, 0x9308f5c7UL, 0x7da740d5UL,
-    0x18c0fc6dUL, 0x4ed09f35UL, 0x2bb7238dUL, 0xc518969fUL, 0xa07f2a27UL,
-    0x1947fdbaUL, 0x7c204102UL, 0x928ff410UL, 0xf7e848a8UL, 0x3d58149bUL,
-    0x583fa823UL, 0xb6901d31UL, 0xd3f7a189UL, 0x6acf7614UL, 0x0fa8caacUL,
-    0xe1077fbeUL, 0x8460c306UL, 0xd270a05eUL, 0xb7171ce6UL, 0x59b8a9f4UL,
-    0x3cdf154cUL, 0x85e7c2d1UL, 0xe0807e69UL, 0x0e2fcb7bUL, 0x6b4877c3UL,
-    0xa20f0dcbUL, 0xc768b173UL, 0x29c70461UL, 0x4ca0b8d9UL, 0xf5986f44UL,
-    0x90ffd3fcUL, 0x7e5066eeUL, 0x1b37da56UL, 0x4d27b90eUL, 0x284005b6UL,
-    0xc6efb0a4UL, 0xa3880c1cUL, 0x1ab0db81UL, 0x7fd76739UL, 0x9178d22bUL,
-    0xf41f6e93UL, 0x03f7263bUL, 0x66909a83UL, 0x883f2f91UL, 0xed589329UL,
-    0x546044b4UL, 0x3107f80cUL, 0xdfa84d1eUL, 0xbacff1a6UL, 0xecdf92feUL,
-    0x89b82e46UL, 0x67179b54UL, 0x027027ecUL, 0xbb48f071UL, 0xde2f4cc9UL,
-    0x3080f9dbUL, 0x55e74563UL, 0x9ca03f6bUL, 0xf9c783d3UL, 0x176836c1UL,
-    0x720f8a79UL, 0xcb375de4UL, 0xae50e15cUL, 0x40ff544eUL, 0x2598e8f6UL,
-    0x73888baeUL, 0x16ef3716UL, 0xf8408204UL, 0x9d273ebcUL, 0x241fe921UL,
-    0x41785599UL, 0xafd7e08bUL, 0xcab05c33UL, 0x3bb659edUL, 0x5ed1e555UL,
-    0xb07e5047UL, 0xd519ecffUL, 0x6c213b62UL, 0x094687daUL, 0xe7e932c8UL,
-    0x828e8e70UL, 0xd49eed28UL, 0xb1f95190UL, 0x5f56e482UL, 0x3a31583aUL,
-    0x83098fa7UL, 0xe66e331fUL, 0x08c1860dUL, 0x6da63ab5UL, 0xa4e140bdUL,
-    0xc186fc05UL, 0x2f294917UL, 0x4a4ef5afUL, 0xf3762232UL, 0x96119e8aUL,
-    0x78be2b98UL, 0x1dd99720UL, 0x4bc9f478UL, 0x2eae48c0UL, 0xc001fdd2UL,
-    0xa566416aUL, 0x1c5e96f7UL, 0x79392a4fUL, 0x97969f5dUL, 0xf2f123e5UL,
-    0x05196b4dUL, 0x607ed7f5UL, 0x8ed162e7UL, 0xebb6de5fUL, 0x528e09c2UL,
-    0x37e9b57aUL, 0xd9460068UL, 0xbc21bcd0UL, 0xea31df88UL, 0x8f566330UL,
-    0x61f9d622UL, 0x049e6a9aUL, 0xbda6bd07UL, 0xd8c101bfUL, 0x366eb4adUL,
-    0x53090815UL, 0x9a4e721dUL, 0xff29cea5UL, 0x11867bb7UL, 0x74e1c70fUL,
-    0xcdd91092UL, 0xa8beac2aUL, 0x46111938UL, 0x2376a580UL, 0x7566c6d8UL,
-    0x10017a60UL, 0xfeaecf72UL, 0x9bc973caUL, 0x22f1a457UL, 0x479618efUL,
-    0xa939adfdUL, 0xcc5e1145UL, 0x06ee4d76UL, 0x6389f1ceUL, 0x8d2644dcUL,
-    0xe841f864UL, 0x51792ff9UL, 0x341e9341UL, 0xdab12653UL, 0xbfd69aebUL,
-    0xe9c6f9b3UL, 0x8ca1450bUL, 0x620ef019UL, 0x07694ca1UL, 0xbe519b3cUL,
-    0xdb362784UL, 0x35999296UL, 0x50fe2e2eUL, 0x99b95426UL, 0xfcdee89eUL,
-    0x12715d8cUL, 0x7716e134UL, 0xce2e36a9UL, 0xab498a11UL, 0x45e63f03UL,
-    0x208183bbUL, 0x7691e0e3UL, 0x13f65c5bUL, 0xfd59e949UL, 0x983e55f1UL,
-    0x2106826cUL, 0x44613ed4UL, 0xaace8bc6UL, 0xcfa9377eUL, 0x38417fd6UL,
-    0x5d26c36eUL, 0xb389767cUL, 0xd6eecac4UL, 0x6fd61d59UL, 0x0ab1a1e1UL,
-    0xe41e14f3UL, 0x8179a84bUL, 0xd769cb13UL, 0xb20e77abUL, 0x5ca1c2b9UL,
-    0x39c67e01UL, 0x80fea99cUL, 0xe5991524UL, 0x0b36a036UL, 0x6e511c8eUL,
-    0xa7166686UL, 0xc271da3eUL, 0x2cde6f2cUL, 0x49b9d394UL, 0xf0810409UL,
-    0x95e6b8b1UL, 0x7b490da3UL, 0x1e2eb11bUL, 0x483ed243UL, 0x2d596efbUL,
-    0xc3f6dbe9UL, 0xa6916751UL, 0x1fa9b0ccUL, 0x7ace0c74UL, 0x9461b966UL,
-    0xf10605deUL
-#endif
-  }
-};
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/deflate.h b/surface/include/pcl/surface/3rdparty/opennurbs/deflate.h
deleted file mode 100644 (file)
index 04220ed..0000000
+++ /dev/null
@@ -1,331 +0,0 @@
-/* deflate.h -- internal compression state
- * Copyright (C) 1995-2004 Jean-loup Gailly
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* WARNING: this file should *not* be used by applications. It is
-   part of the implementation of the compression library and is
-   subject to change. Applications should only use zlib.h.
- */
-
-/* @(#) $Id$ */
-
-#ifndef DEFLATE_H
-#define DEFLATE_H
-
-#include "zutil.h"
-
-/* define NO_GZIP when compiling if you want to disable gzip header and
-   trailer creation by deflate().  NO_GZIP would be used to avoid linking in
-   the crc code when it is not needed.  For shared libraries, gzip encoding
-   should be left enabled. */
-#ifndef NO_GZIP
-#  define GZIP
-#endif
-
-/* ===========================================================================
- * Internal compression state.
- */
-
-#define LENGTH_CODES 29
-/* number of length codes, not counting the special END_BLOCK code */
-
-#define LITERALS  256
-/* number of literal bytes 0..255 */
-
-#define L_CODES (LITERALS+1+LENGTH_CODES)
-/* number of Literal or Length codes, including the END_BLOCK code */
-
-#define D_CODES   30
-/* number of distance codes */
-
-#define BL_CODES  19
-/* number of codes used to transfer the bit lengths */
-
-#define HEAP_SIZE (2*L_CODES+1)
-/* maximum heap size */
-
-#define MAX_BITS 15
-/* All codes must not exceed MAX_BITS bits */
-
-#define INIT_STATE    42
-#define EXTRA_STATE   69
-#define NAME_STATE    73
-#define COMMENT_STATE 91
-#define HCRC_STATE   103
-#define BUSY_STATE   113
-#define FINISH_STATE 666
-/* Stream status */
-
-
-/* Data structure describing a single value and its code string. */
-typedef struct ct_data_s {
-    union {
-        ush  freq;       /* frequency count */
-        ush  code;       /* bit string */
-    } fc;
-    union {
-        ush  dad;        /* father node in Huffman tree */
-        ush  len;        /* length of bit string */
-    } dl;
-} FAR ct_data;
-
-#define Freq fc.freq
-#define Code fc.code
-#define Dad  dl.dad
-#define Len  dl.len
-
-typedef struct static_tree_desc_s  static_tree_desc;
-
-typedef struct tree_desc_s {
-    ct_data *dyn_tree;           /* the dynamic tree */
-    int     max_code;            /* largest code with non zero frequency */
-    static_tree_desc *stat_desc; /* the corresponding static tree */
-} FAR tree_desc;
-
-typedef ush Pos;
-typedef Pos FAR Posf;
-typedef unsigned IPos;
-
-/* A Pos is an index in the character window. We use short instead of int to
- * save space in the various tables. IPos is used only for parameter passing.
- */
-
-typedef struct internal_state {
-    z_streamp strm;      /* pointer back to this zlib stream */
-    int   status;        /* as the name implies */
-    Bytef *pending_buf;  /* output still pending */
-    ulg   pending_buf_size; /* size of pending_buf */
-    Bytef *pending_out;  /* next pending byte to output to the stream */
-    uInt   pending;      /* nb of bytes in the pending buffer */
-    int   wrap;          /* bit 0 true for zlib, bit 1 true for gzip */
-    gz_headerp  gzhead;  /* gzip header information to write */
-    uInt   gzindex;      /* where in extra, name, or comment */
-    Byte  method;        /* STORED (for zip only) or DEFLATED */
-    int   last_flush;    /* value of flush param for previous deflate call */
-
-                /* used by deflate.c: */
-
-    uInt  w_size;        /* LZ77 window size (32K by default) */
-    uInt  w_bits;        /* log2(w_size)  (8..16) */
-    uInt  w_mask;        /* w_size - 1 */
-
-    Bytef *window;
-    /* Sliding window. Input bytes are read into the second half of the window,
-     * and move to the first half later to keep a dictionary of at least wSize
-     * bytes. With this organization, matches are limited to a distance of
-     * wSize-MAX_MATCH bytes, but this ensures that IO is always
-     * performed with a length multiple of the block size. Also, it limits
-     * the window size to 64K, which is quite useful on MSDOS.
-     * To do: use the user input buffer as sliding window.
-     */
-
-    ulg window_size;
-    /* Actual size of window: 2*wSize, except when the user input buffer
-     * is directly used as sliding window.
-     */
-
-    Posf *prev;
-    /* Link to older string with same hash index. To limit the size of this
-     * array to 64K, this link is maintained only for the last 32K strings.
-     * An index in this array is thus a window index modulo 32K.
-     */
-
-    Posf *head; /* Heads of the hash chains or NIL. */
-
-    uInt  ins_h;          /* hash index of string to be inserted */
-    uInt  hash_size;      /* number of elements in hash table */
-    uInt  hash_bits;      /* log2(hash_size) */
-    uInt  hash_mask;      /* hash_size-1 */
-
-    uInt  hash_shift;
-    /* Number of bits by which ins_h must be shifted at each input
-     * step. It must be such that after MIN_MATCH steps, the oldest
-     * byte no longer takes part in the hash key, that is:
-     *   hash_shift * MIN_MATCH >= hash_bits
-     */
-
-    int block_start;
-    /* Window position at the beginning of the current output block. Gets
-     * negative when the window is moved backwards.
-     */
-
-    uInt match_length;           /* length of best match */
-    IPos prev_match;             /* previous match */
-    int match_available;         /* set if previous match exists */
-    uInt strstart;               /* start of string to insert */
-    uInt match_start;            /* start of matching string */
-    uInt lookahead;              /* number of valid bytes ahead in window */
-
-    uInt prev_length;
-    /* Length of the best match at previous step. Matches not greater than this
-     * are discarded. This is used in the lazy match evaluation.
-     */
-
-    uInt max_chain_length;
-    /* To speed up deflation, hash chains are never searched beyond this
-     * length.  A higher limit improves compression ratio but degrades the
-     * speed.
-     */
-
-    uInt max_lazy_match;
-    /* Attempt to find a better match only when the current match is strictly
-     * smaller than this value. This mechanism is used only for compression
-     * levels >= 4.
-     */
-#   define max_insert_length  max_lazy_match
-    /* Insert new strings in the hash table only if the match length is not
-     * greater than this length. This saves time but degrades compression.
-     * max_insert_length is used only for compression levels <= 3.
-     */
-
-    int level;    /* compression level (1..9) */
-    int strategy; /* favor or force Huffman coding*/
-
-    uInt good_match;
-    /* Use a faster search when the previous match is longer than this */
-
-    int nice_match; /* Stop searching when current match exceeds this */
-
-                /* used by trees.c: */
-    /* Didn't use ct_data typedef below to supress compiler warning */
-    struct ct_data_s dyn_ltree[HEAP_SIZE];   /* literal and length tree */
-    struct ct_data_s dyn_dtree[2*D_CODES+1]; /* distance tree */
-    struct ct_data_s bl_tree[2*BL_CODES+1];  /* Huffman tree for bit lengths */
-
-    struct tree_desc_s l_desc;               /* desc. for literal tree */
-    struct tree_desc_s d_desc;               /* desc. for distance tree */
-    struct tree_desc_s bl_desc;              /* desc. for bit length tree */
-
-    ush bl_count[MAX_BITS+1];
-    /* number of codes at each bit length for an optimal tree */
-
-    int heap[2*L_CODES+1];      /* heap used to build the Huffman trees */
-    int heap_len;               /* number of elements in the heap */
-    int heap_max;               /* element of largest frequency */
-    /* The sons of heap[n] are heap[2*n] and heap[2*n+1]. heap[0] is not used.
-     * The same heap array is used to build all trees.
-     */
-
-    uch depth[2*L_CODES+1];
-    /* Depth of each subtree used as tie breaker for trees of equal frequency
-     */
-
-    uchf *l_buf;          /* buffer for literals or lengths */
-
-    uInt  lit_bufsize;
-    /* Size of match buffer for literals/lengths.  There are 4 reasons for
-     * limiting lit_bufsize to 64K:
-     *   - frequencies can be kept in 16 bit counters
-     *   - if compression is not successful for the first block, all input
-     *     data is still in the window so we can still emit a stored block even
-     *     when input comes from standard input.  (This can also be done for
-     *     all blocks if lit_bufsize is not greater than 32K.)
-     *   - if compression is not successful for a file smaller than 64K, we can
-     *     even emit a stored file instead of a stored block (saving 5 bytes).
-     *     This is applicable only for zip (not gzip or zlib).
-     *   - creating new Huffman trees less frequently may not provide fast
-     *     adaptation to changes in the input data statistics. (Take for
-     *     example a binary file with poorly compressible code followed by
-     *     a highly compressible string table.) Smaller buffer sizes give
-     *     fast adaptation but have of course the overhead of transmitting
-     *     trees more frequently.
-     *   - I can't count above 4
-     */
-
-    uInt last_lit;      /* running index in l_buf */
-
-    ushf *d_buf;
-    /* Buffer for distances. To simplify the code, d_buf and l_buf have
-     * the same number of elements. To use different lengths, an extra flag
-     * array would be necessary.
-     */
-
-    ulg opt_len;        /* bit length of current block with optimal trees */
-    ulg static_len;     /* bit length of current block with static trees */
-    uInt matches;       /* number of string matches in current block */
-    int last_eob_len;   /* bit length of EOB code for last block */
-
-#ifdef DEBUG
-    ulg compressed_len; /* total bit length of compressed file mod 2^32 */
-    ulg bits_sent;      /* bit length of compressed data sent mod 2^32 */
-#endif
-
-    ush bi_buf;
-    /* Output buffer. bits are inserted starting at the bottom (least
-     * significant bits).
-     */
-    int bi_valid;
-    /* Number of valid bits in bi_buf.  All bits above the last valid bit
-     * are always zero.
-     */
-
-} FAR deflate_state;
-
-/* Output a byte on the stream.
- * IN assertion: there is enough room in pending_buf.
- */
-#define put_byte(s, c) {s->pending_buf[s->pending++] = (c);}
-
-
-#define MIN_LOOKAHEAD (MAX_MATCH+MIN_MATCH+1)
-/* Minimum amount of lookahead, except at the end of the input file.
- * See deflate.c for comments about the MIN_MATCH+1.
- */
-
-#define MAX_DIST(s)  ((s)->w_size-MIN_LOOKAHEAD)
-/* In order to simplify the code, particularly on 16 bit machines, match
- * distances are limited to MAX_DIST instead of WSIZE.
- */
-
-        /* in trees.c */
-void _tr_init         OF((deflate_state *s));
-int  _tr_tally        OF((deflate_state *s, unsigned dist, unsigned lc));
-void _tr_flush_block  OF((deflate_state *s, charf *buf, ulg stored_len,
-                          int eof));
-void _tr_align        OF((deflate_state *s));
-void _tr_stored_block OF((deflate_state *s, charf *buf, ulg stored_len,
-                          int eof));
-
-#define d_code(dist) \
-   ((dist) < 256 ? _dist_code[dist] : _dist_code[256+((dist)>>7)])
-/* Mapping from a distance to a distance code. dist is the distance - 1 and
- * must not have side effects. _dist_code[256] and _dist_code[257] are never
- * used.
- */
-
-#ifndef DEBUG
-/* Inline versions of _tr_tally for speed: */
-
-#if defined(GEN_TREES_H) || !defined(STDC)
-  extern uch _length_code[];
-  extern uch _dist_code[];
-#else
-  extern const uch _length_code[];
-  extern const uch _dist_code[];
-#endif
-
-# define _tr_tally_lit(s, c, flush) \
-  { uch cc = (c); \
-    s->d_buf[s->last_lit] = 0; \
-    s->l_buf[s->last_lit++] = cc; \
-    s->dyn_ltree[cc].Freq++; \
-    flush = (s->last_lit == s->lit_bufsize-1); \
-   }
-# define _tr_tally_dist(s, distance, length, flush) \
-  { uch len = (length); \
-    ush dist = (distance); \
-    s->d_buf[s->last_lit] = dist; \
-    s->l_buf[s->last_lit++] = len; \
-    dist--; \
-    s->dyn_ltree[_length_code[len]+LITERALS+1].Freq++; \
-    s->dyn_dtree[d_code(dist)].Freq++; \
-    flush = (s->last_lit == s->lit_bufsize-1); \
-  }
-#else
-# define _tr_tally_lit(s, c, flush) flush = _tr_tally(s, 0, c)
-# define _tr_tally_dist(s, distance, length, flush) \
-              flush = _tr_tally(s, distance, length)
-#endif
-
-#endif /* DEFLATE_H */
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/inffast.h b/surface/include/pcl/surface/3rdparty/opennurbs/inffast.h
deleted file mode 100644 (file)
index 1e88d2d..0000000
+++ /dev/null
@@ -1,11 +0,0 @@
-/* inffast.h -- header to use inffast.c
- * Copyright (C) 1995-2003 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* WARNING: this file should *not* be used by applications. It is
-   part of the implementation of the compression library and is
-   subject to change. Applications should only use zlib.h.
- */
-
-void inflate_fast OF((z_streamp strm, unsigned start));
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/inffixed.h b/surface/include/pcl/surface/3rdparty/opennurbs/inffixed.h
deleted file mode 100644 (file)
index 75ed4b5..0000000
+++ /dev/null
@@ -1,94 +0,0 @@
-    /* inffixed.h -- table for decoding fixed codes
-     * Generated automatically by makefixed().
-     */
-
-    /* WARNING: this file should *not* be used by applications. It
-       is part of the implementation of the compression library and
-       is subject to change. Applications should only use zlib.h.
-     */
-
-    static const code lenfix[512] = {
-        {96,7,0},{0,8,80},{0,8,16},{20,8,115},{18,7,31},{0,8,112},{0,8,48},
-        {0,9,192},{16,7,10},{0,8,96},{0,8,32},{0,9,160},{0,8,0},{0,8,128},
-        {0,8,64},{0,9,224},{16,7,6},{0,8,88},{0,8,24},{0,9,144},{19,7,59},
-        {0,8,120},{0,8,56},{0,9,208},{17,7,17},{0,8,104},{0,8,40},{0,9,176},
-        {0,8,8},{0,8,136},{0,8,72},{0,9,240},{16,7,4},{0,8,84},{0,8,20},
-        {21,8,227},{19,7,43},{0,8,116},{0,8,52},{0,9,200},{17,7,13},{0,8,100},
-        {0,8,36},{0,9,168},{0,8,4},{0,8,132},{0,8,68},{0,9,232},{16,7,8},
-        {0,8,92},{0,8,28},{0,9,152},{20,7,83},{0,8,124},{0,8,60},{0,9,216},
-        {18,7,23},{0,8,108},{0,8,44},{0,9,184},{0,8,12},{0,8,140},{0,8,76},
-        {0,9,248},{16,7,3},{0,8,82},{0,8,18},{21,8,163},{19,7,35},{0,8,114},
-        {0,8,50},{0,9,196},{17,7,11},{0,8,98},{0,8,34},{0,9,164},{0,8,2},
-        {0,8,130},{0,8,66},{0,9,228},{16,7,7},{0,8,90},{0,8,26},{0,9,148},
-        {20,7,67},{0,8,122},{0,8,58},{0,9,212},{18,7,19},{0,8,106},{0,8,42},
-        {0,9,180},{0,8,10},{0,8,138},{0,8,74},{0,9,244},{16,7,5},{0,8,86},
-        {0,8,22},{64,8,0},{19,7,51},{0,8,118},{0,8,54},{0,9,204},{17,7,15},
-        {0,8,102},{0,8,38},{0,9,172},{0,8,6},{0,8,134},{0,8,70},{0,9,236},
-        {16,7,9},{0,8,94},{0,8,30},{0,9,156},{20,7,99},{0,8,126},{0,8,62},
-        {0,9,220},{18,7,27},{0,8,110},{0,8,46},{0,9,188},{0,8,14},{0,8,142},
-        {0,8,78},{0,9,252},{96,7,0},{0,8,81},{0,8,17},{21,8,131},{18,7,31},
-        {0,8,113},{0,8,49},{0,9,194},{16,7,10},{0,8,97},{0,8,33},{0,9,162},
-        {0,8,1},{0,8,129},{0,8,65},{0,9,226},{16,7,6},{0,8,89},{0,8,25},
-        {0,9,146},{19,7,59},{0,8,121},{0,8,57},{0,9,210},{17,7,17},{0,8,105},
-        {0,8,41},{0,9,178},{0,8,9},{0,8,137},{0,8,73},{0,9,242},{16,7,4},
-        {0,8,85},{0,8,21},{16,8,258},{19,7,43},{0,8,117},{0,8,53},{0,9,202},
-        {17,7,13},{0,8,101},{0,8,37},{0,9,170},{0,8,5},{0,8,133},{0,8,69},
-        {0,9,234},{16,7,8},{0,8,93},{0,8,29},{0,9,154},{20,7,83},{0,8,125},
-        {0,8,61},{0,9,218},{18,7,23},{0,8,109},{0,8,45},{0,9,186},{0,8,13},
-        {0,8,141},{0,8,77},{0,9,250},{16,7,3},{0,8,83},{0,8,19},{21,8,195},
-        {19,7,35},{0,8,115},{0,8,51},{0,9,198},{17,7,11},{0,8,99},{0,8,35},
-        {0,9,166},{0,8,3},{0,8,131},{0,8,67},{0,9,230},{16,7,7},{0,8,91},
-        {0,8,27},{0,9,150},{20,7,67},{0,8,123},{0,8,59},{0,9,214},{18,7,19},
-        {0,8,107},{0,8,43},{0,9,182},{0,8,11},{0,8,139},{0,8,75},{0,9,246},
-        {16,7,5},{0,8,87},{0,8,23},{64,8,0},{19,7,51},{0,8,119},{0,8,55},
-        {0,9,206},{17,7,15},{0,8,103},{0,8,39},{0,9,174},{0,8,7},{0,8,135},
-        {0,8,71},{0,9,238},{16,7,9},{0,8,95},{0,8,31},{0,9,158},{20,7,99},
-        {0,8,127},{0,8,63},{0,9,222},{18,7,27},{0,8,111},{0,8,47},{0,9,190},
-        {0,8,15},{0,8,143},{0,8,79},{0,9,254},{96,7,0},{0,8,80},{0,8,16},
-        {20,8,115},{18,7,31},{0,8,112},{0,8,48},{0,9,193},{16,7,10},{0,8,96},
-        {0,8,32},{0,9,161},{0,8,0},{0,8,128},{0,8,64},{0,9,225},{16,7,6},
-        {0,8,88},{0,8,24},{0,9,145},{19,7,59},{0,8,120},{0,8,56},{0,9,209},
-        {17,7,17},{0,8,104},{0,8,40},{0,9,177},{0,8,8},{0,8,136},{0,8,72},
-        {0,9,241},{16,7,4},{0,8,84},{0,8,20},{21,8,227},{19,7,43},{0,8,116},
-        {0,8,52},{0,9,201},{17,7,13},{0,8,100},{0,8,36},{0,9,169},{0,8,4},
-        {0,8,132},{0,8,68},{0,9,233},{16,7,8},{0,8,92},{0,8,28},{0,9,153},
-        {20,7,83},{0,8,124},{0,8,60},{0,9,217},{18,7,23},{0,8,108},{0,8,44},
-        {0,9,185},{0,8,12},{0,8,140},{0,8,76},{0,9,249},{16,7,3},{0,8,82},
-        {0,8,18},{21,8,163},{19,7,35},{0,8,114},{0,8,50},{0,9,197},{17,7,11},
-        {0,8,98},{0,8,34},{0,9,165},{0,8,2},{0,8,130},{0,8,66},{0,9,229},
-        {16,7,7},{0,8,90},{0,8,26},{0,9,149},{20,7,67},{0,8,122},{0,8,58},
-        {0,9,213},{18,7,19},{0,8,106},{0,8,42},{0,9,181},{0,8,10},{0,8,138},
-        {0,8,74},{0,9,245},{16,7,5},{0,8,86},{0,8,22},{64,8,0},{19,7,51},
-        {0,8,118},{0,8,54},{0,9,205},{17,7,15},{0,8,102},{0,8,38},{0,9,173},
-        {0,8,6},{0,8,134},{0,8,70},{0,9,237},{16,7,9},{0,8,94},{0,8,30},
-        {0,9,157},{20,7,99},{0,8,126},{0,8,62},{0,9,221},{18,7,27},{0,8,110},
-        {0,8,46},{0,9,189},{0,8,14},{0,8,142},{0,8,78},{0,9,253},{96,7,0},
-        {0,8,81},{0,8,17},{21,8,131},{18,7,31},{0,8,113},{0,8,49},{0,9,195},
-        {16,7,10},{0,8,97},{0,8,33},{0,9,163},{0,8,1},{0,8,129},{0,8,65},
-        {0,9,227},{16,7,6},{0,8,89},{0,8,25},{0,9,147},{19,7,59},{0,8,121},
-        {0,8,57},{0,9,211},{17,7,17},{0,8,105},{0,8,41},{0,9,179},{0,8,9},
-        {0,8,137},{0,8,73},{0,9,243},{16,7,4},{0,8,85},{0,8,21},{16,8,258},
-        {19,7,43},{0,8,117},{0,8,53},{0,9,203},{17,7,13},{0,8,101},{0,8,37},
-        {0,9,171},{0,8,5},{0,8,133},{0,8,69},{0,9,235},{16,7,8},{0,8,93},
-        {0,8,29},{0,9,155},{20,7,83},{0,8,125},{0,8,61},{0,9,219},{18,7,23},
-        {0,8,109},{0,8,45},{0,9,187},{0,8,13},{0,8,141},{0,8,77},{0,9,251},
-        {16,7,3},{0,8,83},{0,8,19},{21,8,195},{19,7,35},{0,8,115},{0,8,51},
-        {0,9,199},{17,7,11},{0,8,99},{0,8,35},{0,9,167},{0,8,3},{0,8,131},
-        {0,8,67},{0,9,231},{16,7,7},{0,8,91},{0,8,27},{0,9,151},{20,7,67},
-        {0,8,123},{0,8,59},{0,9,215},{18,7,19},{0,8,107},{0,8,43},{0,9,183},
-        {0,8,11},{0,8,139},{0,8,75},{0,9,247},{16,7,5},{0,8,87},{0,8,23},
-        {64,8,0},{19,7,51},{0,8,119},{0,8,55},{0,9,207},{17,7,15},{0,8,103},
-        {0,8,39},{0,9,175},{0,8,7},{0,8,135},{0,8,71},{0,9,239},{16,7,9},
-        {0,8,95},{0,8,31},{0,9,159},{20,7,99},{0,8,127},{0,8,63},{0,9,223},
-        {18,7,27},{0,8,111},{0,8,47},{0,9,191},{0,8,15},{0,8,143},{0,8,79},
-        {0,9,255}
-    };
-
-    static const code distfix[32] = {
-        {16,5,1},{23,5,257},{19,5,17},{27,5,4097},{17,5,5},{25,5,1025},
-        {21,5,65},{29,5,16385},{16,5,3},{24,5,513},{20,5,33},{28,5,8193},
-        {18,5,9},{26,5,2049},{22,5,129},{64,5,0},{16,5,2},{23,5,385},
-        {19,5,25},{27,5,6145},{17,5,7},{25,5,1537},{21,5,97},{29,5,24577},
-        {16,5,4},{24,5,769},{20,5,49},{28,5,12289},{18,5,13},{26,5,3073},
-        {22,5,193},{64,5,0}
-    };
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/inflate.h b/surface/include/pcl/surface/3rdparty/opennurbs/inflate.h
deleted file mode 100644 (file)
index 6223638..0000000
+++ /dev/null
@@ -1,115 +0,0 @@
-/* inflate.h -- internal inflate state definition
- * Copyright (C) 1995-2004 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* WARNING: this file should *not* be used by applications. It is
-   part of the implementation of the compression library and is
-   subject to change. Applications should only use zlib.h.
- */
-
-/* define NO_GZIP when compiling if you want to disable gzip header and
-   trailer decoding by inflate().  NO_GZIP would be used to avoid linking in
-   the crc code when it is not needed.  For shared libraries, gzip decoding
-   should be left enabled. */
-#ifndef NO_GZIP
-#  define GUNZIP
-#endif
-
-/* Possible inflate modes between inflate() calls */
-typedef enum {
-    HEAD,       /* i: waiting for magic header */
-    FLAGS,      /* i: waiting for method and flags (gzip) */
-    TIME,       /* i: waiting for modification time (gzip) */
-    OS,         /* i: waiting for extra flags and operating system (gzip) */
-    EXLEN,      /* i: waiting for extra length (gzip) */
-    EXTRA,      /* i: waiting for extra bytes (gzip) */
-    NAME,       /* i: waiting for end of file name (gzip) */
-    COMMENT,    /* i: waiting for end of comment (gzip) */
-    HCRC,       /* i: waiting for header crc (gzip) */
-    DICTID,     /* i: waiting for dictionary check value */
-    DICT,       /* waiting for inflateSetDictionary() call */
-        TYPE,       /* i: waiting for type bits, including last-flag bit */
-        TYPEDO,     /* i: same, but skip check to exit inflate on new block */
-        STORED,     /* i: waiting for stored size (length and complement) */
-        COPY,       /* i/o: waiting for input or output to copy stored block */
-        TABLE,      /* i: waiting for dynamic block table lengths */
-        LENLENS,    /* i: waiting for code length code lengths */
-        CODELENS,   /* i: waiting for length/lit and distance code lengths */
-            LEN,        /* i: waiting for length/lit code */
-            LENEXT,     /* i: waiting for length extra bits */
-            DIST,       /* i: waiting for distance code */
-            DISTEXT,    /* i: waiting for distance extra bits */
-            MATCH,      /* o: waiting for output space to copy string */
-            LIT,        /* o: waiting for output space to write literal */
-    CHECK,      /* i: waiting for 32-bit check value */
-    LENGTH,     /* i: waiting for 32-bit length (gzip) */
-    DONE,       /* finished check, done -- remain here until reset */
-    BAD,        /* got a data error -- remain here until reset */
-    MEM,        /* got an inflate() memory error -- remain here until reset */
-    SYNC        /* looking for synchronization bytes to restart inflate() */
-} inflate_mode;
-
-/*
-    State transitions between above modes -
-
-    (most modes can go to the BAD or MEM mode -- not shown for clarity)
-
-    Process header:
-        HEAD -> (gzip) or (zlib)
-        (gzip) -> FLAGS -> TIME -> OS -> EXLEN -> EXTRA -> NAME
-        NAME -> COMMENT -> HCRC -> TYPE
-        (zlib) -> DICTID or TYPE
-        DICTID -> DICT -> TYPE
-    Read deflate blocks:
-            TYPE -> STORED or TABLE or LEN or CHECK
-            STORED -> COPY -> TYPE
-            TABLE -> LENLENS -> CODELENS -> LEN
-    Read deflate codes:
-                LEN -> LENEXT or LIT or TYPE
-                LENEXT -> DIST -> DISTEXT -> MATCH -> LEN
-                LIT -> LEN
-    Process trailer:
-        CHECK -> LENGTH -> DONE
- */
-
-/* state maintained between inflate() calls.  Approximately 7K bytes. */
-struct inflate_state {
-    inflate_mode mode;          /* current inflate mode */
-    int last;                   /* true if processing last block */
-    int wrap;                   /* bit 0 true for zlib, bit 1 true for gzip */
-    int havedict;               /* true if dictionary provided */
-    int flags;                  /* gzip header method and flags (0 if zlib) */
-    unsigned dmax;              /* zlib header max distance (INFLATE_STRICT) */
-    unsigned int check;        /* protected copy of check value */
-    unsigned int total;        /* protected copy of output count */
-    gz_headerp head;            /* where to save gzip header information */
-        /* sliding window */
-    unsigned wbits;             /* log base 2 of requested window size */
-    unsigned wsize;             /* window size or zero if not using window */
-    unsigned whave;             /* valid bytes in the window */
-    unsigned write;             /* window write index */
-    unsigned char FAR *window;  /* allocated sliding window, if needed */
-        /* bit accumulator */
-    unsigned int hold;         /* input bit accumulator */
-    unsigned bits;              /* number of bits in "in" */
-        /* for string and stored block copying */
-    unsigned length;            /* literal or length of data to copy */
-    unsigned offset;            /* distance back to copy string from */
-        /* for table and code decoding */
-    unsigned extra;             /* extra bits needed */
-        /* fixed and dynamic code tables */
-    code const FAR *lencode;    /* starting table for length/literal codes */
-    code const FAR *distcode;   /* starting table for distance codes */
-    unsigned lenbits;           /* index bits for lencode */
-    unsigned distbits;          /* index bits for distcode */
-        /* dynamic table building */
-    unsigned ncode;             /* number of code length code lengths */
-    unsigned nlen;              /* number of length code lengths */
-    unsigned ndist;             /* number of distance code lengths */
-    unsigned have;              /* number of code lengths in lens[] */
-    code FAR *next;             /* next available space in codes[] */
-    unsigned short lens[320];   /* temporary storage for code lengths */
-    unsigned short work[288];   /* work area for code table building */
-    code codes[ENOUGH];         /* space for code tables */
-};
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/inftrees.h b/surface/include/pcl/surface/3rdparty/opennurbs/inftrees.h
deleted file mode 100644 (file)
index b1104c8..0000000
+++ /dev/null
@@ -1,55 +0,0 @@
-/* inftrees.h -- header to use inftrees.c
- * Copyright (C) 1995-2005 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* WARNING: this file should *not* be used by applications. It is
-   part of the implementation of the compression library and is
-   subject to change. Applications should only use zlib.h.
- */
-
-/* Structure for decoding tables.  Each entry provides either the
-   information needed to do the operation requested by the code that
-   indexed that table entry, or it provides a pointer to another
-   table that indexes more bits of the code.  op indicates whether
-   the entry is a pointer to another table, a literal, a length or
-   distance, an end-of-block, or an invalid code.  For a table
-   pointer, the low four bits of op is the number of index bits of
-   that table.  For a length or distance, the low four bits of op
-   is the number of extra bits to get after the code.  bits is
-   the number of bits in this code or part of the code to drop off
-   of the bit buffer.  val is the actual byte to output in the case
-   of a literal, the base length or distance, or the offset from
-   the current table to the next table.  Each entry is four bytes. */
-typedef struct {
-    unsigned char op;           /* operation, extra bits, table bits */
-    unsigned char bits;         /* bits in this part of the code */
-    unsigned short val;         /* offset in table or code value */
-} code;
-
-/* op values as set by inflate_table():
-    00000000 - literal
-    0000tttt - table link, tttt != 0 is the number of table index bits
-    0001eeee - length or distance, eeee is the number of extra bits
-    01100000 - end of block
-    01000000 - invalid code
- */
-
-/* Maximum size of dynamic tree.  The maximum found in a long but non-
-   exhaustive search was 1444 code structures (852 for length/literals
-   and 592 for distances, the latter actually the result of an
-   exhaustive search).  The true maximum is not known, but the value
-   below is more than safe. */
-#define ENOUGH 2048
-#define MAXD 592
-
-/* Type of code to build for inftable() */
-typedef enum {
-    CODES,
-    LENS,
-    DISTS
-} codetype;
-
-extern int inflate_table OF((codetype type, unsigned short FAR *lens,
-                             unsigned codes, code FAR * FAR *table,
-                             unsigned FAR *bits, unsigned short FAR *work));
index 441ad59d3a06ce04b7fe10467ab97b2a76468b4a..533285a80a6f7f992bd77c763e2c42dbd15ac30d 100644 (file)
@@ -842,7 +842,7 @@ int ON_ClassArray<T>::NewCapacity() const
   // Reserve() size and then wasting gigabytes of memory.
 
   // cap_size = 128 MB on 32-bit os, 256 MB on 64 bit os
-  const std::size_t cap_size = 32*sizeof(void*)*1024*1024;
+  constexpr std::size_t cap_size = 32*sizeof(void*)*1024*1024;
   if (m_count*sizeof(T) <= cap_size || m_count < 8)
     return ((m_count <= 2) ? 4 : 2*m_count);
 
index 384e7bac83e4ed039eee673e2efe315a6fa82089..cde079401211664871b66960e31b58bf3d1b5f74 100644 (file)
 #if defined(_M_X64) && defined(WIN32) && defined(WIN64)
 // 23 August 2007 Dale Lear
 
-#if defined(_INC_WINDOWS)
+//#if defined(_INC_WINDOWS)
 // The user has included Microsoft's windows.h before opennurbs.h,
 // and windows.h has nested includes that unconditionally define WIN32.
 // Just undo the damage here or everybody that includes opennurbs.h after
 // windows.h has to fight with this Microsoft bug.
 #undef WIN32
-#else
-#error do not define WIN32 for x64 builds
-#endif
+//#else
+//#error do not define WIN32 for x64 builds
+//#endif
 
 // NOTE _WIN32 is defined for any type of Windows build
 #endif
index 12787e1201fb8d0813cbd1583e0fb2b4037ea2cd..7622b3a6a7d6704f8d27f38c41f53207d1274339 100644 (file)
 // and statically link with the zlib library. All the necessary
 // header files are included by opennurbs.h.
 
+// PCL can use an external zlib.
+
+#include <pcl/pcl_config.h>
+
+#if defined(HAVE_ZLIB)
+
+#define z_deflate deflate
+#define z_inflate inflate
+#define z_Bytef Bytef
+
+#define zcalloc pcl_zcalloc
+#define zcfree pcl_zcfree
+
+#include <zlib.h>
+
+#else
 
 #if !defined(Z_PREFIX)
 /* decorates zlib functions with a "z_" prefix to prevent symbol collision. */
@@ -41,6 +57,8 @@
 
 #include "zlib.h"
 
+#endif // HAVE_ZLIB
+
 ON_BEGIN_EXTERNC
 voidpf zcalloc (voidpf, unsigned, unsigned);
 void  zcfree (voidpf, voidpf);
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/trees.h b/surface/include/pcl/surface/3rdparty/opennurbs/trees.h
deleted file mode 100644 (file)
index 72facf9..0000000
+++ /dev/null
@@ -1,128 +0,0 @@
-/* header created automatically with -DGEN_TREES_H */
-
-local const ct_data static_ltree[L_CODES+2] = {
-{{ 12},{  8}}, {{140},{  8}}, {{ 76},{  8}}, {{204},{  8}}, {{ 44},{  8}},
-{{172},{  8}}, {{108},{  8}}, {{236},{  8}}, {{ 28},{  8}}, {{156},{  8}},
-{{ 92},{  8}}, {{220},{  8}}, {{ 60},{  8}}, {{188},{  8}}, {{124},{  8}},
-{{252},{  8}}, {{  2},{  8}}, {{130},{  8}}, {{ 66},{  8}}, {{194},{  8}},
-{{ 34},{  8}}, {{162},{  8}}, {{ 98},{  8}}, {{226},{  8}}, {{ 18},{  8}},
-{{146},{  8}}, {{ 82},{  8}}, {{210},{  8}}, {{ 50},{  8}}, {{178},{  8}},
-{{114},{  8}}, {{242},{  8}}, {{ 10},{  8}}, {{138},{  8}}, {{ 74},{  8}},
-{{202},{  8}}, {{ 42},{  8}}, {{170},{  8}}, {{106},{  8}}, {{234},{  8}},
-{{ 26},{  8}}, {{154},{  8}}, {{ 90},{  8}}, {{218},{  8}}, {{ 58},{  8}},
-{{186},{  8}}, {{122},{  8}}, {{250},{  8}}, {{  6},{  8}}, {{134},{  8}},
-{{ 70},{  8}}, {{198},{  8}}, {{ 38},{  8}}, {{166},{  8}}, {{102},{  8}},
-{{230},{  8}}, {{ 22},{  8}}, {{150},{  8}}, {{ 86},{  8}}, {{214},{  8}},
-{{ 54},{  8}}, {{182},{  8}}, {{118},{  8}}, {{246},{  8}}, {{ 14},{  8}},
-{{142},{  8}}, {{ 78},{  8}}, {{206},{  8}}, {{ 46},{  8}}, {{174},{  8}},
-{{110},{  8}}, {{238},{  8}}, {{ 30},{  8}}, {{158},{  8}}, {{ 94},{  8}},
-{{222},{  8}}, {{ 62},{  8}}, {{190},{  8}}, {{126},{  8}}, {{254},{  8}},
-{{  1},{  8}}, {{129},{  8}}, {{ 65},{  8}}, {{193},{  8}}, {{ 33},{  8}},
-{{161},{  8}}, {{ 97},{  8}}, {{225},{  8}}, {{ 17},{  8}}, {{145},{  8}},
-{{ 81},{  8}}, {{209},{  8}}, {{ 49},{  8}}, {{177},{  8}}, {{113},{  8}},
-{{241},{  8}}, {{  9},{  8}}, {{137},{  8}}, {{ 73},{  8}}, {{201},{  8}},
-{{ 41},{  8}}, {{169},{  8}}, {{105},{  8}}, {{233},{  8}}, {{ 25},{  8}},
-{{153},{  8}}, {{ 89},{  8}}, {{217},{  8}}, {{ 57},{  8}}, {{185},{  8}},
-{{121},{  8}}, {{249},{  8}}, {{  5},{  8}}, {{133},{  8}}, {{ 69},{  8}},
-{{197},{  8}}, {{ 37},{  8}}, {{165},{  8}}, {{101},{  8}}, {{229},{  8}},
-{{ 21},{  8}}, {{149},{  8}}, {{ 85},{  8}}, {{213},{  8}}, {{ 53},{  8}},
-{{181},{  8}}, {{117},{  8}}, {{245},{  8}}, {{ 13},{  8}}, {{141},{  8}},
-{{ 77},{  8}}, {{205},{  8}}, {{ 45},{  8}}, {{173},{  8}}, {{109},{  8}},
-{{237},{  8}}, {{ 29},{  8}}, {{157},{  8}}, {{ 93},{  8}}, {{221},{  8}},
-{{ 61},{  8}}, {{189},{  8}}, {{125},{  8}}, {{253},{  8}}, {{ 19},{  9}},
-{{275},{  9}}, {{147},{  9}}, {{403},{  9}}, {{ 83},{  9}}, {{339},{  9}},
-{{211},{  9}}, {{467},{  9}}, {{ 51},{  9}}, {{307},{  9}}, {{179},{  9}},
-{{435},{  9}}, {{115},{  9}}, {{371},{  9}}, {{243},{  9}}, {{499},{  9}},
-{{ 11},{  9}}, {{267},{  9}}, {{139},{  9}}, {{395},{  9}}, {{ 75},{  9}},
-{{331},{  9}}, {{203},{  9}}, {{459},{  9}}, {{ 43},{  9}}, {{299},{  9}},
-{{171},{  9}}, {{427},{  9}}, {{107},{  9}}, {{363},{  9}}, {{235},{  9}},
-{{491},{  9}}, {{ 27},{  9}}, {{283},{  9}}, {{155},{  9}}, {{411},{  9}},
-{{ 91},{  9}}, {{347},{  9}}, {{219},{  9}}, {{475},{  9}}, {{ 59},{  9}},
-{{315},{  9}}, {{187},{  9}}, {{443},{  9}}, {{123},{  9}}, {{379},{  9}},
-{{251},{  9}}, {{507},{  9}}, {{  7},{  9}}, {{263},{  9}}, {{135},{  9}},
-{{391},{  9}}, {{ 71},{  9}}, {{327},{  9}}, {{199},{  9}}, {{455},{  9}},
-{{ 39},{  9}}, {{295},{  9}}, {{167},{  9}}, {{423},{  9}}, {{103},{  9}},
-{{359},{  9}}, {{231},{  9}}, {{487},{  9}}, {{ 23},{  9}}, {{279},{  9}},
-{{151},{  9}}, {{407},{  9}}, {{ 87},{  9}}, {{343},{  9}}, {{215},{  9}},
-{{471},{  9}}, {{ 55},{  9}}, {{311},{  9}}, {{183},{  9}}, {{439},{  9}},
-{{119},{  9}}, {{375},{  9}}, {{247},{  9}}, {{503},{  9}}, {{ 15},{  9}},
-{{271},{  9}}, {{143},{  9}}, {{399},{  9}}, {{ 79},{  9}}, {{335},{  9}},
-{{207},{  9}}, {{463},{  9}}, {{ 47},{  9}}, {{303},{  9}}, {{175},{  9}},
-{{431},{  9}}, {{111},{  9}}, {{367},{  9}}, {{239},{  9}}, {{495},{  9}},
-{{ 31},{  9}}, {{287},{  9}}, {{159},{  9}}, {{415},{  9}}, {{ 95},{  9}},
-{{351},{  9}}, {{223},{  9}}, {{479},{  9}}, {{ 63},{  9}}, {{319},{  9}},
-{{191},{  9}}, {{447},{  9}}, {{127},{  9}}, {{383},{  9}}, {{255},{  9}},
-{{511},{  9}}, {{  0},{  7}}, {{ 64},{  7}}, {{ 32},{  7}}, {{ 96},{  7}},
-{{ 16},{  7}}, {{ 80},{  7}}, {{ 48},{  7}}, {{112},{  7}}, {{  8},{  7}},
-{{ 72},{  7}}, {{ 40},{  7}}, {{104},{  7}}, {{ 24},{  7}}, {{ 88},{  7}},
-{{ 56},{  7}}, {{120},{  7}}, {{  4},{  7}}, {{ 68},{  7}}, {{ 36},{  7}},
-{{100},{  7}}, {{ 20},{  7}}, {{ 84},{  7}}, {{ 52},{  7}}, {{116},{  7}},
-{{  3},{  8}}, {{131},{  8}}, {{ 67},{  8}}, {{195},{  8}}, {{ 35},{  8}},
-{{163},{  8}}, {{ 99},{  8}}, {{227},{  8}}
-};
-
-local const ct_data static_dtree[D_CODES] = {
-{{ 0},{ 5}}, {{16},{ 5}}, {{ 8},{ 5}}, {{24},{ 5}}, {{ 4},{ 5}},
-{{20},{ 5}}, {{12},{ 5}}, {{28},{ 5}}, {{ 2},{ 5}}, {{18},{ 5}},
-{{10},{ 5}}, {{26},{ 5}}, {{ 6},{ 5}}, {{22},{ 5}}, {{14},{ 5}},
-{{30},{ 5}}, {{ 1},{ 5}}, {{17},{ 5}}, {{ 9},{ 5}}, {{25},{ 5}},
-{{ 5},{ 5}}, {{21},{ 5}}, {{13},{ 5}}, {{29},{ 5}}, {{ 3},{ 5}},
-{{19},{ 5}}, {{11},{ 5}}, {{27},{ 5}}, {{ 7},{ 5}}, {{23},{ 5}}
-};
-
-const uch _dist_code[DIST_CODE_LEN] = {
- 0,  1,  2,  3,  4,  4,  5,  5,  6,  6,  6,  6,  7,  7,  7,  7,  8,  8,  8,  8,
- 8,  8,  8,  8,  9,  9,  9,  9,  9,  9,  9,  9, 10, 10, 10, 10, 10, 10, 10, 10,
-10, 10, 10, 10, 10, 10, 10, 10, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11,
-11, 11, 11, 11, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12,
-12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 13,
-13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-13, 13, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 15,
-15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,  0,  0, 16, 17,
-18, 18, 19, 19, 20, 20, 20, 20, 21, 21, 21, 21, 22, 22, 22, 22, 22, 22, 22, 22,
-23, 23, 23, 23, 23, 23, 23, 23, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24,
-24, 24, 24, 24, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25,
-26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26,
-26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 27, 27, 27, 27, 27, 27, 27, 27,
-27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27,
-27, 27, 27, 27, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28,
-28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28,
-28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28,
-28, 28, 28, 28, 28, 28, 28, 28, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29,
-29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29,
-29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29,
-29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29
-};
-
-const uch _length_code[MAX_MATCH-MIN_MATCH+1]= {
- 0,  1,  2,  3,  4,  5,  6,  7,  8,  8,  9,  9, 10, 10, 11, 11, 12, 12, 12, 12,
-13, 13, 13, 13, 14, 14, 14, 14, 15, 15, 15, 15, 16, 16, 16, 16, 16, 16, 16, 16,
-17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 19, 19, 19, 19,
-19, 19, 19, 19, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20,
-21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 22, 22, 22, 22,
-22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 23, 23, 23, 23, 23, 23, 23, 23,
-23, 23, 23, 23, 23, 23, 23, 23, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24,
-24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24,
-25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25,
-25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 26, 26, 26, 26, 26, 26, 26, 26,
-26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26,
-26, 26, 26, 26, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27,
-27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 28
-};
-
-local const int base_length[LENGTH_CODES] = {
-0, 1, 2, 3, 4, 5, 6, 7, 8, 10, 12, 14, 16, 20, 24, 28, 32, 40, 48, 56,
-64, 80, 96, 112, 128, 160, 192, 224, 0
-};
-
-local const int base_dist[D_CODES] = {
-    0,     1,     2,     3,     4,     6,     8,    12,    16,    24,
-   32,    48,    64,    96,   128,   192,   256,   384,   512,   768,
- 1024,  1536,  2048,  3072,  4096,  6144,  8192, 12288, 16384, 24576
-};
-
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/zconf.h b/surface/include/pcl/surface/3rdparty/opennurbs/zconf.h
deleted file mode 100644 (file)
index 4eea79b..0000000
+++ /dev/null
@@ -1,362 +0,0 @@
-/* zconf.h -- configuration of the zlib compression library
- * Copyright (C) 1995-2005 Jean-loup Gailly.
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* @(#) $Id$ */
-
-#ifndef ZCONF_H
-#define ZCONF_H
-
-
-/* BEGIN -- OpenNURBS Modification 
-//          OpenNURBS requires zlib to be compiled
-//          with -DZ_PREFIX and -DMY_ZCALLOC.  While
-//          this was done in the makefiles shipped
-//          with OpenNURBS, it still generated too
-//          many technical support questions.  So,
-//          we've modified the zlib source in this
-//          one spot and added these preprocessor
-//          defines.
-*/
-#if !defined(Z_PREFIX)
-/* decorates zlib functions with a "z_" prefix to prevent symbol collision. */
-#define Z_PREFIX
-#endif
-
-#if !defined(MY_ZCALLOC)
-/* have zlib use oncalloc() and onfree() for memory managment*/
-#define MY_ZCALLOC
-#endif
-/* END - OpenNURBS Modification */
-
-
-/*
- * If you *really* need a unique prefix for all types and library functions,
- * compile with -DZ_PREFIX. The "standard" zlib should be compiled without it.
- */
-#ifdef Z_PREFIX
-#  define deflateInit_          z_deflateInit_
-#  define deflate               z_deflate
-#  define deflateEnd            z_deflateEnd
-#  define inflateInit_          z_inflateInit_
-#  define inflate               z_inflate
-#  define inflateEnd            z_inflateEnd
-#  define deflateInit2_         z_deflateInit2_
-#  define deflateSetDictionary  z_deflateSetDictionary
-#  define deflateCopy           z_deflateCopy
-#  define deflateReset          z_deflateReset
-#  define deflateParams         z_deflateParams
-#  define deflateBound          z_deflateBound
-#  define deflatePrime          z_deflatePrime
-#  define inflateInit2_         z_inflateInit2_
-#  define inflateSetDictionary  z_inflateSetDictionary
-#  define inflateSync           z_inflateSync
-#  define inflateSyncPoint      z_inflateSyncPoint
-#  define inflateCopy           z_inflateCopy
-#  define inflateReset          z_inflateReset
-#  define inflateBack           z_inflateBack
-#  define inflateBackEnd        z_inflateBackEnd
-#  define compress              z_compress
-#  define compress2             z_compress2
-#  define compressBound         z_compressBound
-#  define uncompress            z_uncompress
-#  define adler32               z_adler32
-#  define crc32                 z_crc32
-#  define get_crc_table         z_get_crc_table
-#  define zError                z_zError
-
-#  define alloc_func            z_alloc_func
-#  define free_func             z_free_func
-#  define in_func               z_in_func
-#  define out_func              z_out_func
-#  define Byte                  z_Byte
-#  define uInt                  z_uInt
-#  define uLong                 z_uLong
-#  define Bytef                 z_Bytef
-#  define charf                 z_charf
-#  define intf                  z_intf
-#  define uIntf                 z_uIntf
-#  define uLongf                z_uLongf
-#  define voidpf                z_voidpf
-#  define voidp                 z_voidp
-#endif
-
-#if defined(__MSDOS__) && !defined(MSDOS)
-#  define MSDOS
-#endif
-#if (defined(OS_2) || defined(__OS2__)) && !defined(OS2)
-#  define OS2
-#endif
-#if defined(_WINDOWS) && !defined(WINDOWS)
-#  define WINDOWS
-#endif
-#if defined(_WIN32) || defined(_WIN32_WCE) || defined(__WIN32__)
-#if !defined(WIN64)
-#  ifndef WIN32
-#    define WIN32
-#  endif
-#endif
-#endif
-#if defined(_WIN64) || defined(_WIN64_WCE) || defined(__WIN64__)
-#  ifndef WIN64
-#    define WIN64
-#  endif
-#endif
-#if (defined(MSDOS) || defined(OS2) || defined(WINDOWS)) && !defined(WIN32) && !defined(WIN64)
-#  if !defined(__GNUC__) && !defined(__FLAT__) && !defined(__386__)
-#    ifndef SYS16BIT
-#      define SYS16BIT
-#    endif
-#  endif
-#endif
-
-/*
- * Compile with -DMAXSEG_64K if the alloc function cannot allocate more
- * than 64k bytes at a time (needed on systems with 16-bit int).
- */
-#ifdef SYS16BIT
-#  define MAXSEG_64K
-#endif
-#ifdef MSDOS
-#  define UNALIGNED_OK
-#endif
-
-#ifdef __STDC_VERSION__
-#  ifndef STDC
-#    define STDC
-#  endif
-#  if __STDC_VERSION__ >= 199901L
-#    ifndef STDC99
-#      define STDC99
-#    endif
-#  endif
-#endif
-#if !defined(STDC) && (defined(__STDC__) || defined(__cplusplus))
-#  define STDC
-#endif
-#if !defined(STDC) && (defined(__GNUC__) || defined(__BORLANDC__))
-#  define STDC
-#endif
-#if !defined(STDC) && (defined(MSDOS) || defined(WINDOWS) || defined(WIN32) || defined(WIN64))
-#  define STDC
-#endif
-#if !defined(STDC) && (defined(OS2) || defined(__HOS_AIX__))
-#  define STDC
-#endif
-
-#if defined(__OS400__) && !defined(STDC)    /* iSeries (formerly AS/400). */
-#  define STDC
-#endif
-
-#ifndef STDC
-#  ifndef const /* cannot use !defined(STDC) && !defined(const) on Mac */
-#    define const       /* note: need a more gentle solution here */
-#  endif
-#endif
-
-/* Some Mac compilers merge all .h files incorrectly: */
-#if defined(__MWERKS__)||defined(applec)||defined(THINK_C)||defined(__SC__)
-#  define NO_DUMMY_DECL
-#endif
-
-/* Maximum value for memLevel in deflateInit2 */
-#ifndef MAX_MEM_LEVEL
-#  ifdef MAXSEG_64K
-#    define MAX_MEM_LEVEL 8
-#  else
-#    define MAX_MEM_LEVEL 9
-#  endif
-#endif
-
-/* Maximum value for windowBits in deflateInit2 and inflateInit2.
- * WARNING: reducing MAX_WBITS makes minigzip unable to extract .gz files
- * created by gzip. (Files created by minigzip can still be extracted by
- * gzip.)
- */
-#ifndef MAX_WBITS
-#  define MAX_WBITS   15 /* 32K LZ77 window */
-#endif
-
-/* The memory requirements for deflate are (in bytes):
-            (1 << (windowBits+2)) +  (1 << (memLevel+9))
- that is: 128K for windowBits=15  +  128K for memLevel = 8  (default values)
- plus a few kilobytes for small objects. For example, if you want to reduce
- the default memory requirements from 256K to 128K, compile with
-     make CFLAGS="-O -DMAX_WBITS=14 -DMAX_MEM_LEVEL=7"
- Of course this will generally degrade compression (there's no free lunch).
-
-   The memory requirements for inflate are (in bytes) 1 << windowBits
- that is, 32K for windowBits=15 (default value) plus a few kilobytes
- for small objects.
-*/
-
-                        /* Type declarations */
-
-#ifndef OF /* function prototypes */
-#  ifdef STDC
-#    define OF(args)  args
-#  else
-#    define OF(args)  ()
-#  endif
-#endif
-
-/* The following definitions for FAR are needed only for MSDOS mixed
- * model programming (small or medium model with some far allocations).
- * This was tested only with MSC; for other MSDOS compilers you may have
- * to define NO_MEMCPY in zutil.h.  If you don't need the mixed model,
- * just define FAR to be empty.
- */
-#ifdef SYS16BIT
-#  if defined(M_I86SM) || defined(M_I86MM)
-     /* MSC small or medium model */
-#    define SMALL_MEDIUM
-#    ifdef _MSC_VER
-#      define FAR _far
-#    else
-#      define FAR far
-#    endif
-#  endif
-#  if (defined(__SMALL__) || defined(__MEDIUM__))
-     /* Turbo C small or medium model */
-#    define SMALL_MEDIUM
-#    ifdef __BORLANDC__
-#      define FAR _far
-#    else
-#      define FAR far
-#    endif
-#  endif
-#endif
-
-#if defined(WINDOWS) || defined(WIN32) || defined(WIN64)
-   /* If building or using zlib as a DLL, define ZLIB_DLL.
-    * This is not mandatory, but it offers a little performance increase.
-    */
-#  ifdef ZLIB_DLL
-#    if defined(WIN32) && (!defined(__BORLANDC__) || (__BORLANDC__ >= 0x500))
-#      ifdef ZLIB_INTERNAL
-#        define ZEXTERN extern __declspec(dllexport)
-#      else
-#        define ZEXTERN extern __declspec(dllimport)
-#      endif
-#    endif
-#  endif  /* ZLIB_DLL */
-   /* If building or using zlib with the WINAPI/WINAPIV calling convention,
-    * define ZLIB_WINAPI.
-    * Caution: the standard ZLIB1.DLL is NOT compiled using ZLIB_WINAPI.
-    */
-#  ifdef ZLIB_WINAPI
-#    ifdef FAR
-#      undef FAR
-#    endif
-#    include <windows.h>
-     /* No need for _export, use ZLIB.DEF instead. */
-     /* For complete Windows compatibility, use WINAPI, not __stdcall. */
-#    define ZEXPORT WINAPI
-#    ifdef WIN32
-#      define ZEXPORTVA WINAPIV
-#    else
-#      define ZEXPORTVA FAR CDECL
-#    endif
-#  endif
-#endif
-
-#if defined (__BEOS__)
-#  ifdef ZLIB_DLL
-#    ifdef ZLIB_INTERNAL
-#      define ZEXPORT   __declspec(dllexport)
-#      define ZEXPORTVA __declspec(dllexport)
-#    else
-#      define ZEXPORT   __declspec(dllimport)
-#      define ZEXPORTVA __declspec(dllimport)
-#    endif
-#  endif
-#endif
-
-#ifndef ZEXTERN
-#  define ZEXTERN extern
-#endif
-#ifndef ZEXPORT
-#  define ZEXPORT
-#endif
-#ifndef ZEXPORTVA
-#  define ZEXPORTVA
-#endif
-
-#ifndef FAR
-#  define FAR
-#endif
-
-#if !defined(__MACTYPES__)
-typedef unsigned char  Byte;  /* 8 bits */
-#endif
-typedef unsigned int   uInt;  /* 16 bits or more */
-typedef unsigned int  uLong; /* 32 bits or more */
-
-#ifdef SMALL_MEDIUM
-   /* Borland C/C++ and some old MSC versions ignore FAR inside typedef */
-#  define Bytef Byte FAR
-#else
-   typedef Byte  FAR Bytef;
-#endif
-typedef char  FAR charf;
-typedef int   FAR intf;
-typedef uInt  FAR uIntf;
-typedef uLong FAR uLongf;
-
-#ifdef STDC
-   typedef void const *voidpc;
-   typedef void FAR   *voidpf;
-   typedef void       *voidp;
-#else
-   typedef Byte const *voidpc;
-   typedef Byte FAR   *voidpf;
-   typedef Byte       *voidp;
-#endif
-
-#if 0           /* HAVE_UNISTD_H -- this line is updated by ./configure */
-#  include <sys/types.h> /* for off_t */
-#  include <unistd.h>    /* for SEEK_* and off_t */
-#  ifdef VMS
-#    include <unixio.h>   /* for off_t */
-#  endif
-#  define z_off_t off_t
-#endif
-#ifndef SEEK_SET
-#  define SEEK_SET        0       /* Seek from beginning of file.  */
-#  define SEEK_CUR        1       /* Seek from current position.  */
-#  define SEEK_END        2       /* Set file pointer to EOF plus "offset" */
-#endif
-#ifndef z_off_t
-#  define z_off_t int
-#endif
-
-#if defined(__OS400__)
-#  define NO_vsnprintf
-#endif
-
-#if defined(__MVS__)
-#  define NO_vsnprintf
-#  ifdef FAR
-#    undef FAR
-#  endif
-#endif
-
-/* MVS linker does not support external names larger than 8 bytes */
-#if defined(__MVS__)
-#   pragma map(deflateInit_,"DEIN")
-#   pragma map(deflateInit2_,"DEIN2")
-#   pragma map(deflateEnd,"DEEND")
-#   pragma map(deflateBound,"DEBND")
-#   pragma map(inflateInit_,"ININ")
-#   pragma map(inflateInit2_,"ININ2")
-#   pragma map(inflateEnd,"INEND")
-#   pragma map(inflateSync,"INSY")
-#   pragma map(inflateSetDictionary,"INSEDI")
-#   pragma map(compressBound,"CMBND")
-#   pragma map(inflate_table,"INTABL")
-#   pragma map(inflate_fast,"INFA")
-#   pragma map(inflate_copyright,"INCOPY")
-#endif
-
-#endif /* ZCONF_H */
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/zlib.h b/surface/include/pcl/surface/3rdparty/opennurbs/zlib.h
deleted file mode 100644 (file)
index 0228179..0000000
+++ /dev/null
@@ -1,1357 +0,0 @@
-/* zlib.h -- interface of the 'zlib' general purpose compression library
-  version 1.2.3, July 18th, 2005
-
-  Copyright (C) 1995-2005 Jean-loup Gailly and Mark Adler
-
-  This software is provided 'as-is', without any express or implied
-  warranty.  In no event will the authors be held liable for any damages
-  arising from the use of this software.
-
-  Permission is granted to anyone to use this software for any purpose,
-  including commercial applications, and to alter it and redistribute it
-  freely, subject to the following restrictions:
-
-  1. The origin of this software must not be misrepresented; you must not
-     claim that you wrote the original software. If you use this software
-     in a product, an acknowledgment in the product documentation would be
-     appreciated but is not required.
-  2. Altered source versions must be plainly marked as such, and must not be
-     misrepresented as being the original software.
-  3. This notice may not be removed or altered from any source distribution.
-
-  Jean-loup Gailly        Mark Adler
-  jloup@gzip.org          madler@alumni.caltech.edu
-
-
-  The data format used by the zlib library is described by RFCs (Request for
-  Comments) 1950 to 1952 in the files http://www.ietf.org/rfc/rfc1950.txt
-  (zlib format), rfc1951.txt (deflate format) and rfc1952.txt (gzip format).
-*/
-
-#ifndef ZLIB_H
-#define ZLIB_H
-
-#include "zconf.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#define ZLIB_VERSION "1.2.3"
-#define ZLIB_VERNUM 0x1230
-
-/*
-     The 'zlib' compression library provides in-memory compression and
-  decompression functions, including integrity checks of the uncompressed
-  data.  This version of the library supports only one compression method
-  (deflation) but other algorithms will be added later and will have the same
-  stream interface.
-
-     Compression can be done in a single step if the buffers are large
-  enough (for example if an input file is mmap'ed), or can be done by
-  repeated calls of the compression function.  In the latter case, the
-  application must provide more input and/or consume the output
-  (providing more output space) before each call.
-
-     The compressed data format used by default by the in-memory functions is
-  the zlib format, which is a zlib wrapper documented in RFC 1950, wrapped
-  around a deflate stream, which is itself documented in RFC 1951.
-
-     The library also supports reading and writing files in gzip (.gz) format
-  with an interface similar to that of stdio using the functions that start
-  with "gz".  The gzip format is different from the zlib format.  gzip is a
-  gzip wrapper, documented in RFC 1952, wrapped around a deflate stream.
-
-     This library can optionally read and write gzip streams in memory as well.
-
-     The zlib format was designed to be compact and fast for use in memory
-  and on communications channels.  The gzip format was designed for single-
-  file compression on file systems, has a larger header than zlib to maintain
-  directory information, and uses a different, slower check method than zlib.
-
-     The library does not install any signal handler. The decoder checks
-  the consistency of the compressed data, so the library should never
-  crash even in case of corrupted input.
-*/
-
-typedef voidpf (*alloc_func) OF((voidpf opaque, uInt items, uInt size));
-typedef void   (*free_func)  OF((voidpf opaque, voidpf address));
-
-struct internal_state;
-
-typedef struct z_stream_s {
-    Bytef    *next_in;  /* next input byte */
-    uInt     avail_in;  /* number of bytes available at next_in */
-    uLong    total_in;  /* total nb of input bytes read so far */
-
-    Bytef    *next_out; /* next output byte should be put there */
-    uInt     avail_out; /* remaining free space at next_out */
-    uLong    total_out; /* total nb of bytes output so far */
-
-    char     *msg;      /* last error message, NULL if no error */
-    struct internal_state FAR *state; /* not visible by applications */
-
-    alloc_func zalloc;  /* used to allocate the internal state */
-    free_func  zfree;   /* used to free the internal state */
-    voidpf     opaque;  /* private data object passed to zalloc and zfree */
-
-    int     data_type;  /* best guess about the data type: binary or text */
-    uLong   adler;      /* adler32 value of the uncompressed data */
-    uLong   reserved;   /* reserved for future use */
-} z_stream;
-
-typedef z_stream FAR *z_streamp;
-
-/*
-     gzip header information passed to and from zlib routines.  See RFC 1952
-  for more details on the meanings of these fields.
-*/
-typedef struct gz_header_s {
-    int     text;       /* true if compressed data believed to be text */
-    uLong   time;       /* modification time */
-    int     xflags;     /* extra flags (not used when writing a gzip file) */
-    int     os;         /* operating system */
-    Bytef   *extra;     /* pointer to extra field or Z_NULL if none */
-    uInt    extra_len;  /* extra field length (valid if extra != Z_NULL) */
-    uInt    extra_max;  /* space at extra (only when reading header) */
-    Bytef   *name;      /* pointer to zero-terminated file name or Z_NULL */
-    uInt    name_max;   /* space at name (only when reading header) */
-    Bytef   *comment;   /* pointer to zero-terminated comment or Z_NULL */
-    uInt    comm_max;   /* space at comment (only when reading header) */
-    int     hcrc;       /* true if there was or will be a header crc */
-    int     done;       /* true when done reading gzip header (not used
-                           when writing a gzip file) */
-} gz_header;
-
-typedef gz_header FAR *gz_headerp;
-
-/*
-   The application must update next_in and avail_in when avail_in has
-   dropped to zero. It must update next_out and avail_out when avail_out
-   has dropped to zero. The application must initialize zalloc, zfree and
-   opaque before calling the init function. All other fields are set by the
-   compression library and must not be updated by the application.
-
-   The opaque value provided by the application will be passed as the first
-   parameter for calls of zalloc and zfree. This can be useful for custom
-   memory management. The compression library attaches no meaning to the
-   opaque value.
-
-   zalloc must return Z_NULL if there is not enough memory for the object.
-   If zlib is used in a multi-threaded application, zalloc and zfree must be
-   thread safe.
-
-   On 16-bit systems, the functions zalloc and zfree must be able to allocate
-   exactly 65536 bytes, but will not be required to allocate more than this
-   if the symbol MAXSEG_64K is defined (see zconf.h). WARNING: On MSDOS,
-   pointers returned by zalloc for objects of exactly 65536 bytes *must*
-   have their offset normalized to zero. The default allocation function
-   provided by this library ensures this (see zutil.c). To reduce memory
-   requirements and avoid any allocation of 64K objects, at the expense of
-   compression ratio, compile the library with -DMAX_WBITS=14 (see zconf.h).
-
-   The fields total_in and total_out can be used for statistics or
-   progress reports. After compression, total_in holds the total size of
-   the uncompressed data and may be saved for use in the decompressor
-   (particularly if the decompressor wants to decompress everything in
-   a single step).
-*/
-
-                        /* constants */
-
-#define Z_NO_FLUSH      0
-#define Z_PARTIAL_FLUSH 1 /* will be removed, use Z_SYNC_FLUSH instead */
-#define Z_SYNC_FLUSH    2
-#define Z_FULL_FLUSH    3
-#define Z_FINISH        4
-#define Z_BLOCK         5
-/* Allowed flush values; see deflate() and inflate() below for details */
-
-#define Z_OK            0
-#define Z_STREAM_END    1
-#define Z_NEED_DICT     2
-#define Z_ERRNO        (-1)
-#define Z_STREAM_ERROR (-2)
-#define Z_DATA_ERROR   (-3)
-#define Z_MEM_ERROR    (-4)
-#define Z_BUF_ERROR    (-5)
-#define Z_VERSION_ERROR (-6)
-/* Return codes for the compression/decompression functions. Negative
- * values are errors, positive values are used for special but normal events.
- */
-
-#define Z_NO_COMPRESSION         0
-#define Z_BEST_SPEED             1
-#define Z_BEST_COMPRESSION       9
-#define Z_DEFAULT_COMPRESSION  (-1)
-/* compression levels */
-
-#define Z_FILTERED            1
-#define Z_HUFFMAN_ONLY        2
-#define Z_RLE                 3
-#define Z_FIXED               4
-#define Z_DEFAULT_STRATEGY    0
-/* compression strategy; see deflateInit2() below for details */
-
-#define Z_BINARY   0
-#define Z_TEXT     1
-#define Z_ASCII    Z_TEXT   /* for compatibility with 1.2.2 and earlier */
-#define Z_UNKNOWN  2
-/* Possible values of the data_type field (though see inflate()) */
-
-#define Z_DEFLATED   8
-/* The deflate compression method (the only one supported in this version) */
-
-#define Z_NULL  0  /* for initializing zalloc, zfree, opaque */
-
-#define zlib_version zlibVersion()
-/* for compatibility with versions < 1.0.2 */
-
-                        /* basic functions */
-
-ZEXTERN const char * ZEXPORT zlibVersion OF((void));
-/* The application can compare zlibVersion and ZLIB_VERSION for consistency.
-   If the first character differs, the library code actually used is
-   not compatible with the zlib.h header file used by the application.
-   This check is automatically made by deflateInit and inflateInit.
- */
-
-/*
-ZEXTERN int ZEXPORT deflateInit OF((z_streamp strm, int level));
-
-     Initializes the internal stream state for compression. The fields
-   zalloc, zfree and opaque must be initialized before by the caller.
-   If zalloc and zfree are set to Z_NULL, deflateInit updates them to
-   use default allocation functions.
-
-     The compression level must be Z_DEFAULT_COMPRESSION, or between 0 and 9:
-   1 gives best speed, 9 gives best compression, 0 gives no compression at
-   all (the input data is simply copied a block at a time).
-   Z_DEFAULT_COMPRESSION requests a default compromise between speed and
-   compression (currently equivalent to level 6).
-
-     deflateInit returns Z_OK if success, Z_MEM_ERROR if there was not
-   enough memory, Z_STREAM_ERROR if level is not a valid compression level,
-   Z_VERSION_ERROR if the zlib library version (zlib_version) is incompatible
-   with the version assumed by the caller (ZLIB_VERSION).
-   msg is set to null if there is no error message.  deflateInit does not
-   perform any compression: this will be done by deflate().
-*/
-
-
-ZEXTERN int ZEXPORT deflate OF((z_streamp strm, int flush));
-/*
-    deflate compresses as much data as possible, and stops when the input
-  buffer becomes empty or the output buffer becomes full. It may introduce some
-  output latency (reading input without producing any output) except when
-  forced to flush.
-
-    The detailed semantics are as follows. deflate performs one or both of the
-  following actions:
-
-  - Compress more input starting at next_in and update next_in and avail_in
-    accordingly. If not all input can be processed (because there is not
-    enough room in the output buffer), next_in and avail_in are updated and
-    processing will resume at this point for the next call of deflate().
-
-  - Provide more output starting at next_out and update next_out and avail_out
-    accordingly. This action is forced if the parameter flush is non zero.
-    Forcing flush frequently degrades the compression ratio, so this parameter
-    should be set only when necessary (in interactive applications).
-    Some output may be provided even if flush is not set.
-
-  Before the call of deflate(), the application should ensure that at least
-  one of the actions is possible, by providing more input and/or consuming
-  more output, and updating avail_in or avail_out accordingly; avail_out
-  should never be zero before the call. The application can consume the
-  compressed output when it wants, for example when the output buffer is full
-  (avail_out == 0), or after each call of deflate(). If deflate returns Z_OK
-  and with zero avail_out, it must be called again after making room in the
-  output buffer because there might be more output pending.
-
-    Normally the parameter flush is set to Z_NO_FLUSH, which allows deflate to
-  decide how much data to accumualte before producing output, in order to
-  maximize compression.
-
-    If the parameter flush is set to Z_SYNC_FLUSH, all pending output is
-  flushed to the output buffer and the output is aligned on a byte boundary, so
-  that the decompressor can get all input data available so far. (In particular
-  avail_in is zero after the call if enough output space has been provided
-  before the call.)  Flushing may degrade compression for some compression
-  algorithms and so it should be used only when necessary.
-
-    If flush is set to Z_FULL_FLUSH, all output is flushed as with
-  Z_SYNC_FLUSH, and the compression state is reset so that decompression can
-  restart from this point if previous compressed data has been damaged or if
-  random access is desired. Using Z_FULL_FLUSH too often can seriously degrade
-  compression.
-
-    If deflate returns with avail_out == 0, this function must be called again
-  with the same value of the flush parameter and more output space (updated
-  avail_out), until the flush is complete (deflate returns with non-zero
-  avail_out). In the case of a Z_FULL_FLUSH or Z_SYNC_FLUSH, make sure that
-  avail_out is greater than six to avoid repeated flush markers due to
-  avail_out == 0 on return.
-
-    If the parameter flush is set to Z_FINISH, pending input is processed,
-  pending output is flushed and deflate returns with Z_STREAM_END if there
-  was enough output space; if deflate returns with Z_OK, this function must be
-  called again with Z_FINISH and more output space (updated avail_out) but no
-  more input data, until it returns with Z_STREAM_END or an error. After
-  deflate has returned Z_STREAM_END, the only possible operations on the
-  stream are deflateReset or deflateEnd.
-
-    Z_FINISH can be used immediately after deflateInit if all the compression
-  is to be done in a single step. In this case, avail_out must be at least
-  the value returned by deflateBound (see below). If deflate does not return
-  Z_STREAM_END, then it must be called again as described above.
-
-    deflate() sets strm->adler to the adler32 checksum of all input read
-  so far (that is, total_in bytes).
-
-    deflate() may update strm->data_type if it can make a good guess about
-  the input data type (Z_BINARY or Z_TEXT). In doubt, the data is considered
-  binary. This field is only for information purposes and does not affect
-  the compression algorithm in any manner.
-
-    deflate() returns Z_OK if some progress has been made (more input
-  processed or more output produced), Z_STREAM_END if all input has been
-  consumed and all output has been produced (only when flush is set to
-  Z_FINISH), Z_STREAM_ERROR if the stream state was inconsistent (for example
-  if next_in or next_out was NULL), Z_BUF_ERROR if no progress is possible
-  (for example avail_in or avail_out was zero). Note that Z_BUF_ERROR is not
-  fatal, and deflate() can be called again with more input and more output
-  space to continue compressing.
-*/
-
-
-ZEXTERN int ZEXPORT deflateEnd OF((z_streamp strm));
-/*
-     All dynamically allocated data structures for this stream are freed.
-   This function discards any unprocessed input and does not flush any
-   pending output.
-
-     deflateEnd returns Z_OK if success, Z_STREAM_ERROR if the
-   stream state was inconsistent, Z_DATA_ERROR if the stream was freed
-   prematurely (some input or output was discarded). In the error case,
-   msg may be set but then points to a static string (which must not be
-   deallocated).
-*/
-
-
-/*
-ZEXTERN int ZEXPORT inflateInit OF((z_streamp strm));
-
-     Initializes the internal stream state for decompression. The fields
-   next_in, avail_in, zalloc, zfree and opaque must be initialized before by
-   the caller. If next_in is not Z_NULL and avail_in is large enough (the exact
-   value depends on the compression method), inflateInit determines the
-   compression method from the zlib header and allocates all data structures
-   accordingly; otherwise the allocation will be deferred to the first call of
-   inflate.  If zalloc and zfree are set to Z_NULL, inflateInit updates them to
-   use default allocation functions.
-
-     inflateInit returns Z_OK if success, Z_MEM_ERROR if there was not enough
-   memory, Z_VERSION_ERROR if the zlib library version is incompatible with the
-   version assumed by the caller.  msg is set to null if there is no error
-   message. inflateInit does not perform any decompression apart from reading
-   the zlib header if present: this will be done by inflate().  (So next_in and
-   avail_in may be modified, but next_out and avail_out are unchanged.)
-*/
-
-
-ZEXTERN int ZEXPORT inflate OF((z_streamp strm, int flush));
-/*
-    inflate decompresses as much data as possible, and stops when the input
-  buffer becomes empty or the output buffer becomes full. It may introduce
-  some output latency (reading input without producing any output) except when
-  forced to flush.
-
-  The detailed semantics are as follows. inflate performs one or both of the
-  following actions:
-
-  - Decompress more input starting at next_in and update next_in and avail_in
-    accordingly. If not all input can be processed (because there is not
-    enough room in the output buffer), next_in is updated and processing
-    will resume at this point for the next call of inflate().
-
-  - Provide more output starting at next_out and update next_out and avail_out
-    accordingly.  inflate() provides as much output as possible, until there
-    is no more input data or no more space in the output buffer (see below
-    about the flush parameter).
-
-  Before the call of inflate(), the application should ensure that at least
-  one of the actions is possible, by providing more input and/or consuming
-  more output, and updating the next_* and avail_* values accordingly.
-  The application can consume the uncompressed output when it wants, for
-  example when the output buffer is full (avail_out == 0), or after each
-  call of inflate(). If inflate returns Z_OK and with zero avail_out, it
-  must be called again after making room in the output buffer because there
-  might be more output pending.
-
-    The flush parameter of inflate() can be Z_NO_FLUSH, Z_SYNC_FLUSH,
-  Z_FINISH, or Z_BLOCK. Z_SYNC_FLUSH requests that inflate() flush as much
-  output as possible to the output buffer. Z_BLOCK requests that inflate() stop
-  if and when it gets to the next deflate block boundary. When decoding the
-  zlib or gzip format, this will cause inflate() to return immediately after
-  the header and before the first block. When doing a raw inflate, inflate()
-  will go ahead and process the first block, and will return when it gets to
-  the end of that block, or when it runs out of data.
-
-    The Z_BLOCK option assists in appending to or combining deflate streams.
-  Also to assist in this, on return inflate() will set strm->data_type to the
-  number of unused bits in the last byte taken from strm->next_in, plus 64
-  if inflate() is currently decoding the last block in the deflate stream,
-  plus 128 if inflate() returned immediately after decoding an end-of-block
-  code or decoding the complete header up to just before the first byte of the
-  deflate stream. The end-of-block will not be indicated until all of the
-  uncompressed data from that block has been written to strm->next_out.  The
-  number of unused bits may in general be greater than seven, except when
-  bit 7 of data_type is set, in which case the number of unused bits will be
-  less than eight.
-
-    inflate() should normally be called until it returns Z_STREAM_END or an
-  error. However if all decompression is to be performed in a single step
-  (a single call of inflate), the parameter flush should be set to
-  Z_FINISH. In this case all pending input is processed and all pending
-  output is flushed; avail_out must be large enough to hold all the
-  uncompressed data. (The size of the uncompressed data may have been saved
-  by the compressor for this purpose.) The next operation on this stream must
-  be inflateEnd to deallocate the decompression state. The use of Z_FINISH
-  is never required, but can be used to inform inflate that a faster approach
-  may be used for the single inflate() call.
-
-     In this implementation, inflate() always flushes as much output as
-  possible to the output buffer, and always uses the faster approach on the
-  first call. So the only effect of the flush parameter in this implementation
-  is on the return value of inflate(), as noted below, or when it returns early
-  because Z_BLOCK is used.
-
-     If a preset dictionary is needed after this call (see inflateSetDictionary
-  below), inflate sets strm->adler to the adler32 checksum of the dictionary
-  chosen by the compressor and returns Z_NEED_DICT; otherwise it sets
-  strm->adler to the adler32 checksum of all output produced so far (that is,
-  total_out bytes) and returns Z_OK, Z_STREAM_END or an error code as described
-  below. At the end of the stream, inflate() checks that its computed adler32
-  checksum is equal to that saved by the compressor and returns Z_STREAM_END
-  only if the checksum is correct.
-
-    inflate() will decompress and check either zlib-wrapped or gzip-wrapped
-  deflate data.  The header type is detected automatically.  Any information
-  contained in the gzip header is not retained, so applications that need that
-  information should instead use raw inflate, see inflateInit2() below, or
-  inflateBack() and perform their own processing of the gzip header and
-  trailer.
-
-    inflate() returns Z_OK if some progress has been made (more input processed
-  or more output produced), Z_STREAM_END if the end of the compressed data has
-  been reached and all uncompressed output has been produced, Z_NEED_DICT if a
-  preset dictionary is needed at this point, Z_DATA_ERROR if the input data was
-  corrupted (input stream not conforming to the zlib format or incorrect check
-  value), Z_STREAM_ERROR if the stream structure was inconsistent (for example
-  if next_in or next_out was NULL), Z_MEM_ERROR if there was not enough memory,
-  Z_BUF_ERROR if no progress is possible or if there was not enough room in the
-  output buffer when Z_FINISH is used. Note that Z_BUF_ERROR is not fatal, and
-  inflate() can be called again with more input and more output space to
-  continue decompressing. If Z_DATA_ERROR is returned, the application may then
-  call inflateSync() to look for a good compression block if a partial recovery
-  of the data is desired.
-*/
-
-
-ZEXTERN int ZEXPORT inflateEnd OF((z_streamp strm));
-/*
-     All dynamically allocated data structures for this stream are freed.
-   This function discards any unprocessed input and does not flush any
-   pending output.
-
-     inflateEnd returns Z_OK if success, Z_STREAM_ERROR if the stream state
-   was inconsistent. In the error case, msg may be set but then points to a
-   static string (which must not be deallocated).
-*/
-
-                        /* Advanced functions */
-
-/*
-    The following functions are needed only in some special applications.
-*/
-
-/*
-ZEXTERN int ZEXPORT deflateInit2 OF((z_streamp strm,
-                                     int  level,
-                                     int  method,
-                                     int  windowBits,
-                                     int  memLevel,
-                                     int  strategy));
-
-     This is another version of deflateInit with more compression options. The
-   fields next_in, zalloc, zfree and opaque must be initialized before by
-   the caller.
-
-     The method parameter is the compression method. It must be Z_DEFLATED in
-   this version of the library.
-
-     The windowBits parameter is the base two logarithm of the window size
-   (the size of the history buffer). It should be in the range 8..15 for this
-   version of the library. Larger values of this parameter result in better
-   compression at the expense of memory usage. The default value is 15 if
-   deflateInit is used instead.
-
-     windowBits can also be -8..-15 for raw deflate. In this case, -windowBits
-   determines the window size. deflate() will then generate raw deflate data
-   with no zlib header or trailer, and will not compute an adler32 check value.
-
-     windowBits can also be greater than 15 for optional gzip encoding. Add
-   16 to windowBits to write a simple gzip header and trailer around the
-   compressed data instead of a zlib wrapper. The gzip header will have no
-   file name, no extra data, no comment, no modification time (set to zero),
-   no header crc, and the operating system will be set to 255 (unknown).  If a
-   gzip stream is being written, strm->adler is a crc32 instead of an adler32.
-
-     The memLevel parameter specifies how much memory should be allocated
-   for the internal compression state. memLevel=1 uses minimum memory but
-   is slow and reduces compression ratio; memLevel=9 uses maximum memory
-   for optimal speed. The default value is 8. See zconf.h for total memory
-   usage as a function of windowBits and memLevel.
-
-     The strategy parameter is used to tune the compression algorithm. Use the
-   value Z_DEFAULT_STRATEGY for normal data, Z_FILTERED for data produced by a
-   filter (or predictor), Z_HUFFMAN_ONLY to force Huffman encoding only (no
-   string match), or Z_RLE to limit match distances to one (run-length
-   encoding). Filtered data consists mostly of small values with a somewhat
-   random distribution. In this case, the compression algorithm is tuned to
-   compress them better. The effect of Z_FILTERED is to force more Huffman
-   coding and less string matching; it is somewhat intermediate between
-   Z_DEFAULT and Z_HUFFMAN_ONLY. Z_RLE is designed to be almost as fast as
-   Z_HUFFMAN_ONLY, but give better compression for PNG image data. The strategy
-   parameter only affects the compression ratio but not the correctness of the
-   compressed output even if it is not set appropriately.  Z_FIXED prevents the
-   use of dynamic Huffman codes, allowing for a simpler decoder for special
-   applications.
-
-      deflateInit2 returns Z_OK if success, Z_MEM_ERROR if there was not enough
-   memory, Z_STREAM_ERROR if a parameter is invalid (such as an invalid
-   method). msg is set to null if there is no error message.  deflateInit2 does
-   not perform any compression: this will be done by deflate().
-*/
-
-ZEXTERN int ZEXPORT deflateSetDictionary OF((z_streamp strm,
-                                             const Bytef *dictionary,
-                                             uInt  dictLength));
-/*
-     Initializes the compression dictionary from the given byte sequence
-   without producing any compressed output. This function must be called
-   immediately after deflateInit, deflateInit2 or deflateReset, before any
-   call of deflate. The compressor and decompressor must use exactly the same
-   dictionary (see inflateSetDictionary).
-
-     The dictionary should consist of strings (byte sequences) that are likely
-   to be encountered later in the data to be compressed, with the most commonly
-   used strings preferably put towards the end of the dictionary. Using a
-   dictionary is most useful when the data to be compressed is short and can be
-   predicted with good accuracy; the data can then be compressed better than
-   with the default empty dictionary.
-
-     Depending on the size of the compression data structures selected by
-   deflateInit or deflateInit2, a part of the dictionary may in effect be
-   discarded, for example if the dictionary is larger than the window size in
-   deflate or deflate2. Thus the strings most likely to be useful should be
-   put at the end of the dictionary, not at the front. In addition, the
-   current implementation of deflate will use at most the window size minus
-   262 bytes of the provided dictionary.
-
-     Upon return of this function, strm->adler is set to the adler32 value
-   of the dictionary; the decompressor may later use this value to determine
-   which dictionary has been used by the compressor. (The adler32 value
-   applies to the whole dictionary even if only a subset of the dictionary is
-   actually used by the compressor.) If a raw deflate was requested, then the
-   adler32 value is not computed and strm->adler is not set.
-
-     deflateSetDictionary returns Z_OK if success, or Z_STREAM_ERROR if a
-   parameter is invalid (such as NULL dictionary) or the stream state is
-   inconsistent (for example if deflate has already been called for this stream
-   or if the compression method is bsort). deflateSetDictionary does not
-   perform any compression: this will be done by deflate().
-*/
-
-ZEXTERN int ZEXPORT deflateCopy OF((z_streamp dest,
-                                    z_streamp source));
-/*
-     Sets the destination stream as a complete copy of the source stream.
-
-     This function can be useful when several compression strategies will be
-   tried, for example when there are several ways of pre-processing the input
-   data with a filter. The streams that will be discarded should then be freed
-   by calling deflateEnd.  Note that deflateCopy duplicates the internal
-   compression state which can be quite large, so this strategy is slow and
-   can consume lots of memory.
-
-     deflateCopy returns Z_OK if success, Z_MEM_ERROR if there was not
-   enough memory, Z_STREAM_ERROR if the source stream state was inconsistent
-   (such as zalloc being NULL). msg is left unchanged in both source and
-   destination.
-*/
-
-ZEXTERN int ZEXPORT deflateReset OF((z_streamp strm));
-/*
-     This function is equivalent to deflateEnd followed by deflateInit,
-   but does not free and reallocate all the internal compression state.
-   The stream will keep the same compression level and any other attributes
-   that may have been set by deflateInit2.
-
-      deflateReset returns Z_OK if success, or Z_STREAM_ERROR if the source
-   stream state was inconsistent (such as zalloc or state being NULL).
-*/
-
-ZEXTERN int ZEXPORT deflateParams OF((z_streamp strm,
-                                      int level,
-                                      int strategy));
-/*
-     Dynamically update the compression level and compression strategy.  The
-   interpretation of level and strategy is as in deflateInit2.  This can be
-   used to switch between compression and straight copy of the input data, or
-   to switch to a different kind of input data requiring a different
-   strategy. If the compression level is changed, the input available so far
-   is compressed with the old level (and may be flushed); the new level will
-   take effect only at the next call of deflate().
-
-     Before the call of deflateParams, the stream state must be set as for
-   a call of deflate(), since the currently available input may have to
-   be compressed and flushed. In particular, strm->avail_out must be non-zero.
-
-     deflateParams returns Z_OK if success, Z_STREAM_ERROR if the source
-   stream state was inconsistent or if a parameter was invalid, Z_BUF_ERROR
-   if strm->avail_out was zero.
-*/
-
-ZEXTERN int ZEXPORT deflateTune OF((z_streamp strm,
-                                    int good_length,
-                                    int max_lazy,
-                                    int nice_length,
-                                    int max_chain));
-/*
-     Fine tune deflate's internal compression parameters.  This should only be
-   used by someone who understands the algorithm used by zlib's deflate for
-   searching for the best matching string, and even then only by the most
-   fanatic optimizer trying to squeeze out the last compressed bit for their
-   specific input data.  Read the deflate.c source code for the meaning of the
-   max_lazy, good_length, nice_length, and max_chain parameters.
-
-     deflateTune() can be called after deflateInit() or deflateInit2(), and
-   returns Z_OK on success, or Z_STREAM_ERROR for an invalid deflate stream.
- */
-
-ZEXTERN uLong ZEXPORT deflateBound OF((z_streamp strm,
-                                       uLong sourceLen));
-/*
-     deflateBound() returns an upper bound on the compressed size after
-   deflation of sourceLen bytes.  It must be called after deflateInit()
-   or deflateInit2().  This would be used to allocate an output buffer
-   for deflation in a single pass, and so would be called before deflate().
-*/
-
-ZEXTERN int ZEXPORT deflatePrime OF((z_streamp strm,
-                                     int bits,
-                                     int value));
-/*
-     deflatePrime() inserts bits in the deflate output stream.  The intent
-  is that this function is used to start off the deflate output with the
-  bits leftover from a previous deflate stream when appending to it.  As such,
-  this function can only be used for raw deflate, and must be used before the
-  first deflate() call after a deflateInit2() or deflateReset().  bits must be
-  less than or equal to 16, and that many of the least significant bits of
-  value will be inserted in the output.
-
-      deflatePrime returns Z_OK if success, or Z_STREAM_ERROR if the source
-   stream state was inconsistent.
-*/
-
-ZEXTERN int ZEXPORT deflateSetHeader OF((z_streamp strm,
-                                         gz_headerp head));
-/*
-      deflateSetHeader() provides gzip header information for when a gzip
-   stream is requested by deflateInit2().  deflateSetHeader() may be called
-   after deflateInit2() or deflateReset() and before the first call of
-   deflate().  The text, time, os, extra field, name, and comment information
-   in the provided gz_header structure are written to the gzip header (xflag is
-   ignored -- the extra flags are set according to the compression level).  The
-   caller must assure that, if not Z_NULL, name and comment are terminated with
-   a zero byte, and that if extra is not Z_NULL, that extra_len bytes are
-   available there.  If hcrc is true, a gzip header crc is included.  Note that
-   the current versions of the command-line version of gzip (up through version
-   1.3.x) do not support header crc's, and will report that it is a "multi-part
-   gzip file" and give up.
-
-      If deflateSetHeader is not used, the default gzip header has text false,
-   the time set to zero, and os set to 255, with no extra, name, or comment
-   fields.  The gzip header is returned to the default state by deflateReset().
-
-      deflateSetHeader returns Z_OK if success, or Z_STREAM_ERROR if the source
-   stream state was inconsistent.
-*/
-
-/*
-ZEXTERN int ZEXPORT inflateInit2 OF((z_streamp strm,
-                                     int  windowBits));
-
-     This is another version of inflateInit with an extra parameter. The
-   fields next_in, avail_in, zalloc, zfree and opaque must be initialized
-   before by the caller.
-
-     The windowBits parameter is the base two logarithm of the maximum window
-   size (the size of the history buffer).  It should be in the range 8..15 for
-   this version of the library. The default value is 15 if inflateInit is used
-   instead. windowBits must be greater than or equal to the windowBits value
-   provided to deflateInit2() while compressing, or it must be equal to 15 if
-   deflateInit2() was not used. If a compressed stream with a larger window
-   size is given as input, inflate() will return with the error code
-   Z_DATA_ERROR instead of trying to allocate a larger window.
-
-     windowBits can also be -8..-15 for raw inflate. In this case, -windowBits
-   determines the window size. inflate() will then process raw deflate data,
-   not looking for a zlib or gzip header, not generating a check value, and not
-   looking for any check values for comparison at the end of the stream. This
-   is for use with other formats that use the deflate compressed data format
-   such as zip.  Those formats provide their own check values. If a custom
-   format is developed using the raw deflate format for compressed data, it is
-   recommended that a check value such as an adler32 or a crc32 be applied to
-   the uncompressed data as is done in the zlib, gzip, and zip formats.  For
-   most applications, the zlib format should be used as is. Note that comments
-   above on the use in deflateInit2() applies to the magnitude of windowBits.
-
-     windowBits can also be greater than 15 for optional gzip decoding. Add
-   32 to windowBits to enable zlib and gzip decoding with automatic header
-   detection, or add 16 to decode only the gzip format (the zlib format will
-   return a Z_DATA_ERROR).  If a gzip stream is being decoded, strm->adler is
-   a crc32 instead of an adler32.
-
-     inflateInit2 returns Z_OK if success, Z_MEM_ERROR if there was not enough
-   memory, Z_STREAM_ERROR if a parameter is invalid (such as a null strm). msg
-   is set to null if there is no error message.  inflateInit2 does not perform
-   any decompression apart from reading the zlib header if present: this will
-   be done by inflate(). (So next_in and avail_in may be modified, but next_out
-   and avail_out are unchanged.)
-*/
-
-ZEXTERN int ZEXPORT inflateSetDictionary OF((z_streamp strm,
-                                             const Bytef *dictionary,
-                                             uInt  dictLength));
-/*
-     Initializes the decompression dictionary from the given uncompressed byte
-   sequence. This function must be called immediately after a call of inflate,
-   if that call returned Z_NEED_DICT. The dictionary chosen by the compressor
-   can be determined from the adler32 value returned by that call of inflate.
-   The compressor and decompressor must use exactly the same dictionary (see
-   deflateSetDictionary).  For raw inflate, this function can be called
-   immediately after inflateInit2() or inflateReset() and before any call of
-   inflate() to set the dictionary.  The application must insure that the
-   dictionary that was used for compression is provided.
-
-     inflateSetDictionary returns Z_OK if success, Z_STREAM_ERROR if a
-   parameter is invalid (such as NULL dictionary) or the stream state is
-   inconsistent, Z_DATA_ERROR if the given dictionary doesn't match the
-   expected one (incorrect adler32 value). inflateSetDictionary does not
-   perform any decompression: this will be done by subsequent calls of
-   inflate().
-*/
-
-ZEXTERN int ZEXPORT inflateSync OF((z_streamp strm));
-/*
-    Skips invalid compressed data until a full flush point (see above the
-  description of deflate with Z_FULL_FLUSH) can be found, or until all
-  available input is skipped. No output is provided.
-
-    inflateSync returns Z_OK if a full flush point has been found, Z_BUF_ERROR
-  if no more input was provided, Z_DATA_ERROR if no flush point has been found,
-  or Z_STREAM_ERROR if the stream structure was inconsistent. In the success
-  case, the application may save the current current value of total_in which
-  indicates where valid compressed data was found. In the error case, the
-  application may repeatedly call inflateSync, providing more input each time,
-  until success or end of the input data.
-*/
-
-ZEXTERN int ZEXPORT inflateCopy OF((z_streamp dest,
-                                    z_streamp source));
-/*
-     Sets the destination stream as a complete copy of the source stream.
-
-     This function can be useful when randomly accessing a large stream.  The
-   first pass through the stream can periodically record the inflate state,
-   allowing restarting inflate at those points when randomly accessing the
-   stream.
-
-     inflateCopy returns Z_OK if success, Z_MEM_ERROR if there was not
-   enough memory, Z_STREAM_ERROR if the source stream state was inconsistent
-   (such as zalloc being NULL). msg is left unchanged in both source and
-   destination.
-*/
-
-ZEXTERN int ZEXPORT inflateReset OF((z_streamp strm));
-/*
-     This function is equivalent to inflateEnd followed by inflateInit,
-   but does not free and reallocate all the internal decompression state.
-   The stream will keep attributes that may have been set by inflateInit2.
-
-      inflateReset returns Z_OK if success, or Z_STREAM_ERROR if the source
-   stream state was inconsistent (such as zalloc or state being NULL).
-*/
-
-ZEXTERN int ZEXPORT inflatePrime OF((z_streamp strm,
-                                     int bits,
-                                     int value));
-/*
-     This function inserts bits in the inflate input stream.  The intent is
-  that this function is used to start inflating at a bit position in the
-  middle of a byte.  The provided bits will be used before any bytes are used
-  from next_in.  This function should only be used with raw inflate, and
-  should be used before the first inflate() call after inflateInit2() or
-  inflateReset().  bits must be less than or equal to 16, and that many of the
-  least significant bits of value will be inserted in the input.
-
-      inflatePrime returns Z_OK if success, or Z_STREAM_ERROR if the source
-   stream state was inconsistent.
-*/
-
-ZEXTERN int ZEXPORT inflateGetHeader OF((z_streamp strm,
-                                         gz_headerp head));
-/*
-      inflateGetHeader() requests that gzip header information be stored in the
-   provided gz_header structure.  inflateGetHeader() may be called after
-   inflateInit2() or inflateReset(), and before the first call of inflate().
-   As inflate() processes the gzip stream, head->done is zero until the header
-   is completed, at which time head->done is set to one.  If a zlib stream is
-   being decoded, then head->done is set to -1 to indicate that there will be
-   no gzip header information forthcoming.  Note that Z_BLOCK can be used to
-   force inflate() to return immediately after header processing is complete
-   and before any actual data is decompressed.
-
-      The text, time, xflags, and os fields are filled in with the gzip header
-   contents.  hcrc is set to true if there is a header CRC.  (The header CRC
-   was valid if done is set to one.)  If extra is not Z_NULL, then extra_max
-   contains the maximum number of bytes to write to extra.  Once done is true,
-   extra_len contains the actual extra field length, and extra contains the
-   extra field, or that field truncated if extra_max is less than extra_len.
-   If name is not Z_NULL, then up to name_max characters are written there,
-   terminated with a zero unless the length is greater than name_max.  If
-   comment is not Z_NULL, then up to comm_max characters are written there,
-   terminated with a zero unless the length is greater than comm_max.  When
-   any of extra, name, or comment are not Z_NULL and the respective field is
-   not present in the header, then that field is set to Z_NULL to signal its
-   absence.  This allows the use of deflateSetHeader() with the returned
-   structure to duplicate the header.  However if those fields are set to
-   allocated memory, then the application will need to save those pointers
-   elsewhere so that they can be eventually freed.
-
-      If inflateGetHeader is not used, then the header information is simply
-   discarded.  The header is always checked for validity, including the header
-   CRC if present.  inflateReset() will reset the process to discard the header
-   information.  The application would need to call inflateGetHeader() again to
-   retrieve the header from the next gzip stream.
-
-      inflateGetHeader returns Z_OK if success, or Z_STREAM_ERROR if the source
-   stream state was inconsistent.
-*/
-
-/*
-ZEXTERN int ZEXPORT inflateBackInit OF((z_streamp strm, int windowBits,
-                                        unsigned char FAR *window));
-
-     Initialize the internal stream state for decompression using inflateBack()
-   calls.  The fields zalloc, zfree and opaque in strm must be initialized
-   before the call.  If zalloc and zfree are Z_NULL, then the default library-
-   derived memory allocation routines are used.  windowBits is the base two
-   logarithm of the window size, in the range 8..15.  window is a caller
-   supplied buffer of that size.  Except for special applications where it is
-   assured that deflate was used with small window sizes, windowBits must be 15
-   and a 32K byte window must be supplied to be able to decompress general
-   deflate streams.
-
-     See inflateBack() for the usage of these routines.
-
-     inflateBackInit will return Z_OK on success, Z_STREAM_ERROR if any of
-   the paramaters are invalid, Z_MEM_ERROR if the internal state could not
-   be allocated, or Z_VERSION_ERROR if the version of the library does not
-   match the version of the header file.
-*/
-
-typedef unsigned (*in_func) OF((void FAR *, unsigned char FAR * FAR *));
-typedef int (*out_func) OF((void FAR *, unsigned char FAR *, unsigned));
-
-ZEXTERN int ZEXPORT inflateBack OF((z_streamp strm,
-                                    in_func in, void FAR *in_desc,
-                                    out_func out, void FAR *out_desc));
-/*
-     inflateBack() does a raw inflate with a single call using a call-back
-   interface for input and output.  This is more efficient than inflate() for
-   file i/o applications in that it avoids copying between the output and the
-   sliding window by simply making the window itself the output buffer.  This
-   function trusts the application to not change the output buffer passed by
-   the output function, at least until inflateBack() returns.
-
-     inflateBackInit() must be called first to allocate the internal state
-   and to initialize the state with the user-provided window buffer.
-   inflateBack() may then be used multiple times to inflate a complete, raw
-   deflate stream with each call.  inflateBackEnd() is then called to free
-   the allocated state.
-
-     A raw deflate stream is one with no zlib or gzip header or trailer.
-   This routine would normally be used in a utility that reads zip or gzip
-   files and writes out uncompressed files.  The utility would decode the
-   header and process the trailer on its own, hence this routine expects
-   only the raw deflate stream to decompress.  This is different from the
-   normal behavior of inflate(), which expects either a zlib or gzip header and
-   trailer around the deflate stream.
-
-     inflateBack() uses two subroutines supplied by the caller that are then
-   called by inflateBack() for input and output.  inflateBack() calls those
-   routines until it reads a complete deflate stream and writes out all of the
-   uncompressed data, or until it encounters an error.  The function's
-   parameters and return types are defined above in the in_func and out_func
-   typedefs.  inflateBack() will call in(in_desc, &buf) which should return the
-   number of bytes of provided input, and a pointer to that input in buf.  If
-   there is no input available, in() must return zero--buf is ignored in that
-   case--and inflateBack() will return a buffer error.  inflateBack() will call
-   out(out_desc, buf, len) to write the uncompressed data buf[0..len-1].  out()
-   should return zero on success, or non-zero on failure.  If out() returns
-   non-zero, inflateBack() will return with an error.  Neither in() nor out()
-   are permitted to change the contents of the window provided to
-   inflateBackInit(), which is also the buffer that out() uses to write from.
-   The length written by out() will be at most the window size.  Any non-zero
-   amount of input may be provided by in().
-
-     For convenience, inflateBack() can be provided input on the first call by
-   setting strm->next_in and strm->avail_in.  If that input is exhausted, then
-   in() will be called.  Therefore strm->next_in must be initialized before
-   calling inflateBack().  If strm->next_in is Z_NULL, then in() will be called
-   immediately for input.  If strm->next_in is not Z_NULL, then strm->avail_in
-   must also be initialized, and then if strm->avail_in is not zero, input will
-   initially be taken from strm->next_in[0 .. strm->avail_in - 1].
-
-     The in_desc and out_desc parameters of inflateBack() is passed as the
-   first parameter of in() and out() respectively when they are called.  These
-   descriptors can be optionally used to pass any information that the caller-
-   supplied in() and out() functions need to do their job.
-
-     On return, inflateBack() will set strm->next_in and strm->avail_in to
-   pass back any unused input that was provided by the last in() call.  The
-   return values of inflateBack() can be Z_STREAM_END on success, Z_BUF_ERROR
-   if in() or out() returned an error, Z_DATA_ERROR if there was a format
-   error in the deflate stream (in which case strm->msg is set to indicate the
-   nature of the error), or Z_STREAM_ERROR if the stream was not properly
-   initialized.  In the case of Z_BUF_ERROR, an input or output error can be
-   distinguished using strm->next_in which will be Z_NULL only if in() returned
-   an error.  If strm->next is not Z_NULL, then the Z_BUF_ERROR was due to
-   out() returning non-zero.  (in() will always be called before out(), so
-   strm->next_in is assured to be defined if out() returns non-zero.)  Note
-   that inflateBack() cannot return Z_OK.
-*/
-
-ZEXTERN int ZEXPORT inflateBackEnd OF((z_streamp strm));
-/*
-     All memory allocated by inflateBackInit() is freed.
-
-     inflateBackEnd() returns Z_OK on success, or Z_STREAM_ERROR if the stream
-   state was inconsistent.
-*/
-
-ZEXTERN uLong ZEXPORT zlibCompileFlags OF((void));
-/* Return flags indicating compile-time options.
-
-    Type sizes, two bits each, 00 = 16 bits, 01 = 32, 10 = 64, 11 = other:
-     1.0: size of uInt
-     3.2: size of uLong
-     5.4: size of voidpf (pointer)
-     7.6: size of z_off_t
-
-    Compiler, assembler, and debug options:
-     8: DEBUG
-     9: ASMV or ASMINF -- use ASM code
-     10: ZLIB_WINAPI -- exported functions use the WINAPI calling convention
-     11: 0 (reserved)
-
-    One-time table building (smaller code, but not thread-safe if true):
-     12: BUILDFIXED -- build static block decoding tables when needed
-     13: DYNAMIC_CRC_TABLE -- build CRC calculation tables when needed
-     14,15: 0 (reserved)
-
-    Library content (indicates missing functionality):
-     16: NO_GZCOMPRESS -- gz* functions cannot compress (to avoid linking
-                          deflate code when not needed)
-     17: NO_GZIP -- deflate can't write gzip streams, and inflate can't detect
-                    and decode gzip streams (to avoid linking crc code)
-     18-19: 0 (reserved)
-
-    Operation variations (changes in library functionality):
-     20: PKZIP_BUG_WORKAROUND -- slightly more permissive inflate
-     21: FASTEST -- deflate algorithm with only one, lowest compression level
-     22,23: 0 (reserved)
-
-    The sprintf variant used by gzprintf (zero is best):
-     24: 0 = vs*, 1 = s* -- 1 means limited to 20 arguments after the format
-     25: 0 = *nprintf, 1 = *printf -- 1 means gzprintf() not secure!
-     26: 0 = returns value, 1 = void -- 1 means inferred string length returned
-
-    Remainder:
-     27-31: 0 (reserved)
- */
-
-
-                        /* utility functions */
-
-/*
-     The following utility functions are implemented on top of the
-   basic stream-oriented functions. To simplify the interface, some
-   default options are assumed (compression level and memory usage,
-   standard memory allocation functions). The source code of these
-   utility functions can easily be modified if you need special options.
-*/
-
-ZEXTERN int ZEXPORT compress OF((Bytef *dest,   uLongf *destLen,
-                                 const Bytef *source, uLong sourceLen));
-/*
-     Compresses the source buffer into the destination buffer.  sourceLen is
-   the byte length of the source buffer. Upon entry, destLen is the total
-   size of the destination buffer, which must be at least the value returned
-   by compressBound(sourceLen). Upon exit, destLen is the actual size of the
-   compressed buffer.
-     This function can be used to compress a whole file at once if the
-   input file is mmap'ed.
-     compress returns Z_OK if success, Z_MEM_ERROR if there was not
-   enough memory, Z_BUF_ERROR if there was not enough room in the output
-   buffer.
-*/
-
-ZEXTERN int ZEXPORT compress2 OF((Bytef *dest,   uLongf *destLen,
-                                  const Bytef *source, uLong sourceLen,
-                                  int level));
-/*
-     Compresses the source buffer into the destination buffer. The level
-   parameter has the same meaning as in deflateInit.  sourceLen is the byte
-   length of the source buffer. Upon entry, destLen is the total size of the
-   destination buffer, which must be at least the value returned by
-   compressBound(sourceLen). Upon exit, destLen is the actual size of the
-   compressed buffer.
-
-     compress2 returns Z_OK if success, Z_MEM_ERROR if there was not enough
-   memory, Z_BUF_ERROR if there was not enough room in the output buffer,
-   Z_STREAM_ERROR if the level parameter is invalid.
-*/
-
-ZEXTERN uLong ZEXPORT compressBound OF((uLong sourceLen));
-/*
-     compressBound() returns an upper bound on the compressed size after
-   compress() or compress2() on sourceLen bytes.  It would be used before
-   a compress() or compress2() call to allocate the destination buffer.
-*/
-
-ZEXTERN int ZEXPORT uncompress OF((Bytef *dest,   uLongf *destLen,
-                                   const Bytef *source, uLong sourceLen));
-/*
-     Decompresses the source buffer into the destination buffer.  sourceLen is
-   the byte length of the source buffer. Upon entry, destLen is the total
-   size of the destination buffer, which must be large enough to hold the
-   entire uncompressed data. (The size of the uncompressed data must have
-   been saved previously by the compressor and transmitted to the decompressor
-   by some mechanism outside the scope of this compression library.)
-   Upon exit, destLen is the actual size of the compressed buffer.
-     This function can be used to decompress a whole file at once if the
-   input file is mmap'ed.
-
-     uncompress returns Z_OK if success, Z_MEM_ERROR if there was not
-   enough memory, Z_BUF_ERROR if there was not enough room in the output
-   buffer, or Z_DATA_ERROR if the input data was corrupted or incomplete.
-*/
-
-
-typedef voidp gzFile;
-
-ZEXTERN gzFile ZEXPORT gzopen  OF((const char *path, const char *mode));
-/*
-     Opens a gzip (.gz) file for reading or writing. The mode parameter
-   is as in fopen ("rb" or "wb") but can also include a compression level
-   ("wb9") or a strategy: 'f' for filtered data as in "wb6f", 'h' for
-   Huffman only compression as in "wb1h", or 'R' for run-length encoding
-   as in "wb1R". (See the description of deflateInit2 for more information
-   about the strategy parameter.)
-
-     gzopen can be used to read a file which is not in gzip format; in this
-   case gzread will directly read from the file without decompression.
-
-     gzopen returns NULL if the file could not be opened or if there was
-   insufficient memory to allocate the (de)compression state; errno
-   can be checked to distinguish the two cases (if errno is zero, the
-   zlib error is Z_MEM_ERROR).  */
-
-ZEXTERN gzFile ZEXPORT gzdopen  OF((int fd, const char *mode));
-/*
-     gzdopen() associates a gzFile with the file descriptor fd.  File
-   descriptors are obtained from calls like open, dup, creat, pipe or
-   fileno (in the file has been previously opened with fopen).
-   The mode parameter is as in gzopen.
-     The next call of gzclose on the returned gzFile will also close the
-   file descriptor fd, just like fclose(fdopen(fd), mode) closes the file
-   descriptor fd. If you want to keep fd open, use gzdopen(dup(fd), mode).
-     gzdopen returns NULL if there was insufficient memory to allocate
-   the (de)compression state.
-*/
-
-ZEXTERN int ZEXPORT gzsetparams OF((gzFile file, int level, int strategy));
-/*
-     Dynamically update the compression level or strategy. See the description
-   of deflateInit2 for the meaning of these parameters.
-     gzsetparams returns Z_OK if success, or Z_STREAM_ERROR if the file was not
-   opened for writing.
-*/
-
-ZEXTERN int ZEXPORT    gzread  OF((gzFile file, voidp buf, unsigned len));
-/*
-     Reads the given number of uncompressed bytes from the compressed file.
-   If the input file was not in gzip format, gzread copies the given number
-   of bytes into the buffer.
-     gzread returns the number of uncompressed bytes actually read (0 for
-   end of file, -1 for error). */
-
-ZEXTERN int ZEXPORT    gzwrite OF((gzFile file,
-                                   voidpc buf, unsigned len));
-/*
-     Writes the given number of uncompressed bytes into the compressed file.
-   gzwrite returns the number of uncompressed bytes actually written
-   (0 in case of error).
-*/
-
-ZEXTERN int ZEXPORTVA   gzprintf OF((gzFile file, const char *format, ...));
-/*
-     Converts, formats, and writes the args to the compressed file under
-   control of the format string, as in fprintf. gzprintf returns the number of
-   uncompressed bytes actually written (0 in case of error).  The number of
-   uncompressed bytes written is limited to 4095. The caller should assure that
-   this limit is not exceeded. If it is exceeded, then gzprintf() will return
-   return an error (0) with nothing written. In this case, there may also be a
-   buffer overflow with unpredictable consequences, which is possible only if
-   zlib was compiled with the insecure functions sprintf() or vsprintf()
-   because the secure snprintf() or vsnprintf() functions were not available.
-*/
-
-ZEXTERN int ZEXPORT gzputs OF((gzFile file, const char *s));
-/*
-      Writes the given null-terminated string to the compressed file, excluding
-   the terminating null character.
-      gzputs returns the number of characters written, or -1 in case of error.
-*/
-
-ZEXTERN char * ZEXPORT gzgets OF((gzFile file, char *buf, int len));
-/*
-      Reads bytes from the compressed file until len-1 characters are read, or
-   a newline character is read and transferred to buf, or an end-of-file
-   condition is encountered.  The string is then terminated with a null
-   character.
-      gzgets returns buf, or Z_NULL in case of error.
-*/
-
-ZEXTERN int ZEXPORT    gzputc OF((gzFile file, int c));
-/*
-      Writes c, converted to an unsigned char, into the compressed file.
-   gzputc returns the value that was written, or -1 in case of error.
-*/
-
-ZEXTERN int ZEXPORT    gzgetc OF((gzFile file));
-/*
-      Reads one byte from the compressed file. gzgetc returns this byte
-   or -1 in case of end of file or error.
-*/
-
-ZEXTERN int ZEXPORT    gzungetc OF((int c, gzFile file));
-/*
-      Push one character back onto the stream to be read again later.
-   Only one character of push-back is allowed.  gzungetc() returns the
-   character pushed, or -1 on failure.  gzungetc() will fail if a
-   character has been pushed but not read yet, or if c is -1. The pushed
-   character will be discarded if the stream is repositioned with gzseek()
-   or gzrewind().
-*/
-
-ZEXTERN int ZEXPORT    gzflush OF((gzFile file, int flush));
-/*
-     Flushes all pending output into the compressed file. The parameter
-   flush is as in the deflate() function. The return value is the zlib
-   error number (see function gzerror below). gzflush returns Z_OK if
-   the flush parameter is Z_FINISH and all output could be flushed.
-     gzflush should be called only when strictly necessary because it can
-   degrade compression.
-*/
-
-ZEXTERN z_off_t ZEXPORT    gzseek OF((gzFile file,
-                                      z_off_t offset, int whence));
-/*
-      Sets the starting position for the next gzread or gzwrite on the
-   given compressed file. The offset represents a number of bytes in the
-   uncompressed data stream. The whence parameter is defined as in lseek(2);
-   the value SEEK_END is not supported.
-     If the file is opened for reading, this function is emulated but can be
-   extremely slow. If the file is opened for writing, only forward seeks are
-   supported; gzseek then compresses a sequence of zeroes up to the new
-   starting position.
-
-      gzseek returns the resulting offset location as measured in bytes from
-   the beginning of the uncompressed stream, or -1 in case of error, in
-   particular if the file is opened for writing and the new starting position
-   would be before the current position.
-*/
-
-ZEXTERN int ZEXPORT    gzrewind OF((gzFile file));
-/*
-     Rewinds the given file. This function is supported only for reading.
-
-   gzrewind(file) is equivalent to (int)gzseek(file, 0L, SEEK_SET)
-*/
-
-ZEXTERN z_off_t ZEXPORT    gztell OF((gzFile file));
-/*
-     Returns the starting position for the next gzread or gzwrite on the
-   given compressed file. This position represents a number of bytes in the
-   uncompressed data stream.
-
-   gztell(file) is equivalent to gzseek(file, 0L, SEEK_CUR)
-*/
-
-ZEXTERN int ZEXPORT gzeof OF((gzFile file));
-/*
-     Returns 1 when EOF has previously been detected reading the given
-   input stream, otherwise zero.
-*/
-
-ZEXTERN int ZEXPORT gzdirect OF((gzFile file));
-/*
-     Returns 1 if file is being read directly without decompression, otherwise
-   zero.
-*/
-
-ZEXTERN int ZEXPORT    gzclose OF((gzFile file));
-/*
-     Flushes all pending output if necessary, closes the compressed file
-   and deallocates all the (de)compression state. The return value is the zlib
-   error number (see function gzerror below).
-*/
-
-ZEXTERN const char * ZEXPORT gzerror OF((gzFile file, int *errnum));
-/*
-     Returns the error message for the last error which occurred on the
-   given compressed file. errnum is set to zlib error number. If an
-   error occurred in the file system and not in the compression library,
-   errnum is set to Z_ERRNO and the application may consult errno
-   to get the exact error code.
-*/
-
-ZEXTERN void ZEXPORT gzclearerr OF((gzFile file));
-/*
-     Clears the error and end-of-file flags for file. This is analogous to the
-   clearerr() function in stdio. This is useful for continuing to read a gzip
-   file that is being written concurrently.
-*/
-
-                        /* checksum functions */
-
-/*
-     These functions are not related to compression but are exported
-   anyway because they might be useful in applications using the
-   compression library.
-*/
-
-ZEXTERN uLong ZEXPORT adler32 OF((uLong adler, const Bytef *buf, uInt len));
-/*
-     Update a running Adler-32 checksum with the bytes buf[0..len-1] and
-   return the updated checksum. If buf is NULL, this function returns
-   the required initial value for the checksum.
-   An Adler-32 checksum is almost as reliable as a CRC32 but can be computed
-   much faster. Usage example:
-
-     uLong adler = adler32(0L, Z_NULL, 0);
-
-     while (read_buffer(buffer, length) != EOF) {
-       adler = adler32(adler, buffer, length);
-     }
-     if (adler != original_adler) error();
-*/
-
-ZEXTERN uLong ZEXPORT adler32_combine OF((uLong adler1, uLong adler2,
-                                          z_off_t len2));
-/*
-     Combine two Adler-32 checksums into one.  For two sequences of bytes, seq1
-   and seq2 with lengths len1 and len2, Adler-32 checksums were calculated for
-   each, adler1 and adler2.  adler32_combine() returns the Adler-32 checksum of
-   seq1 and seq2 concatenated, requiring only adler1, adler2, and len2.
-*/
-
-ZEXTERN uLong ZEXPORT crc32   OF((uLong crc, const Bytef *buf, uInt len));
-/*
-     Update a running CRC-32 with the bytes buf[0..len-1] and return the
-   updated CRC-32. If buf is NULL, this function returns the required initial
-   value for the for the crc. Pre- and post-conditioning (one's complement) is
-   performed within this function so it shouldn't be done by the application.
-   Usage example:
-
-     uLong crc = crc32(0L, Z_NULL, 0);
-
-     while (read_buffer(buffer, length) != EOF) {
-       crc = crc32(crc, buffer, length);
-     }
-     if (crc != original_crc) error();
-*/
-
-ZEXTERN uLong ZEXPORT crc32_combine OF((uLong crc1, uLong crc2, z_off_t len2));
-
-/*
-     Combine two CRC-32 check values into one.  For two sequences of bytes,
-   seq1 and seq2 with lengths len1 and len2, CRC-32 check values were
-   calculated for each, crc1 and crc2.  crc32_combine() returns the CRC-32
-   check value of seq1 and seq2 concatenated, requiring only crc1, crc2, and
-   len2.
-*/
-
-
-                        /* various hacks, don't look :) */
-
-/* deflateInit and inflateInit are macros to allow checking the zlib version
- * and the compiler's view of z_stream:
- */
-ZEXTERN int ZEXPORT deflateInit_ OF((z_streamp strm, int level,
-                                     const char *version, int stream_size));
-ZEXTERN int ZEXPORT inflateInit_ OF((z_streamp strm,
-                                     const char *version, int stream_size));
-ZEXTERN int ZEXPORT deflateInit2_ OF((z_streamp strm, int  level, int  method,
-                                      int windowBits, int memLevel,
-                                      int strategy, const char *version,
-                                      int stream_size));
-ZEXTERN int ZEXPORT inflateInit2_ OF((z_streamp strm, int  windowBits,
-                                      const char *version, int stream_size));
-ZEXTERN int ZEXPORT inflateBackInit_ OF((z_streamp strm, int windowBits,
-                                         unsigned char FAR *window,
-                                         const char *version,
-                                         int stream_size));
-#define deflateInit(strm, level) \
-        deflateInit_((strm), (level),       ZLIB_VERSION, sizeof(z_stream))
-#define inflateInit(strm) \
-        inflateInit_((strm),                ZLIB_VERSION, sizeof(z_stream))
-#define deflateInit2(strm, level, method, windowBits, memLevel, strategy) \
-        deflateInit2_((strm),(level),(method),(windowBits),(memLevel),\
-                      (strategy),           ZLIB_VERSION, sizeof(z_stream))
-#define inflateInit2(strm, windowBits) \
-        inflateInit2_((strm), (windowBits), ZLIB_VERSION, sizeof(z_stream))
-#define inflateBackInit(strm, windowBits, window) \
-        inflateBackInit_((strm), (windowBits), (window), \
-        ZLIB_VERSION, sizeof(z_stream))
-
-
-#if !defined(ZUTIL_H) && !defined(NO_DUMMY_DECL)
-    struct internal_state {int dummy;}; /* hack for buggy compilers */
-#endif
-
-ZEXTERN const char   * ZEXPORT zError           OF((int));
-ZEXTERN int            ZEXPORT inflateSyncPoint OF((z_streamp z));
-ZEXTERN const uLongf * ZEXPORT get_crc_table    OF((void));
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* ZLIB_H */
diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/zutil.h b/surface/include/pcl/surface/3rdparty/opennurbs/zutil.h
deleted file mode 100644 (file)
index 22f0559..0000000
+++ /dev/null
@@ -1,269 +0,0 @@
-/* zutil.h -- internal interface and configuration of the compression library
- * Copyright (C) 1995-2005 Jean-loup Gailly.
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* WARNING: this file should *not* be used by applications. It is
-   part of the implementation of the compression library and is
-   subject to change. Applications should only use zlib.h.
- */
-
-/* @(#) $Id$ */
-
-#ifndef ZUTIL_H
-#define ZUTIL_H
-
-#define ZLIB_INTERNAL
-#include "zlib.h"
-
-#ifdef STDC
-#  ifndef _WIN32_WCE
-#    include <stddef.h>
-#  endif
-#  include <string.h>
-#  include <stdlib.h>
-#endif
-#ifdef NO_ERRNO_H
-#   ifdef _WIN32_WCE
-      /* The Microsoft C Run-Time Library for Windows CE doesn't have
-       * errno.  We define it as a global variable to simplify porting.
-       * Its value is always 0 and should not be used.  We rename it to
-       * avoid conflict with other libraries that use the same workaround.
-       */
-#     define errno z_errno
-#   endif
-    extern int errno;
-#else
-#  ifndef _WIN32_WCE
-#    include <errno.h>
-#  endif
-#endif
-
-#ifndef local
-#  define local static
-#endif
-/* compile with -Dlocal if your debugger can't find static symbols */
-
-typedef unsigned char  uch;
-typedef uch FAR uchf;
-typedef unsigned short ush;
-typedef ush FAR ushf;
-typedef unsigned int  ulg;
-
-extern const char * const z_errmsg[10]; /* indexed by 2-zlib_error */
-/* (size given to avoid silly warnings with Visual C++) */
-
-#define ERR_MSG(err) z_errmsg[Z_NEED_DICT-(err)]
-
-#define ERR_RETURN(strm,err) \
-  return (strm->msg = (char*)ERR_MSG(err), (err))
-/* To be used only when the state is known to be valid */
-
-        /* common constants */
-
-#ifndef DEF_WBITS
-#  define DEF_WBITS MAX_WBITS
-#endif
-/* default windowBits for decompression. MAX_WBITS is for compression only */
-
-#if MAX_MEM_LEVEL >= 8
-#  define DEF_MEM_LEVEL 8
-#else
-#  define DEF_MEM_LEVEL  MAX_MEM_LEVEL
-#endif
-/* default memLevel */
-
-#define STORED_BLOCK 0
-#define STATIC_TREES 1
-#define DYN_TREES    2
-/* The three kinds of block type */
-
-#define MIN_MATCH  3
-#define MAX_MATCH  258
-/* The minimum and maximum match lengths */
-
-#define PRESET_DICT 0x20 /* preset dictionary flag in zlib header */
-
-        /* target dependencies */
-
-#if defined(MSDOS) || (defined(WINDOWS) && !defined(WIN32) && !defined(WIN64))
-#  define OS_CODE  0x00
-#  if defined(__TURBOC__) || defined(__BORLANDC__)
-#    if(__STDC__ == 1) && (defined(__LARGE__) || defined(__COMPACT__))
-       /* Allow compilation with ANSI keywords only enabled */
-       void _Cdecl farfree( void *block );
-       void *_Cdecl farmalloc( unsigned int nbytes );
-#    else
-#      include <alloc.h>
-#    endif
-#  else /* MSC or DJGPP */
-#    include <malloc.h>
-#  endif
-#endif
-
-#ifdef AMIGA
-#  define OS_CODE  0x01
-#endif
-
-#if defined(VAXC) || defined(VMS)
-#  define OS_CODE  0x02
-#  define F_OPEN(name, mode) \
-     fopen((name), (mode), "mbc=60", "ctx=stm", "rfm=fix", "mrs=512")
-#endif
-
-#if defined(ATARI) || defined(atarist)
-#  define OS_CODE  0x05
-#endif
-
-#ifdef OS2
-#  define OS_CODE  0x06
-#  ifdef M_I86
-     #include <malloc.h>
-#  endif
-#endif
-
-#if defined(MACOS) || defined(TARGET_OS_MAC)
-#  define OS_CODE  0x07
-#  if defined(__MWERKS__) && __dest_os != __be_os && __dest_os != __win32_os
-#    include <unix.h> /* for fdopen */
-#  else
-#    ifndef fdopen
-#      define fdopen(fd,mode) NULL /* No fdopen() */
-#    endif
-#  endif
-#endif
-
-#ifdef TOPS20
-#  define OS_CODE  0x0a
-#endif
-
-#if defined(WIN32) || defined(WIN64)
-#  ifndef __CYGWIN__  /* Cygwin is Unix, not Win32 */
-#    define OS_CODE  0x0b
-#  endif
-#endif
-
-#ifdef __50SERIES /* Prime/PRIMOS */
-#  define OS_CODE  0x0f
-#endif
-
-#if defined(_BEOS_) || defined(RISCOS)
-#  define fdopen(fd,mode) NULL /* No fdopen() */
-#endif
-
-#if (defined(_MSC_VER) && (_MSC_VER > 600))
-#  if defined(_WIN32_WCE)
-#    define fdopen(fd,mode) NULL /* No fdopen() */
-#    ifndef _PTRDIFF_T_DEFINED
-       typedef int ptrdiff_t;
-#      define _PTRDIFF_T_DEFINED
-#    endif
-#  else
-#    define fdopen(fd,type)  _fdopen(fd,type)
-#  endif
-#endif
-
-        /* common defaults */
-
-#ifndef OS_CODE
-#  define OS_CODE  0x03  /* assume Unix */
-#endif
-
-#ifndef F_OPEN
-#  define F_OPEN(name, mode) fopen((name), (mode))
-#endif
-
-         /* functions */
-
-#if defined(STDC99) || (defined(__TURBOC__) && __TURBOC__ >= 0x550)
-#  ifndef HAVE_VSNPRINTF
-#    define HAVE_VSNPRINTF
-#  endif
-#endif
-#if defined(__CYGWIN__)
-#  ifndef HAVE_VSNPRINTF
-#    define HAVE_VSNPRINTF
-#  endif
-#endif
-#ifndef HAVE_VSNPRINTF
-#  ifdef MSDOS
-     /* vsnprintf may exist on some MS-DOS compilers (DJGPP?),
-        but for now we just assume it doesn't. */
-#    define NO_vsnprintf
-#  endif
-#  ifdef __TURBOC__
-#    define NO_vsnprintf
-#  endif
-#  if defined(WIN32) || defined(WIN64)
-     /* In Win32, vsnprintf is available as the "non-ANSI" _vsnprintf. */
-#    if !defined(vsnprintf) && !defined(NO_vsnprintf)
-#      define vsnprintf _vsnprintf
-#    endif
-#  endif
-#  ifdef __SASC
-#    define NO_vsnprintf
-#  endif
-#endif
-#ifdef VMS
-#  define NO_vsnprintf
-#endif
-
-#if defined(pyr)
-#  define NO_MEMCPY
-#endif
-#if defined(SMALL_MEDIUM) && !defined(_MSC_VER) && !defined(__SC__)
- /* Use our own functions for small and medium model with MSC <= 5.0.
-  * You may have to use the same strategy for Borland C (untested).
-  * The __SC__ check is for Symantec.
-  */
-#  define NO_MEMCPY
-#endif
-#if defined(STDC) && !defined(HAVE_MEMCPY) && !defined(NO_MEMCPY)
-#  define HAVE_MEMCPY
-#endif
-#ifdef HAVE_MEMCPY
-#  ifdef SMALL_MEDIUM /* MSDOS small or medium model */
-#    define zmemcpy _fmemcpy
-#    define zmemcmp _fmemcmp
-#    define zmemzero(dest, len) _fmemset(dest, 0, len)
-#  else
-#    define zmemcpy memcpy
-#    define zmemcmp memcmp
-#    define zmemzero(dest, len) memset(dest, 0, len)
-#  endif
-#else
-   extern void zmemcpy  OF((Bytef* dest, const Bytef* source, uInt len));
-   extern int  zmemcmp  OF((const Bytef* s1, const Bytef* s2, uInt len));
-   extern void zmemzero OF((Bytef* dest, uInt len));
-#endif
-
-/* Diagnostic functions */
-#ifdef DEBUG
-#  include <stdio.h>
-   extern int z_verbose;
-   extern void z_error    OF((char *m));
-#  define Assert(cond,msg) {if(!(cond)) z_error(msg);}
-#  define Trace(x) {if (z_verbose>=0) fprintf x ;}
-#  define Tracev(x) {if (z_verbose>0) fprintf x ;}
-#  define Tracevv(x) {if (z_verbose>1) fprintf x ;}
-#  define Tracec(c,x) {if (z_verbose>0 && (c)) fprintf x ;}
-#  define Tracecv(c,x) {if (z_verbose>1 && (c)) fprintf x ;}
-#else
-#  define Assert(cond,msg)
-#  define Trace(x)
-#  define Tracev(x)
-#  define Tracevv(x)
-#  define Tracec(c,x)
-#  define Tracecv(c,x)
-#endif
-
-
-voidpf zcalloc OF((voidpf opaque, unsigned items, unsigned size));
-void   zcfree  OF((voidpf opaque, voidpf ptr));
-
-#define ZALLOC(strm, items, size) \
-           (*((strm)->zalloc))((strm)->opaque, (items), (size))
-#define ZFREE(strm, addr)  (*((strm)->zfree))((strm)->opaque, (voidpf)(addr))
-#define TRY_FREE(s, p) {if (p) ZFREE(s, p);}
-
-#endif /* ZUTIL_H */
index c0f590bbaa9476c58a0656369f81323b46497a7e..7fbbbf2132b30979fc8f8fcb76e0024b75c4d617 100644 (file)
@@ -126,13 +126,13 @@ namespace pcl
       baseBSplines = new BSplineComponents[functionCount];
 
       baseFunction = PPolynomial< Degree >::BSpline();
-      for( int i=0 ; i<=Degree ; i++ ) baseBSpline[i] = Polynomial< Degree >::BSplineComponent( i ).shift( double(-(Degree+1)/2) + i - 0.5 );
+      for( int i=0 ; i<=Degree ; i++ ) baseBSpline[i] = Polynomial< Degree >::BSplineComponent( i ).shift( static_cast<double>(-(Degree+1)/2) + i - 0.5 );
       dBaseFunction = baseFunction.derivative();
       StartingPolynomial< Degree > sPolys[Degree+3];
 
       for( int i=0 ; i<Degree+3 ; i++ )
       {
-        sPolys[i].start = double(-(Degree+1)/2) + i - 1.5;
+        sPolys[i].start = static_cast<double>(-(Degree+1)/2) + i - 1.5;
         sPolys[i].p *= 0;
         if(         i<=Degree   )  sPolys[i].p += baseBSpline[i  ].shift( -1 );
         if( i>=1 && i<=Degree+1 )  sPolys[i].p += baseBSpline[i-1];
@@ -141,7 +141,7 @@ namespace pcl
       leftBaseFunction.set( sPolys , Degree+3 );
       for( int i=0 ; i<Degree+3 ; i++ )
       {
-        sPolys[i].start = double(-(Degree+1)/2) + i - 0.5;
+        sPolys[i].start = static_cast<double>(-(Degree+1)/2) + i - 0.5;
         sPolys[i].p *= 0;
         if(         i<=Degree   )  sPolys[i].p += baseBSpline[i  ];
         if( i>=1 && i<=Degree+1 )  sPolys[i].p += baseBSpline[i-1].shift( 1 );
@@ -179,18 +179,15 @@ namespace pcl
       int fullSize = functionCount*functionCount;
       if( flags & VV_DOT_FLAG )
       {
-        vvDotTable = new Real[size];
-        memset( vvDotTable , 0 , sizeof(Real)*size );
+        vvDotTable = new Real[size]{};
       }
       if( flags & DV_DOT_FLAG )
       {
-        dvDotTable = new Real[fullSize];
-        memset( dvDotTable , 0 , sizeof(Real)*fullSize );
+        dvDotTable = new Real[fullSize]{};
       }
       if( flags & DD_DOT_FLAG )
       {
-        ddDotTable = new Real[size];
-        memset( ddDotTable , 0 , sizeof(Real)*size );
+        ddDotTable = new Real[size]{};
       }
       double vvIntegrals[Degree+1][Degree+1];
       double vdIntegrals[Degree+1][Degree  ];
@@ -294,7 +291,11 @@ namespace pcl
     {
       if (flags & VV_DOT_FLAG) {
         delete[] vvDotTable ; vvDotTable = NULL;
+      }
+      if (flags & DV_DOT_FLAG) {
         delete[] dvDotTable ; dvDotTable = NULL;
+      }
+      if (flags & DD_DOT_FLAG) {
         delete[] ddDotTable ; ddDotTable = NULL;
       }
     }
@@ -309,12 +310,12 @@ namespace pcl
       //   (start)/(sampleCount-1) >_start && (start-1)/(sampleCount-1)<=_start
       // => start > _start * (sampleCount-1 ) && start <= _start*(sampleCount-1) + 1
       // => _start * (sampleCount-1) + 1 >= start > _start * (sampleCount-1)
-      start = int( floor( _start * (sampleCount-1) + 1 ) );
+      start = static_cast<int>( floor( _start * (sampleCount-1) + 1 ) );
       if( start<0 ) start = 0;
       //   (end)/(sampleCount-1)<_end && (end+1)/(sampleCount-1)>=_end
       // => end < _end * (sampleCount-1 ) && end >= _end*(sampleCount-1) - 1
       // => _end * (sampleCount-1) > end >= _end * (sampleCount-1) - 1
-      end = int( ceil( _end * (sampleCount-1) - 1 ) );
+      end = static_cast<int>( ceil( _end * (sampleCount-1) - 1 ) );
       if( end>=sampleCount ) end = sampleCount-1;
     }
     template<int Degree,class Real>
@@ -339,7 +340,7 @@ namespace pcl
         }
         for( int j=0 ; j<sampleCount ; j++ )
         {
-          double x=double(j)/(sampleCount-1);
+          double x=static_cast<double>(j)/(sampleCount-1);
           if(flags &   VALUE_FLAG){ valueTables[j*functionCount+i]=Real( function(x));}
           if(flags & D_VALUE_FLAG){dValueTables[j*functionCount+i]=Real(dFunction(x));}
         }
@@ -359,7 +360,7 @@ namespace pcl
         else                           {dFunction=baseFunctions[i].derivative();}
 
         for(int j=0;j<sampleCount;j++){
-          double x=double(j)/(sampleCount-1);
+          double x=static_cast<double>(j)/(sampleCount-1);
           if(flags &   VALUE_FLAG){ valueTables[j*functionCount+i]=Real( function(x));}
           if(flags & D_VALUE_FLAG){dValueTables[j*functionCount+i]=Real(dFunction(x));}
         }
index 187eba0e5cac94a4d280da14fbf35c10e2d29a59..e48b0da4374fe922439ad2b41057b580ec9cf5fc 100644 (file)
@@ -48,9 +48,9 @@ namespace pcl
   namespace poisson
   {
 
-    const Real MATRIX_ENTRY_EPSILON = Real(0);
-    const Real EPSILON=Real(1e-6);
-    const Real ROUND_EPS=Real(1e-5);
+    constexpr Real MATRIX_ENTRY_EPSILON = Real(0);
+    constexpr Real EPSILON=Real(1e-6);
+    constexpr Real ROUND_EPS = Real(1e-5);
 
     void atomicOr(volatile int& dest, int value)
     {
@@ -736,7 +736,7 @@ namespace pcl
       Real w;
       node->centerAndWidth( center , w );
       width=w;
-      const double SAMPLE_SCALE = 1. / ( 0.125 * 0.125 + 0.75 * 0.75 + 0.125 * 0.125 );
+      constexpr double SAMPLE_SCALE = 1. / ( 0.125 * 0.125 + 0.75 * 0.75 + 0.125 * 0.125 );
 
       for( int i=0 ; i<DIMENSION ; i++ )
       {
index 1c3601b3bfc1989e4884d82775fc2ff4ea91b781..1be6fc857771fcd72d36d6ce1a1115bf3dcfcdba 100644 (file)
@@ -77,10 +77,7 @@ namespace pcl
       Eigen::Matrix3f KinectVGAProjectionMatrix, KinectSXGAProjectionMatrix;
 
       /** \brief Constructor. */
-      BilateralUpsampling () 
-        : window_size_ (5)
-        , sigma_color_ (15.0f)
-        , sigma_depth_ (0.5f)
+      BilateralUpsampling ()
       {
         KinectVGAProjectionMatrix << 525.0f, 0.0f, 320.0f,
                                      0.0f, 525.0f, 240.0f,
@@ -148,8 +145,8 @@ namespace pcl
       computeDistances (Eigen::MatrixXf &val_exp_depth, Eigen::VectorXf &val_exp_rgb);
 
     private:
-      int window_size_;
-      float sigma_color_, sigma_depth_;
+      int window_size_{5};
+      float sigma_color_{15.0f}, sigma_depth_{0.5f};
       Eigen::Matrix3f projection_matrix_, unprojection_matrix_;
 
     public:
index dc7ab370251b5d298bbaaec585ce5c21260a91c8..65aeb585b3e25fc16c8ab56e8e8ff3663ecdcf44 100644 (file)
@@ -71,9 +71,7 @@ namespace pcl
       using PointCloudConstPtr = typename PointCloud::ConstPtr;
 
       /** \brief Empty constructor. */
-      ConcaveHull () : alpha_ (0), keep_information_ (false), voronoi_centers_ (), dim_(0)
-      {
-      };
+      ConcaveHull () = default;
       
       /** \brief Empty destructor */
       ~ConcaveHull () override = default;
@@ -189,18 +187,18 @@ namespace pcl
       /** \brief The method accepts facets only if the distance from any vertex to the facet->center 
         * (center of the voronoi cell) is smaller than alpha 
         */
-      double alpha_;
+      double alpha_{0.0};
 
       /** \brief If set to true, the reconstructed point cloud describing the hull is obtained from 
         * the original input cloud by performing a nearest neighbor search from Qhull output. 
         */
-      bool keep_information_;
+      bool keep_information_{false};
 
       /** \brief the centers of the voronoi cells */
-      PointCloudPtr voronoi_centers_;
+      PointCloudPtr voronoi_centers_{nullptr};
       
       /** \brief the dimensionality of the concave hull */
-      int dim_;
+      int dim_{0};
 
       /** \brief vector containing the point cloud indices of the convex hull points. */
       pcl::PointIndices hull_indices_;
index d763eaeedd99644f1f4117077e92dbfac7c94c9d..330a4b80e51e27fded2b5444e46c5421943e7d86 100644 (file)
@@ -88,12 +88,8 @@ namespace pcl
       using PointCloudConstPtr = typename PointCloud::ConstPtr;
 
       /** \brief Empty constructor. */
-      ConvexHull () : compute_area_ (false), total_area_ (0), total_volume_ (0), dimension_ (0),
-                      projection_angle_thresh_ (std::cos (0.174532925) ), qhull_flags ("qhull "),
-                      x_axis_ (1.0, 0.0, 0.0), y_axis_ (0.0, 1.0, 0.0), z_axis_ (0.0, 0.0, 1.0)
-      {
-      }
-      
+      ConvexHull() = default;
+
       /** \brief Empty destructor */
       ~ConvexHull () override = default;
 
@@ -237,31 +233,31 @@ namespace pcl
       }
 
       /* \brief True if we should compute the area and volume of the convex hull. */
-      bool compute_area_;
+      bool compute_area_{false};
 
       /* \brief The area of the convex hull. */
-      double total_area_;
+      double total_area_{0.0};
 
       /* \brief The volume of the convex hull (only for 3D hulls, zero for 2D). */
-      double total_volume_;
+      double total_volume_{0.0};
       
       /** \brief The dimensionality of the concave hull (2D or 3D). */
-      int dimension_;
+      int dimension_{0};
 
       /** \brief How close can a 2D plane's normal be to an axis to make projection problematic. */
-      double projection_angle_thresh_;
+      double projection_angle_thresh_{std::cos (0.174532925)};
 
       /** \brief Option flag string to be used calling qhull. */
-      std::string qhull_flags;
+      std::string qhull_flags{"qhull "};
 
       /* \brief x-axis - for checking valid projections. */
-      const Eigen::Vector3d x_axis_;
+      const Eigen::Vector3d x_axis_{1.0, 0.0, 0.0};
 
       /* \brief y-axis - for checking valid projections. */
-      const Eigen::Vector3d y_axis_;
+      const Eigen::Vector3d y_axis_{0.0, 1.0, 0.0};
 
       /* \brief z-axis - for checking valid projections. */
-      const Eigen::Vector3d z_axis_;
+      const Eigen::Vector3d z_axis_{0.0, 0.0, 1.0};
 
       /* \brief vector containing the point cloud indices of the convex hull points. */
       pcl::PointIndices hull_indices_;
index e2d1b920332226e54323ccdc1b0bf8d9939a6abb..0f6530e914016b2fc32f6507e6975ac67414381d 100644 (file)
@@ -87,17 +87,6 @@ namespace pcl
       float
       area (const Indices& vertices);
 
-      /** \brief Compute the signed area of a polygon.
-        * \param[in] vertices the vertices representing the polygon
-        */
-      template <typename T = pcl::index_t, std::enable_if_t<!std::is_same<T, std::uint32_t>::value, pcl::index_t> = 0>
-      PCL_DEPRECATED(1, 14, "This method creates a useless copy of the vertices vector. Use  area method which accepts Indices instead")
-      float
-      area (const std::vector<std::uint32_t>& vertices)
-      {
-        return area(Indices (vertices.cbegin(), vertices.cend()));
-      }
-
       /** \brief Check if the triangle (u,v,w) is an ear. 
         * \param[in] u the first triangle vertex 
         * \param[in] v the second triangle vertex 
@@ -107,20 +96,6 @@ namespace pcl
       bool
       isEar (int u, int v, int w, const Indices& vertices);
 
-      /** \brief Check if the triangle (u,v,w) is an ear. 
-        * \param[in] u the first triangle vertex 
-        * \param[in] v the second triangle vertex 
-        * \param[in] w the third triangle vertex 
-        * \param[in] vertices a set of input vertices
-        */
-      template <typename T = pcl::index_t, std::enable_if_t<!std::is_same<T, std::uint32_t>::value, pcl::index_t> = 0>
-      PCL_DEPRECATED(1, 14, "This method creates a useless copy of the vertices vector. Use  isEar method which accepts Indices instead")
-      bool
-      isEar (int u, int v, int w, const std::vector<std::uint32_t>& vertices)
-      {
-        return isEar(u, v, w, Indices (vertices.cbegin(), vertices.cend()));
-      }
-
       /** \brief Check if p is inside the triangle (u,v,w). 
         * \param[in] u the first triangle vertex 
         * \param[in] v the second triangle vertex 
index 27be42ccacc3fa1503337254188fe4b863e67a0c..9a3cdbbd3f27eea36e6c0ef221a6bfaf80381d6b 100644 (file)
@@ -123,6 +123,7 @@ namespace pcl
   /** \brief GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points
     * based on local 2D projections. It assumes locally smooth surfaces and relatively smooth transitions between
     * areas with different point densities.
+    * \tparam PointInT Point type must have XYZ and normal information, for example `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal`
     * \author Zoltan Csaba Marton
     * \ingroup surface
     */
@@ -154,28 +155,7 @@ namespace pcl
       };
     
       /** \brief Empty constructor. */
-      GreedyProjectionTriangulation () : 
-        mu_ (0), 
-        search_radius_ (0), // must be set by user
-        nnn_ (100),
-        minimum_angle_ (M_PI/18), // 10 degrees
-        maximum_angle_ (2*M_PI/3), // 120 degrees
-        eps_angle_(M_PI/4), //45 degrees,
-        consistent_(false), 
-        consistent_ordering_ (false),
-        angles_ (),
-        R_ (),
-        is_current_free_ (false),
-        current_index_ (),
-        prev_is_ffn_ (false),
-        prev_is_sfn_ (false),
-        next_is_ffn_ (false),
-        next_is_sfn_ (false),
-        changed_1st_fn_ (false),
-        changed_2nd_fn_ (false),
-        new2boundary_ (),
-        already_connected_ (false)
-      {};
+      GreedyProjectionTriangulation () = default;
 
       /** \brief Set the multiplier of the nearest neighbor distance to obtain the final search radius for each point
        *  (this will make the algorithm adapt to different point densities in the cloud).
@@ -287,28 +267,28 @@ namespace pcl
 
     protected:
       /** \brief The nearest neighbor distance multiplier to obtain the final search radius. */
-      double mu_;
+      double mu_{0.0};
 
       /** \brief The nearest neighbors search radius for each point and the maximum edge length. */
-      double search_radius_;
+      double search_radius_{0.0};
 
       /** \brief The maximum number of nearest neighbors accepted by searching. */
-      int nnn_;
+      int nnn_{100};
 
       /** \brief The preferred minimum angle for the triangles. */
-      double minimum_angle_;
+      double minimum_angle_{M_PI/18};
 
       /** \brief The maximum angle for the triangles. */
-      double maximum_angle_;
+      double maximum_angle_{2*M_PI/3};
 
       /** \brief Maximum surface angle. */
-      double eps_angle_;
+      double eps_angle_{M_PI/4};
 
       /** \brief Set this to true if the normals of the input are consistently oriented. */
-      bool consistent_;
+      bool consistent_{false};
       
       /** \brief Set this to true if the output triangle vertices should be consistently oriented. */
-      bool consistent_ordering_;
+      bool consistent_ordering_{false};
 
      private:
       /** \brief Struct for storing the angles to nearest neighbors **/
@@ -323,8 +303,8 @@ namespace pcl
       /** \brief Struct for storing the edges starting from a fringe point **/
       struct doubleEdge
       {
-        doubleEdge () : index (0) {}
-        int index;
+        doubleEdge () = default;
+        int index{0};
         Eigen::Vector2f first;
         Eigen::Vector2f second;
       };
@@ -332,50 +312,50 @@ namespace pcl
       // Variables made global to decrease the number of parameters to helper functions
 
       /** \brief Temporary variable to store a triangle (as a set of point indices) **/
-      pcl::Vertices triangle_;
+      pcl::Vertices triangle_{};
       /** \brief Temporary variable to store point coordinates **/
-      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > coords_;
+      std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > coords_{};
 
       /** \brief A list of angles to neighbors **/
-      std::vector<nnAngle> angles_;
+      std::vector<nnAngle> angles_{};
       /** \brief Index of the current query point **/
-      pcl::index_t R_;
+      pcl::index_t R_{};
       /** \brief List of point states **/
-      std::vector<int> state_;
+      std::vector<int> state_{};
       /** \brief List of sources **/
-      pcl::Indices source_;
+      pcl::Indices source_{};
       /** \brief List of fringe neighbors in one direction **/
-      pcl::Indices ffn_;
+      pcl::Indices ffn_{};
       /** \brief List of fringe neighbors in other direction **/
-      pcl::Indices sfn_;
+      pcl::Indices sfn_{};
       /** \brief Connected component labels for each point **/
-      std::vector<int> part_;
+      std::vector<int> part_{};
       /** \brief Points on the outer edge from which the mesh has to be grown **/
-      std::vector<int> fringe_queue_;
+      std::vector<int> fringe_queue_{};
 
       /** \brief Flag to set if the current point is free **/
-      bool is_current_free_;
+      bool is_current_free_{false};
       /** \brief Current point's index **/
-      pcl::index_t current_index_;
+      pcl::index_t current_index_{};
       /** \brief Flag to set if the previous point is the first fringe neighbor **/
-      bool prev_is_ffn_;
+      bool prev_is_ffn_{false};
       /** \brief Flag to set if the next point is the second fringe neighbor **/
-      bool prev_is_sfn_;
+      bool prev_is_sfn_{false};
       /** \brief Flag to set if the next point is the first fringe neighbor **/
-      bool next_is_ffn_;
+      bool next_is_ffn_{false};
       /** \brief Flag to set if the next point is the second fringe neighbor **/
-      bool next_is_sfn_;
+      bool next_is_sfn_{false};
       /** \brief Flag to set if the first fringe neighbor was changed **/
-      bool changed_1st_fn_;
+      bool changed_1st_fn_{false};
       /** \brief Flag to set if the second fringe neighbor was changed **/
-      bool changed_2nd_fn_;
+      bool changed_2nd_fn_{false};
       /** \brief New boundary point **/
-      pcl::index_t new2boundary_;
+      pcl::index_t new2boundary_{};
       
       /** \brief Flag to set if the next neighbor was already connected in the previous step.
         * To avoid inconsistency it should not be connected again.
         */
-      bool already_connected_; 
+      bool already_connected_{false}
 
       /** \brief Point coordinates projected onto the plane defined by the point normal **/
       Eigen::Vector3f proj_qp_;
index e1ca758c2b3e3b21fa6abd1b926f5d5af67c3c6a..77142c50006020c68500d50a9f1fafb61a504116 100644 (file)
@@ -318,7 +318,7 @@ namespace pcl
       getDataPtsUnion (const Eigen::Vector3i &index, pcl::Indices &pt_union_indices);
 
       /** \brief Given the index of a cell, exam it's up, left, front edges, and add
-        * the vectices to m_surface list.the up, left, front edges only share 4
+        * the vertices to m_surface list.the up, left, front edges only share 4
         * points, we first get the vectors at these 4 points and exam whether those
         * three edges are intersected by the surface \param index the input index
         * \param pt_union_indices the union of input data points within the cell and padding cells
@@ -399,7 +399,7 @@ namespace pcl
 
       /** \brief Test whether the edge is intersected by the surface by 
         * doing the dot product of the vector at two end points. Also test 
-        * whether the edge is intersected by the maximum surface by examing 
+        * whether the edge is intersected by the maximum surface by examinin
         * the 2nd derivative of the intersection point 
         * \param end_pts the two points of the edge
         * \param vect_at_end_pts 
index bb807abf65b567dd97bf31b0e6f9a7fa7ff1d775..346daad24b6becb66974b28235d0444e902b6c83 100644 (file)
@@ -249,7 +249,7 @@ pcl::ConcaveHull<PointInT>::performReconstruction (PointCloud &alpha_shape, std:
   int max_vertex_id = 0;
   FORALLvertices
   {
-    if (vertex->id + 1 > unsigned (max_vertex_id))
+    if (vertex->id + 1 > static_cast<unsigned>(max_vertex_id))
       max_vertex_id = vertex->id + 1;
   }
 
index aa36cdd9efb939069eaf40d855920752fbb0567c..47d7e80d82c187a15d4c511fc7b7b5c74020270c 100644 (file)
@@ -136,7 +136,7 @@ pcl::ConvexHull<PointInT>::performReconstruction2D (PointCloud &hull, std::vecto
   // output from qh_produce_output(), use NULL to skip qh_produce_output()
   FILE *outfile = nullptr;
 
-  if (compute_area_)
+  if (compute_area_ && pcl::console::isVerbosityLevelEnabled(pcl::console::L_DEBUG))
     outfile = stderr;
 
   // option flags for qhull, see qh_opt.htm
@@ -299,7 +299,7 @@ pcl::ConvexHull<PointInT>::performReconstruction3D (
   // output from qh_produce_output(), use NULL to skip qh_produce_output()
   FILE *outfile = nullptr;
 
-  if (compute_area_)
+  if (compute_area_ && pcl::console::isVerbosityLevelEnabled(pcl::console::L_DEBUG))
     outfile = stderr;
 
   // option flags for qhull, see qh_opt.htm
index bcd87a7037372e7b728f336125a341dff27d64f9..5f6c4bd449e4a2ca83594a0175ade6a2711a8735 100644 (file)
@@ -134,7 +134,7 @@ pcl::GreedyProjectionTriangulation<PointInT>::reconstructPolygons (std::vector<p
   }
 
   // Initializing
-  int is_free=0, nr_parts=0, increase_nnn4fn=0, increase_nnn4s=0, increase_dist=0, nr_touched = 0;
+  int is_free=0, nr_parts=0, increase_nnn4fn=0, increase_nnn4s=0, increase_dist=0;
   angles_.resize(nnn_);
   std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > uvn_nn (nnn_);
   Eigen::Vector2f uvn_s;
@@ -909,10 +909,6 @@ pcl::GreedyProjectionTriangulation<PointInT>::reconstructPolygons (std::vector<p
           prev_is_sfn_ = (sfn_[current_index_] == angles_[*(it-1)].index) && (!gaps[*(it-1)]);
           next_is_ffn_ = (ffn_[current_index_] == angles_[*(it+1)].index) && (!gaps[*it]);
           next_is_sfn_ = (sfn_[current_index_] == angles_[*(it+1)].index) && (!gaps[*it]);
-          if (!prev_is_ffn_ && !next_is_sfn_ && !prev_is_sfn_ && !next_is_ffn_)
-          {
-            nr_touched++;
-          }
         }
                                    
         if (gaps[*it])
index cf4a282135f8ff6623d1eb92d21f9a25822d7bf7..c5e232fa606a757a1189d667b03b4fab6568c541 100644 (file)
@@ -319,7 +319,11 @@ pcl::GridProjection<PointNT>::getProjectionWithPlaneFit (const Eigen::Vector4f &
   Eigen::Matrix3f covariance_matrix;
   Eigen::Vector4f xyz_centroid;
 
-  computeMeanAndCovarianceMatrix (*data_, pt_union_indices, covariance_matrix, xyz_centroid);
+  if (computeMeanAndCovarianceMatrix (*data_, pt_union_indices, covariance_matrix, xyz_centroid) == 0) {
+    PCL_ERROR("[pcl::GridProjection::getProjectionWithPlaneFit] cloud or indices are empty!\n");
+    projection = p;
+    return;
+  }
 
   // Get the plane normal
   EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value;
@@ -640,7 +644,7 @@ pcl::GridProjection<PointNT>::reconstructPolygons (std::vector<pcl::Vertices> &p
       cell_data.data_indices.push_back (cp);
       getCellCenterFromIndex (index_3d, cell_data.pt_on_surface);
       cell_hash_map_[index_1d] = cell_data;
-      occupied_cell_list_[index_1d] = 1;
+      occupied_cell_list_[index_1d] = true;
     }
     else
     {
@@ -651,7 +655,6 @@ pcl::GridProjection<PointNT>::reconstructPolygons (std::vector<pcl::Vertices> &p
   }
 
   Eigen::Vector3i index;
-  int numOfFilledPad = 0;
 
   for (int i = 0; i < data_size_; ++i)
   {
@@ -665,7 +668,6 @@ pcl::GridProjection<PointNT>::reconstructPolygons (std::vector<pcl::Vertices> &p
         if (occupied_cell_list_[getIndexIn1D (index)])
         {
           fillPad (index);
-          numOfFilledPad++;
         }
       }
     }
index 84f9304cc4e229428a7dee49e452b7f41cf83b6c..a70f16c5c20028a112c6b08b33f0b828b392011f 100644 (file)
@@ -243,9 +243,9 @@ pcl::MarchingCubes<PointNT>::performReconstruction (pcl::PointCloud<PointNT> &po
   voxelizeData ();
 
   // preallocate memory assuming a hull. suppose 6 point per voxel
-  double size_reserve = std::min((double) intermediate_cloud.points.max_size (),
-      2.0 * 6.0 * (double) (res_y_*res_z_ + res_x_*res_z_ + res_x_*res_y_));
-  intermediate_cloud.reserve ((std::size_t) size_reserve);
+  double size_reserve = std::min(static_cast<double>(intermediate_cloud.points.max_size ()),
+      2.0 * 6.0 * static_cast<double>(res_y_*res_z_ + res_x_*res_z_ + res_x_*res_y_));
+  intermediate_cloud.reserve (static_cast<std::size_t>(size_reserve));
 
   for (int x = 1; x < res_x_-1; ++x)
     for (int y = 1; y < res_y_-1; ++y)
index 89692b521a3e7f7e75e5048ddc680fb9d9291a81..3c8529c978ce8af6951c09e92e982096d68e94ad 100644 (file)
@@ -99,7 +99,7 @@ pcl::MarchingCubesRBF<PointNT>::voxelizeData ()
              c_it != centers.end (); ++c_it, ++w_it)
           f += *w_it * kernel (*c_it, point);
 
-        grid_[x * res_y_*res_z_ + y * res_z_ + z] = float (f);
+        grid_[x * res_y_*res_z_ + y * res_z_ + z] = static_cast<float>(f);
       }
 }
 
index 329a3f2c375d65719fb2c6113a118ae0bee176c4..79ec961e0b0b6d7394bc61bf171b7d786216a575 100644 (file)
 #ifndef PCL_SURFACE_IMPL_MLS_H_
 #define PCL_SURFACE_IMPL_MLS_H_
 
-#include <pcl/type_traits.h>
-#include <pcl/surface/mls.h>
+#include <pcl/common/centroid.h>
 #include <pcl/common/common.h> // for getMinMax3D
 #include <pcl/common/copy_point.h>
-#include <pcl/common/centroid.h>
 #include <pcl/common/eigen.h>
 #include <pcl/search/kdtree.h> // for KdTree
 #include <pcl/search/organized.h> // for OrganizedNeighbor
+#include <pcl/surface/mls.h>
+#include <pcl/type_traits.h>
 
 #include <Eigen/Geometry> // for cross
 #include <Eigen/LU> // for inverse
 
+#include <memory>
+
 #ifdef _OPENMP
 #include <omp.h>
 #endif
@@ -117,7 +119,7 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::process (PointCloudOut &output)
       std::random_device rd;
       rng_.seed (rd());
       const double tmp = search_radius_ / 2.0;
-      rng_uniform_distribution_.reset (new std::uniform_real_distribution<> (-tmp, tmp));
+      rng_uniform_distribution_ = std::make_unique<std::uniform_real_distribution<>> (-tmp, tmp);
 
       break;
     }
@@ -388,7 +390,7 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::performUpsampling (PointCloudOut &
 
       // If the closest point did not have a valid MLS fitting result
       // OR if it is too far away from the sampled point
-      if (mls_results_[input_index].valid == false)
+      if (!mls_results_[input_index].valid)
         continue;
 
       Eigen::Vector3d add_point = (*distinct_cloud_)[dp_i].getVector3fMap ().template cast<double> ();
@@ -425,7 +427,7 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::performUpsampling (PointCloudOut &
 
       // If the closest point did not have a valid MLS fitting result
       // OR if it is too far away from the sampled point
-      if (mls_results_[input_index].valid == false)
+      if (!mls_results_[input_index].valid)
         continue;
 
       Eigen::Vector3d add_point = p.getVector3fMap ().template cast<double> ();
@@ -807,7 +809,7 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::MLSVoxelGrid::MLSVoxelGrid (PointC
                                                                           IndicesPtr &indices,
                                                                           float voxel_size,
                                                                           int dilation_iteration_num) :
-  voxel_grid_ (), data_size_ (), voxel_size_ (voxel_size)
+  voxel_grid_ (),  voxel_size_ (voxel_size)
 {
   pcl::getMinMax3D (*cloud, *indices, bounding_min_, bounding_max_);
   bounding_min_ -= Eigen::Vector4f::Constant(voxel_size_ * (dilation_iteration_num + 1));
index 1b99b91836672fae7fbaa2a06d0423ec6fe83b4e..71b4dc59c74f4b08af4058f3c6bd6195397c267e 100644 (file)
 template <typename PointInT> void
 pcl::OrganizedFastMesh<PointInT>::performReconstruction (pcl::PolygonMesh &output)
 {
+  if (!input_->isOrganized()) {
+    PCL_ERROR("[OrganizedFastMesh::performReconstruction] Input point cloud must be organized but isn't!\n");
+    return;
+  }
   reconstructPolygons (output.polygons);
 
   // Get the field names
@@ -69,6 +73,10 @@ pcl::OrganizedFastMesh<PointInT>::performReconstruction (pcl::PolygonMesh &outpu
 template <typename PointInT> void
 pcl::OrganizedFastMesh<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons)
 {
+  if (!input_->isOrganized()) {
+    PCL_ERROR("[OrganizedFastMesh::performReconstruction] Input point cloud must be organized but isn't!\n");
+    return;
+  }
   reconstructPolygons (polygons);
 }
 
index 46652733359f936f18eeae371d428e206dbe67b9..9e0cd210a901676139343990e9ade45a73aaeb34 100644 (file)
@@ -60,29 +60,7 @@ using namespace pcl;
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointNT>
-pcl::Poisson<PointNT>::Poisson ()
-  : depth_ (8)
-  , min_depth_ (5)
-  , point_weight_ (4)
-  , scale_ (1.1f)
-  , solver_divide_ (8)
-  , iso_divide_ (8)
-  , samples_per_node_ (1.0)
-  , confidence_ (false)
-  , output_polygons_ (false)
-  , no_reset_samples_ (false)
-  , no_clip_tree_ (false)
-  , manifold_ (true)
-  , refine_ (3)
-  , kernel_depth_ (8)
-  , degree_ (2)
-  , non_adaptive_weights_ (false)
-  , show_residual_ (false)
-  , min_iterations_ (8)
-  , solver_accuracy_ (1e-3f)
-  , threads_(1)
-{
-}
+pcl::Poisson<PointNT>::Poisson () = default;
 
 //////////////////////////////////////////////////////////////////////////////////////////////
 template <typename PointNT>
@@ -132,7 +110,7 @@ pcl::Poisson<PointNT>::execute (poisson::CoredVectorMeshData &mesh,
 
   kernel_depth_ = depth_ - 2;
 
-  tree.setBSplineData (depth_, pcl::poisson::Real (1.0 / (1 << depth_)), true);
+  tree.setBSplineData (depth_, static_cast<pcl::poisson::Real>(1.0 / (1 << depth_)), true);
 
   tree.maxMemoryUsage = 0;
 
@@ -202,16 +180,16 @@ pcl::Poisson<PointNT>::performReconstruction (PolygonMesh &output)
 
   // Write output PolygonMesh
   pcl::PointCloud<pcl::PointXYZ> cloud;
-  cloud.resize (int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ()));
+  cloud.resize (static_cast<int>(mesh.outOfCorePointCount () + mesh.inCorePoints.size ()));
   poisson::Point3D<float> p;
-  for (int i = 0; i < int (mesh.inCorePoints.size ()); i++)
+  for (int i = 0; i < static_cast<int>(mesh.inCorePoints.size ()); i++)
   {
     p = mesh.inCorePoints[i];
     cloud[i].x = p.coords[0]*scale+center.coords[0];
     cloud[i].y = p.coords[1]*scale+center.coords[1];
     cloud[i].z = p.coords[2]*scale+center.coords[2];
   }
-  for (int i = int (mesh.inCorePoints.size ()); i < int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ()); i++)
+  for (int i = static_cast<int>(mesh.inCorePoints.size ()); i < static_cast<int>(mesh.outOfCorePointCount () + mesh.inCorePoints.size ()); i++)
   {
     mesh.nextOutOfCorePoint (p);
     cloud[i].x = p.coords[0]*scale+center.coords[0];
@@ -233,7 +211,7 @@ pcl::Poisson<PointNT>::performReconstruction (PolygonMesh &output)
       if (polygon[i].inCore )
         v.vertices[i] = polygon[i].idx;
       else
-        v.vertices[i] = polygon[i].idx + int (mesh.inCorePoints.size ());
+        v.vertices[i] = polygon[i].idx + static_cast<int>(mesh.inCorePoints.size ());
 
     output.polygons[p_i] = v;
   }
@@ -283,16 +261,16 @@ pcl::Poisson<PointNT>::performReconstruction (pcl::PointCloud<PointNT> &points,
 
   // Write output PolygonMesh
   // Write vertices
-  points.resize (int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ()));
+  points.resize (static_cast<int>(mesh.outOfCorePointCount () + mesh.inCorePoints.size ()));
   poisson::Point3D<float> p;
-  for (int i = 0; i < int(mesh.inCorePoints.size ()); i++)
+  for (int i = 0; i < static_cast<int>(mesh.inCorePoints.size ()); i++)
   {
     p = mesh.inCorePoints[i];
     points[i].x = p.coords[0]*scale+center.coords[0];
     points[i].y = p.coords[1]*scale+center.coords[1];
     points[i].z = p.coords[2]*scale+center.coords[2];
   }
-  for (int i = int(mesh.inCorePoints.size()); i < int (mesh.outOfCorePointCount() + mesh.inCorePoints.size ()); i++)
+  for (int i = static_cast<int>(mesh.inCorePoints.size()); i < static_cast<int>(mesh.outOfCorePointCount() + mesh.inCorePoints.size ()); i++)
   {
     mesh.nextOutOfCorePoint (p);
     points[i].x = p.coords[0]*scale+center.coords[0];
@@ -314,7 +292,7 @@ pcl::Poisson<PointNT>::performReconstruction (pcl::PointCloud<PointNT> &points,
       if (polygon[i].inCore )
         v.vertices[i] = polygon[i].idx;
       else
-        v.vertices[i] = polygon[i].idx + int (mesh.inCorePoints.size ());
+        v.vertices[i] = polygon[i].idx + static_cast<int>(mesh.inCorePoints.size ());
 
     polygons[p_i] = v;
   }
index 6ce1afeda851c17bddbda3414584d9fe310e94e4..95ebc342f44e29c27be501541480163fb5957f86 100644 (file)
@@ -851,7 +851,7 @@ pcl::TextureMapping<PointInT>::textureMeshwithMultipleCameras (pcl::TextureMesh
                       // current neighbor is inside triangle and is closer => the corresponding face
                       visibility[indexes_uv_to_points[idxNeighbor].idx_face] = false;
                       cpt_invisible++;
-                      //TODO we could remove the projections of this face from the kd-tree cloud, but I fond it slower, and I need the point to keep ordered to querry UV coordinates later
+                      //TODO we could remove the projections of this face from the kd-tree cloud, but I found it slower, and I need the point to keep ordered to query UV coordinates later
                     }
                   }
                 }
index 97296ad05e6750aa3155dbb85165a1dc61d693ad..c09c0aafa5095d777090e4fbfff8423a67722d4e 100644 (file)
@@ -356,6 +356,7 @@ namespace pcl
     * Lorensen W.E., Cline H.E., "Marching cubes: A high resolution 3d surface construction algorithm",
     * SIGGRAPH '87
     *
+    * \tparam PointNT Use `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal`
     * \author Alexandru E. Ichim
     * \ingroup surface
     */
index f1014a7c928a645c7e2816d52d6274b5a4b06358..7f66bdd960a76b29a882c224acbef9a5b652f9b5 100644 (file)
@@ -45,6 +45,7 @@ namespace pcl
      * from tangent planes, proposed by Hoppe et. al. in:
      * Hoppe H., DeRose T., Duchamp T., MC-Donald J., Stuetzle W., "Surface reconstruction from unorganized points",
      * SIGGRAPH '92
+     * \tparam PointNT Use `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal`
      * \author Alexandru E. Ichim
      * \ingroup surface
      */
index 7a81c7c0fcdf006d93465be54d379a58e7a54e47..8acaed9b8ccc8b671b18ed8baf7f0163a6a42c03 100644 (file)
@@ -49,6 +49,7 @@ namespace pcl
     *
     * \note This algorithm in its current implementation may not be suitable for very
     * large point clouds, due to high memory requirements.
+    * \tparam PointNT Use `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal`
     * \author Alexandru E. Ichim
     * \ingroup surface
     */
index b5cb6080d93fb66aee295a66685a4338148e40f5..8c3a45e1dff81a9ecf887f0a6ea807b1b4dabdbd 100644 (file)
@@ -79,10 +79,10 @@ namespace pcl
     /** \brief Data structure used to store the MLS projection results */
     struct MLSProjectionResults
     {
-      MLSProjectionResults () : u (0), v (0) {}
+      MLSProjectionResults () = default;
 
-      double u;               /**< \brief The u-coordinate of the projected point in local MLS frame. */
-      double v;               /**< \brief The v-coordinate of the projected point in local MLS frame. */
+      double u{0.0};               /**< \brief The u-coordinate of the projected point in local MLS frame. */
+      double v{0.0};               /**< \brief The v-coordinate of the projected point in local MLS frame. */
       Eigen::Vector3d point;  /**< \brief The projected point. */
       Eigen::Vector3d normal; /**< \brief The projected point's normal. */
       PCL_MAKE_ALIGNED_OPERATOR_NEW
@@ -307,20 +307,9 @@ namespace pcl
       MovingLeastSquares () : CloudSurfaceProcessing<PointInT, PointOutT> (),
                               distinct_cloud_ (),
                               tree_ (),
-                              order_ (2),
-                              search_radius_ (0.0),
-                              sqr_gauss_param_ (0.0),
-                              compute_normals_ (false),
+                              
                               upsample_method_ (NONE),
-                              upsampling_radius_ (0.0),
-                              upsampling_step_ (0.0),
-                              desired_num_points_in_radius_ (0),
-                              cache_mls_results_ (true),
-                              projection_method_ (MLSResult::SIMPLE),
-                              threads_ (1),
-                              voxel_size_ (1.0),
-                              dilation_iteration_num_ (0),
-                              nr_coeff_ (),
+                              
                               rng_uniform_distribution_ ()
                               {};
 
@@ -523,28 +512,28 @@ namespace pcl
 
     protected:
       /** \brief The point cloud that will hold the estimated normals, if set. */
-      NormalCloudPtr normals_;
+      NormalCloudPtr normals_{nullptr};
 
       /** \brief The distinct point cloud that will be projected to the MLS surface. */
-      PointCloudInConstPtr distinct_cloud_;
+      PointCloudInConstPtr distinct_cloud_{nullptr};
 
       /** \brief The search method template for indices. */
       SearchMethod search_method_;
 
       /** \brief A pointer to the spatial search object. */
-      KdTreePtr tree_;
+      KdTreePtr tree_{nullptr};
 
       /** \brief The order of the polynomial to be fit. */
-      int order_;
+      int order_{2};
 
       /** \brief The nearest neighbors search radius for each point. */
-      double search_radius_;
+      double search_radius_{0.0};
 
       /** \brief Parameter for distance based weighting of neighbors (search_radius_ * search_radius_ works fine) */
-      double sqr_gauss_param_;
+      double sqr_gauss_param_{0.0};
 
       /** \brief Parameter that specifies whether the normals should be computed for the input cloud or not */
-      bool compute_normals_;
+      bool compute_normals_{false};
 
       /** \brief Parameter that specifies the upsampling method to be used */
       UpsamplingMethod upsample_method_;
@@ -552,33 +541,33 @@ namespace pcl
       /** \brief Radius of the circle in the local point plane that will be sampled
         * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling
         */
-      double upsampling_radius_;
+      double upsampling_radius_{0.0};
 
       /** \brief Step size for the local plane sampling
         * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling
         */
-      double upsampling_step_;
+      double upsampling_step_{0.0};
 
       /** \brief Parameter that specifies the desired number of points within the search radius
         * \note Used only in the case of RANDOM_UNIFORM_DENSITY upsampling
         */
-      int desired_num_points_in_radius_;
+      int desired_num_points_in_radius_{0};
 
       /** \brief True if the mls results for the input cloud should be stored
         * \note This is forced to be true when using upsampling methods VOXEL_GRID_DILATION or DISTINCT_CLOUD.
         */
-      bool cache_mls_results_;
+      bool cache_mls_results_{true};
 
       /** \brief Stores the MLS result for each point in the input cloud
         * \note Used only in the case of VOXEL_GRID_DILATION or DISTINCT_CLOUD upsampling
         */
-      std::vector<MLSResult> mls_results_;
+      std::vector<MLSResult> mls_results_{};
 
       /** \brief Parameter that specifies the projection method to be used. */
-      MLSResult::ProjectionMethod projection_method_;
+      MLSResult::ProjectionMethod projection_method_{MLSResult::SIMPLE};
 
       /** \brief The maximum number of threads the scheduler should use. */
-      unsigned int threads_;
+      unsigned int threads_{1};
 
 
       /** \brief A minimalistic implementation of a voxel grid, necessary for the point cloud upsampling
@@ -587,7 +576,7 @@ namespace pcl
       class MLSVoxelGrid
       {
         public:
-          struct Leaf { Leaf () : valid (true) {} bool valid; };
+          struct Leaf { Leaf () = default; bool valid{true}; };
 
           MLSVoxelGrid (PointCloudInConstPtr& cloud,
                         IndicesPtr &indices,
@@ -633,23 +622,23 @@ namespace pcl
           using HashMap = std::map<std::uint64_t, Leaf>;
           HashMap voxel_grid_;
           Eigen::Vector4f bounding_min_, bounding_max_;
-          std::uint64_t data_size_;
+          std::uint64_t data_size_{0};
           float voxel_size_;
           PCL_MAKE_ALIGNED_OPERATOR_NEW
       };
 
 
       /** \brief Voxel size for the VOXEL_GRID_DILATION upsampling method */
-      float voxel_size_;
+      float voxel_size_{1.0f};
 
       /** \brief Number of dilation steps for the VOXEL_GRID_DILATION upsampling method */
-      int dilation_iteration_num_;
+      int dilation_iteration_num_{0};
 
       /** \brief Number of coefficients, to be computed from the requested order.*/
-      int nr_coeff_;
+      int nr_coeff_{0};
 
-      /** \brief Collects for each point in output the corrseponding point in the input. */
-      PointIndicesPtr corresponding_input_indices_;
+      /** \brief Collects for each point in output the corresponding point in the input. */
+      PointIndicesPtr corresponding_input_indices_{nullptr};
 
       /** \brief Search for the nearest neighbors of a given point using a radius search
         * \param[in] index the index of the query point
index 4aeafec644fae352c502f777fd767351bec72554..3e0810c8e826f41bc0aca152a246cc502f95c141 100644 (file)
@@ -86,20 +86,6 @@ namespace pcl
 
       /** \brief Constructor. Triangulation type defaults to \a QUAD_MESH. */
       OrganizedFastMesh ()
-      : max_edge_length_a_ (0.0f)
-      , max_edge_length_b_ (0.0f)
-      , max_edge_length_c_ (0.0f)
-      , max_edge_length_set_ (false)
-      , max_edge_length_dist_dependent_ (false)
-      , triangle_pixel_size_rows_ (1)
-      , triangle_pixel_size_columns_ (1)
-      , triangulation_type_ (QUAD_MESH)
-      , viewpoint_ (Eigen::Vector3f::Zero ())
-      , store_shadowed_faces_ (false)
-      , cos_angle_tolerance_ (std::abs (std::cos (pcl::deg2rad (12.5f))))
-      , distance_tolerance_ (-1.0f)
-      , distance_dependent_ (false)
-      , use_depth_as_distance_(false)
       {
         check_tree_ = false;
       };
@@ -120,10 +106,7 @@ namespace pcl
         max_edge_length_a_ = a;
         max_edge_length_b_ = b;
         max_edge_length_c_ = c;
-        if ((max_edge_length_a_ + max_edge_length_b_ + max_edge_length_c_) > std::numeric_limits<float>::min())
-          max_edge_length_set_ = true;
-        else
-          max_edge_length_set_ = false;
+        max_edge_length_set_ = (max_edge_length_a_ + max_edge_length_b_ + max_edge_length_c_) > std::numeric_limits<float>::min();
       };
 
       inline void
@@ -231,44 +214,44 @@ namespace pcl
 
     protected:
       /** \brief max length of edge, scalar component */
-      float max_edge_length_a_;
+      float max_edge_length_a_{0.0f};
       /** \brief max length of edge, scalar component */
-      float max_edge_length_b_;
+      float max_edge_length_b_{0.0f};
       /** \brief max length of edge, scalar component */
-      float max_edge_length_c_;
+      float max_edge_length_c_{0.0f};
       /** \brief flag whether or not edges are limited in length */
-      bool max_edge_length_set_;
+      bool max_edge_length_set_{false};
 
       /** \brief flag whether or not max edge length is distance dependent. */
-      bool max_edge_length_dist_dependent_;
+      bool max_edge_length_dist_dependent_{false};
 
       /** \brief size of triangle edges (in pixels) for iterating over rows. */
-      int triangle_pixel_size_rows_;
+      int triangle_pixel_size_rows_{1};
 
       /** \brief size of triangle edges (in pixels) for iterating over columns*/
-      int triangle_pixel_size_columns_;
+      int triangle_pixel_size_columns_{1};
 
       /** \brief Type of meshing scheme (quads vs. triangles, left cut vs. right cut ... */
-      TriangulationType triangulation_type_;
+      TriangulationType triangulation_type_{QUAD_MESH};
 
       /** \brief Viewpoint from which the point cloud has been acquired (in the same coordinate frame as the data). */
-      Eigen::Vector3f viewpoint_;
+      Eigen::Vector3f viewpoint_{Eigen::Vector3f::Zero ()};
 
       /** \brief Whether or not shadowed faces are stored, e.g., for exploration */
-      bool store_shadowed_faces_;
+      bool store_shadowed_faces_{false};
 
       /** \brief (Cosine of the) angle tolerance used when checking whether or not an edge between two points is shadowed. */
-      float cos_angle_tolerance_;
+      float cos_angle_tolerance_{std::abs (std::cos (pcl::deg2rad (12.5f)))};
 
       /** \brief distance tolerance for filtering out shadowed/occluded edges */
-      float distance_tolerance_;
+      float distance_tolerance_{-1.0f};
 
       /** \brief flag whether or not \a distance_tolerance_ is distance dependent (multiplied by the squared distance to the point) or not. */
-      bool distance_dependent_;
+      bool distance_dependent_{false};
 
       /** \brief flag whether or not the points' depths are used instead of measured distances (points' distances to the viewpoint).
           This flag may be set using useDepthAsDistance(true) for (RGB-)Depth cameras to skip computations and gain additional speed up. */
-      bool use_depth_as_distance_;
+      bool use_depth_as_distance_{false};
 
 
       /** \brief Perform the actual polygonal reconstruction.
index 9f1e36e9de4c1b69eceddd18f74ab8635d414448..9fca5b4b34394c26bf5cccf7ce41e7e51e6d7cb0 100644 (file)
@@ -236,28 +236,28 @@ namespace pcl
       getClassName () const override { return ("Poisson"); }
 
     private:
-      int depth_;
-      int min_depth_;
-      float point_weight_;
-      float scale_;
-      int solver_divide_;
-      int iso_divide_;
-      float samples_per_node_;
-      bool confidence_;
-      bool output_polygons_;
-
-      bool no_reset_samples_;
-      bool no_clip_tree_;
-      bool manifold_;
-
-      int refine_;
-      int kernel_depth_;
-      int degree_;
-      bool non_adaptive_weights_;
-      bool show_residual_;
-      int min_iterations_;
-      float solver_accuracy_;
-      int threads_;
+      int depth_{8};
+      int min_depth_{5};
+      float point_weight_{4};
+      float scale_{1.1f};
+      int solver_divide_{8};
+      int iso_divide_{8};
+      float samples_per_node_{1.0};
+      bool confidence_{false};
+      bool output_polygons_{false};
+
+      bool no_reset_samples_{false};
+      bool no_clip_tree_{false};
+      bool manifold_{true};
+
+      int refine_{3};
+      int kernel_depth_{8};
+      int degree_{2};
+      bool non_adaptive_weights_{false};
+      bool show_residual_{false};
+      int min_iterations_{8};
+      float solver_accuracy_{1e-3f};
+      int threads_{1};
 
       template<int Degree> void
       execute (poisson::CoredVectorMeshData &mesh,
index 34ffe7c107238060a7bb893f80c328ae6236b4fe..75ae4308effaa9529132699c4638cedd18ba637c 100644 (file)
@@ -128,7 +128,7 @@ namespace pcl
       using PCLSurfaceBase<PointInT>::getClassName;
 
       /** \brief Constructor. */
-      SurfaceReconstruction () : check_tree_ (true) {}
+      SurfaceReconstruction () = default;
 
       /** \brief Destructor. */
       ~SurfaceReconstruction () override = default;
@@ -153,7 +153,7 @@ namespace pcl
     protected:
       /** \brief A flag specifying whether or not the derived reconstruction
         * algorithm needs the search object \a tree.*/
-      bool check_tree_;
+      bool check_tree_{true};
 
       /** \brief Abstract surface reconstruction method. 
         * \param[out] output the output polygonal mesh 
@@ -197,7 +197,7 @@ namespace pcl
       using PCLSurfaceBase<PointInT>::getClassName;
 
       /** \brief Constructor. */
-      MeshConstruction () : check_tree_ (true) {}
+      MeshConstruction () = default;
 
       /** \brief Destructor. */
       ~MeshConstruction () override = default;
@@ -225,7 +225,7 @@ namespace pcl
     protected:
       /** \brief A flag specifying whether or not the derived reconstruction
         * algorithm needs the search object \a tree.*/
-      bool check_tree_;
+      bool check_tree_{true};
 
       /** \brief Abstract surface reconstruction method. 
         * \param[out] output the output polygonal mesh 
index b7318cc8e4a203f838ffd0a80cbee14e9e4e63b0..2aa8ef9df9fd152839f9382a4f73f92b8b44ef3d 100644 (file)
@@ -64,16 +64,15 @@ namespace pcl
       */
     struct Camera
     {
-      Camera () : focal_length (), focal_length_w (-1), focal_length_h (-1),
-        center_w (-1), center_h (-1), height (), width () {}
+      Camera () = default;
       Eigen::Affine3f pose;
-      double focal_length;
-      double focal_length_w;  // optional
-      double focal_length_h;  // optinoal
-      double center_w;  // optional
-      double center_h;  // optional
-      double height;
-      double width;
+      double focal_length{0.0};
+      double focal_length_w{-1.0};  // optional
+      double focal_length_h{-1.0};  // optinoal
+      double center_w{-1.0};  // optional
+      double center_h{-1.0};  // optional
+      double height{0.0};
+      double width{0.0};
       std::string texture_file;
 
       PCL_MAKE_ALIGNED_OPERATOR_NEW
@@ -83,9 +82,9 @@ namespace pcl
       */
     struct UvIndex
     {
-      UvIndex () : idx_cloud (), idx_face () {}
-      int idx_cloud; // Index of the PointXYZ in the camera's cloud
-      int idx_face; // Face corresponding to that projection
+      UvIndex () = default;
+      int idx_cloud{0}; // Index of the PointXYZ in the camera's cloud
+      int idx_face{0}; // Face corresponding to that projection
     };
     
     using CameraVector = std::vector<Camera, Eigen::aligned_allocator<Camera> >;
@@ -116,10 +115,7 @@ namespace pcl
       using UvIndex = pcl::texture_mapping::UvIndex;
 
       /** \brief Constructor. */
-      TextureMapping () :
-        f_ ()
-      {
-      }
+      TextureMapping () = default;
 
       /** \brief Destructor. */
       ~TextureMapping () = default;
@@ -335,7 +331,7 @@ namespace pcl
 
     protected:
       /** \brief mesh scale control. */
-      float f_;
+      float f_{0.0f};
 
       /** \brief vector field */
       Eigen::Vector3f vector_field_;
@@ -355,7 +351,7 @@ namespace pcl
       mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3);
 
       /** \brief Returns the circumcenter of a triangle and the circle's radius.
-        * \details see http://en.wikipedia.org/wiki/Circumcenter for formulas.
+        * \details see https://en.wikipedia.org/wiki/Circumcenter for formulas.
         * \param[in] p1 first point of the triangle.
         * \param[in] p2 second point of the triangle.
         * \param[in] p3 third point of the triangle.
@@ -406,7 +402,7 @@ namespace pcl
         * \param[in] p1 first point of the triangle.
         * \param[in] p2 second point of the triangle.
         * \param[in] p3 third point of the triangle.
-        * \param[in] pt the querry point.
+        * \param[in] pt the query point.
         */
       inline bool
       checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt);
index 3f9884b2725fa78f68e59dd67d3c2cedfe6cf850..d4232144465572c3586af2df921a80214485dd6b 100644 (file)
@@ -75,7 +75,7 @@ namespace pcl
       performProcessing (pcl::PolygonMesh &output) override;
 
     private:
-      float target_reduction_factor_;
+      float target_reduction_factor_{0.5f};
 
       vtkSmartPointer<vtkPolyData> vtk_polygons_;
   };
index e2edb7710d70f19a503e8bb0aaa08482143f8126..8a68c40f6583c33c4b11f11c4e509cf73fd4c8d1 100644 (file)
@@ -52,15 +52,7 @@ namespace pcl
   {
     public:
       /** \brief Empty constructor that sets the values of the algorithm parameters to the VTK defaults */
-      MeshSmoothingLaplacianVTK ()
-        : num_iter_ (20)
-        , convergence_ (0.0f)
-        , relaxation_factor_ (0.01f)
-        , feature_edge_smoothing_ (false)
-        , feature_angle_ (45.f)
-        , edge_angle_ (15.f)
-        , boundary_smoothing_ (true)
-      {};
+      MeshSmoothingLaplacianVTK () = default;
 
       /** \brief Set the number of iterations for the smoothing filter.
         * \param[in] num_iter the number of iterations
@@ -185,12 +177,12 @@ namespace pcl
       vtkSmartPointer<vtkPolyData> vtk_polygons_;
 
       /// Parameters
-      int num_iter_;
-      float convergence_;
-      float relaxation_factor_;
-      bool feature_edge_smoothing_;
-      float feature_angle_;
-      float edge_angle_;
-      bool boundary_smoothing_;
+      int num_iter_{20};
+      float convergence_{0.0f};
+      float relaxation_factor_{0.01f};
+      bool feature_edge_smoothing_{false};
+      float feature_angle_{45.f};
+      float edge_angle_{15.f};
+      bool boundary_smoothing_{true};
   };
 }
index 220e17baa006b80eddc5a73fef9e6dd3073ade62..f52119d84816442369110d0df6c7873dc2a1a604 100644 (file)
@@ -52,15 +52,7 @@ namespace pcl
   {
     public:
       /** \brief Empty constructor that sets the values of the algorithm parameters to the VTK defaults */
-      MeshSmoothingWindowedSincVTK ()
-        : num_iter_ (20),
-          pass_band_ (0.1f),
-          feature_edge_smoothing_ (false),
-          feature_angle_ (45.f),
-          edge_angle_ (15.f),
-          boundary_smoothing_ (true),
-          normalize_coordinates_ (false)
-      {};
+      MeshSmoothingWindowedSincVTK () = default;
 
       /** \brief Set the number of iterations for the smoothing filter.
         * \param[in] num_iter the number of iterations
@@ -185,12 +177,12 @@ namespace pcl
 
     private:
       vtkSmartPointer<vtkPolyData> vtk_polygons_;
-      int num_iter_;
-      float pass_band_;
-      bool feature_edge_smoothing_;
-      float feature_angle_;
-      float edge_angle_;
-      bool boundary_smoothing_;
-      bool normalize_coordinates_;
+      int num_iter_{20};
+      float pass_band_{0.1f};
+      bool feature_edge_smoothing_{false};
+      float feature_angle_{45.f};
+      float edge_angle_{15.f};
+      bool boundary_smoothing_{true};
+      bool normalize_coordinates_{false};
   };
 }
index 52fe077d27d0915efbb7aefdbb01adaaf410f78e..fee48b56461f710053c76eeb858423e00d5c9b41 100644 (file)
@@ -79,7 +79,7 @@ namespace pcl
       performProcessing (pcl::PolygonMesh &output) override;
 
     private:
-      MeshSubdivisionVTKFilterType filter_type_;
+      MeshSubdivisionVTKFilterType filter_type_{LINEAR};
 
       vtkSmartPointer<vtkPolyData> vtk_polygons_;
   };
diff --git a/surface/src/3rdparty/opennurbs/adler32.c b/surface/src/3rdparty/opennurbs/adler32.c
deleted file mode 100644 (file)
index f9669e8..0000000
+++ /dev/null
@@ -1,149 +0,0 @@
-/* adler32.c -- compute the Adler-32 checksum of a data stream
- * Copyright (C) 1995-2004 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* @(#) $Id$ */
-
-#define ZLIB_INTERNAL
-#include "pcl/surface/3rdparty/opennurbs/zlib.h"
-
-#define BASE 65521UL    /* largest prime smaller than 65536 */
-#define NMAX 5552
-/* NMAX is the largest n such that 255n(n+1)/2 + (n+1)(BASE-1) <= 2^32-1 */
-
-#define DO1(buf,i)  {adler += (buf)[i]; sum2 += adler;}
-#define DO2(buf,i)  DO1(buf,i); DO1(buf,i+1);
-#define DO4(buf,i)  DO2(buf,i); DO2(buf,i+2);
-#define DO8(buf,i)  DO4(buf,i); DO4(buf,i+4);
-#define DO16(buf)   DO8(buf,0); DO8(buf,8);
-
-/* use NO_DIVIDE if your processor does not do division in hardware */
-#ifdef NO_DIVIDE
-#  define MOD(a) \
-    do { \
-        if (a >= (BASE << 16)) a -= (BASE << 16); \
-        if (a >= (BASE << 15)) a -= (BASE << 15); \
-        if (a >= (BASE << 14)) a -= (BASE << 14); \
-        if (a >= (BASE << 13)) a -= (BASE << 13); \
-        if (a >= (BASE << 12)) a -= (BASE << 12); \
-        if (a >= (BASE << 11)) a -= (BASE << 11); \
-        if (a >= (BASE << 10)) a -= (BASE << 10); \
-        if (a >= (BASE << 9)) a -= (BASE << 9); \
-        if (a >= (BASE << 8)) a -= (BASE << 8); \
-        if (a >= (BASE << 7)) a -= (BASE << 7); \
-        if (a >= (BASE << 6)) a -= (BASE << 6); \
-        if (a >= (BASE << 5)) a -= (BASE << 5); \
-        if (a >= (BASE << 4)) a -= (BASE << 4); \
-        if (a >= (BASE << 3)) a -= (BASE << 3); \
-        if (a >= (BASE << 2)) a -= (BASE << 2); \
-        if (a >= (BASE << 1)) a -= (BASE << 1); \
-        if (a >= BASE) a -= BASE; \
-    } while (0)
-#  define MOD4(a) \
-    do { \
-        if (a >= (BASE << 4)) a -= (BASE << 4); \
-        if (a >= (BASE << 3)) a -= (BASE << 3); \
-        if (a >= (BASE << 2)) a -= (BASE << 2); \
-        if (a >= (BASE << 1)) a -= (BASE << 1); \
-        if (a >= BASE) a -= BASE; \
-    } while (0)
-#else
-#  define MOD(a) a %= BASE
-#  define MOD4(a) a %= BASE
-#endif
-
-/* ========================================================================= */
-uLong ZEXPORT adler32(adler, buf, len)
-    uLong adler;
-    const Bytef *buf;
-    uInt len;
-{
-    unsigned int sum2;
-    unsigned n;
-
-    /* split Adler-32 into component sums */
-    sum2 = (adler >> 16) & 0xffff;
-    adler &= 0xffff;
-
-    /* in case user likes doing a byte at a time, keep it fast */
-    if (len == 1) {
-        adler += buf[0];
-        if (adler >= BASE)
-            adler -= BASE;
-        sum2 += adler;
-        if (sum2 >= BASE)
-            sum2 -= BASE;
-        return adler | (sum2 << 16);
-    }
-
-    /* initial Adler-32 value (deferred check for len == 1 speed) */
-    if (buf == Z_NULL)
-        return 1L;
-
-    /* in case short lengths are provided, keep it somewhat fast */
-    if (len < 16) {
-        while (len--) {
-            adler += *buf++;
-            sum2 += adler;
-        }
-        if (adler >= BASE)
-            adler -= BASE;
-        MOD4(sum2);             /* only added so many BASE's */
-        return adler | (sum2 << 16);
-    }
-
-    /* do length NMAX blocks -- requires just one modulo operation */
-    while (len >= NMAX) {
-        len -= NMAX;
-        n = NMAX / 16;          /* NMAX is divisible by 16 */
-        do {
-            DO16(buf);          /* 16 sums unrolled */
-            buf += 16;
-        } while (--n);
-        MOD(adler);
-        MOD(sum2);
-    }
-
-    /* do remaining bytes (less than NMAX, still just one modulo) */
-    if (len) {                  /* avoid modulos if none remaining */
-        while (len >= 16) {
-            len -= 16;
-            DO16(buf);
-            buf += 16;
-        }
-        while (len--) {
-            adler += *buf++;
-            sum2 += adler;
-        }
-        MOD(adler);
-        MOD(sum2);
-    }
-
-    /* return recombined sums */
-    return adler | (sum2 << 16);
-}
-
-/* ========================================================================= */
-uLong ZEXPORT adler32_combine(adler1, adler2, len2)
-    uLong adler1;
-    uLong adler2;
-    z_off_t len2;
-{
-    unsigned int sum1;
-    unsigned int sum2;
-    unsigned rem;
-
-    /* the derivation of this formula is left as an exercise for the reader */
-    rem = (unsigned)(len2 % BASE);
-    sum1 = adler1 & 0xffff;
-    sum2 = rem * sum1;
-    MOD(sum2);
-    sum1 += (adler2 & 0xffff) + BASE - 1;
-    sum2 += ((adler1 >> 16) & 0xffff) + ((adler2 >> 16) & 0xffff) + BASE - rem;
-    if (sum1 > BASE) sum1 -= BASE;
-    if (sum1 > BASE) sum1 -= BASE;
-    if (sum2 > (BASE << 1)) sum2 -= (BASE << 1);
-    if (sum2 > BASE) sum2 -= BASE;
-    return sum1 | (sum2 << 16);
-}
diff --git a/surface/src/3rdparty/opennurbs/compress.c b/surface/src/3rdparty/opennurbs/compress.c
deleted file mode 100644 (file)
index 5520d71..0000000
+++ /dev/null
@@ -1,79 +0,0 @@
-/* compress.c -- compress a memory buffer
- * Copyright (C) 1995-2003 Jean-loup Gailly.
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* @(#) $Id$ */
-
-#define ZLIB_INTERNAL
-#include "pcl/surface/3rdparty/opennurbs/zlib.h"
-
-/* ===========================================================================
-     Compresses the source buffer into the destination buffer. The level
-   parameter has the same meaning as in deflateInit.  sourceLen is the byte
-   length of the source buffer. Upon entry, destLen is the total size of the
-   destination buffer, which must be at least 0.1% larger than sourceLen plus
-   12 bytes. Upon exit, destLen is the actual size of the compressed buffer.
-
-     compress2 returns Z_OK if success, Z_MEM_ERROR if there was not enough
-   memory, Z_BUF_ERROR if there was not enough room in the output buffer,
-   Z_STREAM_ERROR if the level parameter is invalid.
-*/
-int ZEXPORT compress2 (dest, destLen, source, sourceLen, level)
-    Bytef *dest;
-    uLongf *destLen;
-    const Bytef *source;
-    uLong sourceLen;
-    int level;
-{
-    z_stream stream;
-    int err;
-
-    stream.next_in = (Bytef*)source;
-    stream.avail_in = (uInt)sourceLen;
-#ifdef MAXSEG_64K
-    /* Check for source > 64K on 16-bit machine: */
-    if ((uLong)stream.avail_in != sourceLen) return Z_BUF_ERROR;
-#endif
-    stream.next_out = dest;
-    stream.avail_out = (uInt)*destLen;
-    if ((uLong)stream.avail_out != *destLen) return Z_BUF_ERROR;
-
-    stream.zalloc = (alloc_func)0;
-    stream.zfree = (free_func)0;
-    stream.opaque = (voidpf)0;
-
-    err = deflateInit(&stream, level);
-    if (err != Z_OK) return err;
-
-    err = deflate(&stream, Z_FINISH);
-    if (err != Z_STREAM_END) {
-        deflateEnd(&stream);
-        return err == Z_OK ? Z_BUF_ERROR : err;
-    }
-    *destLen = stream.total_out;
-
-    err = deflateEnd(&stream);
-    return err;
-}
-
-/* ===========================================================================
- */
-int ZEXPORT compress (dest, destLen, source, sourceLen)
-    Bytef *dest;
-    uLongf *destLen;
-    const Bytef *source;
-    uLong sourceLen;
-{
-    return compress2(dest, destLen, source, sourceLen, Z_DEFAULT_COMPRESSION);
-}
-
-/* ===========================================================================
-     If the default memLevel or windowBits for deflateInit() is changed, then
-   this function needs to be updated.
- */
-uLong ZEXPORT compressBound (sourceLen)
-    uLong sourceLen;
-{
-    return sourceLen + (sourceLen >> 12) + (sourceLen >> 14) + 11;
-}
diff --git a/surface/src/3rdparty/opennurbs/crc32.c b/surface/src/3rdparty/opennurbs/crc32.c
deleted file mode 100644 (file)
index c2499c3..0000000
+++ /dev/null
@@ -1,423 +0,0 @@
-/* crc32.c -- compute the CRC-32 of a data stream
- * Copyright (C) 1995-2005 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- *
- * Thanks to Rodney Brown <rbrown64@csc.com.au> for his contribution of faster
- * CRC methods: exclusive-oring 32 bits of data at a time, and pre-computing
- * tables for updating the shift register in one step with three exclusive-ors
- * instead of four steps with four exclusive-ors.  This results in about a
- * factor of two increase in speed on a Power PC G4 (PPC7455) using gcc -O3.
- */
-
-/* @(#) $Id$ */
-
-/*
-  Note on the use of DYNAMIC_CRC_TABLE: there is no mutex or semaphore
-  protection on the static variables used to control the first-use generation
-  of the crc tables.  Therefore, if you #define DYNAMIC_CRC_TABLE, you should
-  first call get_crc_table() to initialize the tables before allowing more than
-  one thread to use crc32().
- */
-
-#ifdef MAKECRCH
-#  include <stdio.h>
-#  ifndef DYNAMIC_CRC_TABLE
-#    define DYNAMIC_CRC_TABLE
-#  endif /* !DYNAMIC_CRC_TABLE */
-#endif /* MAKECRCH */
-
-#include "pcl/surface/3rdparty/opennurbs/zutil.h"      /* for STDC and FAR definitions */
-
-#define local static
-
-/* Find a four-byte integer type for crc32_little() and crc32_big(). */
-#ifndef NOBYFOUR
-#  ifdef STDC           /* need ANSI C limits.h to determine sizes */
-#    include <limits.h>
-#    define BYFOUR
-#    if (UINT_MAX == 0xffffffffUL)
-       typedef unsigned int u4;
-#    else
-#      if (ULONG_MAX == 0xffffffffUL)
-         typedef unsigned long u4;
-#      else
-#        if (USHRT_MAX == 0xffffffffUL)
-           typedef unsigned short u4;
-#        else
-#          undef BYFOUR     /* can't find a four-byte integer type! */
-#        endif
-#      endif
-#    endif
-#  endif /* STDC */
-#endif /* !NOBYFOUR */
-
-/* Definitions for doing the crc four data bytes at a time. */
-#ifdef BYFOUR
-#  define REV(w) (((w)>>24)+(((w)>>8)&0xff00)+ \
-                (((w)&0xff00)<<8)+(((w)&0xff)<<24))
-   local unsigned int crc32_little OF((unsigned int,
-                        const unsigned char FAR *, unsigned));
-   local unsigned int crc32_big OF((unsigned int,
-                        const unsigned char FAR *, unsigned));
-#  define TBLS 8
-#else
-#  define TBLS 1
-#endif /* BYFOUR */
-
-/* Local functions for crc concatenation */
-local unsigned int gf2_matrix_times OF((unsigned int *mat,
-                                         unsigned int vec));
-local void gf2_matrix_square OF((unsigned int *square, unsigned int *mat));
-
-#ifdef DYNAMIC_CRC_TABLE
-
-local volatile int crc_table_empty = 1;
-local unsigned int FAR crc_table[TBLS][256];
-local void make_crc_table OF((void));
-#ifdef MAKECRCH
-   local void write_table OF((FILE *, const unsigned int FAR *));
-#endif /* MAKECRCH */
-/*
-  Generate tables for a byte-wise 32-bit CRC calculation on the polynomial:
-  x^32+x^26+x^23+x^22+x^16+x^12+x^11+x^10+x^8+x^7+x^5+x^4+x^2+x+1.
-
-  Polynomials over GF(2) are represented in binary, one bit per coefficient,
-  with the lowest powers in the most significant bit.  Then adding polynomials
-  is just exclusive-or, and multiplying a polynomial by x is a right shift by
-  one.  If we call the above polynomial p, and represent a byte as the
-  polynomial q, also with the lowest power in the most significant bit (so the
-  byte 0xb1 is the polynomial x^7+x^3+x+1), then the CRC is (q*x^32) mod p,
-  where a mod b means the remainder after dividing a by b.
-
-  This calculation is done using the shift-register method of multiplying and
-  taking the remainder.  The register is initialized to zero, and for each
-  incoming bit, x^32 is added mod p to the register if the bit is a one (where
-  x^32 mod p is p+x^32 = x^26+...+1), and the register is multiplied mod p by
-  x (which is shifting right by one and adding x^32 mod p if the bit shifted
-  out is a one).  We start with the highest power (least significant bit) of
-  q and repeat for all eight bits of q.
-
-  The first table is simply the CRC of all possible eight bit values.  This is
-  all the information needed to generate CRCs on data a byte at a time for all
-  combinations of CRC register values and incoming bytes.  The remaining tables
-  allow for word-at-a-time CRC calculation for both big-endian and little-
-  endian machines, where a word is four bytes.
-*/
-local void make_crc_table()
-{
-    unsigned int c;
-    int n, k;
-    unsigned int poly;                 /* polynomial exclusive-or pattern */
-    /* terms of polynomial defining this crc (except x^32): */
-    static volatile int first = 1;      /* flag to limit concurrent making */
-    static const unsigned char p[] = {0,1,2,4,5,7,8,10,11,12,16,22,23,26};
-
-    /* See if another task is already doing this (not thread-safe, but better
-       than nothing -- significantly reduces duration of vulnerability in
-       case the advice about DYNAMIC_CRC_TABLE is ignored) */
-    if (first) {
-        first = 0;
-
-        /* make exclusive-or pattern from polynomial (0xedb88320UL) */
-        poly = 0UL;
-        for (n = 0; n < sizeof(p)/sizeof(unsigned char); n++)
-            poly |= 1UL << (31 - p[n]);
-
-        /* generate a crc for every 8-bit value */
-        for (n = 0; n < 256; n++) {
-            c = (unsigned int)n;
-            for (k = 0; k < 8; k++)
-                c = c & 1 ? poly ^ (c >> 1) : c >> 1;
-            crc_table[0][n] = c;
-        }
-
-#ifdef BYFOUR
-        /* generate crc for each value followed by one, two, and three zeros,
-           and then the byte reversal of those as well as the first table */
-        for (n = 0; n < 256; n++) {
-            c = crc_table[0][n];
-            crc_table[4][n] = REV(c);
-            for (k = 1; k < 4; k++) {
-                c = crc_table[0][c & 0xff] ^ (c >> 8);
-                crc_table[k][n] = c;
-                crc_table[k + 4][n] = REV(c);
-            }
-        }
-#endif /* BYFOUR */
-
-        crc_table_empty = 0;
-    }
-    else {      /* not first */
-        /* wait for the other guy to finish (not efficient, but rare) */
-        while (crc_table_empty)
-            ;
-    }
-
-#ifdef MAKECRCH
-    /* write out CRC tables to crc32.h */
-    {
-        FILE *out;
-
-        out = fopen("crc32.h", "w");
-        if (0 == out) return;
-        fprintf(out, "/* crc32.h -- tables for rapid CRC calculation\n");
-        fprintf(out, " * Generated automatically by crc32.c\n */\n\n");
-        fprintf(out, "local const unsigned int FAR ");
-        fprintf(out, "crc_table[TBLS][256] =\n{\n  {\n");
-        write_table(out, crc_table[0]);
-#  ifdef BYFOUR
-        fprintf(out, "#ifdef BYFOUR\n");
-        for (k = 1; k < 8; k++) {
-            fprintf(out, "  },\n  {\n");
-            write_table(out, crc_table[k]);
-        }
-        fprintf(out, "#endif\n");
-#  endif /* BYFOUR */
-        fprintf(out, "  }\n};\n");
-        fclose(out);
-    }
-#endif /* MAKECRCH */
-}
-
-#ifdef MAKECRCH
-local void write_table(out, table)
-    FILE *out;
-    const unsigned int FAR *table;
-{
-    int n;
-
-    for (n = 0; n < 256; n++)
-        fprintf(out, "%s0x%08lxUL%s", n % 5 ? "" : "    ", table[n],
-                n == 255 ? "\n" : (n % 5 == 4 ? ",\n" : ", "));
-}
-#endif /* MAKECRCH */
-
-#else /* !DYNAMIC_CRC_TABLE */
-/* ========================================================================
- * Tables of CRC-32s of all single-byte values, made by make_crc_table().
- */
-#include "pcl/surface/3rdparty/opennurbs/crc32.h"
-#endif /* DYNAMIC_CRC_TABLE */
-
-/* =========================================================================
- * This function can be used by asm versions of crc32()
- */
-const unsigned int FAR * ZEXPORT get_crc_table()
-{
-#ifdef DYNAMIC_CRC_TABLE
-    if (crc_table_empty)
-        make_crc_table();
-#endif /* DYNAMIC_CRC_TABLE */
-    return (const unsigned int FAR *)crc_table;
-}
-
-/* ========================================================================= */
-#define DO1 crc = crc_table[0][((int)crc ^ (*buf++)) & 0xff] ^ (crc >> 8)
-#define DO8 DO1; DO1; DO1; DO1; DO1; DO1; DO1; DO1
-
-/* ========================================================================= */
-unsigned int ZEXPORT crc32(crc, buf, len)
-    unsigned int crc;
-    const unsigned char FAR *buf;
-    unsigned len;
-{
-    if (buf == Z_NULL) return 0UL;
-
-#ifdef DYNAMIC_CRC_TABLE
-    if (crc_table_empty)
-        make_crc_table();
-#endif /* DYNAMIC_CRC_TABLE */
-
-#ifdef BYFOUR
-    if (sizeof(void *) == sizeof(ptrdiff_t)) {
-        u4 endian;
-
-        endian = 1;
-        if (*((unsigned char *)(&endian)))
-            return crc32_little(crc, buf, len);
-        else
-            return crc32_big(crc, buf, len);
-    }
-#endif /* BYFOUR */
-    crc = crc ^ 0xffffffffUL;
-    while (len >= 8) {
-        DO8;
-        len -= 8;
-    }
-    if (len) do {
-        DO1;
-    } while (--len);
-    return crc ^ 0xffffffffUL;
-}
-
-#ifdef BYFOUR
-
-/* ========================================================================= */
-#define DOLIT4 c ^= *buf4++; \
-        c = crc_table[3][c & 0xff] ^ crc_table[2][(c >> 8) & 0xff] ^ \
-            crc_table[1][(c >> 16) & 0xff] ^ crc_table[0][c >> 24]
-#define DOLIT32 DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4
-
-/* ========================================================================= */
-local unsigned int crc32_little(crc, buf, len)
-    unsigned int crc;
-    const unsigned char FAR *buf;
-    unsigned len;
-{
-    register u4 c;
-    register const u4 FAR *buf4;
-
-    c = (u4)crc;
-    c = ~c;
-    while (len && ((ptrdiff_t)buf & 3)) {
-        c = crc_table[0][(c ^ *buf++) & 0xff] ^ (c >> 8);
-        len--;
-    }
-
-    buf4 = (const u4 FAR *)(const void FAR *)buf;
-    while (len >= 32) {
-        DOLIT32;
-        len -= 32;
-    }
-    while (len >= 4) {
-        DOLIT4;
-        len -= 4;
-    }
-    buf = (const unsigned char FAR *)buf4;
-
-    if (len) do {
-        c = crc_table[0][(c ^ *buf++) & 0xff] ^ (c >> 8);
-    } while (--len);
-    c = ~c;
-    return (unsigned int)c;
-}
-
-/* ========================================================================= */
-#define DOBIG4 c ^= *++buf4; \
-        c = crc_table[4][c & 0xff] ^ crc_table[5][(c >> 8) & 0xff] ^ \
-            crc_table[6][(c >> 16) & 0xff] ^ crc_table[7][c >> 24]
-#define DOBIG32 DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4
-
-/* ========================================================================= */
-local unsigned int crc32_big(crc, buf, len)
-    unsigned int crc;
-    const unsigned char FAR *buf;
-    unsigned len;
-{
-    register u4 c;
-    register const u4 FAR *buf4;
-
-    c = REV((u4)crc);
-    c = ~c;
-    while (len && ((ptrdiff_t)buf & 3)) {
-        c = crc_table[4][(c >> 24) ^ *buf++] ^ (c << 8);
-        len--;
-    }
-
-    buf4 = (const u4 FAR *)(const void FAR *)buf;
-    buf4--;
-    while (len >= 32) {
-        DOBIG32;
-        len -= 32;
-    }
-    while (len >= 4) {
-        DOBIG4;
-        len -= 4;
-    }
-    buf4++;
-    buf = (const unsigned char FAR *)buf4;
-
-    if (len) do {
-        c = crc_table[4][(c >> 24) ^ *buf++] ^ (c << 8);
-    } while (--len);
-    c = ~c;
-    return (unsigned int)(REV(c));
-}
-
-#endif /* BYFOUR */
-
-#define GF2_DIM 32      /* dimension of GF(2) vectors (length of CRC) */
-
-/* ========================================================================= */
-local unsigned int gf2_matrix_times(mat, vec)
-    unsigned int *mat;
-    unsigned int vec;
-{
-    unsigned int sum;
-
-    sum = 0;
-    while (vec) {
-        if (vec & 1)
-            sum ^= *mat;
-        vec >>= 1;
-        mat++;
-    }
-    return sum;
-}
-
-/* ========================================================================= */
-local void gf2_matrix_square(square, mat)
-    unsigned int *square;
-    unsigned int *mat;
-{
-    int n;
-
-    for (n = 0; n < GF2_DIM; n++)
-        square[n] = gf2_matrix_times(mat, mat[n]);
-}
-
-/* ========================================================================= */
-uLong ZEXPORT crc32_combine(crc1, crc2, len2)
-    uLong crc1;
-    uLong crc2;
-    z_off_t len2;
-{
-    int n;
-    unsigned int row;
-    unsigned int even[GF2_DIM];    /* even-power-of-two zeros operator */
-    unsigned int odd[GF2_DIM];     /* odd-power-of-two zeros operator */
-
-    /* degenerate case */
-    if (len2 == 0)
-        return crc1;
-
-    /* put operator for one zero bit in odd */
-    odd[0] = 0xedb88320L;           /* CRC-32 polynomial */
-    row = 1;
-    for (n = 1; n < GF2_DIM; n++) {
-        odd[n] = row;
-        row <<= 1;
-    }
-
-    /* put operator for two zero bits in even */
-    gf2_matrix_square(even, odd);
-
-    /* put operator for four zero bits in odd */
-    gf2_matrix_square(odd, even);
-
-    /* apply len2 zeros to crc1 (first square will put the operator for one
-       zero byte, eight zero bits, in even) */
-    do {
-        /* apply zeros operator for this bit of len2 */
-        gf2_matrix_square(even, odd);
-        if (len2 & 1)
-            crc1 = gf2_matrix_times(even, crc1);
-        len2 >>= 1;
-
-        /* if no more bits set, then done */
-        if (len2 == 0)
-            break;
-
-        /* another iteration of the loop with odd and even swapped */
-        gf2_matrix_square(odd, even);
-        if (len2 & 1)
-            crc1 = gf2_matrix_times(odd, crc1);
-        len2 >>= 1;
-
-        /* if no more bits set, then done */
-    } while (len2 != 0);
-
-    /* return combined crc */
-    crc1 ^= crc2;
-    return crc1;
-}
diff --git a/surface/src/3rdparty/opennurbs/deflate.c b/surface/src/3rdparty/opennurbs/deflate.c
deleted file mode 100644 (file)
index 5a0f1b3..0000000
+++ /dev/null
@@ -1,1736 +0,0 @@
-/* deflate.c -- compress data using the deflation algorithm
- * Copyright (C) 1995-2005 Jean-loup Gailly.
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/*
- *  ALGORITHM
- *
- *      The "deflation" process depends on being able to identify portions
- *      of the input text which are identical to earlier input (within a
- *      sliding window trailing behind the input currently being processed).
- *
- *      The most straightforward technique turns out to be the fastest for
- *      most input files: try all possible matches and select the longest.
- *      The key feature of this algorithm is that insertions into the string
- *      dictionary are very simple and thus fast, and deletions are avoided
- *      completely. Insertions are performed at each input character, whereas
- *      string matches are performed only when the previous match ends. So it
- *      is preferable to spend more time in matches to allow very fast string
- *      insertions and avoid deletions. The matching algorithm for small
- *      strings is inspired from that of Rabin & Karp. A brute force approach
- *      is used to find longer strings when a small match has been found.
- *      A similar algorithm is used in comic (by Jan-Mark Wams) and freeze
- *      (by Leonid Broukhis).
- *         A previous version of this file used a more sophisticated algorithm
- *      (by Fiala and Greene) which is guaranteed to run in linear amortized
- *      time, but has a larger average cost, uses more memory and is patented.
- *      However the F&G algorithm may be faster for some highly redundant
- *      files if the parameter max_chain_length (described below) is too large.
- *
- *  ACKNOWLEDGEMENTS
- *
- *      The idea of lazy evaluation of matches is due to Jan-Mark Wams, and
- *      I found it in 'freeze' written by Leonid Broukhis.
- *      Thanks to many people for bug reports and testing.
- *
- *  REFERENCES
- *
- *      Deutsch, L.P.,"DEFLATE Compressed Data Format Specification".
- *      Available in http://www.ietf.org/rfc/rfc1951.txt
- *
- *      A description of the Rabin and Karp algorithm is given in the book
- *         "Algorithms" by R. Sedgewick, Addison-Wesley, p252.
- *
- *      Fiala,E.R., and Greene,D.H.
- *         Data Compression with Finite Windows, Comm.ACM, 32,4 (1989) 490-595
- *
- */
-
-/* @(#) $Id$ */
-
-#include "pcl/surface/3rdparty/opennurbs/deflate.h"
-
-const char deflate_copyright[] =
-   " deflate 1.2.3 Copyright 1995-2005 Jean-loup Gailly ";
-/*
-  If you use the zlib library in a product, an acknowledgment is welcome
-  in the documentation of your product. If for some reason you cannot
-  include such an acknowledgment, I would appreciate that you keep this
-  copyright string in the executable of your product.
- */
-
-/* ===========================================================================
- *  Function prototypes.
- */
-typedef enum {
-    need_more,      /* block not completed, need more input or more output */
-    block_done,     /* block flush performed */
-    finish_started, /* finish started, need only more output at next deflate */
-    finish_done     /* finish done, accept no more input or output */
-} block_state;
-
-typedef block_state (*compress_func) OF((deflate_state *s, int flush));
-/* Compression function. Returns the block state after the call. */
-
-local void fill_window    OF((deflate_state *s));
-local block_state deflate_stored OF((deflate_state *s, int flush));
-local block_state deflate_fast   OF((deflate_state *s, int flush));
-#ifndef FASTEST
-local block_state deflate_slow   OF((deflate_state *s, int flush));
-#endif
-local void lm_init        OF((deflate_state *s));
-local void putShortMSB    OF((deflate_state *s, uInt b));
-local void flush_pending  OF((z_streamp strm));
-local int read_buf        OF((z_streamp strm, Bytef *buf, unsigned size));
-#ifndef FASTEST
-#ifdef ASMV
-      void match_init OF((void)); /* asm code initialization */
-      uInt longest_match  OF((deflate_state *s, IPos cur_match));
-#else
-local uInt longest_match  OF((deflate_state *s, IPos cur_match));
-#endif
-#endif
-local uInt longest_match_fast OF((deflate_state *s, IPos cur_match));
-
-#ifdef DEBUG
-local  void check_match OF((deflate_state *s, IPos start, IPos match,
-                            int length));
-#endif
-
-/* ===========================================================================
- * Local data
- */
-
-#define NIL 0
-/* Tail of hash chains */
-
-#ifndef TOO_FAR
-#  define TOO_FAR 4096
-#endif
-/* Matches of length 3 are discarded if their distance exceeds TOO_FAR */
-
-#define MIN_LOOKAHEAD (MAX_MATCH+MIN_MATCH+1)
-/* Minimum amount of lookahead, except at the end of the input file.
- * See deflate.c for comments about the MIN_MATCH+1.
- */
-
-/* Values for max_lazy_match, good_match and max_chain_length, depending on
- * the desired pack level (0..9). The values given below have been tuned to
- * exclude worst case performance for pathological files. Better values may be
- * found for specific files.
- */
-typedef struct config_s {
-   ush good_length; /* reduce lazy search above this match length */
-   ush max_lazy;    /* do not perform lazy search above this match length */
-   ush nice_length; /* quit search above this match length */
-   ush max_chain;
-   compress_func func;
-} config;
-
-#ifdef FASTEST
-local const config configuration_table[2] = {
-/*      good lazy nice chain */
-/* 0 */ {0,    0,  0,    0, deflate_stored},  /* store only */
-/* 1 */ {4,    4,  8,    4, deflate_fast}}; /* max speed, no lazy matches */
-#else
-local const config configuration_table[10] = {
-/*      good lazy nice chain */
-/* 0 */ {0,    0,  0,    0, deflate_stored},  /* store only */
-/* 1 */ {4,    4,  8,    4, deflate_fast}, /* max speed, no lazy matches */
-/* 2 */ {4,    5, 16,    8, deflate_fast},
-/* 3 */ {4,    6, 32,   32, deflate_fast},
-
-/* 4 */ {4,    4, 16,   16, deflate_slow},  /* lazy matches */
-/* 5 */ {8,   16, 32,   32, deflate_slow},
-/* 6 */ {8,   16, 128, 128, deflate_slow},
-/* 7 */ {8,   32, 128, 256, deflate_slow},
-/* 8 */ {32, 128, 258, 1024, deflate_slow},
-/* 9 */ {32, 258, 258, 4096, deflate_slow}}; /* max compression */
-#endif
-
-/* Note: the deflate() code requires max_lazy >= MIN_MATCH and max_chain >= 4
- * For deflate_fast() (levels <= 3) good is ignored and lazy has a different
- * meaning.
- */
-
-#define EQUAL 0
-/* result of memcmp for equal strings */
-
-#ifndef NO_DUMMY_DECL
-struct static_tree_desc_s {int dummy;}; /* for buggy compilers */
-#endif
-
-/* ===========================================================================
- * Update a hash value with the given input byte
- * IN  assertion: all calls to to UPDATE_HASH are made with consecutive
- *    input characters, so that a running hash key can be computed from the
- *    previous key instead of complete recalculation each time.
- */
-#define UPDATE_HASH(s,h,c) (h = (((h)<<s->hash_shift) ^ (c)) & s->hash_mask)
-
-
-/* ===========================================================================
- * Insert string str in the dictionary and set match_head to the previous head
- * of the hash chain (the most recent string with same hash key). Return
- * the previous length of the hash chain.
- * If this file is compiled with -DFASTEST, the compression level is forced
- * to 1, and no hash chains are maintained.
- * IN  assertion: all calls to to INSERT_STRING are made with consecutive
- *    input characters and the first MIN_MATCH bytes of str are valid
- *    (except for the last MIN_MATCH-1 bytes of the input file).
- */
-#ifdef FASTEST
-#define INSERT_STRING(s, str, match_head) \
-   (UPDATE_HASH(s, s->ins_h, s->window[(str) + (MIN_MATCH-1)]), \
-    match_head = s->head[s->ins_h], \
-    s->head[s->ins_h] = (Pos)(str))
-#else
-#define INSERT_STRING(s, str, match_head) \
-   (UPDATE_HASH(s, s->ins_h, s->window[(str) + (MIN_MATCH-1)]), \
-    match_head = s->prev[(str) & s->w_mask] = s->head[s->ins_h], \
-    s->head[s->ins_h] = (Pos)(str))
-#endif
-
-/* ===========================================================================
- * Initialize the hash table (avoiding 64K overflow for 16 bit systems).
- * prev[] will be initialized on the fly.
- */
-#define CLEAR_HASH(s) \
-    s->head[s->hash_size-1] = NIL; \
-    zmemzero((Bytef *)s->head, (unsigned)(s->hash_size-1)*sizeof(*s->head));
-
-/* ========================================================================= */
-int ZEXPORT deflateInit_(strm, level, version, stream_size)
-    z_streamp strm;
-    int level;
-    const char *version;
-    int stream_size;
-{
-    return deflateInit2_(strm, level, Z_DEFLATED, MAX_WBITS, DEF_MEM_LEVEL,
-                         Z_DEFAULT_STRATEGY, version, stream_size);
-    /* To do: ignore strm->next_in if we use it as window */
-}
-
-/* ========================================================================= */
-int ZEXPORT deflateInit2_(strm, level, method, windowBits, memLevel, strategy,
-                  version, stream_size)
-    z_streamp strm;
-    int  level;
-    int  method;
-    int  windowBits;
-    int  memLevel;
-    int  strategy;
-    const char *version;
-    int stream_size;
-{
-    deflate_state *s;
-    int wrap = 1;
-    static const char my_version[] = ZLIB_VERSION;
-
-    ushf *overlay;
-    /* We overlay pending_buf and d_buf+l_buf. This works since the average
-     * output size for (length,distance) codes is <= 24 bits.
-     */
-
-    if (version == Z_NULL || version[0] != my_version[0] ||
-        stream_size != sizeof(z_stream)) {
-        return Z_VERSION_ERROR;
-    }
-    if (strm == Z_NULL) return Z_STREAM_ERROR;
-
-    strm->msg = Z_NULL;
-    if (strm->zalloc == (alloc_func)0) {
-        strm->zalloc = zcalloc;
-        strm->opaque = (voidpf)0;
-    }
-    if (strm->zfree == (free_func)0) strm->zfree = zcfree;
-
-#ifdef FASTEST
-    if (level != 0) level = 1;
-#else
-    if (level == Z_DEFAULT_COMPRESSION) level = 6;
-#endif
-
-    if (windowBits < 0) { /* suppress zlib wrapper */
-        wrap = 0;
-        windowBits = -windowBits;
-    }
-#ifdef GZIP
-    else if (windowBits > 15) {
-        wrap = 2;       /* write gzip wrapper instead */
-        windowBits -= 16;
-    }
-#endif
-    if (memLevel < 1 || memLevel > MAX_MEM_LEVEL || method != Z_DEFLATED ||
-        windowBits < 8 || windowBits > 15 || level < 0 || level > 9 ||
-        strategy < 0 || strategy > Z_FIXED) {
-        return Z_STREAM_ERROR;
-    }
-    if (windowBits == 8) windowBits = 9;  /* until 256-byte window bug fixed */
-    s = (deflate_state *) ZALLOC(strm, 1, sizeof(deflate_state));
-    if (s == Z_NULL) return Z_MEM_ERROR;
-    strm->state = (struct internal_state FAR *)s;
-    s->strm = strm;
-
-    s->wrap = wrap;
-    s->gzhead = Z_NULL;
-    s->w_bits = windowBits;
-    s->w_size = 1 << s->w_bits;
-    s->w_mask = s->w_size - 1;
-
-    s->hash_bits = memLevel + 7;
-    s->hash_size = 1 << s->hash_bits;
-    s->hash_mask = s->hash_size - 1;
-    s->hash_shift =  ((s->hash_bits+MIN_MATCH-1)/MIN_MATCH);
-
-    s->window = (Bytef *) ZALLOC(strm, s->w_size, 2*sizeof(Byte));
-    s->prev   = (Posf *)  ZALLOC(strm, s->w_size, sizeof(Pos));
-    s->head   = (Posf *)  ZALLOC(strm, s->hash_size, sizeof(Pos));
-
-    s->lit_bufsize = 1 << (memLevel + 6); /* 16K elements by default */
-
-    overlay = (ushf *) ZALLOC(strm, s->lit_bufsize, sizeof(ush)+2);
-    s->pending_buf = (uchf *) overlay;
-    s->pending_buf_size = (ulg)s->lit_bufsize * (sizeof(ush)+2L);
-
-    if (s->window == Z_NULL || s->prev == Z_NULL || s->head == Z_NULL ||
-        s->pending_buf == Z_NULL) {
-        s->status = FINISH_STATE;
-        strm->msg = (char*)ERR_MSG(Z_MEM_ERROR);
-        deflateEnd (strm);
-        return Z_MEM_ERROR;
-    }
-    s->d_buf = overlay + s->lit_bufsize/sizeof(ush);
-    s->l_buf = s->pending_buf + (1+sizeof(ush))*s->lit_bufsize;
-
-    s->level = level;
-    s->strategy = strategy;
-    s->method = (Byte)method;
-
-    return deflateReset(strm);
-}
-
-/* ========================================================================= */
-int ZEXPORT deflateSetDictionary (strm, dictionary, dictLength)
-    z_streamp strm;
-    const Bytef *dictionary;
-    uInt  dictLength;
-{
-    deflate_state *s;
-    uInt length = dictLength;
-    uInt n;
-    IPos hash_head = 0;
-
-    if (strm == Z_NULL || strm->state == Z_NULL || dictionary == Z_NULL ||
-        strm->state->wrap == 2 ||
-        (strm->state->wrap == 1 && strm->state->status != INIT_STATE))
-        return Z_STREAM_ERROR;
-
-    s = strm->state;
-    if (s->wrap)
-        strm->adler = adler32(strm->adler, dictionary, dictLength);
-
-    if (length < MIN_MATCH) return Z_OK;
-    if (length > MAX_DIST(s)) {
-        length = MAX_DIST(s);
-        dictionary += dictLength - length; /* use the tail of the dictionary */
-    }
-    zmemcpy(s->window, dictionary, length);
-    s->strstart = length;
-    s->block_start = (int)length;
-
-    /* Insert all strings in the hash table (except for the last two bytes).
-     * s->lookahead stays null, so s->ins_h will be recomputed at the next
-     * call of fill_window.
-     */
-    s->ins_h = s->window[0];
-    UPDATE_HASH(s, s->ins_h, s->window[1]);
-    for (n = 0; n <= length - MIN_MATCH; n++) {
-        INSERT_STRING(s, n, hash_head);
-    }
-    if (hash_head) hash_head = 0;  /* to make compiler happy */
-    return Z_OK;
-}
-
-/* ========================================================================= */
-int ZEXPORT deflateReset (strm)
-    z_streamp strm;
-{
-    deflate_state *s;
-
-    if (strm == Z_NULL || strm->state == Z_NULL ||
-        strm->zalloc == (alloc_func)0 || strm->zfree == (free_func)0) {
-        return Z_STREAM_ERROR;
-    }
-
-    strm->total_in = strm->total_out = 0;
-    strm->msg = Z_NULL; /* use zfree if we ever allocate msg dynamically */
-    strm->data_type = Z_UNKNOWN;
-
-    s = (deflate_state *)strm->state;
-    s->pending = 0;
-    s->pending_out = s->pending_buf;
-
-    if (s->wrap < 0) {
-        s->wrap = -s->wrap; /* was made negative by deflate(..., Z_FINISH); */
-    }
-    s->status = s->wrap ? INIT_STATE : BUSY_STATE;
-    strm->adler =
-#ifdef GZIP
-        s->wrap == 2 ? crc32(0L, Z_NULL, 0) :
-#endif
-        adler32(0L, Z_NULL, 0);
-    s->last_flush = Z_NO_FLUSH;
-
-    _tr_init(s);
-    lm_init(s);
-
-    return Z_OK;
-}
-
-/* ========================================================================= */
-int ZEXPORT deflateSetHeader (strm, head)
-    z_streamp strm;
-    gz_headerp head;
-{
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    if (strm->state->wrap != 2) return Z_STREAM_ERROR;
-    strm->state->gzhead = head;
-    return Z_OK;
-}
-
-/* ========================================================================= */
-int ZEXPORT deflatePrime (strm, bits, value)
-    z_streamp strm;
-    int bits;
-    int value;
-{
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    strm->state->bi_valid = bits;
-    strm->state->bi_buf = (ush)(value & ((1 << bits) - 1));
-    return Z_OK;
-}
-
-/* ========================================================================= */
-int ZEXPORT deflateParams(strm, level, strategy)
-    z_streamp strm;
-    int level;
-    int strategy;
-{
-    deflate_state *s;
-    compress_func func;
-    int err = Z_OK;
-
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    s = strm->state;
-
-#ifdef FASTEST
-    if (level != 0) level = 1;
-#else
-    if (level == Z_DEFAULT_COMPRESSION) level = 6;
-#endif
-    if (level < 0 || level > 9 || strategy < 0 || strategy > Z_FIXED) {
-        return Z_STREAM_ERROR;
-    }
-    func = configuration_table[s->level].func;
-
-    if (func != configuration_table[level].func && strm->total_in != 0) {
-        /* Flush the last buffer: */
-        err = deflate(strm, Z_PARTIAL_FLUSH);
-    }
-    if (s->level != level) {
-        s->level = level;
-        s->max_lazy_match   = configuration_table[level].max_lazy;
-        s->good_match       = configuration_table[level].good_length;
-        s->nice_match       = configuration_table[level].nice_length;
-        s->max_chain_length = configuration_table[level].max_chain;
-    }
-    s->strategy = strategy;
-    return err;
-}
-
-/* ========================================================================= */
-int ZEXPORT deflateTune(strm, good_length, max_lazy, nice_length, max_chain)
-    z_streamp strm;
-    int good_length;
-    int max_lazy;
-    int nice_length;
-    int max_chain;
-{
-    deflate_state *s;
-
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    s = strm->state;
-    s->good_match = good_length;
-    s->max_lazy_match = max_lazy;
-    s->nice_match = nice_length;
-    s->max_chain_length = max_chain;
-    return Z_OK;
-}
-
-/* =========================================================================
- * For the default windowBits of 15 and memLevel of 8, this function returns
- * a close to exact, as well as small, upper bound on the compressed size.
- * They are coded as constants here for a reason--if the #define's are
- * changed, then this function needs to be changed as well.  The return
- * value for 15 and 8 only works for those exact settings.
- *
- * For any setting other than those defaults for windowBits and memLevel,
- * the value returned is a conservative worst case for the maximum expansion
- * resulting from using fixed blocks instead of stored blocks, which deflate
- * can emit on compressed data for some combinations of the parameters.
- *
- * This function could be more sophisticated to provide closer upper bounds
- * for every combination of windowBits and memLevel, as well as wrap.
- * But even the conservative upper bound of about 14% expansion does not
- * seem onerous for output buffer allocation.
- */
-uLong ZEXPORT deflateBound(strm, sourceLen)
-    z_streamp strm;
-    uLong sourceLen;
-{
-    deflate_state *s;
-    uLong destLen;
-
-    /* conservative upper bound */
-    destLen = sourceLen +
-              ((sourceLen + 7) >> 3) + ((sourceLen + 63) >> 6) + 11;
-
-    /* if can't get parameters, return conservative bound */
-    if (strm == Z_NULL || strm->state == Z_NULL)
-        return destLen;
-
-    /* if not default parameters, return conservative bound */
-    s = strm->state;
-    if (s->w_bits != 15 || s->hash_bits != 8 + 7)
-        return destLen;
-
-    /* default settings: return tight bound for that case */
-    return compressBound(sourceLen);
-}
-
-/* =========================================================================
- * Put a short in the pending buffer. The 16-bit value is put in MSB order.
- * IN assertion: the stream state is correct and there is enough room in
- * pending_buf.
- */
-local void putShortMSB (s, b)
-    deflate_state *s;
-    uInt b;
-{
-    put_byte(s, (Byte)(b >> 8));
-    put_byte(s, (Byte)(b & 0xff));
-}
-
-/* =========================================================================
- * Flush as much pending output as possible. All deflate() output goes
- * through this function so some applications may wish to modify it
- * to avoid allocating a large strm->next_out buffer and copying into it.
- * (See also read_buf()).
- */
-local void flush_pending(strm)
-    z_streamp strm;
-{
-    unsigned len = strm->state->pending;
-
-    if (len > strm->avail_out) len = strm->avail_out;
-    if (len == 0) return;
-
-    zmemcpy(strm->next_out, strm->state->pending_out, len);
-    strm->next_out  += len;
-    strm->state->pending_out  += len;
-    strm->total_out += len;
-    strm->avail_out  -= len;
-    strm->state->pending -= len;
-    if (strm->state->pending == 0) {
-        strm->state->pending_out = strm->state->pending_buf;
-    }
-}
-
-/* ========================================================================= */
-int ZEXPORT deflate (strm, flush)
-    z_streamp strm;
-    int flush;
-{
-    int old_flush; /* value of flush param for previous deflate call */
-    deflate_state *s;
-
-    if (strm == Z_NULL || strm->state == Z_NULL ||
-        flush > Z_FINISH || flush < 0) {
-        return Z_STREAM_ERROR;
-    }
-    s = strm->state;
-
-    if (strm->next_out == Z_NULL ||
-        (strm->next_in == Z_NULL && strm->avail_in != 0) ||
-        (s->status == FINISH_STATE && flush != Z_FINISH)) {
-        ERR_RETURN(strm, Z_STREAM_ERROR);
-    }
-    if (strm->avail_out == 0) ERR_RETURN(strm, Z_BUF_ERROR);
-
-    s->strm = strm; /* just in case */
-    old_flush = s->last_flush;
-    s->last_flush = flush;
-
-    /* Write the header */
-    if (s->status == INIT_STATE) {
-#ifdef GZIP
-        if (s->wrap == 2) {
-            strm->adler = crc32(0L, Z_NULL, 0);
-            put_byte(s, 31);
-            put_byte(s, 139);
-            put_byte(s, 8);
-            if (0 == s->gzhead) {
-                put_byte(s, 0);
-                put_byte(s, 0);
-                put_byte(s, 0);
-                put_byte(s, 0);
-                put_byte(s, 0);
-                put_byte(s, s->level == 9 ? 2 :
-                            (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2 ?
-                             4 : 0));
-                put_byte(s, OS_CODE);
-                s->status = BUSY_STATE;
-            }
-            else {
-                put_byte(s, (s->gzhead->text ? 1 : 0) +
-                            (s->gzhead->hcrc ? 2 : 0) +
-                            (s->gzhead->extra == Z_NULL ? 0 : 4) +
-                            (s->gzhead->name == Z_NULL ? 0 : 8) +
-                            (s->gzhead->comment == Z_NULL ? 0 : 16)
-                        );
-                put_byte(s, (Byte)(s->gzhead->time & 0xff));
-                put_byte(s, (Byte)((s->gzhead->time >> 8) & 0xff));
-                put_byte(s, (Byte)((s->gzhead->time >> 16) & 0xff));
-                put_byte(s, (Byte)((s->gzhead->time >> 24) & 0xff));
-                put_byte(s, s->level == 9 ? 2 :
-                            (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2 ?
-                             4 : 0));
-                put_byte(s, s->gzhead->os & 0xff);
-                if (s->gzhead->extra != 0) {
-                    put_byte(s, s->gzhead->extra_len & 0xff);
-                    put_byte(s, (s->gzhead->extra_len >> 8) & 0xff);
-                }
-                if (s->gzhead->hcrc)
-                    strm->adler = crc32(strm->adler, s->pending_buf,
-                                        s->pending);
-                s->gzindex = 0;
-                s->status = EXTRA_STATE;
-            }
-        }
-        else
-#endif
-        {
-            uInt header = (Z_DEFLATED + ((s->w_bits-8)<<4)) << 8;
-            uInt level_flags;
-
-            if (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2)
-                level_flags = 0;
-            else if (s->level < 6)
-                level_flags = 1;
-            else if (s->level == 6)
-                level_flags = 2;
-            else
-                level_flags = 3;
-            header |= (level_flags << 6);
-            if (s->strstart != 0) header |= PRESET_DICT;
-            header += 31 - (header % 31);
-
-            s->status = BUSY_STATE;
-            putShortMSB(s, header);
-
-            /* Save the adler32 of the preset dictionary: */
-            if (s->strstart != 0) {
-                putShortMSB(s, (uInt)(strm->adler >> 16));
-                putShortMSB(s, (uInt)(strm->adler & 0xffff));
-            }
-            strm->adler = adler32(0L, Z_NULL, 0);
-        }
-    }
-#ifdef GZIP
-    if (s->status == EXTRA_STATE) {
-        if (s->gzhead->extra != 0) {
-            uInt beg = s->pending;  /* start of bytes to update crc */
-
-            while (s->gzindex < (s->gzhead->extra_len & 0xffff)) {
-                if (s->pending == s->pending_buf_size) {
-                    if (s->gzhead->hcrc && s->pending > beg)
-                        strm->adler = crc32(strm->adler, s->pending_buf + beg,
-                                            s->pending - beg);
-                    flush_pending(strm);
-                    beg = s->pending;
-                    if (s->pending == s->pending_buf_size)
-                        break;
-                }
-                put_byte(s, s->gzhead->extra[s->gzindex]);
-                s->gzindex++;
-            }
-            if (s->gzhead->hcrc && s->pending > beg)
-                strm->adler = crc32(strm->adler, s->pending_buf + beg,
-                                    s->pending - beg);
-            if (s->gzindex == s->gzhead->extra_len) {
-                s->gzindex = 0;
-                s->status = NAME_STATE;
-            }
-        }
-        else
-            s->status = NAME_STATE;
-    }
-    if (s->status == NAME_STATE) {
-        if (s->gzhead->name != 0) {
-            uInt beg = s->pending;  /* start of bytes to update crc */
-            int val;
-
-            do {
-                if (s->pending == s->pending_buf_size) {
-                    if (s->gzhead->hcrc && s->pending > beg)
-                        strm->adler = crc32(strm->adler, s->pending_buf + beg,
-                                            s->pending - beg);
-                    flush_pending(strm);
-                    beg = s->pending;
-                    if (s->pending == s->pending_buf_size) {
-                        val = 1;
-                        break;
-                    }
-                }
-                val = s->gzhead->name[s->gzindex++];
-                put_byte(s, val);
-            } while (val != 0);
-            if (s->gzhead->hcrc && s->pending > beg)
-                strm->adler = crc32(strm->adler, s->pending_buf + beg,
-                                    s->pending - beg);
-            if (val == 0) {
-                s->gzindex = 0;
-                s->status = COMMENT_STATE;
-            }
-        }
-        else
-            s->status = COMMENT_STATE;
-    }
-    if (s->status == COMMENT_STATE) {
-        if (s->gzhead->comment != 0) {
-            uInt beg = s->pending;  /* start of bytes to update crc */
-            int val;
-
-            do {
-                if (s->pending == s->pending_buf_size) {
-                    if (s->gzhead->hcrc && s->pending > beg)
-                        strm->adler = crc32(strm->adler, s->pending_buf + beg,
-                                            s->pending - beg);
-                    flush_pending(strm);
-                    beg = s->pending;
-                    if (s->pending == s->pending_buf_size) {
-                        val = 1;
-                        break;
-                    }
-                }
-                val = s->gzhead->comment[s->gzindex++];
-                put_byte(s, val);
-            } while (val != 0);
-            if (s->gzhead->hcrc && s->pending > beg)
-                strm->adler = crc32(strm->adler, s->pending_buf + beg,
-                                    s->pending - beg);
-            if (val == 0)
-                s->status = HCRC_STATE;
-        }
-        else
-            s->status = HCRC_STATE;
-    }
-    if (s->status == HCRC_STATE) {
-        if (s->gzhead->hcrc) {
-            if (s->pending + 2 > s->pending_buf_size)
-                flush_pending(strm);
-            if (s->pending + 2 <= s->pending_buf_size) {
-                put_byte(s, (Byte)(strm->adler & 0xff));
-                put_byte(s, (Byte)((strm->adler >> 8) & 0xff));
-                strm->adler = crc32(0L, Z_NULL, 0);
-                s->status = BUSY_STATE;
-            }
-        }
-        else
-            s->status = BUSY_STATE;
-    }
-#endif
-
-    /* Flush as much pending output as possible */
-    if (s->pending != 0) {
-        flush_pending(strm);
-        if (strm->avail_out == 0) {
-            /* Since avail_out is 0, deflate will be called again with
-             * more output space, but possibly with both pending and
-             * avail_in equal to zero. There won't be anything to do,
-             * but this is not an error situation so make sure we
-             * return OK instead of BUF_ERROR at next call of deflate:
-             */
-            s->last_flush = -1;
-            return Z_OK;
-        }
-
-    /* Make sure there is something to do and avoid duplicate consecutive
-     * flushes. For repeated and useless calls with Z_FINISH, we keep
-     * returning Z_STREAM_END instead of Z_BUF_ERROR.
-     */
-    } else if (strm->avail_in == 0 && flush <= old_flush &&
-               flush != Z_FINISH) {
-        ERR_RETURN(strm, Z_BUF_ERROR);
-    }
-
-    /* User must not provide more input after the first FINISH: */
-    if (s->status == FINISH_STATE && strm->avail_in != 0) {
-        ERR_RETURN(strm, Z_BUF_ERROR);
-    }
-
-    /* Start a new block or continue the current one.
-     */
-    if (strm->avail_in != 0 || s->lookahead != 0 ||
-        (flush != Z_NO_FLUSH && s->status != FINISH_STATE)) {
-        block_state bstate;
-
-        bstate = (*(configuration_table[s->level].func))(s, flush);
-
-        if (bstate == finish_started || bstate == finish_done) {
-            s->status = FINISH_STATE;
-        }
-        if (bstate == need_more || bstate == finish_started) {
-            if (strm->avail_out == 0) {
-                s->last_flush = -1; /* avoid BUF_ERROR next call, see above */
-            }
-            return Z_OK;
-            /* If flush != Z_NO_FLUSH && avail_out == 0, the next call
-             * of deflate should use the same flush parameter to make sure
-             * that the flush is complete. So we don't have to output an
-             * empty block here, this will be done at next call. This also
-             * ensures that for a very small output buffer, we emit at most
-             * one empty block.
-             */
-        }
-        if (bstate == block_done) {
-            if (flush == Z_PARTIAL_FLUSH) {
-                _tr_align(s);
-            } else { /* FULL_FLUSH or SYNC_FLUSH */
-                _tr_stored_block(s, (char*)0, 0L, 0);
-                /* For a full flush, this empty block will be recognized
-                 * as a special marker by inflate_sync().
-                 */
-                if (flush == Z_FULL_FLUSH) {
-                    CLEAR_HASH(s);             /* forget history */
-                }
-            }
-            flush_pending(strm);
-            if (strm->avail_out == 0) {
-              s->last_flush = -1; /* avoid BUF_ERROR at next call, see above */
-              return Z_OK;
-            }
-        }
-    }
-    Assert(strm->avail_out > 0, "bug2");
-
-    if (flush != Z_FINISH) return Z_OK;
-    if (s->wrap <= 0) return Z_STREAM_END;
-
-    /* Write the trailer */
-#ifdef GZIP
-    if (s->wrap == 2) {
-        put_byte(s, (Byte)(strm->adler & 0xff));
-        put_byte(s, (Byte)((strm->adler >> 8) & 0xff));
-        put_byte(s, (Byte)((strm->adler >> 16) & 0xff));
-        put_byte(s, (Byte)((strm->adler >> 24) & 0xff));
-        put_byte(s, (Byte)(strm->total_in & 0xff));
-        put_byte(s, (Byte)((strm->total_in >> 8) & 0xff));
-        put_byte(s, (Byte)((strm->total_in >> 16) & 0xff));
-        put_byte(s, (Byte)((strm->total_in >> 24) & 0xff));
-    }
-    else
-#endif
-    {
-        putShortMSB(s, (uInt)(strm->adler >> 16));
-        putShortMSB(s, (uInt)(strm->adler & 0xffff));
-    }
-    flush_pending(strm);
-    /* If avail_out is zero, the application will call deflate again
-     * to flush the rest.
-     */
-    if (s->wrap > 0) s->wrap = -s->wrap; /* write the trailer only once! */
-    return s->pending != 0 ? Z_OK : Z_STREAM_END;
-}
-
-/* ========================================================================= */
-int ZEXPORT deflateEnd (strm)
-    z_streamp strm;
-{
-    int status;
-
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-
-    status = strm->state->status;
-    if (status != INIT_STATE &&
-        status != EXTRA_STATE &&
-        status != NAME_STATE &&
-        status != COMMENT_STATE &&
-        status != HCRC_STATE &&
-        status != BUSY_STATE &&
-        status != FINISH_STATE) {
-      return Z_STREAM_ERROR;
-    }
-
-    /* Deallocate in reverse order of allocations: */
-    TRY_FREE(strm, strm->state->pending_buf);
-    TRY_FREE(strm, strm->state->head);
-    TRY_FREE(strm, strm->state->prev);
-    TRY_FREE(strm, strm->state->window);
-
-    ZFREE(strm, strm->state);
-    strm->state = Z_NULL;
-
-    return status == BUSY_STATE ? Z_DATA_ERROR : Z_OK;
-}
-
-/* =========================================================================
- * Copy the source state to the destination state.
- * To simplify the source, this is not supported for 16-bit MSDOS (which
- * doesn't have enough memory anyway to duplicate compression states).
- */
-int ZEXPORT deflateCopy (dest, source)
-    z_streamp dest;
-    z_streamp source;
-{
-#ifdef MAXSEG_64K
-    return Z_STREAM_ERROR;
-#else
-    deflate_state *ds;
-    deflate_state *ss;
-    ushf *overlay;
-
-
-    if (source == Z_NULL || dest == Z_NULL || source->state == Z_NULL) {
-        return Z_STREAM_ERROR;
-    }
-
-    ss = source->state;
-
-    zmemcpy(dest, source, sizeof(z_stream));
-
-    ds = (deflate_state *) ZALLOC(dest, 1, sizeof(deflate_state));
-    if (ds == Z_NULL) return Z_MEM_ERROR;
-    dest->state = (struct internal_state FAR *) ds;
-    zmemcpy(ds, ss, sizeof(deflate_state));
-    ds->strm = dest;
-
-    ds->window = (Bytef *) ZALLOC(dest, ds->w_size, 2*sizeof(Byte));
-    ds->prev   = (Posf *)  ZALLOC(dest, ds->w_size, sizeof(Pos));
-    ds->head   = (Posf *)  ZALLOC(dest, ds->hash_size, sizeof(Pos));
-    overlay = (ushf *) ZALLOC(dest, ds->lit_bufsize, sizeof(ush)+2);
-    ds->pending_buf = (uchf *) overlay;
-
-    if (ds->window == Z_NULL || ds->prev == Z_NULL || ds->head == Z_NULL ||
-        ds->pending_buf == Z_NULL) {
-        deflateEnd (dest);
-        return Z_MEM_ERROR;
-    }
-    /* following zmemcpy do not work for 16-bit MSDOS */
-    zmemcpy(ds->window, ss->window, ds->w_size * 2 * sizeof(Byte));
-    zmemcpy(ds->prev, ss->prev, ds->w_size * sizeof(Pos));
-    zmemcpy(ds->head, ss->head, ds->hash_size * sizeof(Pos));
-    zmemcpy(ds->pending_buf, ss->pending_buf, (uInt)ds->pending_buf_size);
-
-    ds->pending_out = ds->pending_buf + (ss->pending_out - ss->pending_buf);
-    ds->d_buf = overlay + ds->lit_bufsize/sizeof(ush);
-    ds->l_buf = ds->pending_buf + (1+sizeof(ush))*ds->lit_bufsize;
-
-    ds->l_desc.dyn_tree = ds->dyn_ltree;
-    ds->d_desc.dyn_tree = ds->dyn_dtree;
-    ds->bl_desc.dyn_tree = ds->bl_tree;
-
-    return Z_OK;
-#endif /* MAXSEG_64K */
-}
-
-/* ===========================================================================
- * Read a new buffer from the current input stream, update the adler32
- * and total number of bytes read.  All deflate() input goes through
- * this function so some applications may wish to modify it to avoid
- * allocating a large strm->next_in buffer and copying from it.
- * (See also flush_pending()).
- */
-local int read_buf(strm, buf, size)
-    z_streamp strm;
-    Bytef *buf;
-    unsigned size;
-{
-    unsigned len = strm->avail_in;
-
-    if (len > size) len = size;
-    if (len == 0) return 0;
-
-    strm->avail_in  -= len;
-
-    if (strm->state->wrap == 1) {
-        strm->adler = adler32(strm->adler, strm->next_in, len);
-    }
-#ifdef GZIP
-    else if (strm->state->wrap == 2) {
-        strm->adler = crc32(strm->adler, strm->next_in, len);
-    }
-#endif
-    zmemcpy(buf, strm->next_in, len);
-    strm->next_in  += len;
-    strm->total_in += len;
-
-    return (int)len;
-}
-
-/* ===========================================================================
- * Initialize the "longest match" routines for a new zlib stream
- */
-local void lm_init (s)
-    deflate_state *s;
-{
-    s->window_size = (ulg)2L*s->w_size;
-
-    CLEAR_HASH(s);
-
-    /* Set the default configuration parameters:
-     */
-    s->max_lazy_match   = configuration_table[s->level].max_lazy;
-    s->good_match       = configuration_table[s->level].good_length;
-    s->nice_match       = configuration_table[s->level].nice_length;
-    s->max_chain_length = configuration_table[s->level].max_chain;
-
-    s->strstart = 0;
-    s->block_start = 0L;
-    s->lookahead = 0;
-    s->match_length = s->prev_length = MIN_MATCH-1;
-    s->match_available = 0;
-    s->ins_h = 0;
-#ifndef FASTEST
-#ifdef ASMV
-    match_init(); /* initialize the asm code */
-#endif
-#endif
-}
-
-#ifndef FASTEST
-/* ===========================================================================
- * Set match_start to the longest match starting at the given string and
- * return its length. Matches shorter or equal to prev_length are discarded,
- * in which case the result is equal to prev_length and match_start is
- * garbage.
- * IN assertions: cur_match is the head of the hash chain for the current
- *   string (strstart) and its distance is <= MAX_DIST, and prev_length >= 1
- * OUT assertion: the match length is not greater than s->lookahead.
- */
-#ifndef ASMV
-/* For 80x86 and 680x0, an optimized version will be provided in match.asm or
- * match.S. The code will be functionally equivalent.
- */
-local uInt longest_match(s, cur_match)
-    deflate_state *s;
-    IPos cur_match;                             /* current match */
-{
-    unsigned chain_length = s->max_chain_length;/* max hash chain length */
-    register Bytef *scan = s->window + s->strstart; /* current string */
-    register Bytef *match;                       /* matched string */
-    register int len;                           /* length of current match */
-    int best_len = s->prev_length;              /* best match length so far */
-    int nice_match = s->nice_match;             /* stop if match long enough */
-    IPos limit = s->strstart > (IPos)MAX_DIST(s) ?
-        s->strstart - (IPos)MAX_DIST(s) : NIL;
-    /* Stop when cur_match becomes <= limit. To simplify the code,
-     * we prevent matches with the string of window index 0.
-     */
-    Posf *prev = s->prev;
-    uInt wmask = s->w_mask;
-
-#ifdef UNALIGNED_OK
-    /* Compare two bytes at a time. Note: this is not always beneficial.
-     * Try with and without -DUNALIGNED_OK to check.
-     */
-    register Bytef *strend = s->window + s->strstart + MAX_MATCH - 1;
-    register ush scan_start = *(ushf*)scan;
-    register ush scan_end   = *(ushf*)(scan+best_len-1);
-#else
-    register Bytef *strend = s->window + s->strstart + MAX_MATCH;
-    register Byte scan_end1  = scan[best_len-1];
-    register Byte scan_end   = scan[best_len];
-#endif
-
-    /* The code is optimized for HASH_BITS >= 8 and MAX_MATCH-2 multiple of 16.
-     * It is easy to get rid of this optimization if necessary.
-     */
-    Assert(s->hash_bits >= 8 && MAX_MATCH == 258, "Code too clever");
-
-    /* Do not waste too much time if we already have a good match: */
-    if (s->prev_length >= s->good_match) {
-        chain_length >>= 2;
-    }
-    /* Do not look for matches beyond the end of the input. This is necessary
-     * to make deflate deterministic.
-     */
-    if ((uInt)nice_match > s->lookahead) nice_match = s->lookahead;
-
-    Assert((ulg)s->strstart <= s->window_size-MIN_LOOKAHEAD, "need lookahead");
-
-    do {
-        Assert(cur_match < s->strstart, "no future");
-        match = s->window + cur_match;
-
-        /* Skip to next match if the match length cannot increase
-         * or if the match length is less than 2.  Note that the checks below
-         * for insufficient lookahead only occur occasionally for performance
-         * reasons.  Therefore uninitialized memory will be accessed, and
-         * conditional jumps will be made that depend on those values.
-         * However the length of the match is limited to the lookahead, so
-         * the output of deflate is not affected by the uninitialized values.
-         */
-#if (defined(UNALIGNED_OK) && MAX_MATCH == 258)
-        /* This code assumes sizeof(unsigned short) == 2. Do not use
-         * UNALIGNED_OK if your compiler uses a different size.
-         */
-        if (*(ushf*)(match+best_len-1) != scan_end ||
-            *(ushf*)match != scan_start) continue;
-
-        /* It is not necessary to compare scan[2] and match[2] since they are
-         * always equal when the other bytes match, given that the hash keys
-         * are equal and that HASH_BITS >= 8. Compare 2 bytes at a time at
-         * strstart+3, +5, ... up to strstart+257. We check for insufficient
-         * lookahead only every 4th comparison; the 128th check will be made
-         * at strstart+257. If MAX_MATCH-2 is not a multiple of 8, it is
-         * necessary to put more guard bytes at the end of the window, or
-         * to check more often for insufficient lookahead.
-         */
-        Assert(scan[2] == match[2], "scan[2]?");
-        scan++, match++;
-        do {
-        } while (*(ushf*)(scan+=2) == *(ushf*)(match+=2) &&
-                 *(ushf*)(scan+=2) == *(ushf*)(match+=2) &&
-                 *(ushf*)(scan+=2) == *(ushf*)(match+=2) &&
-                 *(ushf*)(scan+=2) == *(ushf*)(match+=2) &&
-                 scan < strend);
-        /* The funny "do {}" generates better code on most compilers */
-
-        /* Here, scan <= window+strstart+257 */
-        Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan");
-        if (*scan == *match) scan++;
-
-        len = (MAX_MATCH - 1) - (int)(strend-scan);
-        scan = strend - (MAX_MATCH-1);
-
-#else /* UNALIGNED_OK */
-
-        if (match[best_len]   != scan_end  ||
-            match[best_len-1] != scan_end1 ||
-            *match            != *scan     ||
-            *++match          != scan[1])      continue;
-
-        /* The check at best_len-1 can be removed because it will be made
-         * again later. (This heuristic is not always a win.)
-         * It is not necessary to compare scan[2] and match[2] since they
-         * are always equal when the other bytes match, given that
-         * the hash keys are equal and that HASH_BITS >= 8.
-         */
-        scan += 2, match++;
-        Assert(*scan == *match, "match[2]?");
-
-        /* We check for insufficient lookahead only every 8th comparison;
-         * the 256th check will be made at strstart+258.
-         */
-        do {
-        } while (*++scan == *++match && *++scan == *++match &&
-                 *++scan == *++match && *++scan == *++match &&
-                 *++scan == *++match && *++scan == *++match &&
-                 *++scan == *++match && *++scan == *++match &&
-                 scan < strend);
-
-        Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan");
-
-        len = MAX_MATCH - (int)(strend - scan);
-        scan = strend - MAX_MATCH;
-
-#endif /* UNALIGNED_OK */
-
-        if (len > best_len) {
-            s->match_start = cur_match;
-            best_len = len;
-            if (len >= nice_match) break;
-#ifdef UNALIGNED_OK
-            scan_end = *(ushf*)(scan+best_len-1);
-#else
-            scan_end1  = scan[best_len-1];
-            scan_end   = scan[best_len];
-#endif
-        }
-    } while ((cur_match = prev[cur_match & wmask]) > limit
-             && --chain_length != 0);
-
-    if ((uInt)best_len <= s->lookahead) return (uInt)best_len;
-    return s->lookahead;
-}
-#endif /* ASMV */
-#endif /* FASTEST */
-
-/* ---------------------------------------------------------------------------
- * Optimized version for level == 1 or strategy == Z_RLE only
- */
-local uInt longest_match_fast(s, cur_match)
-    deflate_state *s;
-    IPos cur_match;                             /* current match */
-{
-    register Bytef *scan = s->window + s->strstart; /* current string */
-    register Bytef *match;                       /* matched string */
-    register int len;                           /* length of current match */
-    register Bytef *strend = s->window + s->strstart + MAX_MATCH;
-
-    /* The code is optimized for HASH_BITS >= 8 and MAX_MATCH-2 multiple of 16.
-     * It is easy to get rid of this optimization if necessary.
-     */
-    Assert(s->hash_bits >= 8 && MAX_MATCH == 258, "Code too clever");
-
-    Assert((ulg)s->strstart <= s->window_size-MIN_LOOKAHEAD, "need lookahead");
-
-    Assert(cur_match < s->strstart, "no future");
-
-    match = s->window + cur_match;
-
-    /* Return failure if the match length is less than 2:
-     */
-    if (match[0] != scan[0] || match[1] != scan[1]) return MIN_MATCH-1;
-
-    /* The check at best_len-1 can be removed because it will be made
-     * again later. (This heuristic is not always a win.)
-     * It is not necessary to compare scan[2] and match[2] since they
-     * are always equal when the other bytes match, given that
-     * the hash keys are equal and that HASH_BITS >= 8.
-     */
-    scan += 2, match += 2;
-    Assert(*scan == *match, "match[2]?");
-
-    /* We check for insufficient lookahead only every 8th comparison;
-     * the 256th check will be made at strstart+258.
-     */
-    do {
-    } while (*++scan == *++match && *++scan == *++match &&
-             *++scan == *++match && *++scan == *++match &&
-             *++scan == *++match && *++scan == *++match &&
-             *++scan == *++match && *++scan == *++match &&
-             scan < strend);
-
-    Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan");
-
-    len = MAX_MATCH - (int)(strend - scan);
-
-    if (len < MIN_MATCH) return MIN_MATCH - 1;
-
-    s->match_start = cur_match;
-    return (uInt)len <= s->lookahead ? (uInt)len : s->lookahead;
-}
-
-#ifdef DEBUG
-/* ===========================================================================
- * Check that the match at match_start is indeed a match.
- */
-local void check_match(s, start, match, length)
-    deflate_state *s;
-    IPos start, match;
-    int length;
-{
-    /* check that the match is indeed a match */
-    if (zmemcmp(s->window + match,
-                s->window + start, length) != EQUAL) {
-        fprintf(stderr, " start %u, match %u, length %d\n",
-                start, match, length);
-        do {
-            fprintf(stderr, "%c%c", s->window[match++], s->window[start++]);
-        } while (--length != 0);
-        z_error("invalid match");
-    }
-    if (z_verbose > 1) {
-        fprintf(stderr,"\\[%d,%d]", start-match, length);
-        do { putc(s->window[start++], stderr); } while (--length != 0);
-    }
-}
-#else
-#  define check_match(s, start, match, length)
-#endif /* DEBUG */
-
-/* ===========================================================================
- * Fill the window when the lookahead becomes insufficient.
- * Updates strstart and lookahead.
- *
- * IN assertion: lookahead < MIN_LOOKAHEAD
- * OUT assertions: strstart <= window_size-MIN_LOOKAHEAD
- *    At least one byte has been read, or avail_in == 0; reads are
- *    performed for at least two bytes (required for the zip translate_eol
- *    option -- not supported here).
- */
-local void fill_window(s)
-    deflate_state *s;
-{
-    register unsigned n, m;
-    register Posf *p;
-    unsigned more;    /* Amount of free space at the end of the window. */
-    uInt wsize = s->w_size;
-
-    do {
-        more = (unsigned)(s->window_size -(ulg)s->lookahead -(ulg)s->strstart);
-
-        /* Deal with !@#$% 64K limit: */
-        if (sizeof(int) <= 2) {
-            if (more == 0 && s->strstart == 0 && s->lookahead == 0) {
-                more = wsize;
-
-            } else if (more == (unsigned)(-1)) {
-                /* Very unlikely, but possible on 16 bit machine if
-                 * strstart == 0 && lookahead == 1 (input done a byte at time)
-                 */
-                more--;
-            }
-        }
-
-        /* If the window is almost full and there is insufficient lookahead,
-         * move the upper half to the lower one to make room in the upper half.
-         */
-        if (s->strstart >= wsize+MAX_DIST(s)) {
-
-            zmemcpy(s->window, s->window+wsize, (unsigned)wsize);
-            s->match_start -= wsize;
-            s->strstart    -= wsize; /* we now have strstart >= MAX_DIST */
-            s->block_start -= (int) wsize;
-
-            /* Slide the hash table (could be avoided with 32 bit values
-               at the expense of memory usage). We slide even when level == 0
-               to keep the hash table consistent if we switch back to level > 0
-               later. (Using level 0 permanently is not an optimal usage of
-               zlib, so we don't care about this pathological case.)
-             */
-            /* %%% avoid this when Z_RLE */
-            n = s->hash_size;
-            p = &s->head[n];
-            do {
-                m = *--p;
-                *p = (Pos)(m >= wsize ? m-wsize : NIL);
-            } while (--n);
-
-            n = wsize;
-#ifndef FASTEST
-            p = &s->prev[n];
-            do {
-                m = *--p;
-                *p = (Pos)(m >= wsize ? m-wsize : NIL);
-                /* If n is not on any hash chain, prev[n] is garbage but
-                 * its value will never be used.
-                 */
-            } while (--n);
-#endif
-            more += wsize;
-        }
-        if (s->strm->avail_in == 0) return;
-
-        /* If there was no sliding:
-         *    strstart <= WSIZE+MAX_DIST-1 && lookahead <= MIN_LOOKAHEAD - 1 &&
-         *    more == window_size - lookahead - strstart
-         * => more >= window_size - (MIN_LOOKAHEAD-1 + WSIZE + MAX_DIST-1)
-         * => more >= window_size - 2*WSIZE + 2
-         * In the BIG_MEM or MMAP case (not yet supported),
-         *   window_size == input_size + MIN_LOOKAHEAD  &&
-         *   strstart + s->lookahead <= input_size => more >= MIN_LOOKAHEAD.
-         * Otherwise, window_size == 2*WSIZE so more >= 2.
-         * If there was sliding, more >= WSIZE. So in all cases, more >= 2.
-         */
-        Assert(more >= 2, "more < 2");
-
-        n = read_buf(s->strm, s->window + s->strstart + s->lookahead, more);
-        s->lookahead += n;
-
-        /* Initialize the hash value now that we have some input: */
-        if (s->lookahead >= MIN_MATCH) {
-            s->ins_h = s->window[s->strstart];
-            UPDATE_HASH(s, s->ins_h, s->window[s->strstart+1]);
-#if MIN_MATCH != 3
-            Call UPDATE_HASH() MIN_MATCH-3 more times
-#endif
-        }
-        /* If the whole input has less than MIN_MATCH bytes, ins_h is garbage,
-         * but this is not important since only literal bytes will be emitted.
-         */
-
-    } while (s->lookahead < MIN_LOOKAHEAD && s->strm->avail_in != 0);
-}
-
-/* ===========================================================================
- * Flush the current block, with given end-of-file flag.
- * IN assertion: strstart is set to the end of the current match.
- */
-#define FLUSH_BLOCK_ONLY(s, eof) { \
-   _tr_flush_block(s, (s->block_start >= 0L ? \
-                   (charf *)&s->window[(unsigned)s->block_start] : \
-                   (charf *)Z_NULL), \
-                (ulg)((int)s->strstart - s->block_start), \
-                (eof)); \
-   s->block_start = s->strstart; \
-   flush_pending(s->strm); \
-   Tracev((stderr,"[FLUSH]")); \
-}
-
-/* Same but force premature exit if necessary. */
-#define FLUSH_BLOCK(s, eof) { \
-   FLUSH_BLOCK_ONLY(s, eof); \
-   if (s->strm->avail_out == 0) return (eof) ? finish_started : need_more; \
-}
-
-/* ===========================================================================
- * Copy without compression as much as possible from the input stream, return
- * the current block state.
- * This function does not insert new strings in the dictionary since
- * uncompressible data is probably not useful. This function is used
- * only for the level=0 compression option.
- * NOTE: this function should be optimized to avoid extra copying from
- * window to pending_buf.
- */
-local block_state deflate_stored(s, flush)
-    deflate_state *s;
-    int flush;
-{
-    /* Stored blocks are limited to 0xffff bytes, pending_buf is limited
-     * to pending_buf_size, and each stored block has a 5 byte header:
-     */
-    ulg max_block_size = 0xffff;
-    ulg max_start;
-
-    if (max_block_size > s->pending_buf_size - 5) {
-        max_block_size = s->pending_buf_size - 5;
-    }
-
-    /* Copy as much as possible from input to output: */
-    for (;;) {
-        /* Fill the window as much as possible: */
-        if (s->lookahead <= 1) {
-
-            Assert(s->strstart < s->w_size+MAX_DIST(s) ||
-                   s->block_start >= (int)s->w_size, "slide too late");
-
-            fill_window(s);
-            if (s->lookahead == 0 && flush == Z_NO_FLUSH) return need_more;
-
-            if (s->lookahead == 0) break; /* flush the current block */
-        }
-        Assert(s->block_start >= 0L, "block gone");
-
-        s->strstart += s->lookahead;
-        s->lookahead = 0;
-
-        /* Emit a stored block if pending_buf will be full: */
-        max_start = s->block_start + max_block_size;
-        if (s->strstart == 0 || (ulg)s->strstart >= max_start) {
-            /* strstart == 0 is possible when wraparound on 16-bit machine */
-            s->lookahead = (uInt)(s->strstart - max_start);
-            s->strstart = (uInt)max_start;
-            FLUSH_BLOCK(s, 0);
-        }
-        /* Flush if we may have to slide, otherwise block_start may become
-         * negative and the data will be gone:
-         */
-        if (s->strstart - (uInt)s->block_start >= MAX_DIST(s)) {
-            FLUSH_BLOCK(s, 0);
-        }
-    }
-    FLUSH_BLOCK(s, flush == Z_FINISH);
-    return flush == Z_FINISH ? finish_done : block_done;
-}
-
-/* ===========================================================================
- * Compress as much as possible from the input stream, return the current
- * block state.
- * This function does not perform lazy evaluation of matches and inserts
- * new strings in the dictionary only for unmatched strings or for short
- * matches. It is used only for the fast compression options.
- */
-local block_state deflate_fast(s, flush)
-    deflate_state *s;
-    int flush;
-{
-    IPos hash_head = NIL; /* head of the hash chain */
-    int bflush;           /* set if current block must be flushed */
-
-    for (;;) {
-        /* Make sure that we always have enough lookahead, except
-         * at the end of the input file. We need MAX_MATCH bytes
-         * for the next match, plus MIN_MATCH bytes to insert the
-         * string following the next match.
-         */
-        if (s->lookahead < MIN_LOOKAHEAD) {
-            fill_window(s);
-            if (s->lookahead < MIN_LOOKAHEAD && flush == Z_NO_FLUSH) {
-                return need_more;
-            }
-            if (s->lookahead == 0) break; /* flush the current block */
-        }
-
-        /* Insert the string window[strstart .. strstart+2] in the
-         * dictionary, and set hash_head to the head of the hash chain:
-         */
-        if (s->lookahead >= MIN_MATCH) {
-            INSERT_STRING(s, s->strstart, hash_head);
-        }
-
-        /* Find the longest match, discarding those <= prev_length.
-         * At this point we have always match_length < MIN_MATCH
-         */
-        if (hash_head != NIL && s->strstart - hash_head <= MAX_DIST(s)) {
-            /* To simplify the code, we prevent matches with the string
-             * of window index 0 (in particular we have to avoid a match
-             * of the string with itself at the start of the input file).
-             */
-#ifdef FASTEST
-            if ((s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) ||
-                (s->strategy == Z_RLE && s->strstart - hash_head == 1)) {
-                s->match_length = longest_match_fast (s, hash_head);
-            }
-#else
-            if (s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) {
-                s->match_length = longest_match (s, hash_head);
-            } else if (s->strategy == Z_RLE && s->strstart - hash_head == 1) {
-                s->match_length = longest_match_fast (s, hash_head);
-            }
-#endif
-            /* longest_match() or longest_match_fast() sets match_start */
-        }
-        if (s->match_length >= MIN_MATCH) {
-            check_match(s, s->strstart, s->match_start, s->match_length);
-
-            _tr_tally_dist(s, s->strstart - s->match_start,
-                           s->match_length - MIN_MATCH, bflush);
-
-            s->lookahead -= s->match_length;
-
-            /* Insert new strings in the hash table only if the match length
-             * is not too large. This saves time but degrades compression.
-             */
-#ifndef FASTEST
-            if (s->match_length <= s->max_insert_length &&
-                s->lookahead >= MIN_MATCH) {
-                s->match_length--; /* string at strstart already in table */
-                do {
-                    s->strstart++;
-                    INSERT_STRING(s, s->strstart, hash_head);
-                    /* strstart never exceeds WSIZE-MAX_MATCH, so there are
-                     * always MIN_MATCH bytes ahead.
-                     */
-                } while (--s->match_length != 0);
-                s->strstart++;
-            } else
-#endif
-            {
-                s->strstart += s->match_length;
-                s->match_length = 0;
-                s->ins_h = s->window[s->strstart];
-                UPDATE_HASH(s, s->ins_h, s->window[s->strstart+1]);
-#if MIN_MATCH != 3
-                Call UPDATE_HASH() MIN_MATCH-3 more times
-#endif
-                /* If lookahead < MIN_MATCH, ins_h is garbage, but it does not
-                 * matter since it will be recomputed at next deflate call.
-                 */
-            }
-        } else {
-            /* No match, output a literal byte */
-            Tracevv((stderr,"%c", s->window[s->strstart]));
-            _tr_tally_lit (s, s->window[s->strstart], bflush);
-            s->lookahead--;
-            s->strstart++;
-        }
-        if (bflush) FLUSH_BLOCK(s, 0);
-    }
-    FLUSH_BLOCK(s, flush == Z_FINISH);
-    return flush == Z_FINISH ? finish_done : block_done;
-}
-
-#ifndef FASTEST
-/* ===========================================================================
- * Same as above, but achieves better compression. We use a lazy
- * evaluation for matches: a match is finally adopted only if there is
- * no better match at the next window position.
- */
-local block_state deflate_slow(s, flush)
-    deflate_state *s;
-    int flush;
-{
-    IPos hash_head = NIL;    /* head of hash chain */
-    int bflush;              /* set if current block must be flushed */
-
-    /* Process the input block. */
-    for (;;) {
-        /* Make sure that we always have enough lookahead, except
-         * at the end of the input file. We need MAX_MATCH bytes
-         * for the next match, plus MIN_MATCH bytes to insert the
-         * string following the next match.
-         */
-        if (s->lookahead < MIN_LOOKAHEAD) {
-            fill_window(s);
-            if (s->lookahead < MIN_LOOKAHEAD && flush == Z_NO_FLUSH) {
-                return need_more;
-            }
-            if (s->lookahead == 0) break; /* flush the current block */
-        }
-
-        /* Insert the string window[strstart .. strstart+2] in the
-         * dictionary, and set hash_head to the head of the hash chain:
-         */
-        if (s->lookahead >= MIN_MATCH) {
-            INSERT_STRING(s, s->strstart, hash_head);
-        }
-
-        /* Find the longest match, discarding those <= prev_length.
-         */
-        s->prev_length = s->match_length, s->prev_match = s->match_start;
-        s->match_length = MIN_MATCH-1;
-
-        if (hash_head != NIL && s->prev_length < s->max_lazy_match &&
-            s->strstart - hash_head <= MAX_DIST(s)) {
-            /* To simplify the code, we prevent matches with the string
-             * of window index 0 (in particular we have to avoid a match
-             * of the string with itself at the start of the input file).
-             */
-            if (s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) {
-                s->match_length = longest_match (s, hash_head);
-            } else if (s->strategy == Z_RLE && s->strstart - hash_head == 1) {
-                s->match_length = longest_match_fast (s, hash_head);
-            }
-            /* longest_match() or longest_match_fast() sets match_start */
-
-            if (s->match_length <= 5 && (s->strategy == Z_FILTERED
-#if TOO_FAR <= 32767
-                || (s->match_length == MIN_MATCH &&
-                    s->strstart - s->match_start > TOO_FAR)
-#endif
-                )) {
-
-                /* If prev_match is also MIN_MATCH, match_start is garbage
-                 * but we will ignore the current match anyway.
-                 */
-                s->match_length = MIN_MATCH-1;
-            }
-        }
-        /* If there was a match at the previous step and the current
-         * match is not better, output the previous match:
-         */
-        if (s->prev_length >= MIN_MATCH && s->match_length <= s->prev_length) {
-            uInt max_insert = s->strstart + s->lookahead - MIN_MATCH;
-            /* Do not insert strings in hash table beyond this. */
-
-            check_match(s, s->strstart-1, s->prev_match, s->prev_length);
-
-            _tr_tally_dist(s, s->strstart -1 - s->prev_match,
-                           s->prev_length - MIN_MATCH, bflush);
-
-            /* Insert in hash table all strings up to the end of the match.
-             * strstart-1 and strstart are already inserted. If there is not
-             * enough lookahead, the last two strings are not inserted in
-             * the hash table.
-             */
-            s->lookahead -= s->prev_length-1;
-            s->prev_length -= 2;
-            do {
-                if (++s->strstart <= max_insert) {
-                    INSERT_STRING(s, s->strstart, hash_head);
-                }
-            } while (--s->prev_length != 0);
-            s->match_available = 0;
-            s->match_length = MIN_MATCH-1;
-            s->strstart++;
-
-            if (bflush) FLUSH_BLOCK(s, 0);
-
-        } else if (s->match_available) {
-            /* If there was no match at the previous position, output a
-             * single literal. If there was a match but the current match
-             * is longer, truncate the previous match to a single literal.
-             */
-            Tracevv((stderr,"%c", s->window[s->strstart-1]));
-            _tr_tally_lit(s, s->window[s->strstart-1], bflush);
-            if (bflush) {
-                FLUSH_BLOCK_ONLY(s, 0);
-            }
-            s->strstart++;
-            s->lookahead--;
-            if (s->strm->avail_out == 0) return need_more;
-        } else {
-            /* There is no previous match to compare with, wait for
-             * the next step to decide.
-             */
-            s->match_available = 1;
-            s->strstart++;
-            s->lookahead--;
-        }
-    }
-    Assert (flush != Z_NO_FLUSH, "no flush?");
-    if (s->match_available) {
-        Tracevv((stderr,"%c", s->window[s->strstart-1]));
-        _tr_tally_lit(s, s->window[s->strstart-1], bflush);
-        s->match_available = 0;
-    }
-    FLUSH_BLOCK(s, flush == Z_FINISH);
-    return flush == Z_FINISH ? finish_done : block_done;
-}
-#endif /* FASTEST */
-
-#if 0
-/* ===========================================================================
- * For Z_RLE, simply look for runs of bytes, generate matches only of distance
- * one.  Do not maintain a hash table.  (It will be regenerated if this run of
- * deflate switches away from Z_RLE.)
- */
-local block_state deflate_rle(s, flush)
-    deflate_state *s;
-    int flush;
-{
-    int bflush;         /* set if current block must be flushed */
-    uInt run;           /* length of run */
-    uInt max;           /* maximum length of run */
-    uInt prev;          /* byte at distance one to match */
-    Bytef *scan;        /* scan for end of run */
-
-    for (;;) {
-        /* Make sure that we always have enough lookahead, except
-         * at the end of the input file. We need MAX_MATCH bytes
-         * for the longest encodable run.
-         */
-        if (s->lookahead < MAX_MATCH) {
-            fill_window(s);
-            if (s->lookahead < MAX_MATCH && flush == Z_NO_FLUSH) {
-                return need_more;
-            }
-            if (s->lookahead == 0) break; /* flush the current block */
-        }
-
-        /* See how many times the previous byte repeats */
-        run = 0;
-        if (s->strstart > 0) {      /* if there is a previous byte, that is */
-            max = s->lookahead < MAX_MATCH ? s->lookahead : MAX_MATCH;
-            scan = s->window + s->strstart - 1;
-            prev = *scan++;
-            do {
-                if (*scan++ != prev)
-                    break;
-            } while (++run < max);
-        }
-
-        /* Emit match if have run of MIN_MATCH or longer, else emit literal */
-        if (run >= MIN_MATCH) {
-            check_match(s, s->strstart, s->strstart - 1, run);
-            _tr_tally_dist(s, 1, run - MIN_MATCH, bflush);
-            s->lookahead -= run;
-            s->strstart += run;
-        } else {
-            /* No match, output a literal byte */
-            Tracevv((stderr,"%c", s->window[s->strstart]));
-            _tr_tally_lit (s, s->window[s->strstart], bflush);
-            s->lookahead--;
-            s->strstart++;
-        }
-        if (bflush) FLUSH_BLOCK(s, 0);
-    }
-    FLUSH_BLOCK(s, flush == Z_FINISH);
-    return flush == Z_FINISH ? finish_done : block_done;
-}
-#endif
diff --git a/surface/src/3rdparty/opennurbs/infback.c b/surface/src/3rdparty/opennurbs/infback.c
deleted file mode 100644 (file)
index bd347de..0000000
+++ /dev/null
@@ -1,623 +0,0 @@
-/* infback.c -- inflate using a call-back interface
- * Copyright (C) 1995-2005 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/*
-   This code is largely copied from inflate.c.  Normally either infback.o or
-   inflate.o would be linked into an application--not both.  The interface
-   with inffast.c is retained so that optimized assembler-coded versions of
-   inflate_fast() can be used with either inflate.c or infback.c.
- */
-
-#include "pcl/surface/3rdparty/opennurbs/zutil.h"
-#include "pcl/surface/3rdparty/opennurbs/inftrees.h"
-#include "pcl/surface/3rdparty/opennurbs/inflate.h"
-#include "pcl/surface/3rdparty/opennurbs/inffast.h"
-
-/* function prototypes */
-local void fixedtables OF((struct inflate_state FAR *state));
-
-/*
-   strm provides memory allocation functions in zalloc and zfree, or
-   Z_NULL to use the library memory allocation functions.
-
-   windowBits is in the range 8..15, and window is a user-supplied
-   window and output buffer that is 2**windowBits bytes.
- */
-int ZEXPORT inflateBackInit_(strm, windowBits, window, version, stream_size)
-z_streamp strm;
-int windowBits;
-unsigned char FAR *window;
-const char *version;
-int stream_size;
-{
-    struct inflate_state FAR *state;
-
-    if (version == Z_NULL || version[0] != ZLIB_VERSION[0] ||
-        stream_size != (int)(sizeof(z_stream)))
-        return Z_VERSION_ERROR;
-    if (strm == Z_NULL || window == Z_NULL ||
-        windowBits < 8 || windowBits > 15)
-        return Z_STREAM_ERROR;
-    strm->msg = Z_NULL;                 /* in case we return an error */
-    if (strm->zalloc == (alloc_func)0) {
-        strm->zalloc = zcalloc;
-        strm->opaque = (voidpf)0;
-    }
-    if (strm->zfree == (free_func)0) strm->zfree = zcfree;
-    state = (struct inflate_state FAR *)ZALLOC(strm, 1,
-                                               sizeof(struct inflate_state));
-    if (state == Z_NULL) return Z_MEM_ERROR;
-    Tracev((stderr, "inflate: allocated\n"));
-    strm->state = (struct internal_state FAR *)state;
-    state->dmax = 32768U;
-    state->wbits = windowBits;
-    state->wsize = 1U << windowBits;
-    state->window = window;
-    state->write = 0;
-    state->whave = 0;
-    return Z_OK;
-}
-
-/*
-   Return state with length and distance decoding tables and index sizes set to
-   fixed code decoding.  Normally this returns fixed tables from inffixed.h.
-   If BUILDFIXED is defined, then instead this routine builds the tables the
-   first time it's called, and returns those tables the first time and
-   thereafter.  This reduces the size of the code by about 2K bytes, in
-   exchange for a little execution time.  However, BUILDFIXED should not be
-   used for threaded applications, since the rewriting of the tables and virgin
-   may not be thread-safe.
- */
-local void fixedtables(state)
-struct inflate_state FAR *state;
-{
-#ifdef BUILDFIXED
-    static int virgin = 1;
-    static code *lenfix, *distfix;
-    static code fixed[544];
-
-    /* build fixed huffman tables if first call (may not be thread safe) */
-    if (virgin) {
-        unsigned sym, bits;
-        static code *next;
-
-        /* literal/length table */
-        sym = 0;
-        while (sym < 144) state->lens[sym++] = 8;
-        while (sym < 256) state->lens[sym++] = 9;
-        while (sym < 280) state->lens[sym++] = 7;
-        while (sym < 288) state->lens[sym++] = 8;
-        next = fixed;
-        lenfix = next;
-        bits = 9;
-        inflate_table(LENS, state->lens, 288, &(next), &(bits), state->work);
-
-        /* distance table */
-        sym = 0;
-        while (sym < 32) state->lens[sym++] = 5;
-        distfix = next;
-        bits = 5;
-        inflate_table(DISTS, state->lens, 32, &(next), &(bits), state->work);
-
-        /* do this just once */
-        virgin = 0;
-    }
-#else /* !BUILDFIXED */
-#   include "pcl/surface/3rdparty/opennurbs/inffixed.h"
-#endif /* BUILDFIXED */
-    state->lencode = lenfix;
-    state->lenbits = 9;
-    state->distcode = distfix;
-    state->distbits = 5;
-}
-
-/* Macros for inflateBack(): */
-
-/* Load returned state from inflate_fast() */
-#define LOAD() \
-    do { \
-        put = strm->next_out; \
-        left = strm->avail_out; \
-        next = strm->next_in; \
-        have = strm->avail_in; \
-        hold = state->hold; \
-        bits = state->bits; \
-    } while (0)
-
-/* Set state from registers for inflate_fast() */
-#define RESTORE() \
-    do { \
-        strm->next_out = put; \
-        strm->avail_out = left; \
-        strm->next_in = next; \
-        strm->avail_in = have; \
-        state->hold = hold; \
-        state->bits = bits; \
-    } while (0)
-
-/* Clear the input bit accumulator */
-#define INITBITS() \
-    do { \
-        hold = 0; \
-        bits = 0; \
-    } while (0)
-
-/* Assure that some input is available.  If input is requested, but denied,
-   then return a Z_BUF_ERROR from inflateBack(). */
-#define PULL() \
-    do { \
-        if (have == 0) { \
-            have = in(in_desc, &next); \
-            if (have == 0) { \
-                next = Z_NULL; \
-                ret = Z_BUF_ERROR; \
-                goto inf_leave; \
-            } \
-        } \
-    } while (0)
-
-/* Get a byte of input into the bit accumulator, or return from inflateBack()
-   with an error if there is no input available. */
-#define PULLBYTE() \
-    do { \
-        PULL(); \
-        have--; \
-        hold += (unsigned int)(*next++) << bits; \
-        bits += 8; \
-    } while (0)
-
-/* Assure that there are at least n bits in the bit accumulator.  If there is
-   not enough available input to do that, then return from inflateBack() with
-   an error. */
-#define NEEDBITS(n) \
-    do { \
-        while (bits < (unsigned)(n)) \
-            PULLBYTE(); \
-    } while (0)
-
-/* Return the low n bits of the bit accumulator (n < 16) */
-#define BITS(n) \
-    ((unsigned)hold & ((1U << (n)) - 1))
-
-/* Remove n bits from the bit accumulator */
-#define DROPBITS(n) \
-    do { \
-        hold >>= (n); \
-        bits -= (unsigned)(n); \
-    } while (0)
-
-/* Remove zero to seven bits as needed to go to a byte boundary */
-#define BYTEBITS() \
-    do { \
-        hold >>= bits & 7; \
-        bits -= bits & 7; \
-    } while (0)
-
-/* Assure that some output space is available, by writing out the window
-   if it's full.  If the write fails, return from inflateBack() with a
-   Z_BUF_ERROR. */
-#define ROOM() \
-    do { \
-        if (left == 0) { \
-            put = state->window; \
-            left = state->wsize; \
-            state->whave = left; \
-            if (out(out_desc, put, left)) { \
-                ret = Z_BUF_ERROR; \
-                goto inf_leave; \
-            } \
-        } \
-    } while (0)
-
-/*
-   strm provides the memory allocation functions and window buffer on input,
-   and provides information on the unused input on return.  For Z_DATA_ERROR
-   returns, strm will also provide an error message.
-
-   in() and out() are the call-back input and output functions.  When
-   inflateBack() needs more input, it calls in().  When inflateBack() has
-   filled the window with output, or when it completes with data in the
-   window, it calls out() to write out the data.  The application must not
-   change the provided input until in() is called again or inflateBack()
-   returns.  The application must not change the window/output buffer until
-   inflateBack() returns.
-
-   in() and out() are called with a descriptor parameter provided in the
-   inflateBack() call.  This parameter can be a structure that provides the
-   information required to do the read or write, as well as accumulated
-   information on the input and output such as totals and check values.
-
-   in() should return zero on failure.  out() should return non-zero on
-   failure.  If either in() or out() fails, than inflateBack() returns a
-   Z_BUF_ERROR.  strm->next_in can be checked for Z_NULL to see whether it
-   was in() or out() that caused in the error.  Otherwise,  inflateBack()
-   returns Z_STREAM_END on success, Z_DATA_ERROR for an deflate format
-   error, or Z_MEM_ERROR if it could not allocate memory for the state.
-   inflateBack() can also return Z_STREAM_ERROR if the input parameters
-   are not correct, i.e. strm is Z_NULL or the state was not initialized.
- */
-int ZEXPORT inflateBack(strm, in, in_desc, out, out_desc)
-z_streamp strm;
-in_func in;
-void FAR *in_desc;
-out_func out;
-void FAR *out_desc;
-{
-    struct inflate_state FAR *state;
-    unsigned char FAR *next;    /* next input */
-    unsigned char FAR *put;     /* next output */
-    unsigned have, left;        /* available input and output */
-    unsigned int hold;         /* bit buffer */
-    unsigned bits;              /* bits in bit buffer */
-    unsigned copy;              /* number of stored or match bytes to copy */
-    unsigned char FAR *from;    /* where to copy match bytes from */
-    code this;                  /* current decoding table entry */
-    code last;                  /* parent table entry */
-    unsigned len;               /* length to copy for repeats, bits to drop */
-    int ret;                    /* return code */
-    static const unsigned short order[19] = /* permutation of code lengths */
-        {16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15};
-
-    /* Check that the strm exists and that the state was initialized */
-    if (strm == Z_NULL || strm->state == Z_NULL)
-        return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-
-    /* Reset the state */
-    strm->msg = Z_NULL;
-    state->mode = TYPE;
-    state->last = 0;
-    state->whave = 0;
-    next = strm->next_in;
-    have = next != Z_NULL ? strm->avail_in : 0;
-    hold = 0;
-    bits = 0;
-    put = state->window;
-    left = state->wsize;
-
-    /* Inflate until end of block marked as last */
-    for (;;)
-        switch (state->mode) {
-        case TYPE:
-            /* determine and dispatch block type */
-            if (state->last) {
-                BYTEBITS();
-                state->mode = DONE;
-                break;
-            }
-            NEEDBITS(3);
-            state->last = BITS(1);
-            DROPBITS(1);
-            switch (BITS(2)) {
-            case 0:                             /* stored block */
-                Tracev((stderr, "inflate:     stored block%s\n",
-                        state->last ? " (last)" : ""));
-                state->mode = STORED;
-                break;
-            case 1:                             /* fixed block */
-                fixedtables(state);
-                Tracev((stderr, "inflate:     fixed codes block%s\n",
-                        state->last ? " (last)" : ""));
-                state->mode = LEN;              /* decode codes */
-                break;
-            case 2:                             /* dynamic block */
-                Tracev((stderr, "inflate:     dynamic codes block%s\n",
-                        state->last ? " (last)" : ""));
-                state->mode = TABLE;
-                break;
-            case 3:
-                strm->msg = (char *)"invalid block type";
-                state->mode = BAD;
-            }
-            DROPBITS(2);
-            break;
-
-        case STORED:
-            /* get and verify stored block length */
-            BYTEBITS();                         /* go to byte boundary */
-            NEEDBITS(32);
-            if ((hold & 0xffff) != ((hold >> 16) ^ 0xffff)) {
-                strm->msg = (char *)"invalid stored block lengths";
-                state->mode = BAD;
-                break;
-            }
-            state->length = (unsigned)hold & 0xffff;
-            Tracev((stderr, "inflate:       stored length %u\n",
-                    state->length));
-            INITBITS();
-
-            /* copy stored block from input to output */
-            while (state->length != 0) {
-                copy = state->length;
-                PULL();
-                ROOM();
-                if (copy > have) copy = have;
-                if (copy > left) copy = left;
-                zmemcpy(put, next, copy);
-                have -= copy;
-                next += copy;
-                left -= copy;
-                put += copy;
-                state->length -= copy;
-            }
-            Tracev((stderr, "inflate:       stored end\n"));
-            state->mode = TYPE;
-            break;
-
-        case TABLE:
-            /* get dynamic table entries descriptor */
-            NEEDBITS(14);
-            state->nlen = BITS(5) + 257;
-            DROPBITS(5);
-            state->ndist = BITS(5) + 1;
-            DROPBITS(5);
-            state->ncode = BITS(4) + 4;
-            DROPBITS(4);
-#ifndef PKZIP_BUG_WORKAROUND
-            if (state->nlen > 286 || state->ndist > 30) {
-                strm->msg = (char *)"too many length or distance symbols";
-                state->mode = BAD;
-                break;
-            }
-#endif
-            Tracev((stderr, "inflate:       table sizes ok\n"));
-
-            /* get code length code lengths (not a typo) */
-            state->have = 0;
-            while (state->have < state->ncode) {
-                NEEDBITS(3);
-                state->lens[order[state->have++]] = (unsigned short)BITS(3);
-                DROPBITS(3);
-            }
-            while (state->have < 19)
-                state->lens[order[state->have++]] = 0;
-            state->next = state->codes;
-            state->lencode = (code const FAR *)(state->next);
-            state->lenbits = 7;
-            ret = inflate_table(CODES, state->lens, 19, &(state->next),
-                                &(state->lenbits), state->work);
-            if (ret) {
-                strm->msg = (char *)"invalid code lengths set";
-                state->mode = BAD;
-                break;
-            }
-            Tracev((stderr, "inflate:       code lengths ok\n"));
-
-            /* get length and distance code code lengths */
-            state->have = 0;
-            while (state->have < state->nlen + state->ndist) {
-                for (;;) {
-                    this = state->lencode[BITS(state->lenbits)];
-                    if ((unsigned)(this.bits) <= bits) break;
-                    PULLBYTE();
-                }
-                if (this.val < 16) {
-                    NEEDBITS(this.bits);
-                    DROPBITS(this.bits);
-                    state->lens[state->have++] = this.val;
-                }
-                else {
-                    if (this.val == 16) {
-                        NEEDBITS(this.bits + 2);
-                        DROPBITS(this.bits);
-                        if (state->have == 0) {
-                            strm->msg = (char *)"invalid bit length repeat";
-                            state->mode = BAD;
-                            break;
-                        }
-                        len = (unsigned)(state->lens[state->have - 1]);
-                        copy = 3 + BITS(2);
-                        DROPBITS(2);
-                    }
-                    else if (this.val == 17) {
-                        NEEDBITS(this.bits + 3);
-                        DROPBITS(this.bits);
-                        len = 0;
-                        copy = 3 + BITS(3);
-                        DROPBITS(3);
-                    }
-                    else {
-                        NEEDBITS(this.bits + 7);
-                        DROPBITS(this.bits);
-                        len = 0;
-                        copy = 11 + BITS(7);
-                        DROPBITS(7);
-                    }
-                    if (state->have + copy > state->nlen + state->ndist) {
-                        strm->msg = (char *)"invalid bit length repeat";
-                        state->mode = BAD;
-                        break;
-                    }
-                    while (copy--)
-                        state->lens[state->have++] = (unsigned short)len;
-                }
-            }
-
-            /* handle error breaks in while */
-            if (state->mode == BAD) break;
-
-            /* build code tables */
-            state->next = state->codes;
-            state->lencode = (code const FAR *)(state->next);
-            state->lenbits = 9;
-            ret = inflate_table(LENS, state->lens, state->nlen, &(state->next),
-                                &(state->lenbits), state->work);
-            if (ret) {
-                strm->msg = (char *)"invalid literal/lengths set";
-                state->mode = BAD;
-                break;
-            }
-            state->distcode = (code const FAR *)(state->next);
-            state->distbits = 6;
-            ret = inflate_table(DISTS, state->lens + state->nlen, state->ndist,
-                            &(state->next), &(state->distbits), state->work);
-            if (ret) {
-                strm->msg = (char *)"invalid distances set";
-                state->mode = BAD;
-                break;
-            }
-            Tracev((stderr, "inflate:       codes ok\n"));
-            state->mode = LEN;
-
-        case LEN:
-            /* use inflate_fast() if we have enough input and output */
-            if (have >= 6 && left >= 258) {
-                RESTORE();
-                if (state->whave < state->wsize)
-                    state->whave = state->wsize - left;
-                inflate_fast(strm, state->wsize);
-                LOAD();
-                break;
-            }
-
-            /* get a literal, length, or end-of-block code */
-            for (;;) {
-                this = state->lencode[BITS(state->lenbits)];
-                if ((unsigned)(this.bits) <= bits) break;
-                PULLBYTE();
-            }
-            if (this.op && (this.op & 0xf0) == 0) {
-                last = this;
-                for (;;) {
-                    this = state->lencode[last.val +
-                            (BITS(last.bits + last.op) >> last.bits)];
-                    if ((unsigned)(last.bits + this.bits) <= bits) break;
-                    PULLBYTE();
-                }
-                DROPBITS(last.bits);
-            }
-            DROPBITS(this.bits);
-            state->length = (unsigned)this.val;
-
-            /* process literal */
-            if (this.op == 0) {
-                Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ?
-                        "inflate:         literal '%c'\n" :
-                        "inflate:         literal 0x%02x\n", this.val));
-                ROOM();
-                *put++ = (unsigned char)(state->length);
-                left--;
-                state->mode = LEN;
-                break;
-            }
-
-            /* process end of block */
-            if (this.op & 32) {
-                Tracevv((stderr, "inflate:         end of block\n"));
-                state->mode = TYPE;
-                break;
-            }
-
-            /* invalid code */
-            if (this.op & 64) {
-                strm->msg = (char *)"invalid literal/length code";
-                state->mode = BAD;
-                break;
-            }
-
-            /* length code -- get extra bits, if any */
-            state->extra = (unsigned)(this.op) & 15;
-            if (state->extra != 0) {
-                NEEDBITS(state->extra);
-                state->length += BITS(state->extra);
-                DROPBITS(state->extra);
-            }
-            Tracevv((stderr, "inflate:         length %u\n", state->length));
-
-            /* get distance code */
-            for (;;) {
-                this = state->distcode[BITS(state->distbits)];
-                if ((unsigned)(this.bits) <= bits) break;
-                PULLBYTE();
-            }
-            if ((this.op & 0xf0) == 0) {
-                last = this;
-                for (;;) {
-                    this = state->distcode[last.val +
-                            (BITS(last.bits + last.op) >> last.bits)];
-                    if ((unsigned)(last.bits + this.bits) <= bits) break;
-                    PULLBYTE();
-                }
-                DROPBITS(last.bits);
-            }
-            DROPBITS(this.bits);
-            if (this.op & 64) {
-                strm->msg = (char *)"invalid distance code";
-                state->mode = BAD;
-                break;
-            }
-            state->offset = (unsigned)this.val;
-
-            /* get distance extra bits, if any */
-            state->extra = (unsigned)(this.op) & 15;
-            if (state->extra != 0) {
-                NEEDBITS(state->extra);
-                state->offset += BITS(state->extra);
-                DROPBITS(state->extra);
-            }
-            if (state->offset > state->wsize - (state->whave < state->wsize ?
-                                                left : 0)) {
-                strm->msg = (char *)"invalid distance too far back";
-                state->mode = BAD;
-                break;
-            }
-            Tracevv((stderr, "inflate:         distance %u\n", state->offset));
-
-            /* copy match from window to output */
-            do {
-                ROOM();
-                copy = state->wsize - state->offset;
-                if (copy < left) {
-                    from = put + copy;
-                    copy = left - copy;
-                }
-                else {
-                    from = put - state->offset;
-                    copy = left;
-                }
-                if (copy > state->length) copy = state->length;
-                state->length -= copy;
-                left -= copy;
-                do {
-                    *put++ = *from++;
-                } while (--copy);
-            } while (state->length != 0);
-            break;
-
-        case DONE:
-            /* inflate stream terminated properly -- write leftover output */
-            ret = Z_STREAM_END;
-            if (left < state->wsize) {
-                if (out(out_desc, state->window, state->wsize - left))
-                    ret = Z_BUF_ERROR;
-            }
-            goto inf_leave;
-
-        case BAD:
-            ret = Z_DATA_ERROR;
-            goto inf_leave;
-
-        default:                /* can't happen, but makes compilers happy */
-            ret = Z_STREAM_ERROR;
-            goto inf_leave;
-        }
-
-    /* Return unused input */
-  inf_leave:
-    strm->next_in = next;
-    strm->avail_in = have;
-    return ret;
-}
-
-int ZEXPORT inflateBackEnd(strm)
-z_streamp strm;
-{
-    if (strm == Z_NULL || strm->state == Z_NULL || strm->zfree == (free_func)0)
-        return Z_STREAM_ERROR;
-    ZFREE(strm, strm->state);
-    strm->state = Z_NULL;
-    Tracev((stderr, "inflate: end\n"));
-    return Z_OK;
-}
diff --git a/surface/src/3rdparty/opennurbs/inffast.c b/surface/src/3rdparty/opennurbs/inffast.c
deleted file mode 100644 (file)
index 63d9fdf..0000000
+++ /dev/null
@@ -1,318 +0,0 @@
-/* inffast.c -- fast decoding
- * Copyright (C) 1995-2004 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-#include "pcl/surface/3rdparty/opennurbs/zutil.h"
-#include "pcl/surface/3rdparty/opennurbs/inftrees.h"
-#include "pcl/surface/3rdparty/opennurbs/inflate.h"
-#include "pcl/surface/3rdparty/opennurbs/inffast.h"
-
-#ifndef ASMINF
-
-/* Allow machine dependent optimization for post-increment or pre-increment.
-   Based on testing to date,
-   Pre-increment preferred for:
-   - PowerPC G3 (Adler)
-   - MIPS R5000 (Randers-Pehrson)
-   Post-increment preferred for:
-   - none
-   No measurable difference:
-   - Pentium III (Anderson)
-   - M68060 (Nikl)
- */
-#ifdef POSTINC
-#  define OFF 0
-#  define PUP(a) *(a)++
-#else
-#  define OFF 1
-#  define PUP(a) *++(a)
-#endif
-
-/*
-   Decode literal, length, and distance codes and write out the resulting
-   literal and match bytes until either not enough input or output is
-   available, an end-of-block is encountered, or a data error is encountered.
-   When large enough input and output buffers are supplied to inflate(), for
-   example, a 16K input buffer and a 64K output buffer, more than 95% of the
-   inflate execution time is spent in this routine.
-
-   Entry assumptions:
-
-        state->mode == LEN
-        strm->avail_in >= 6
-        strm->avail_out >= 258
-        start >= strm->avail_out
-        state->bits < 8
-
-   On return, state->mode is one of:
-
-        LEN -- ran out of enough output space or enough available input
-        TYPE -- reached end of block code, inflate() to interpret next block
-        BAD -- error in block data
-
-   Notes:
-
-    - The maximum input bits used by a length/distance pair is 15 bits for the
-      length code, 5 bits for the length extra, 15 bits for the distance code,
-      and 13 bits for the distance extra.  This totals 48 bits, or six bytes.
-      Therefore if strm->avail_in >= 6, then there is enough input to avoid
-      checking for available input while decoding.
-
-    - The maximum bytes that a single length/distance pair can output is 258
-      bytes, which is the maximum length that can be coded.  inflate_fast()
-      requires strm->avail_out >= 258 for each loop to avoid checking for
-      output space.
- */
-void inflate_fast(strm, start)
-z_streamp strm;
-unsigned start;         /* inflate()'s starting value for strm->avail_out */
-{
-    struct inflate_state FAR *state;
-    unsigned char FAR *in;      /* local strm->next_in */
-    unsigned char FAR *last;    /* while in < last, enough input available */
-    unsigned char FAR *out;     /* local strm->next_out */
-    unsigned char FAR *beg;     /* inflate()'s initial strm->next_out */
-    unsigned char FAR *end;     /* while out < end, enough space available */
-#ifdef INFLATE_STRICT
-    unsigned dmax;              /* maximum distance from zlib header */
-#endif
-    unsigned wsize;             /* window size or zero if not using window */
-    unsigned whave;             /* valid bytes in the window */
-    unsigned write;             /* window write index */
-    unsigned char FAR *window;  /* allocated sliding window, if wsize != 0 */
-    unsigned int hold;         /* local strm->hold */
-    unsigned bits;              /* local strm->bits */
-    code const FAR *lcode;      /* local strm->lencode */
-    code const FAR *dcode;      /* local strm->distcode */
-    unsigned lmask;             /* mask for first level of length codes */
-    unsigned dmask;             /* mask for first level of distance codes */
-    code this;                  /* retrieved table entry */
-    unsigned op;                /* code bits, operation, extra bits, or */
-                                /*  window position, window bytes to copy */
-    unsigned len;               /* match length, unused bytes */
-    unsigned dist;              /* match distance */
-    unsigned char FAR *from;    /* where to copy match from */
-
-    /* copy state to local variables */
-    state = (struct inflate_state FAR *)strm->state;
-    in = strm->next_in - OFF;
-    last = in + (strm->avail_in - 5);
-    out = strm->next_out - OFF;
-    beg = out - (start - strm->avail_out);
-    end = out + (strm->avail_out - 257);
-#ifdef INFLATE_STRICT
-    dmax = state->dmax;
-#endif
-    wsize = state->wsize;
-    whave = state->whave;
-    write = state->write;
-    window = state->window;
-    hold = state->hold;
-    bits = state->bits;
-    lcode = state->lencode;
-    dcode = state->distcode;
-    lmask = (1U << state->lenbits) - 1;
-    dmask = (1U << state->distbits) - 1;
-
-    /* decode literals and length/distances until end-of-block or not enough
-       input data or output space */
-    do {
-        if (bits < 15) {
-            hold += (unsigned int)(PUP(in)) << bits;
-            bits += 8;
-            hold += (unsigned int)(PUP(in)) << bits;
-            bits += 8;
-        }
-        this = lcode[hold & lmask];
-      dolen:
-        op = (unsigned)(this.bits);
-        hold >>= op;
-        bits -= op;
-        op = (unsigned)(this.op);
-        if (op == 0) {                          /* literal */
-            Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ?
-                    "inflate:         literal '%c'\n" :
-                    "inflate:         literal 0x%02x\n", this.val));
-            PUP(out) = (unsigned char)(this.val);
-        }
-        else if (op & 16) {                     /* length base */
-            len = (unsigned)(this.val);
-            op &= 15;                           /* number of extra bits */
-            if (op) {
-                if (bits < op) {
-                    hold += (unsigned int)(PUP(in)) << bits;
-                    bits += 8;
-                }
-                len += (unsigned)hold & ((1U << op) - 1);
-                hold >>= op;
-                bits -= op;
-            }
-            Tracevv((stderr, "inflate:         length %u\n", len));
-            if (bits < 15) {
-                hold += (unsigned int)(PUP(in)) << bits;
-                bits += 8;
-                hold += (unsigned int)(PUP(in)) << bits;
-                bits += 8;
-            }
-            this = dcode[hold & dmask];
-          dodist:
-            op = (unsigned)(this.bits);
-            hold >>= op;
-            bits -= op;
-            op = (unsigned)(this.op);
-            if (op & 16) {                      /* distance base */
-                dist = (unsigned)(this.val);
-                op &= 15;                       /* number of extra bits */
-                if (bits < op) {
-                    hold += (unsigned int)(PUP(in)) << bits;
-                    bits += 8;
-                    if (bits < op) {
-                        hold += (unsigned int)(PUP(in)) << bits;
-                        bits += 8;
-                    }
-                }
-                dist += (unsigned)hold & ((1U << op) - 1);
-#ifdef INFLATE_STRICT
-                if (dist > dmax) {
-                    strm->msg = (char *)"invalid distance too far back";
-                    state->mode = BAD;
-                    break;
-                }
-#endif
-                hold >>= op;
-                bits -= op;
-                Tracevv((stderr, "inflate:         distance %u\n", dist));
-                op = (unsigned)(out - beg);     /* max distance in output */
-                if (dist > op) {                /* see if copy from window */
-                    op = dist - op;             /* distance back in window */
-                    if (op > whave) {
-                        strm->msg = (char *)"invalid distance too far back";
-                        state->mode = BAD;
-                        break;
-                    }
-                    from = window - OFF;
-                    if (write == 0) {           /* very common case */
-                        from += wsize - op;
-                        if (op < len) {         /* some from window */
-                            len -= op;
-                            do {
-                                PUP(out) = PUP(from);
-                            } while (--op);
-                            from = out - dist;  /* rest from output */
-                        }
-                    }
-                    else if (write < op) {      /* wrap around window */
-                        from += wsize + write - op;
-                        op -= write;
-                        if (op < len) {         /* some from end of window */
-                            len -= op;
-                            do {
-                                PUP(out) = PUP(from);
-                            } while (--op);
-                            from = window - OFF;
-                            if (write < len) {  /* some from start of window */
-                                op = write;
-                                len -= op;
-                                do {
-                                    PUP(out) = PUP(from);
-                                } while (--op);
-                                from = out - dist;      /* rest from output */
-                            }
-                        }
-                    }
-                    else {                      /* contiguous in window */
-                        from += write - op;
-                        if (op < len) {         /* some from window */
-                            len -= op;
-                            do {
-                                PUP(out) = PUP(from);
-                            } while (--op);
-                            from = out - dist;  /* rest from output */
-                        }
-                    }
-                    while (len > 2) {
-                        PUP(out) = PUP(from);
-                        PUP(out) = PUP(from);
-                        PUP(out) = PUP(from);
-                        len -= 3;
-                    }
-                    if (len) {
-                        PUP(out) = PUP(from);
-                        if (len > 1)
-                            PUP(out) = PUP(from);
-                    }
-                }
-                else {
-                    from = out - dist;          /* copy direct from output */
-                    do {                        /* minimum length is three */
-                        PUP(out) = PUP(from);
-                        PUP(out) = PUP(from);
-                        PUP(out) = PUP(from);
-                        len -= 3;
-                    } while (len > 2);
-                    if (len) {
-                        PUP(out) = PUP(from);
-                        if (len > 1)
-                            PUP(out) = PUP(from);
-                    }
-                }
-            }
-            else if ((op & 64) == 0) {          /* 2nd level distance code */
-                this = dcode[this.val + (hold & ((1U << op) - 1))];
-                goto dodist;
-            }
-            else {
-                strm->msg = (char *)"invalid distance code";
-                state->mode = BAD;
-                break;
-            }
-        }
-        else if ((op & 64) == 0) {              /* 2nd level length code */
-            this = lcode[this.val + (hold & ((1U << op) - 1))];
-            goto dolen;
-        }
-        else if (op & 32) {                     /* end-of-block */
-            Tracevv((stderr, "inflate:         end of block\n"));
-            state->mode = TYPE;
-            break;
-        }
-        else {
-            strm->msg = (char *)"invalid literal/length code";
-            state->mode = BAD;
-            break;
-        }
-    } while (in < last && out < end);
-
-    /* return unused bytes (on entry, bits < 8, so in won't go too far back) */
-    len = bits >> 3;
-    in -= len;
-    bits -= len << 3;
-    hold &= (1U << bits) - 1;
-
-    /* update state and return */
-    strm->next_in = in + OFF;
-    strm->next_out = out + OFF;
-    strm->avail_in = (unsigned)(in < last ? 5 + (last - in) : 5 - (in - last));
-    strm->avail_out = (unsigned)(out < end ?
-                                 257 + (end - out) : 257 - (out - end));
-    state->hold = hold;
-    state->bits = bits;
-    return;
-}
-
-/*
-   inflate_fast() speedups that turned out slower (on a PowerPC G3 750CXe):
-   - Using bit fields for code structure
-   - Different op definition to avoid & for extra bits (do & for table bits)
-   - Three separate decoding do-loops for direct, window, and write == 0
-   - Special case for distance > 1 copies to do overlapped load and store copy
-   - Explicit branch predictions (based on measured branch probabilities)
-   - Deferring match copy and interspersed it with decoding subsequent codes
-   - Swapping literal/length else
-   - Swapping window/direct else
-   - Larger unrolled copy loops (three is about right)
-   - Moving len -= 3 statement into middle of loop
- */
-
-#endif /* !ASMINF */
diff --git a/surface/src/3rdparty/opennurbs/inflate.c b/surface/src/3rdparty/opennurbs/inflate.c
deleted file mode 100644 (file)
index 61a9df9..0000000
+++ /dev/null
@@ -1,1368 +0,0 @@
-/* inflate.c -- zlib decompression
- * Copyright (C) 1995-2005 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/*
- * Change history:
- *
- * 1.2.beta0    24 Nov 2002
- * - First version -- complete rewrite of inflate to simplify code, avoid
- *   creation of window when not needed, minimize use of window when it is
- *   needed, make inffast.c even faster, implement gzip decoding, and to
- *   improve code readability and style over the previous zlib inflate code
- *
- * 1.2.beta1    25 Nov 2002
- * - Use pointers for available input and output checking in inffast.c
- * - Remove input and output counters in inffast.c
- * - Change inffast.c entry and loop from avail_in >= 7 to >= 6
- * - Remove unnecessary second byte pull from length extra in inffast.c
- * - Unroll direct copy to three copies per loop in inffast.c
- *
- * 1.2.beta2    4 Dec 2002
- * - Change external routine names to reduce potential conflicts
- * - Correct filename to inffixed.h for fixed tables in inflate.c
- * - Make hbuf[] unsigned char to match parameter type in inflate.c
- * - Change strm->next_out[-state->offset] to *(strm->next_out - state->offset)
- *   to avoid negation problem on Alphas (64 bit) in inflate.c
- *
- * 1.2.beta3    22 Dec 2002
- * - Add comments on state->bits assertion in inffast.c
- * - Add comments on op field in inftrees.h
- * - Fix bug in reuse of allocated window after inflateReset()
- * - Remove bit fields--back to byte structure for speed
- * - Remove distance extra == 0 check in inflate_fast()--only helps for lengths
- * - Change post-increments to pre-increments in inflate_fast(), PPC biased?
- * - Add compile time option, POSTINC, to use post-increments instead (Intel?)
- * - Make MATCH copy in inflate() much faster for when inflate_fast() not used
- * - Use local copies of stream next and avail values, as well as local bit
- *   buffer and bit count in inflate()--for speed when inflate_fast() not used
- *
- * 1.2.beta4    1 Jan 2003
- * - Split ptr - 257 statements in inflate_table() to avoid compiler warnings
- * - Move a comment on output buffer sizes from inffast.c to inflate.c
- * - Add comments in inffast.c to introduce the inflate_fast() routine
- * - Rearrange window copies in inflate_fast() for speed and simplification
- * - Unroll last copy for window match in inflate_fast()
- * - Use local copies of window variables in inflate_fast() for speed
- * - Pull out common write == 0 case for speed in inflate_fast()
- * - Make op and len in inflate_fast() unsigned for consistency
- * - Add FAR to lcode and dcode declarations in inflate_fast()
- * - Simplified bad distance check in inflate_fast()
- * - Added inflateBackInit(), inflateBack(), and inflateBackEnd() in new
- *   source file infback.c to provide a call-back interface to inflate for
- *   programs like gzip and unzip -- uses window as output buffer to avoid
- *   window copying
- *
- * 1.2.beta5    1 Jan 2003
- * - Improved inflateBack() interface to allow the caller to provide initial
- *   input in strm.
- * - Fixed stored blocks bug in inflateBack()
- *
- * 1.2.beta6    4 Jan 2003
- * - Added comments in inffast.c on effectiveness of POSTINC
- * - Typecasting all around to reduce compiler warnings
- * - Changed loops from while (1) or do {} while (1) to for (;;), again to
- *   make compilers happy
- * - Changed type of window in inflateBackInit() to unsigned char *
- *
- * 1.2.beta7    27 Jan 2003
- * - Changed many types to unsigned or unsigned short to avoid warnings
- * - Added inflateCopy() function
- *
- * 1.2.0        9 Mar 2003
- * - Changed inflateBack() interface to provide separate opaque descriptors
- *   for the in() and out() functions
- * - Changed inflateBack() argument and in_func typedef to swap the length
- *   and buffer address return values for the input function
- * - Check next_in and next_out for Z_NULL on entry to inflate()
- *
- * The history for versions after 1.2.0 are in ChangeLog in zlib distribution.
- */
-
-#include "pcl/surface/3rdparty/opennurbs/zutil.h"
-#include "pcl/surface/3rdparty/opennurbs/inftrees.h"
-#include "pcl/surface/3rdparty/opennurbs/inflate.h"
-#include "pcl/surface/3rdparty/opennurbs/inffast.h"
-
-#ifdef MAKEFIXED
-#  ifndef BUILDFIXED
-#    define BUILDFIXED
-#  endif
-#endif
-
-/* function prototypes */
-local void fixedtables OF((struct inflate_state FAR *state));
-local int updatewindow OF((z_streamp strm, unsigned out));
-#ifdef BUILDFIXED
-   void makefixed OF((void));
-#endif
-local unsigned syncsearch OF((unsigned FAR *have, unsigned char FAR *buf,
-                              unsigned len));
-
-int ZEXPORT inflateReset(strm)
-z_streamp strm;
-{
-    struct inflate_state FAR *state;
-
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-    strm->total_in = strm->total_out = state->total = 0;
-    strm->msg = Z_NULL;
-    strm->adler = 1;        /* to support ill-conceived Java test suite */
-    state->mode = HEAD;
-    state->last = 0;
-    state->havedict = 0;
-    state->dmax = 32768U;
-    state->head = Z_NULL;
-    state->wsize = 0;
-    state->whave = 0;
-    state->write = 0;
-    state->hold = 0;
-    state->bits = 0;
-    state->lencode = state->distcode = state->next = state->codes;
-    Tracev((stderr, "inflate: reset\n"));
-    return Z_OK;
-}
-
-int ZEXPORT inflatePrime(strm, bits, value)
-z_streamp strm;
-int bits;
-int value;
-{
-    struct inflate_state FAR *state;
-
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-    if (bits > 16 || state->bits + bits > 32) return Z_STREAM_ERROR;
-    value &= (1L << bits) - 1;
-    state->hold += value << state->bits;
-    state->bits += bits;
-    return Z_OK;
-}
-
-int ZEXPORT inflateInit2_(strm, windowBits, version, stream_size)
-z_streamp strm;
-int windowBits;
-const char *version;
-int stream_size;
-{
-    struct inflate_state FAR *state;
-
-    if (version == Z_NULL || version[0] != ZLIB_VERSION[0] ||
-        stream_size != (int)(sizeof(z_stream)))
-        return Z_VERSION_ERROR;
-    if (strm == Z_NULL) return Z_STREAM_ERROR;
-    strm->msg = Z_NULL;                 /* in case we return an error */
-    if (strm->zalloc == (alloc_func)0) {
-        strm->zalloc = zcalloc;
-        strm->opaque = (voidpf)0;
-    }
-    if (strm->zfree == (free_func)0) strm->zfree = zcfree;
-    state = (struct inflate_state FAR *)
-            ZALLOC(strm, 1, sizeof(struct inflate_state));
-    if (state == Z_NULL) return Z_MEM_ERROR;
-    Tracev((stderr, "inflate: allocated\n"));
-    strm->state = (struct internal_state FAR *)state;
-    if (windowBits < 0) {
-        state->wrap = 0;
-        windowBits = -windowBits;
-    }
-    else {
-        state->wrap = (windowBits >> 4) + 1;
-#ifdef GUNZIP
-        if (windowBits < 48) windowBits &= 15;
-#endif
-    }
-    if (windowBits < 8 || windowBits > 15) {
-        ZFREE(strm, state);
-        strm->state = Z_NULL;
-        return Z_STREAM_ERROR;
-    }
-    state->wbits = (unsigned)windowBits;
-    state->window = Z_NULL;
-    return inflateReset(strm);
-}
-
-int ZEXPORT inflateInit_(strm, version, stream_size)
-z_streamp strm;
-const char *version;
-int stream_size;
-{
-    return inflateInit2_(strm, DEF_WBITS, version, stream_size);
-}
-
-/*
-   Return state with length and distance decoding tables and index sizes set to
-   fixed code decoding.  Normally this returns fixed tables from inffixed.h.
-   If BUILDFIXED is defined, then instead this routine builds the tables the
-   first time it's called, and returns those tables the first time and
-   thereafter.  This reduces the size of the code by about 2K bytes, in
-   exchange for a little execution time.  However, BUILDFIXED should not be
-   used for threaded applications, since the rewriting of the tables and virgin
-   may not be thread-safe.
- */
-local void fixedtables(state)
-struct inflate_state FAR *state;
-{
-#ifdef BUILDFIXED
-    static int virgin = 1;
-    static code *lenfix, *distfix;
-    static code fixed[544];
-
-    /* build fixed huffman tables if first call (may not be thread safe) */
-    if (virgin) {
-        unsigned sym, bits;
-        static code *next;
-
-        /* literal/length table */
-        sym = 0;
-        while (sym < 144) state->lens[sym++] = 8;
-        while (sym < 256) state->lens[sym++] = 9;
-        while (sym < 280) state->lens[sym++] = 7;
-        while (sym < 288) state->lens[sym++] = 8;
-        next = fixed;
-        lenfix = next;
-        bits = 9;
-        inflate_table(LENS, state->lens, 288, &(next), &(bits), state->work);
-
-        /* distance table */
-        sym = 0;
-        while (sym < 32) state->lens[sym++] = 5;
-        distfix = next;
-        bits = 5;
-        inflate_table(DISTS, state->lens, 32, &(next), &(bits), state->work);
-
-        /* do this just once */
-        virgin = 0;
-    }
-#else /* !BUILDFIXED */
-#   include "pcl/surface/3rdparty/opennurbs/inffixed.h"
-#endif /* BUILDFIXED */
-    state->lencode = lenfix;
-    state->lenbits = 9;
-    state->distcode = distfix;
-    state->distbits = 5;
-}
-
-#ifdef MAKEFIXED
-#include <stdio.h>
-
-/*
-   Write out the inffixed.h that is #include'd above.  Defining MAKEFIXED also
-   defines BUILDFIXED, so the tables are built on the fly.  makefixed() writes
-   those tables to stdout, which would be piped to inffixed.h.  A small program
-   can simply call makefixed to do this:
-
-    void makefixed(void);
-
-    int main(void)
-    {
-        makefixed();
-        return 0;
-    }
-
-   Then that can be linked with zlib built with MAKEFIXED defined and run:
-
-    a.out > inffixed.h
- */
-void makefixed()
-{
-    unsigned low, size;
-    struct inflate_state state;
-
-    fixedtables(&state);
-    puts("    /* inffixed.h -- table for decoding fixed codes");
-    puts("     * Generated automatically by makefixed().");
-    puts("     */");
-    puts("");
-    puts("    /* WARNING: this file should *not* be used by applications.");
-    puts("       It is part of the implementation of this library and is");
-    puts("       subject to change. Applications should only use zlib.h.");
-    puts("     */");
-    puts("");
-    size = 1U << 9;
-    printf("    static const code lenfix[%u] = {", size);
-    low = 0;
-    for (;;) {
-        if ((low % 7) == 0) printf("\n        ");
-        printf("{%u,%u,%d}", state.lencode[low].op, state.lencode[low].bits,
-               state.lencode[low].val);
-        if (++low == size) break;
-        putchar(',');
-    }
-    puts("\n    };");
-    size = 1U << 5;
-    printf("\n    static const code distfix[%u] = {", size);
-    low = 0;
-    for (;;) {
-        if ((low % 6) == 0) printf("\n        ");
-        printf("{%u,%u,%d}", state.distcode[low].op, state.distcode[low].bits,
-               state.distcode[low].val);
-        if (++low == size) break;
-        putchar(',');
-    }
-    puts("\n    };");
-}
-#endif /* MAKEFIXED */
-
-/*
-   Update the window with the last wsize (normally 32K) bytes written before
-   returning.  If window does not exist yet, create it.  This is only called
-   when a window is already in use, or when output has been written during this
-   inflate call, but the end of the deflate stream has not been reached yet.
-   It is also called to create a window for dictionary data when a dictionary
-   is loaded.
-
-   Providing output buffers larger than 32K to inflate() should provide a speed
-   advantage, since only the last 32K of output is copied to the sliding window
-   upon return from inflate(), and since all distances after the first 32K of
-   output will fall in the output data, making match copies simpler and faster.
-   The advantage may be dependent on the size of the processor's data caches.
- */
-local int updatewindow(strm, out)
-z_streamp strm;
-unsigned out;
-{
-    struct inflate_state FAR *state;
-    unsigned copy, dist;
-
-    state = (struct inflate_state FAR *)strm->state;
-
-    /* if it hasn't been done already, allocate space for the window */
-    if (state->window == Z_NULL) {
-        state->window = (unsigned char FAR *)
-                        ZALLOC(strm, 1U << state->wbits,
-                               sizeof(unsigned char));
-        if (state->window == Z_NULL) return 1;
-    }
-
-    /* if window not in use yet, initialize */
-    if (state->wsize == 0) {
-        state->wsize = 1U << state->wbits;
-        state->write = 0;
-        state->whave = 0;
-    }
-
-    /* copy state->wsize or less output bytes into the circular window */
-    copy = out - strm->avail_out;
-    if (copy >= state->wsize) {
-        zmemcpy(state->window, strm->next_out - state->wsize, state->wsize);
-        state->write = 0;
-        state->whave = state->wsize;
-    }
-    else {
-        dist = state->wsize - state->write;
-        if (dist > copy) dist = copy;
-        zmemcpy(state->window + state->write, strm->next_out - copy, dist);
-        copy -= dist;
-        if (copy) {
-            zmemcpy(state->window, strm->next_out - copy, copy);
-            state->write = copy;
-            state->whave = state->wsize;
-        }
-        else {
-            state->write += dist;
-            if (state->write == state->wsize) state->write = 0;
-            if (state->whave < state->wsize) state->whave += dist;
-        }
-    }
-    return 0;
-}
-
-/* Macros for inflate(): */
-
-/* check function to use adler32() for zlib or crc32() for gzip */
-#ifdef GUNZIP
-#  define UPDATE(check, buf, len) \
-    (state->flags ? crc32(check, buf, len) : adler32(check, buf, len))
-#else
-#  define UPDATE(check, buf, len) adler32(check, buf, len)
-#endif
-
-/* check macros for header crc */
-#ifdef GUNZIP
-#  define CRC2(check, word) \
-    do { \
-        hbuf[0] = (unsigned char)(word); \
-        hbuf[1] = (unsigned char)((word) >> 8); \
-        check = crc32(check, hbuf, 2); \
-    } while (0)
-
-#  define CRC4(check, word) \
-    do { \
-        hbuf[0] = (unsigned char)(word); \
-        hbuf[1] = (unsigned char)((word) >> 8); \
-        hbuf[2] = (unsigned char)((word) >> 16); \
-        hbuf[3] = (unsigned char)((word) >> 24); \
-        check = crc32(check, hbuf, 4); \
-    } while (0)
-#endif
-
-/* Load registers with state in inflate() for speed */
-#define LOAD() \
-    do { \
-        put = strm->next_out; \
-        left = strm->avail_out; \
-        next = strm->next_in; \
-        have = strm->avail_in; \
-        hold = state->hold; \
-        bits = state->bits; \
-    } while (0)
-
-/* Restore state from registers in inflate() */
-#define RESTORE() \
-    do { \
-        strm->next_out = put; \
-        strm->avail_out = left; \
-        strm->next_in = next; \
-        strm->avail_in = have; \
-        state->hold = hold; \
-        state->bits = bits; \
-    } while (0)
-
-/* Clear the input bit accumulator */
-#define INITBITS() \
-    do { \
-        hold = 0; \
-        bits = 0; \
-    } while (0)
-
-/* Get a byte of input into the bit accumulator, or return from inflate()
-   if there is no input available. */
-#define PULLBYTE() \
-    do { \
-        if (have == 0) goto inf_leave; \
-        have--; \
-        hold += (unsigned int)(*next++) << bits; \
-        bits += 8; \
-    } while (0)
-
-/* Assure that there are at least n bits in the bit accumulator.  If there is
-   not enough available input to do that, then return from inflate(). */
-#define NEEDBITS(n) \
-    do { \
-        while (bits < (unsigned)(n)) \
-            PULLBYTE(); \
-    } while (0)
-
-/* Return the low n bits of the bit accumulator (n < 16) */
-#define BITS(n) \
-    ((unsigned)hold & ((1U << (n)) - 1))
-
-/* Remove n bits from the bit accumulator */
-#define DROPBITS(n) \
-    do { \
-        hold >>= (n); \
-        bits -= (unsigned)(n); \
-    } while (0)
-
-/* Remove zero to seven bits as needed to go to a byte boundary */
-#define BYTEBITS() \
-    do { \
-        hold >>= bits & 7; \
-        bits -= bits & 7; \
-    } while (0)
-
-/* Reverse the bytes in a 32-bit value */
-#define REVERSE(q) \
-    ((((q) >> 24) & 0xff) + (((q) >> 8) & 0xff00) + \
-     (((q) & 0xff00) << 8) + (((q) & 0xff) << 24))
-
-/*
-   inflate() uses a state machine to process as much input data and generate as
-   much output data as possible before returning.  The state machine is
-   structured roughly as follows:
-
-    for (;;) switch (state) {
-    ...
-    case STATEn:
-        if (not enough input data or output space to make progress)
-            return;
-        ... make progress ...
-        state = STATEm;
-        break;
-    ...
-    }
-
-   so when inflate() is called again, the same case is attempted again, and
-   if the appropriate resources are provided, the machine proceeds to the
-   next state.  The NEEDBITS() macro is usually the way the state evaluates
-   whether it can proceed or should return.  NEEDBITS() does the return if
-   the requested bits are not available.  The typical use of the BITS macros
-   is:
-
-        NEEDBITS(n);
-        ... do something with BITS(n) ...
-        DROPBITS(n);
-
-   where NEEDBITS(n) either returns from inflate() if there isn't enough
-   input left to load n bits into the accumulator, or it continues.  BITS(n)
-   gives the low n bits in the accumulator.  When done, DROPBITS(n) drops
-   the low n bits off the accumulator.  INITBITS() clears the accumulator
-   and sets the number of available bits to zero.  BYTEBITS() discards just
-   enough bits to put the accumulator on a byte boundary.  After BYTEBITS()
-   and a NEEDBITS(8), then BITS(8) would return the next byte in the stream.
-
-   NEEDBITS(n) uses PULLBYTE() to get an available byte of input, or to return
-   if there is no input available.  The decoding of variable length codes uses
-   PULLBYTE() directly in order to pull just enough bytes to decode the next
-   code, and no more.
-
-   Some states loop until they get enough input, making sure that enough
-   state information is maintained to continue the loop where it left off
-   if NEEDBITS() returns in the loop.  For example, want, need, and keep
-   would all have to actually be part of the saved state in case NEEDBITS()
-   returns:
-
-    case STATEw:
-        while (want < need) {
-            NEEDBITS(n);
-            keep[want++] = BITS(n);
-            DROPBITS(n);
-        }
-        state = STATEx;
-    case STATEx:
-
-   As shown above, if the next state is also the next case, then the break
-   is omitted.
-
-   A state may also return if there is not enough output space available to
-   complete that state.  Those states are copying stored data, writing a
-   literal byte, and copying a matching string.
-
-   When returning, a "goto inf_leave" is used to update the total counters,
-   update the check value, and determine whether any progress has been made
-   during that inflate() call in order to return the proper return code.
-   Progress is defined as a change in either strm->avail_in or strm->avail_out.
-   When there is a window, goto inf_leave will update the window with the last
-   output written.  If a goto inf_leave occurs in the middle of decompression
-   and there is no window currently, goto inf_leave will create one and copy
-   output to the window for the next call of inflate().
-
-   In this implementation, the flush parameter of inflate() only affects the
-   return code (per zlib.h).  inflate() always writes as much as possible to
-   strm->next_out, given the space available and the provided input--the effect
-   documented in zlib.h of Z_SYNC_FLUSH.  Furthermore, inflate() always defers
-   the allocation of and copying into a sliding window until necessary, which
-   provides the effect documented in zlib.h for Z_FINISH when the entire input
-   stream available.  So the only thing the flush parameter actually does is:
-   when flush is set to Z_FINISH, inflate() cannot return Z_OK.  Instead it
-   will return Z_BUF_ERROR if it has not reached the end of the stream.
- */
-
-int ZEXPORT inflate(strm, flush)
-z_streamp strm;
-int flush;
-{
-    struct inflate_state FAR *state;
-    unsigned char FAR *next;    /* next input */
-    unsigned char FAR *put;     /* next output */
-    unsigned have, left;        /* available input and output */
-    unsigned int hold;         /* bit buffer */
-    unsigned bits;              /* bits in bit buffer */
-    unsigned in, out;           /* save starting available input and output */
-    unsigned copy;              /* number of stored or match bytes to copy */
-    unsigned char FAR *from;    /* where to copy match bytes from */
-    code this;                  /* current decoding table entry */
-    code last;                  /* parent table entry */
-    unsigned len;               /* length to copy for repeats, bits to drop */
-    int ret;                    /* return code */
-#ifdef GUNZIP
-    unsigned char hbuf[4];      /* buffer for gzip header crc calculation */
-#endif
-    static const unsigned short order[19] = /* permutation of code lengths */
-        {16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15};
-
-    if (strm == Z_NULL || strm->state == Z_NULL || strm->next_out == Z_NULL ||
-        (strm->next_in == Z_NULL && strm->avail_in != 0))
-        return Z_STREAM_ERROR;
-
-    state = (struct inflate_state FAR *)strm->state;
-    if (state->mode == TYPE) state->mode = TYPEDO;      /* skip check */
-    LOAD();
-    in = have;
-    out = left;
-    ret = Z_OK;
-    for (;;)
-        switch (state->mode) {
-        case HEAD:
-            if (state->wrap == 0) {
-                state->mode = TYPEDO;
-                break;
-            }
-            NEEDBITS(16);
-#ifdef GUNZIP
-            if ((state->wrap & 2) && hold == 0x8b1f) {  /* gzip header */
-                state->check = crc32(0L, Z_NULL, 0);
-                CRC2(state->check, hold);
-                INITBITS();
-                state->mode = FLAGS;
-                break;
-            }
-            state->flags = 0;           /* expect zlib header */
-            if (state->head != Z_NULL)
-                state->head->done = -1;
-            if (!(state->wrap & 1) ||   /* check if zlib header allowed */
-#else
-            if (
-#endif
-                ((BITS(8) << 8) + (hold >> 8)) % 31) {
-                strm->msg = (char *)"incorrect header check";
-                state->mode = BAD;
-                break;
-            }
-            if (BITS(4) != Z_DEFLATED) {
-                strm->msg = (char *)"unknown compression method";
-                state->mode = BAD;
-                break;
-            }
-            DROPBITS(4);
-            len = BITS(4) + 8;
-            if (len > state->wbits) {
-                strm->msg = (char *)"invalid window size";
-                state->mode = BAD;
-                break;
-            }
-            state->dmax = 1U << len;
-            Tracev((stderr, "inflate:   zlib header ok\n"));
-            strm->adler = state->check = adler32(0L, Z_NULL, 0);
-            state->mode = hold & 0x200 ? DICTID : TYPE;
-            INITBITS();
-            break;
-#ifdef GUNZIP
-        case FLAGS:
-            NEEDBITS(16);
-            state->flags = (int)(hold);
-            if ((state->flags & 0xff) != Z_DEFLATED) {
-                strm->msg = (char *)"unknown compression method";
-                state->mode = BAD;
-                break;
-            }
-            if (state->flags & 0xe000) {
-                strm->msg = (char *)"unknown header flags set";
-                state->mode = BAD;
-                break;
-            }
-            if (state->head != Z_NULL)
-                state->head->text = (int)((hold >> 8) & 1);
-            if (state->flags & 0x0200) CRC2(state->check, hold);
-            INITBITS();
-            state->mode = TIME;
-        case TIME:
-            NEEDBITS(32);
-            if (state->head != Z_NULL)
-                state->head->time = hold;
-            if (state->flags & 0x0200) CRC4(state->check, hold);
-            INITBITS();
-            state->mode = OS;
-        case OS:
-            NEEDBITS(16);
-            if (state->head != Z_NULL) {
-                state->head->xflags = (int)(hold & 0xff);
-                state->head->os = (int)(hold >> 8);
-            }
-            if (state->flags & 0x0200) CRC2(state->check, hold);
-            INITBITS();
-            state->mode = EXLEN;
-        case EXLEN:
-            if (state->flags & 0x0400) {
-                NEEDBITS(16);
-                state->length = (unsigned)(hold);
-                if (state->head != Z_NULL)
-                    state->head->extra_len = (unsigned)hold;
-                if (state->flags & 0x0200) CRC2(state->check, hold);
-                INITBITS();
-            }
-            else if (state->head != Z_NULL)
-                state->head->extra = Z_NULL;
-            state->mode = EXTRA;
-        case EXTRA:
-            if (state->flags & 0x0400) {
-                copy = state->length;
-                if (copy > have) copy = have;
-                if (copy) {
-                    if (state->head != Z_NULL &&
-                        state->head->extra != Z_NULL) {
-                        len = state->head->extra_len - state->length;
-                        zmemcpy(state->head->extra + len, next,
-                                len + copy > state->head->extra_max ?
-                                state->head->extra_max - len : copy);
-                    }
-                    if (state->flags & 0x0200)
-                        state->check = crc32(state->check, next, copy);
-                    have -= copy;
-                    next += copy;
-                    state->length -= copy;
-                }
-                if (state->length) goto inf_leave;
-            }
-            state->length = 0;
-            state->mode = NAME;
-        case NAME:
-            if (state->flags & 0x0800) {
-                if (have == 0) goto inf_leave;
-                copy = 0;
-                do {
-                    len = (unsigned)(next[copy++]);
-                    if (state->head != Z_NULL &&
-                            state->head->name != Z_NULL &&
-                            state->length < state->head->name_max)
-                        state->head->name[state->length++] = len;
-                } while (len && copy < have);
-                if (state->flags & 0x0200)
-                    state->check = crc32(state->check, next, copy);
-                have -= copy;
-                next += copy;
-                if (len) goto inf_leave;
-            }
-            else if (state->head != Z_NULL)
-                state->head->name = Z_NULL;
-            state->length = 0;
-            state->mode = COMMENT;
-        case COMMENT:
-            if (state->flags & 0x1000) {
-                if (have == 0) goto inf_leave;
-                copy = 0;
-                do {
-                    len = (unsigned)(next[copy++]);
-                    if (state->head != Z_NULL &&
-                            state->head->comment != Z_NULL &&
-                            state->length < state->head->comm_max)
-                        state->head->comment[state->length++] = len;
-                } while (len && copy < have);
-                if (state->flags & 0x0200)
-                    state->check = crc32(state->check, next, copy);
-                have -= copy;
-                next += copy;
-                if (len) goto inf_leave;
-            }
-            else if (state->head != Z_NULL)
-                state->head->comment = Z_NULL;
-            state->mode = HCRC;
-        case HCRC:
-            if (state->flags & 0x0200) {
-                NEEDBITS(16);
-                if (hold != (state->check & 0xffff)) {
-                    strm->msg = (char *)"header crc mismatch";
-                    state->mode = BAD;
-                    break;
-                }
-                INITBITS();
-            }
-            if (state->head != Z_NULL) {
-                state->head->hcrc = (int)((state->flags >> 9) & 1);
-                state->head->done = 1;
-            }
-            strm->adler = state->check = crc32(0L, Z_NULL, 0);
-            state->mode = TYPE;
-            break;
-#endif
-        case DICTID:
-            NEEDBITS(32);
-            strm->adler = state->check = REVERSE(hold);
-            INITBITS();
-            state->mode = DICT;
-        case DICT:
-            if (state->havedict == 0) {
-                RESTORE();
-                return Z_NEED_DICT;
-            }
-            strm->adler = state->check = adler32(0L, Z_NULL, 0);
-            state->mode = TYPE;
-        case TYPE:
-            if (flush == Z_BLOCK) goto inf_leave;
-        case TYPEDO:
-            if (state->last) {
-                BYTEBITS();
-                state->mode = CHECK;
-                break;
-            }
-            NEEDBITS(3);
-            state->last = BITS(1);
-            DROPBITS(1);
-            switch (BITS(2)) {
-            case 0:                             /* stored block */
-                Tracev((stderr, "inflate:     stored block%s\n",
-                        state->last ? " (last)" : ""));
-                state->mode = STORED;
-                break;
-            case 1:                             /* fixed block */
-                fixedtables(state);
-                Tracev((stderr, "inflate:     fixed codes block%s\n",
-                        state->last ? " (last)" : ""));
-                state->mode = LEN;              /* decode codes */
-                break;
-            case 2:                             /* dynamic block */
-                Tracev((stderr, "inflate:     dynamic codes block%s\n",
-                        state->last ? " (last)" : ""));
-                state->mode = TABLE;
-                break;
-            case 3:
-                strm->msg = (char *)"invalid block type";
-                state->mode = BAD;
-            }
-            DROPBITS(2);
-            break;
-        case STORED:
-            BYTEBITS();                         /* go to byte boundary */
-            NEEDBITS(32);
-            if ((hold & 0xffff) != ((hold >> 16) ^ 0xffff)) {
-                strm->msg = (char *)"invalid stored block lengths";
-                state->mode = BAD;
-                break;
-            }
-            state->length = (unsigned)hold & 0xffff;
-            Tracev((stderr, "inflate:       stored length %u\n",
-                    state->length));
-            INITBITS();
-            state->mode = COPY;
-        case COPY:
-            copy = state->length;
-            if (copy) {
-                if (copy > have) copy = have;
-                if (copy > left) copy = left;
-                if (copy == 0) goto inf_leave;
-                zmemcpy(put, next, copy);
-                have -= copy;
-                next += copy;
-                left -= copy;
-                put += copy;
-                state->length -= copy;
-                break;
-            }
-            Tracev((stderr, "inflate:       stored end\n"));
-            state->mode = TYPE;
-            break;
-        case TABLE:
-            NEEDBITS(14);
-            state->nlen = BITS(5) + 257;
-            DROPBITS(5);
-            state->ndist = BITS(5) + 1;
-            DROPBITS(5);
-            state->ncode = BITS(4) + 4;
-            DROPBITS(4);
-#ifndef PKZIP_BUG_WORKAROUND
-            if (state->nlen > 286 || state->ndist > 30) {
-                strm->msg = (char *)"too many length or distance symbols";
-                state->mode = BAD;
-                break;
-            }
-#endif
-            Tracev((stderr, "inflate:       table sizes ok\n"));
-            state->have = 0;
-            state->mode = LENLENS;
-        case LENLENS:
-            while (state->have < state->ncode) {
-                NEEDBITS(3);
-                state->lens[order[state->have++]] = (unsigned short)BITS(3);
-                DROPBITS(3);
-            }
-            while (state->have < 19)
-                state->lens[order[state->have++]] = 0;
-            state->next = state->codes;
-            state->lencode = (code const FAR *)(state->next);
-            state->lenbits = 7;
-            ret = inflate_table(CODES, state->lens, 19, &(state->next),
-                                &(state->lenbits), state->work);
-            if (ret) {
-                strm->msg = (char *)"invalid code lengths set";
-                state->mode = BAD;
-                break;
-            }
-            Tracev((stderr, "inflate:       code lengths ok\n"));
-            state->have = 0;
-            state->mode = CODELENS;
-        case CODELENS:
-            while (state->have < state->nlen + state->ndist) {
-                for (;;) {
-                    this = state->lencode[BITS(state->lenbits)];
-                    if ((unsigned)(this.bits) <= bits) break;
-                    PULLBYTE();
-                }
-                if (this.val < 16) {
-                    NEEDBITS(this.bits);
-                    DROPBITS(this.bits);
-                    state->lens[state->have++] = this.val;
-                }
-                else {
-                    if (this.val == 16) {
-                        NEEDBITS(this.bits + 2);
-                        DROPBITS(this.bits);
-                        if (state->have == 0) {
-                            strm->msg = (char *)"invalid bit length repeat";
-                            state->mode = BAD;
-                            break;
-                        }
-                        len = state->lens[state->have - 1];
-                        copy = 3 + BITS(2);
-                        DROPBITS(2);
-                    }
-                    else if (this.val == 17) {
-                        NEEDBITS(this.bits + 3);
-                        DROPBITS(this.bits);
-                        len = 0;
-                        copy = 3 + BITS(3);
-                        DROPBITS(3);
-                    }
-                    else {
-                        NEEDBITS(this.bits + 7);
-                        DROPBITS(this.bits);
-                        len = 0;
-                        copy = 11 + BITS(7);
-                        DROPBITS(7);
-                    }
-                    if (state->have + copy > state->nlen + state->ndist) {
-                        strm->msg = (char *)"invalid bit length repeat";
-                        state->mode = BAD;
-                        break;
-                    }
-                    while (copy--)
-                        state->lens[state->have++] = (unsigned short)len;
-                }
-            }
-
-            /* handle error breaks in while */
-            if (state->mode == BAD) break;
-
-            /* build code tables */
-            state->next = state->codes;
-            state->lencode = (code const FAR *)(state->next);
-            state->lenbits = 9;
-            ret = inflate_table(LENS, state->lens, state->nlen, &(state->next),
-                                &(state->lenbits), state->work);
-            if (ret) {
-                strm->msg = (char *)"invalid literal/lengths set";
-                state->mode = BAD;
-                break;
-            }
-            state->distcode = (code const FAR *)(state->next);
-            state->distbits = 6;
-            ret = inflate_table(DISTS, state->lens + state->nlen, state->ndist,
-                            &(state->next), &(state->distbits), state->work);
-            if (ret) {
-                strm->msg = (char *)"invalid distances set";
-                state->mode = BAD;
-                break;
-            }
-            Tracev((stderr, "inflate:       codes ok\n"));
-            state->mode = LEN;
-        case LEN:
-            if (have >= 6 && left >= 258) {
-                RESTORE();
-                inflate_fast(strm, out);
-                LOAD();
-                break;
-            }
-            for (;;) {
-                this = state->lencode[BITS(state->lenbits)];
-                if ((unsigned)(this.bits) <= bits) break;
-                PULLBYTE();
-            }
-            if (this.op && (this.op & 0xf0) == 0) {
-                last = this;
-                for (;;) {
-                    this = state->lencode[last.val +
-                            (BITS(last.bits + last.op) >> last.bits)];
-                    if ((unsigned)(last.bits + this.bits) <= bits) break;
-                    PULLBYTE();
-                }
-                DROPBITS(last.bits);
-            }
-            DROPBITS(this.bits);
-            state->length = (unsigned)this.val;
-            if ((int)(this.op) == 0) {
-                Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ?
-                        "inflate:         literal '%c'\n" :
-                        "inflate:         literal 0x%02x\n", this.val));
-                state->mode = LIT;
-                break;
-            }
-            if (this.op & 32) {
-                Tracevv((stderr, "inflate:         end of block\n"));
-                state->mode = TYPE;
-                break;
-            }
-            if (this.op & 64) {
-                strm->msg = (char *)"invalid literal/length code";
-                state->mode = BAD;
-                break;
-            }
-            state->extra = (unsigned)(this.op) & 15;
-            state->mode = LENEXT;
-        case LENEXT:
-            if (state->extra) {
-                NEEDBITS(state->extra);
-                state->length += BITS(state->extra);
-                DROPBITS(state->extra);
-            }
-            Tracevv((stderr, "inflate:         length %u\n", state->length));
-            state->mode = DIST;
-        case DIST:
-            for (;;) {
-                this = state->distcode[BITS(state->distbits)];
-                if ((unsigned)(this.bits) <= bits) break;
-                PULLBYTE();
-            }
-            if ((this.op & 0xf0) == 0) {
-                last = this;
-                for (;;) {
-                    this = state->distcode[last.val +
-                            (BITS(last.bits + last.op) >> last.bits)];
-                    if ((unsigned)(last.bits + this.bits) <= bits) break;
-                    PULLBYTE();
-                }
-                DROPBITS(last.bits);
-            }
-            DROPBITS(this.bits);
-            if (this.op & 64) {
-                strm->msg = (char *)"invalid distance code";
-                state->mode = BAD;
-                break;
-            }
-            state->offset = (unsigned)this.val;
-            state->extra = (unsigned)(this.op) & 15;
-            state->mode = DISTEXT;
-        case DISTEXT:
-            if (state->extra) {
-                NEEDBITS(state->extra);
-                state->offset += BITS(state->extra);
-                DROPBITS(state->extra);
-            }
-#ifdef INFLATE_STRICT
-            if (state->offset > state->dmax) {
-                strm->msg = (char *)"invalid distance too far back";
-                state->mode = BAD;
-                break;
-            }
-#endif
-            if (state->offset > state->whave + out - left) {
-                strm->msg = (char *)"invalid distance too far back";
-                state->mode = BAD;
-                break;
-            }
-            Tracevv((stderr, "inflate:         distance %u\n", state->offset));
-            state->mode = MATCH;
-        case MATCH:
-            if (left == 0) goto inf_leave;
-            copy = out - left;
-            if (state->offset > copy) {         /* copy from window */
-                copy = state->offset - copy;
-                if (copy > state->write) {
-                    copy -= state->write;
-                    from = state->window + (state->wsize - copy);
-                }
-                else
-                    from = state->window + (state->write - copy);
-                if (copy > state->length) copy = state->length;
-            }
-            else {                              /* copy from output */
-                from = put - state->offset;
-                copy = state->length;
-            }
-            if (copy > left) copy = left;
-            left -= copy;
-            state->length -= copy;
-            do {
-                *put++ = *from++;
-            } while (--copy);
-            if (state->length == 0) state->mode = LEN;
-            break;
-        case LIT:
-            if (left == 0) goto inf_leave;
-            *put++ = (unsigned char)(state->length);
-            left--;
-            state->mode = LEN;
-            break;
-        case CHECK:
-            if (state->wrap) {
-                NEEDBITS(32);
-                out -= left;
-                strm->total_out += out;
-                state->total += out;
-                if (out)
-                    strm->adler = state->check =
-                        UPDATE(state->check, put - out, out);
-                out = left;
-                if ((
-#ifdef GUNZIP
-                     state->flags ? hold :
-#endif
-                     REVERSE(hold)) != state->check) {
-                    strm->msg = (char *)"incorrect data check";
-                    state->mode = BAD;
-                    break;
-                }
-                INITBITS();
-                Tracev((stderr, "inflate:   check matches trailer\n"));
-            }
-#ifdef GUNZIP
-            state->mode = LENGTH;
-        case LENGTH:
-            if (state->wrap && state->flags) {
-                NEEDBITS(32);
-                if (hold != (state->total & 0xffffffffUL)) {
-                    strm->msg = (char *)"incorrect length check";
-                    state->mode = BAD;
-                    break;
-                }
-                INITBITS();
-                Tracev((stderr, "inflate:   length matches trailer\n"));
-            }
-#endif
-            state->mode = DONE;
-        case DONE:
-            ret = Z_STREAM_END;
-            goto inf_leave;
-        case BAD:
-            ret = Z_DATA_ERROR;
-            goto inf_leave;
-        case MEM:
-            return Z_MEM_ERROR;
-        case SYNC:
-        default:
-            return Z_STREAM_ERROR;
-        }
-
-    /*
-       Return from inflate(), updating the total counts and the check value.
-       If there was no progress during the inflate() call, return a buffer
-       error.  Call updatewindow() to create and/or update the window state.
-       Note: a memory error from inflate() is non-recoverable.
-     */
-  inf_leave:
-    RESTORE();
-    if (state->wsize || (state->mode < CHECK && out != strm->avail_out))
-        if (updatewindow(strm, out)) {
-            state->mode = MEM;
-            return Z_MEM_ERROR;
-        }
-    in -= strm->avail_in;
-    out -= strm->avail_out;
-    strm->total_in += in;
-    strm->total_out += out;
-    state->total += out;
-    if (state->wrap && out)
-        strm->adler = state->check =
-            UPDATE(state->check, strm->next_out - out, out);
-    strm->data_type = state->bits + (state->last ? 64 : 0) +
-                      (state->mode == TYPE ? 128 : 0);
-    if (((in == 0 && out == 0) || flush == Z_FINISH) && ret == Z_OK)
-        ret = Z_BUF_ERROR;
-    return ret;
-}
-
-int ZEXPORT inflateEnd(strm)
-z_streamp strm;
-{
-    struct inflate_state FAR *state;
-    if (strm == Z_NULL || strm->state == Z_NULL || strm->zfree == (free_func)0)
-        return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-    if (state->window != Z_NULL) ZFREE(strm, state->window);
-    ZFREE(strm, strm->state);
-    strm->state = Z_NULL;
-    Tracev((stderr, "inflate: end\n"));
-    return Z_OK;
-}
-
-int ZEXPORT inflateSetDictionary(strm, dictionary, dictLength)
-z_streamp strm;
-const Bytef *dictionary;
-uInt dictLength;
-{
-    struct inflate_state FAR *state;
-    unsigned int id;
-
-    /* check state */
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-    if (state->wrap != 0 && state->mode != DICT)
-        return Z_STREAM_ERROR;
-
-    /* check for correct dictionary id */
-    if (state->mode == DICT) {
-        id = adler32(0L, Z_NULL, 0);
-        id = adler32(id, dictionary, dictLength);
-        if (id != state->check)
-            return Z_DATA_ERROR;
-    }
-
-    /* copy dictionary to window */
-    if (updatewindow(strm, strm->avail_out)) {
-        state->mode = MEM;
-        return Z_MEM_ERROR;
-    }
-    if (dictLength > state->wsize) {
-        zmemcpy(state->window, dictionary + dictLength - state->wsize,
-                state->wsize);
-        state->whave = state->wsize;
-    }
-    else {
-        zmemcpy(state->window + state->wsize - dictLength, dictionary,
-                dictLength);
-        state->whave = dictLength;
-    }
-    state->havedict = 1;
-    Tracev((stderr, "inflate:   dictionary set\n"));
-    return Z_OK;
-}
-
-int ZEXPORT inflateGetHeader(strm, head)
-z_streamp strm;
-gz_headerp head;
-{
-    struct inflate_state FAR *state;
-
-    /* check state */
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-    if ((state->wrap & 2) == 0) return Z_STREAM_ERROR;
-
-    /* save header structure */
-    state->head = head;
-    head->done = 0;
-    return Z_OK;
-}
-
-/*
-   Search buf[0..len-1] for the pattern: 0, 0, 0xff, 0xff.  Return when found
-   or when out of input.  When called, *have is the number of pattern bytes
-   found in order so far, in 0..3.  On return *have is updated to the new
-   state.  If on return *have equals four, then the pattern was found and the
-   return value is how many bytes were read including the last byte of the
-   pattern.  If *have is less than four, then the pattern has not been found
-   yet and the return value is len.  In the latter case, syncsearch() can be
-   called again with more data and the *have state.  *have is initialized to
-   zero for the first call.
- */
-local unsigned syncsearch(have, buf, len)
-unsigned FAR *have;
-unsigned char FAR *buf;
-unsigned len;
-{
-    unsigned got;
-    unsigned next;
-
-    got = *have;
-    next = 0;
-    while (next < len && got < 4) {
-        if ((int)(buf[next]) == (got < 2 ? 0 : 0xff))
-            got++;
-        else if (buf[next])
-            got = 0;
-        else
-            got = 4 - got;
-        next++;
-    }
-    *have = got;
-    return next;
-}
-
-int ZEXPORT inflateSync(strm)
-z_streamp strm;
-{
-    unsigned len;               /* number of bytes to look at or looked at */
-    unsigned int in, out;      /* temporary to save total_in and total_out */
-    unsigned char buf[4];       /* to restore bit buffer to byte string */
-    struct inflate_state FAR *state;
-
-    /* check parameters */
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-    if (strm->avail_in == 0 && state->bits < 8) return Z_BUF_ERROR;
-
-    /* if first time, start search in bit buffer */
-    if (state->mode != SYNC) {
-        state->mode = SYNC;
-        state->hold <<= state->bits & 7;
-        state->bits -= state->bits & 7;
-        len = 0;
-        while (state->bits >= 8) {
-            buf[len++] = (unsigned char)(state->hold);
-            state->hold >>= 8;
-            state->bits -= 8;
-        }
-        state->have = 0;
-        syncsearch(&(state->have), buf, len);
-    }
-
-    /* search available input */
-    len = syncsearch(&(state->have), strm->next_in, strm->avail_in);
-    strm->avail_in -= len;
-    strm->next_in += len;
-    strm->total_in += len;
-
-    /* return no joy or set up to restart inflate() on a new block */
-    if (state->have != 4) return Z_DATA_ERROR;
-    in = strm->total_in;  out = strm->total_out;
-    inflateReset(strm);
-    strm->total_in = in;  strm->total_out = out;
-    state->mode = TYPE;
-    return Z_OK;
-}
-
-/*
-   Returns true if inflate is currently at the end of a block generated by
-   Z_SYNC_FLUSH or Z_FULL_FLUSH. This function is used by one PPP
-   implementation to provide an additional safety check. PPP uses
-   Z_SYNC_FLUSH but removes the length bytes of the resulting empty stored
-   block. When decompressing, PPP checks that at the end of input packet,
-   inflate is waiting for these length bytes.
- */
-int ZEXPORT inflateSyncPoint(strm)
-z_streamp strm;
-{
-    struct inflate_state FAR *state;
-
-    if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)strm->state;
-    return state->mode == STORED && state->bits == 0;
-}
-
-int ZEXPORT inflateCopy(dest, source)
-z_streamp dest;
-z_streamp source;
-{
-    struct inflate_state FAR *state;
-    struct inflate_state FAR *copy;
-    unsigned char FAR *window;
-    unsigned wsize;
-
-    /* check input */
-    if (dest == Z_NULL || source == Z_NULL || source->state == Z_NULL ||
-        source->zalloc == (alloc_func)0 || source->zfree == (free_func)0)
-        return Z_STREAM_ERROR;
-    state = (struct inflate_state FAR *)source->state;
-
-    /* allocate space */
-    copy = (struct inflate_state FAR *)
-           ZALLOC(source, 1, sizeof(struct inflate_state));
-    if (copy == Z_NULL) return Z_MEM_ERROR;
-    window = Z_NULL;
-    if (state->window != Z_NULL) {
-        window = (unsigned char FAR *)
-                 ZALLOC(source, 1U << state->wbits, sizeof(unsigned char));
-        if (window == Z_NULL) {
-            ZFREE(source, copy);
-            return Z_MEM_ERROR;
-        }
-    }
-
-    /* copy state */
-    zmemcpy(dest, source, sizeof(z_stream));
-    zmemcpy(copy, state, sizeof(struct inflate_state));
-    if (state->lencode >= state->codes &&
-        state->lencode <= state->codes + ENOUGH - 1) {
-        copy->lencode = copy->codes + (state->lencode - state->codes);
-        copy->distcode = copy->codes + (state->distcode - state->codes);
-    }
-    copy->next = copy->codes + (state->next - state->codes);
-    if (window != Z_NULL) {
-        wsize = 1U << state->wbits;
-        zmemcpy(window, state->window, wsize);
-    }
-    copy->window = window;
-    dest->state = (struct internal_state FAR *)copy;
-    return Z_OK;
-}
diff --git a/surface/src/3rdparty/opennurbs/inftrees.c b/surface/src/3rdparty/opennurbs/inftrees.c
deleted file mode 100644 (file)
index d6a648e..0000000
+++ /dev/null
@@ -1,329 +0,0 @@
-/* inftrees.c -- generate Huffman trees for efficient decoding
- * Copyright (C) 1995-2005 Mark Adler
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-#include "pcl/surface/3rdparty/opennurbs/zutil.h"
-#include "pcl/surface/3rdparty/opennurbs/inftrees.h"
-
-#define MAXBITS 15
-
-const char inflate_copyright[] =
-   " inflate 1.2.3 Copyright 1995-2005 Mark Adler ";
-/*
-  If you use the zlib library in a product, an acknowledgment is welcome
-  in the documentation of your product. If for some reason you cannot
-  include such an acknowledgment, I would appreciate that you keep this
-  copyright string in the executable of your product.
- */
-
-/*
-   Build a set of tables to decode the provided canonical Huffman code.
-   The code lengths are lens[0..codes-1].  The result starts at *table,
-   whose indices are 0..2^bits-1.  work is a writable array of at least
-   lens shorts, which is used as a work area.  type is the type of code
-   to be generated, CODES, LENS, or DISTS.  On return, zero is success,
-   -1 is an invalid code, and +1 means that ENOUGH isn't enough.  table
-   on return points to the next available entry's address.  bits is the
-   requested root table index bits, and on return it is the actual root
-   table index bits.  It will differ if the request is greater than the
-   longest code or if it is less than the shortest code.
- */
-int inflate_table(type, lens, codes, table, bits, work)
-codetype type;
-unsigned short FAR *lens;
-unsigned codes;
-code FAR * FAR *table;
-unsigned FAR *bits;
-unsigned short FAR *work;
-{
-    unsigned len;               /* a code's length in bits */
-    unsigned sym;               /* index of code symbols */
-    unsigned min, max;          /* minimum and maximum code lengths */
-    unsigned root;              /* number of index bits for root table */
-    unsigned curr;              /* number of index bits for current table */
-    unsigned drop;              /* code bits to drop for sub-table */
-    int left;                   /* number of prefix codes available */
-    unsigned used;              /* code entries in table used */
-    unsigned huff;              /* Huffman code */
-    unsigned incr;              /* for incrementing code, index */
-    unsigned fill;              /* index for replicating entries */
-    unsigned low;               /* low bits for current root entry */
-    unsigned mask;              /* mask for low root bits */
-    code this;                  /* table entry for duplication */
-    code FAR *next;             /* next available space in table */
-    const unsigned short FAR *base;     /* base value table to use */
-    const unsigned short FAR *extra;    /* extra bits table to use */
-    int end;                    /* use base and extra for symbol > end */
-    unsigned short count[MAXBITS+1];    /* number of codes of each length */
-    unsigned short offs[MAXBITS+1];     /* offsets in table for each length */
-    static const unsigned short lbase[31] = { /* Length codes 257..285 base */
-        3, 4, 5, 6, 7, 8, 9, 10, 11, 13, 15, 17, 19, 23, 27, 31,
-        35, 43, 51, 59, 67, 83, 99, 115, 131, 163, 195, 227, 258, 0, 0};
-    static const unsigned short lext[31] = { /* Length codes 257..285 extra */
-        16, 16, 16, 16, 16, 16, 16, 16, 17, 17, 17, 17, 18, 18, 18, 18,
-        19, 19, 19, 19, 20, 20, 20, 20, 21, 21, 21, 21, 16, 201, 196};
-    static const unsigned short dbase[32] = { /* Distance codes 0..29 base */
-        1, 2, 3, 4, 5, 7, 9, 13, 17, 25, 33, 49, 65, 97, 129, 193,
-        257, 385, 513, 769, 1025, 1537, 2049, 3073, 4097, 6145,
-        8193, 12289, 16385, 24577, 0, 0};
-    static const unsigned short dext[32] = { /* Distance codes 0..29 extra */
-        16, 16, 16, 16, 17, 17, 18, 18, 19, 19, 20, 20, 21, 21, 22, 22,
-        23, 23, 24, 24, 25, 25, 26, 26, 27, 27,
-        28, 28, 29, 29, 64, 64};
-
-    /*
-       Process a set of code lengths to create a canonical Huffman code.  The
-       code lengths are lens[0..codes-1].  Each length corresponds to the
-       symbols 0..codes-1.  The Huffman code is generated by first sorting the
-       symbols by length from short to int, and retaining the symbol order
-       for codes with equal lengths.  Then the code starts with all zero bits
-       for the first code of the shortest length, and the codes are integer
-       increments for the same length, and zeros are appended as the length
-       increases.  For the deflate format, these bits are stored backwards
-       from their more natural integer increment ordering, and so when the
-       decoding tables are built in the large loop below, the integer codes
-       are incremented backwards.
-
-       This routine assumes, but does not check, that all of the entries in
-       lens[] are in the range 0..MAXBITS.  The caller must assure this.
-       1..MAXBITS is interpreted as that code length.  zero means that that
-       symbol does not occur in this code.
-
-       The codes are sorted by computing a count of codes for each length,
-       creating from that a table of starting indices for each length in the
-       sorted table, and then entering the symbols in order in the sorted
-       table.  The sorted table is work[], with that space being provided by
-       the caller.
-
-       The length counts are used for other purposes as well, i.e. finding
-       the minimum and maximum length codes, determining if there are any
-       codes at all, checking for a valid set of lengths, and looking ahead
-       at length counts to determine sub-table sizes when building the
-       decoding tables.
-     */
-
-    /* accumulate lengths for codes (assumes lens[] all in 0..MAXBITS) */
-    for (len = 0; len <= MAXBITS; len++)
-        count[len] = 0;
-    for (sym = 0; sym < codes; sym++)
-        count[lens[sym]]++;
-
-    /* bound code lengths, force root to be within code lengths */
-    root = *bits;
-    for (max = MAXBITS; max >= 1; max--)
-        if (count[max] != 0) break;
-    if (root > max) root = max;
-    if (max == 0) {                     /* no symbols to code at all */
-        this.op = (unsigned char)64;    /* invalid code marker */
-        this.bits = (unsigned char)1;
-        this.val = (unsigned short)0;
-        *(*table)++ = this;             /* make a table to force an error */
-        *(*table)++ = this;
-        *bits = 1;
-        return 0;     /* no symbols, but wait for decoding to report error */
-    }
-    for (min = 1; min <= MAXBITS; min++)
-        if (count[min] != 0) break;
-    if (root < min) root = min;
-
-    /* check for an over-subscribed or incomplete set of lengths */
-    left = 1;
-    for (len = 1; len <= MAXBITS; len++) {
-        left <<= 1;
-        left -= count[len];
-        if (left < 0) return -1;        /* over-subscribed */
-    }
-    if (left > 0 && (type == CODES || max != 1))
-        return -1;                      /* incomplete set */
-
-    /* generate offsets into symbol table for each length for sorting */
-    offs[1] = 0;
-    for (len = 1; len < MAXBITS; len++)
-        offs[len + 1] = offs[len] + count[len];
-
-    /* sort symbols by length, by symbol order within each length */
-    for (sym = 0; sym < codes; sym++)
-        if (lens[sym] != 0) work[offs[lens[sym]]++] = (unsigned short)sym;
-
-    /*
-       Create and fill in decoding tables.  In this loop, the table being
-       filled is at next and has curr index bits.  The code being used is huff
-       with length len.  That code is converted to an index by dropping drop
-       bits off of the bottom.  For codes where len is less than drop + curr,
-       those top drop + curr - len bits are incremented through all values to
-       fill the table with replicated entries.
-
-       root is the number of index bits for the root table.  When len exceeds
-       root, sub-tables are created pointed to by the root entry with an index
-       of the low root bits of huff.  This is saved in low to check for when a
-       new sub-table should be started.  drop is zero when the root table is
-       being filled, and drop is root when sub-tables are being filled.
-
-       When a new sub-table is needed, it is necessary to look ahead in the
-       code lengths to determine what size sub-table is needed.  The length
-       counts are used for this, and so count[] is decremented as codes are
-       entered in the tables.
-
-       used keeps track of how many table entries have been allocated from the
-       provided *table space.  It is checked when a LENS table is being made
-       against the space in *table, ENOUGH, minus the maximum space needed by
-       the worst case distance code, MAXD.  This should never happen, but the
-       sufficiency of ENOUGH has not been proven exhaustively, hence the check.
-       This assumes that when type == LENS, bits == 9.
-
-       sym increments through all symbols, and the loop terminates when
-       all codes of length max, i.e. all codes, have been processed.  This
-       routine permits incomplete codes, so another loop after this one fills
-       in the rest of the decoding tables with invalid code markers.
-     */
-
-    /* set up for code type */
-    switch (type) {
-    case CODES:
-        base = extra = work;    /* dummy value--not used */
-        end = 19;
-        break;
-    case LENS:
-        base = lbase;
-        base -= 257;
-        extra = lext;
-        extra -= 257;
-        end = 256;
-        break;
-    default:            /* DISTS */
-        base = dbase;
-        extra = dext;
-        end = -1;
-    }
-
-    /* initialize state for loop */
-    huff = 0;                   /* starting code */
-    sym = 0;                    /* starting code symbol */
-    len = min;                  /* starting code length */
-    next = *table;              /* current table to fill in */
-    curr = root;                /* current table index bits */
-    drop = 0;                   /* current bits to drop from code for index */
-    low = (unsigned)(-1);       /* trigger new sub-table when len > root */
-    used = 1U << root;          /* use root table entries */
-    mask = used - 1;            /* mask for comparing low */
-
-    /* check available table space */
-    if (type == LENS && used >= ENOUGH - MAXD)
-        return 1;
-
-    /* process all codes and make table entries */
-    for (;;) {
-        /* create table entry */
-        this.bits = (unsigned char)(len - drop);
-        if ((int)(work[sym]) < end) {
-            this.op = (unsigned char)0;
-            this.val = work[sym];
-        }
-        else if ((int)(work[sym]) > end) {
-            this.op = (unsigned char)(extra[work[sym]]);
-            this.val = base[work[sym]];
-        }
-        else {
-            this.op = (unsigned char)(32 + 64);         /* end of block */
-            this.val = 0;
-        }
-
-        /* replicate for those indices with low len bits equal to huff */
-        incr = 1U << (len - drop);
-        fill = 1U << curr;
-        min = fill;                 /* save offset to next table */
-        do {
-            fill -= incr;
-            next[(huff >> drop) + fill] = this;
-        } while (fill != 0);
-
-        /* backwards increment the len-bit code huff */
-        incr = 1U << (len - 1);
-        while (huff & incr)
-            incr >>= 1;
-        if (incr != 0) {
-            huff &= incr - 1;
-            huff += incr;
-        }
-        else
-            huff = 0;
-
-        /* go to next symbol, update count, len */
-        sym++;
-        if (--(count[len]) == 0) {
-            if (len == max) break;
-            len = lens[work[sym]];
-        }
-
-        /* create new sub-table if needed */
-        if (len > root && (huff & mask) != low) {
-            /* if first time, transition to sub-tables */
-            if (drop == 0)
-                drop = root;
-
-            /* increment past last table */
-            next += min;            /* here min is 1 << curr */
-
-            /* determine length of next table */
-            curr = len - drop;
-            left = (int)(1 << curr);
-            while (curr + drop < max) {
-                left -= count[curr + drop];
-                if (left <= 0) break;
-                curr++;
-                left <<= 1;
-            }
-
-            /* check for enough space */
-            used += 1U << curr;
-            if (type == LENS && used >= ENOUGH - MAXD)
-                return 1;
-
-            /* point entry in root table to sub-table */
-            low = huff & mask;
-            (*table)[low].op = (unsigned char)curr;
-            (*table)[low].bits = (unsigned char)root;
-            (*table)[low].val = (unsigned short)(next - *table);
-        }
-    }
-
-    /*
-       Fill in rest of table for incomplete codes.  This loop is similar to the
-       loop above in incrementing huff for table indices.  It is assumed that
-       len is equal to curr + drop, so there is no loop needed to increment
-       through high index bits.  When the current sub-table is filled, the loop
-       drops back to the root table to fill in any remaining entries there.
-     */
-    this.op = (unsigned char)64;                /* invalid code marker */
-    this.bits = (unsigned char)(len - drop);
-    this.val = (unsigned short)0;
-    while (huff != 0) {
-        /* when done with sub-table, drop back to root table */
-        if (drop != 0 && (huff & mask) != low) {
-            drop = 0;
-            len = root;
-            next = *table;
-            this.bits = (unsigned char)len;
-        }
-
-        /* put invalid code marker in table */
-        next[huff >> drop] = this;
-
-        /* backwards increment the len-bit code huff */
-        incr = 1U << (len - 1);
-        while (huff & incr)
-            incr >>= 1;
-        if (incr != 0) {
-            huff &= incr - 1;
-            huff += incr;
-        }
-        else
-            huff = 0;
-    }
-
-    /* set return parameters */
-    *table += used;
-    *bits = root;
-    return 0;
-}
index 51ca678d01827c54b690859221ebfc358a64c7fa..fdcfa7e92dd4e011cd48139e69f9dec1c3085324 100644 (file)
@@ -102,16 +102,7 @@ set(OPENNURBS_INCLUDES
     include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/opennurbs_workspace.h
     include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/opennurbs_xform.h
     include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/opennurbs_zlib.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/crc32.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/deflate.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffast.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffixed.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inflate.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inftrees.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/trees.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zconf.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zlib.h
-    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zutil.h)
+)
 
 set(OPENNURBS_SOURCES
     src/3rdparty/opennurbs/opennurbs_3dm_attributes.cpp
@@ -222,14 +213,4 @@ set(OPENNURBS_SOURCES
     src/3rdparty/opennurbs/opennurbs_xform.cpp
     src/3rdparty/opennurbs/opennurbs_zlib.cpp
     src/3rdparty/opennurbs/opennurbs_zlib_memory.cpp
-    src/3rdparty/opennurbs/adler32.c
-    src/3rdparty/opennurbs/compress.c
-    src/3rdparty/opennurbs/crc32.c
-    src/3rdparty/opennurbs/deflate.c
-    src/3rdparty/opennurbs/infback.c
-    src/3rdparty/opennurbs/inffast.c
-    src/3rdparty/opennurbs/inflate.c
-    src/3rdparty/opennurbs/inftrees.c
-    src/3rdparty/opennurbs/trees.c
-    src/3rdparty/opennurbs/uncompr.c
-    src/3rdparty/opennurbs/zutil.c)
+)
index 688c803df65f5f1a5f79362e3d472d49eae0a821..03e6199317758bd8ddb475f9a1e6097f3c99081c 100644 (file)
@@ -16,6 +16,8 @@
 
 #include "pcl/surface/3rdparty/opennurbs/opennurbs.h"
 
+#if !defined(HAVE_ZLIB)
+
 #if defined(ON_DLL_EXPORTS)
 // When compiling a Windows DLL opennurbs, we
 // statically link ./zlib/.../zlib....lib into
@@ -72,6 +74,8 @@
 
 #endif // ON_DLL_EXPORTS
 
+#endif // !HAVE_ZLIB
+
 
 bool ON_BinaryArchive::WriteCompressedBuffer(
         std::size_t sizeof__inbuffer,  // sizeof uncompressed input data
@@ -641,7 +645,11 @@ struct ON_CompressedBufferHelper
     sizeof_x_buffer = 16384
   };
   unsigned char    buffer[sizeof_x_buffer];
+#if defined(HAVE_ZLIB)
+  z_stream         strm = []() { z_stream zs; zs.zalloc = pcl_zcalloc; zs.zfree = pcl_zcfree; return zs; } ();
+#else
   z_stream         strm;
+#endif
   std::size_t           m_buffer_compressed_capacity;
 };
 
diff --git a/surface/src/3rdparty/opennurbs/trees.c b/surface/src/3rdparty/opennurbs/trees.c
deleted file mode 100644 (file)
index 60527f4..0000000
+++ /dev/null
@@ -1,1232 +0,0 @@
-/* trees.c -- output deflated data using Huffman coding
- * Copyright (C) 1995-2005 Jean-loup Gailly
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/*
- *  ALGORITHM
- *
- *      The "deflation" process uses several Huffman trees. The more
- *      common source values are represented by shorter bit sequences.
- *
- *      Each code tree is stored in a compressed form which is itself
- * a Huffman encoding of the lengths of all the code strings (in
- * ascending order by source values).  The actual code strings are
- * reconstructed from the lengths in the inflate process, as described
- * in the deflate specification.
- *
- *  REFERENCES
- *
- *      Deutsch, L.P.,"'Deflate' Compressed Data Format Specification".
- *      Available in ftp.uu.net:/pub/archiving/zip/doc/deflate-1.1.doc
- *
- *      Storer, James A.
- *          Data Compression:  Methods and Theory, pp. 49-50.
- *          Computer Science Press, 1988.  ISBN 0-7167-8156-5.
- *
- *      Sedgewick, R.
- *          Algorithms, p290.
- *          Addison-Wesley, 1983. ISBN 0-201-06672-6.
- */
-
-/* @(#) $Id$ */
-
-/* #define GEN_TREES_H */
-
-#include "pcl/surface/3rdparty/opennurbs/deflate.h"
-
-#ifdef DEBUG
-#  include <ctype.h>
-#endif
-
-/* ===========================================================================
- * Constants
- */
-
-#define MAX_BL_BITS 7
-/* Bit length codes must not exceed MAX_BL_BITS bits */
-
-#define END_BLOCK 256
-/* end of block literal code */
-
-#define REP_3_6      16
-/* repeat previous bit length 3-6 times (2 bits of repeat count) */
-
-#define REPZ_3_10    17
-/* repeat a zero length 3-10 times  (3 bits of repeat count) */
-
-#define REPZ_11_138  18
-/* repeat a zero length 11-138 times  (7 bits of repeat count) */
-
-local const int extra_lbits[LENGTH_CODES] /* extra bits for each length code */
-   = {0,0,0,0,0,0,0,0,1,1,1,1,2,2,2,2,3,3,3,3,4,4,4,4,5,5,5,5,0};
-
-local const int extra_dbits[D_CODES] /* extra bits for each distance code */
-   = {0,0,0,0,1,1,2,2,3,3,4,4,5,5,6,6,7,7,8,8,9,9,10,10,11,11,12,12,13,13};
-
-local const int extra_blbits[BL_CODES]/* extra bits for each bit length code */
-   = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,2,3,7};
-
-local const uch bl_order[BL_CODES]
-   = {16,17,18,0,8,7,9,6,10,5,11,4,12,3,13,2,14,1,15};
-/* The lengths of the bit length codes are sent in order of decreasing
- * probability, to avoid transmitting the lengths for unused bit length codes.
- */
-
-#if defined(_MSC_VER)
-#if _MSC_VER >= 1400
-// 24 Feb 2006 Dale Lear
-//     Replaced (8 * 2*sizeof(char)) with 16 to get rid
-//     of VC 2005 size_t to ush warnings with Visual Studio 2005.
-#define Buf_size 16
-#endif
-#endif
-
-#if !defined(Buf_size)
-// original zlib code
-#define Buf_size (8 * 2*sizeof(char))
-#endif
-
-/* Number of bits used within bi_buf. (bi_buf might be implemented on
- * more than 16 bits on some systems.)
- */
-
-/* ===========================================================================
- * Local data. These are initialized only once.
- */
-
-#define DIST_CODE_LEN  512 /* see definition of array dist_code below */
-
-#if defined(GEN_TREES_H) || !defined(STDC)
-/* non ANSI compilers may not accept trees.h */
-
-local ct_data static_ltree[L_CODES+2];
-/* The static literal tree. Since the bit lengths are imposed, there is no
- * need for the L_CODES extra codes used during heap construction. However
- * The codes 286 and 287 are needed to build a canonical tree (see _tr_init
- * below).
- */
-
-local ct_data static_dtree[D_CODES];
-/* The static distance tree. (Actually a trivial tree since all codes use
- * 5 bits.)
- */
-
-uch _dist_code[DIST_CODE_LEN];
-/* Distance codes. The first 256 values correspond to the distances
- * 3 .. 258, the last 256 values correspond to the top 8 bits of
- * the 15 bit distances.
- */
-
-uch _length_code[MAX_MATCH-MIN_MATCH+1];
-/* length code for each normalized match length (0 == MIN_MATCH) */
-
-local int base_length[LENGTH_CODES];
-/* First normalized length for each code (0 = MIN_MATCH) */
-
-local int base_dist[D_CODES];
-/* First normalized distance for each code (0 = distance of 1) */
-
-#else
-#  include "pcl/surface/3rdparty/opennurbs/trees.h"
-#endif /* GEN_TREES_H */
-
-struct static_tree_desc_s {
-    const ct_data *static_tree;  /* static tree or NULL */
-    const intf *extra_bits;      /* extra bits for each code or NULL */
-    int     extra_base;          /* base index for extra_bits */
-    int     elems;               /* max number of elements in the tree */
-    int     max_length;          /* max bit length for the codes */
-};
-
-local static_tree_desc  static_l_desc =
-{static_ltree, extra_lbits, LITERALS+1, L_CODES, MAX_BITS};
-
-local static_tree_desc  static_d_desc =
-{static_dtree, extra_dbits, 0,          D_CODES, MAX_BITS};
-
-local static_tree_desc  static_bl_desc =
-{(const ct_data *)0, extra_blbits, 0,   BL_CODES, MAX_BL_BITS};
-
-/* ===========================================================================
- * Local (static) routines in this file.
- */
-
-local void tr_static_init OF((void));
-local void init_block     OF((deflate_state *s));
-local void pqdownheap     OF((deflate_state *s, ct_data *tree, int k));
-local void gen_bitlen     OF((deflate_state *s, tree_desc *desc));
-local void gen_codes      OF((ct_data *tree, int max_code, ushf *bl_count));
-local void build_tree     OF((deflate_state *s, tree_desc *desc));
-local void scan_tree      OF((deflate_state *s, ct_data *tree, int max_code));
-local void send_tree      OF((deflate_state *s, ct_data *tree, int max_code));
-local int  build_bl_tree  OF((deflate_state *s));
-local void send_all_trees OF((deflate_state *s, int lcodes, int dcodes,
-                              int blcodes));
-local void compress_block OF((deflate_state *s, ct_data *ltree,
-                              ct_data *dtree));
-local void set_data_type  OF((deflate_state *s));
-local unsigned bi_reverse OF((unsigned value, int length));
-local void bi_windup      OF((deflate_state *s));
-local void bi_flush       OF((deflate_state *s));
-local void copy_block     OF((deflate_state *s, charf *buf, unsigned len,
-                              int header));
-
-#ifdef GEN_TREES_H
-local void gen_trees_header OF((void));
-#endif
-
-#ifndef DEBUG
-#  define send_code(s, c, tree) send_bits(s, tree[c].Code, tree[c].Len)
-   /* Send a code of the given tree. c and tree must not have side effects */
-
-#else /* DEBUG */
-#  define send_code(s, c, tree) \
-     { if (z_verbose>2) fprintf(stderr,"\ncd %3d ",(c)); \
-       send_bits(s, tree[c].Code, tree[c].Len); }
-#endif
-
-/* ===========================================================================
- * Output a short LSB first on the stream.
- * IN assertion: there is enough room in pendingBuf.
- */
-#define put_short(s, w) { \
-    put_byte(s, (uch)((w) & 0xff)); \
-    put_byte(s, (uch)((ush)(w) >> 8)); \
-}
-
-/* ===========================================================================
- * Send a value on a given number of bits.
- * IN assertion: length <= 16 and value fits in length bits.
- */
-#ifdef DEBUG
-local void send_bits      OF((deflate_state *s, int value, int length));
-
-local void send_bits(s, value, length)
-    deflate_state *s;
-    int value;  /* value to send */
-    int length; /* number of bits */
-{
-    Tracevv((stderr," l %2d v %4x ", length, value));
-    Assert(length > 0 && length <= 15, "invalid length");
-    s->bits_sent += (ulg)length;
-
-    /* If not enough room in bi_buf, use (valid) bits from bi_buf and
-     * (16 - bi_valid) bits from value, leaving (width - (16-bi_valid))
-     * unused bits in value.
-     */
-    if (s->bi_valid > (int)Buf_size - length) {
-        s->bi_buf |= (value << s->bi_valid);
-        put_short(s, s->bi_buf);
-        s->bi_buf = (ush)value >> (Buf_size - s->bi_valid);
-        s->bi_valid += length - Buf_size;
-    } else {
-        s->bi_buf |= value << s->bi_valid;
-        s->bi_valid += length;
-    }
-}
-#else /* !DEBUG */
-
-#define send_bits(s, value, length) \
-{ int len = length;\
-  if (s->bi_valid > (int)Buf_size - len) {\
-    int val = value;\
-    s->bi_buf |= (val << s->bi_valid);\
-    put_short(s, s->bi_buf);\
-    s->bi_buf = (ush)val >> (Buf_size - s->bi_valid);\
-    s->bi_valid += len - Buf_size;\
-  } else {\
-    s->bi_buf |= (value) << s->bi_valid;\
-    s->bi_valid += len;\
-  }\
-}
-#endif /* DEBUG */
-
-
-/* the arguments must not have side effects */
-
-/* ===========================================================================
- * Initialize the various 'constant' tables.
- */
-local void tr_static_init()
-{
-#if defined(GEN_TREES_H) || !defined(STDC)
-    static int static_init_done = 0;
-    int n;        /* iterates over tree elements */
-    int bits;     /* bit counter */
-    int length;   /* length value */
-    int code;     /* code value */
-    int dist;     /* distance index */
-    ush bl_count[MAX_BITS+1];
-    /* number of codes at each bit length for an optimal tree */
-
-    if (static_init_done) return;
-
-    /* For some embedded targets, global variables are not initialized: */
-    static_l_desc.static_tree = static_ltree;
-    static_l_desc.extra_bits = extra_lbits;
-    static_d_desc.static_tree = static_dtree;
-    static_d_desc.extra_bits = extra_dbits;
-    static_bl_desc.extra_bits = extra_blbits;
-
-    /* Initialize the mapping length (0..255) -> length code (0..28) */
-    length = 0;
-    for (code = 0; code < LENGTH_CODES-1; code++) {
-        base_length[code] = length;
-        for (n = 0; n < (1<<extra_lbits[code]); n++) {
-            _length_code[length++] = (uch)code;
-        }
-    }
-    Assert (length == 256, "tr_static_init: length != 256");
-    /* Note that the length 255 (match length 258) can be represented
-     * in two different ways: code 284 + 5 bits or code 285, so we
-     * overwrite length_code[255] to use the best encoding:
-     */
-    _length_code[length-1] = (uch)code;
-
-    /* Initialize the mapping dist (0..32K) -> dist code (0..29) */
-    dist = 0;
-    for (code = 0 ; code < 16; code++) {
-        base_dist[code] = dist;
-        for (n = 0; n < (1<<extra_dbits[code]); n++) {
-            _dist_code[dist++] = (uch)code;
-        }
-    }
-    Assert (dist == 256, "tr_static_init: dist != 256");
-    dist >>= 7; /* from now on, all distances are divided by 128 */
-    for ( ; code < D_CODES; code++) {
-        base_dist[code] = dist << 7;
-        for (n = 0; n < (1<<(extra_dbits[code]-7)); n++) {
-            _dist_code[256 + dist++] = (uch)code;
-        }
-    }
-    Assert (dist == 256, "tr_static_init: 256+dist != 512");
-
-    /* Construct the codes of the static literal tree */
-    for (bits = 0; bits <= MAX_BITS; bits++) bl_count[bits] = 0;
-    n = 0;
-    while (n <= 143) static_ltree[n++].Len = 8, bl_count[8]++;
-    while (n <= 255) static_ltree[n++].Len = 9, bl_count[9]++;
-    while (n <= 279) static_ltree[n++].Len = 7, bl_count[7]++;
-    while (n <= 287) static_ltree[n++].Len = 8, bl_count[8]++;
-    /* Codes 286 and 287 do not exist, but we must include them in the
-     * tree construction to get a canonical Huffman tree (longest code
-     * all ones)
-     */
-    gen_codes((ct_data *)static_ltree, L_CODES+1, bl_count);
-
-    /* The static distance tree is trivial: */
-    for (n = 0; n < D_CODES; n++) {
-        static_dtree[n].Len = 5;
-        static_dtree[n].Code = bi_reverse((unsigned)n, 5);
-    }
-    static_init_done = 1;
-
-#  ifdef GEN_TREES_H
-    gen_trees_header();
-#  endif
-#endif /* defined(GEN_TREES_H) || !defined(STDC) */
-}
-
-/* ===========================================================================
- * Genererate the file trees.h describing the static trees.
- */
-#ifdef GEN_TREES_H
-#  ifndef DEBUG
-#    include <stdio.h>
-#  endif
-
-#  define SEPARATOR(i, last, width) \
-      ((i) == (last)? "\n};\n\n" :    \
-       ((i) % (width) == (width)-1 ? ",\n" : ", "))
-
-void gen_trees_header()
-{
-    FILE *header = fopen("trees.h", "w");
-    int i;
-
-    Assert (header != 0, "Can't open trees.h");
-    fprintf(header,
-            "/* header created automatically with -DGEN_TREES_H */\n\n");
-
-    fprintf(header, "local const ct_data static_ltree[L_CODES+2] = {\n");
-    for (i = 0; i < L_CODES+2; i++) {
-        fprintf(header, "{{%3u},{%3u}}%s", static_ltree[i].Code,
-                static_ltree[i].Len, SEPARATOR(i, L_CODES+1, 5));
-    }
-
-    fprintf(header, "local const ct_data static_dtree[D_CODES] = {\n");
-    for (i = 0; i < D_CODES; i++) {
-        fprintf(header, "{{%2u},{%2u}}%s", static_dtree[i].Code,
-                static_dtree[i].Len, SEPARATOR(i, D_CODES-1, 5));
-    }
-
-    fprintf(header, "const uch _dist_code[DIST_CODE_LEN] = {\n");
-    for (i = 0; i < DIST_CODE_LEN; i++) {
-        fprintf(header, "%2u%s", _dist_code[i],
-                SEPARATOR(i, DIST_CODE_LEN-1, 20));
-    }
-
-    fprintf(header, "const uch _length_code[MAX_MATCH-MIN_MATCH+1]= {\n");
-    for (i = 0; i < MAX_MATCH-MIN_MATCH+1; i++) {
-        fprintf(header, "%2u%s", _length_code[i],
-                SEPARATOR(i, MAX_MATCH-MIN_MATCH, 20));
-    }
-
-    fprintf(header, "local const int base_length[LENGTH_CODES] = {\n");
-    for (i = 0; i < LENGTH_CODES; i++) {
-        fprintf(header, "%1u%s", base_length[i],
-                SEPARATOR(i, LENGTH_CODES-1, 20));
-    }
-
-    fprintf(header, "local const int base_dist[D_CODES] = {\n");
-    for (i = 0; i < D_CODES; i++) {
-        fprintf(header, "%5u%s", base_dist[i],
-                SEPARATOR(i, D_CODES-1, 10));
-    }
-
-    fclose(header);
-}
-#endif /* GEN_TREES_H */
-
-/* ===========================================================================
- * Initialize the tree data structures for a new zlib stream.
- */
-void _tr_init(s)
-    deflate_state *s;
-{
-    tr_static_init();
-
-    s->l_desc.dyn_tree = s->dyn_ltree;
-    s->l_desc.stat_desc = &static_l_desc;
-
-    s->d_desc.dyn_tree = s->dyn_dtree;
-    s->d_desc.stat_desc = &static_d_desc;
-
-    s->bl_desc.dyn_tree = s->bl_tree;
-    s->bl_desc.stat_desc = &static_bl_desc;
-
-    s->bi_buf = 0;
-    s->bi_valid = 0;
-    s->last_eob_len = 8; /* enough lookahead for inflate */
-#ifdef DEBUG
-    s->compressed_len = 0L;
-    s->bits_sent = 0L;
-#endif
-
-    /* Initialize the first block of the first file: */
-    init_block(s);
-}
-
-/* ===========================================================================
- * Initialize a new block.
- */
-local void init_block(s)
-    deflate_state *s;
-{
-    int n; /* iterates over tree elements */
-
-    /* Initialize the trees. */
-    for (n = 0; n < L_CODES;  n++) s->dyn_ltree[n].Freq = 0;
-    for (n = 0; n < D_CODES;  n++) s->dyn_dtree[n].Freq = 0;
-    for (n = 0; n < BL_CODES; n++) s->bl_tree[n].Freq = 0;
-
-    s->dyn_ltree[END_BLOCK].Freq = 1;
-    s->opt_len = s->static_len = 0L;
-    s->last_lit = s->matches = 0;
-}
-
-#define SMALLEST 1
-/* Index within the heap array of least frequent node in the Huffman tree */
-
-
-/* ===========================================================================
- * Remove the smallest element from the heap and recreate the heap with
- * one less element. Updates heap and heap_len.
- */
-#define pqremove(s, tree, top) \
-{\
-    top = s->heap[SMALLEST]; \
-    s->heap[SMALLEST] = s->heap[s->heap_len--]; \
-    pqdownheap(s, tree, SMALLEST); \
-}
-
-/* ===========================================================================
- * Compares to subtrees, using the tree depth as tie breaker when
- * the subtrees have equal frequency. This minimizes the worst case length.
- */
-#define smaller(tree, n, m, depth) \
-   (tree[n].Freq < tree[m].Freq || \
-   (tree[n].Freq == tree[m].Freq && depth[n] <= depth[m]))
-
-/* ===========================================================================
- * Restore the heap property by moving down the tree starting at node k,
- * exchanging a node with the smallest of its two sons if necessary, stopping
- * when the heap property is re-established (each father smaller than its
- * two sons).
- */
-local void pqdownheap(s, tree, k)
-    deflate_state *s;
-    ct_data *tree;  /* the tree to restore */
-    int k;               /* node to move down */
-{
-    int v = s->heap[k];
-    int j = k << 1;  /* left son of k */
-    while (j <= s->heap_len) {
-        /* Set j to the smallest of the two sons: */
-        if (j < s->heap_len &&
-            smaller(tree, s->heap[j+1], s->heap[j], s->depth)) {
-            j++;
-        }
-        /* Exit if v is smaller than both sons */
-        if (smaller(tree, v, s->heap[j], s->depth)) break;
-
-        /* Exchange v with the smallest son */
-        s->heap[k] = s->heap[j];  k = j;
-
-        /* And continue down the tree, setting j to the left son of k */
-        j <<= 1;
-    }
-    s->heap[k] = v;
-}
-
-/* ===========================================================================
- * Compute the optimal bit lengths for a tree and update the total bit length
- * for the current block.
- * IN assertion: the fields freq and dad are set, heap[heap_max] and
- *    above are the tree nodes sorted by increasing frequency.
- * OUT assertions: the field len is set to the optimal bit length, the
- *     array bl_count contains the frequencies for each bit length.
- *     The length opt_len is updated; static_len is also updated if stree is
- *     not null.
- */
-local void gen_bitlen(s, desc)
-    deflate_state *s;
-    tree_desc *desc;    /* the tree descriptor */
-{
-    ct_data *tree        = desc->dyn_tree;
-    int max_code         = desc->max_code;
-    const ct_data *stree = desc->stat_desc->static_tree;
-    const intf *extra    = desc->stat_desc->extra_bits;
-    int base             = desc->stat_desc->extra_base;
-    int max_length       = desc->stat_desc->max_length;
-    int h;              /* heap index */
-    int n, m;           /* iterate over the tree elements */
-    int bits;           /* bit length */
-    int xbits;          /* extra bits */
-    ush f;              /* frequency */
-    int overflow = 0;   /* number of elements with bit length too large */
-
-    for (bits = 0; bits <= MAX_BITS; bits++) s->bl_count[bits] = 0;
-
-    /* In a first pass, compute the optimal bit lengths (which may
-     * overflow in the case of the bit length tree).
-     */
-    tree[s->heap[s->heap_max]].Len = 0; /* root of the heap */
-
-    for (h = s->heap_max+1; h < HEAP_SIZE; h++) {
-        n = s->heap[h];
-        bits = tree[tree[n].Dad].Len + 1;
-        if (bits > max_length) bits = max_length, overflow++;
-        tree[n].Len = (ush)bits;
-        /* We overwrite tree[n].Dad which is no longer needed */
-
-        if (n > max_code) continue; /* not a leaf node */
-
-        s->bl_count[bits]++;
-        xbits = 0;
-        if (n >= base) xbits = extra[n-base];
-        f = tree[n].Freq;
-        s->opt_len += (ulg)f * (bits + xbits);
-        if (stree) s->static_len += (ulg)f * (stree[n].Len + xbits);
-    }
-    if (overflow == 0) return;
-
-    Trace((stderr,"\nbit length overflow\n"));
-    /* This happens for example on obj2 and pic of the Calgary corpus */
-
-    /* Find the first bit length which could increase: */
-    do {
-        bits = max_length-1;
-        while (s->bl_count[bits] == 0) bits--;
-        s->bl_count[bits]--;      /* move one leaf down the tree */
-        s->bl_count[bits+1] += 2; /* move one overflow item as its brother */
-        s->bl_count[max_length]--;
-        /* The brother of the overflow item also moves one step up,
-         * but this does not affect bl_count[max_length]
-         */
-        overflow -= 2;
-    } while (overflow > 0);
-
-    /* Now recompute all bit lengths, scanning in increasing frequency.
-     * h is still equal to HEAP_SIZE. (It is simpler to reconstruct all
-     * lengths instead of fixing only the wrong ones. This idea is taken
-     * from 'ar' written by Haruhiko Okumura.)
-     */
-    for (bits = max_length; bits != 0; bits--) {
-        n = s->bl_count[bits];
-        while (n != 0) {
-            m = s->heap[--h];
-            if (m > max_code) continue;
-            if ((unsigned) tree[m].Len != (unsigned) bits) {
-                Trace((stderr,"code %d bits %d->%d\n", m, tree[m].Len, bits));
-                s->opt_len += ((int)bits - (int)tree[m].Len)
-                              *(int)tree[m].Freq;
-                tree[m].Len = (ush)bits;
-            }
-            n--;
-        }
-    }
-}
-
-/* ===========================================================================
- * Generate the codes for a given tree and bit counts (which need not be
- * optimal).
- * IN assertion: the array bl_count contains the bit length statistics for
- * the given tree and the field len is set for all tree elements.
- * OUT assertion: the field code is set for all tree elements of non
- *     zero code length.
- */
-local void gen_codes (tree, max_code, bl_count)
-    ct_data *tree;             /* the tree to decorate */
-    int max_code;              /* largest code with non zero frequency */
-    ushf *bl_count;            /* number of codes at each bit length */
-{
-    ush next_code[MAX_BITS+1]; /* next code value for each bit length */
-    ush code = 0;              /* running code value */
-    int bits;                  /* bit index */
-    int n;                     /* code index */
-
-    /* The distribution counts are first used to generate the code values
-     * without bit reversal.
-     */
-    for (bits = 1; bits <= MAX_BITS; bits++) {
-        next_code[bits] = code = (code + bl_count[bits-1]) << 1;
-    }
-    /* Check that the bit counts in bl_count are consistent. The last code
-     * must be all ones.
-     */
-    Assert (code + bl_count[MAX_BITS]-1 == (1<<MAX_BITS)-1,
-            "inconsistent bit counts");
-    Tracev((stderr,"\ngen_codes: max_code %d ", max_code));
-
-    for (n = 0;  n <= max_code; n++) {
-        int len = tree[n].Len;
-        if (len == 0) continue;
-        /* Now reverse the bits */
-        tree[n].Code = bi_reverse(next_code[len]++, len);
-
-        Tracecv(tree != static_ltree, (stderr,"\nn %3d %c l %2d c %4x (%x) ",
-             n, (isgraph(n) ? n : ' '), len, tree[n].Code, next_code[len]-1));
-    }
-}
-
-/* ===========================================================================
- * Construct one Huffman tree and assigns the code bit strings and lengths.
- * Update the total bit length for the current block.
- * IN assertion: the field freq is set for all tree elements.
- * OUT assertions: the fields len and code are set to the optimal bit length
- *     and corresponding code. The length opt_len is updated; static_len is
- *     also updated if stree is not null. The field max_code is set.
- */
-local void build_tree(s, desc)
-    deflate_state *s;
-    tree_desc *desc; /* the tree descriptor */
-{
-    ct_data *tree         = desc->dyn_tree;
-    const ct_data *stree  = desc->stat_desc->static_tree;
-    int elems             = desc->stat_desc->elems;
-    int n, m;          /* iterate over heap elements */
-    int max_code = -1; /* largest code with non zero frequency */
-    int node;          /* new node being created */
-
-    /* Construct the initial heap, with least frequent element in
-     * heap[SMALLEST]. The sons of heap[n] are heap[2*n] and heap[2*n+1].
-     * heap[0] is not used.
-     */
-    s->heap_len = 0, s->heap_max = HEAP_SIZE;
-
-    for (n = 0; n < elems; n++) {
-        if (tree[n].Freq != 0) {
-            s->heap[++(s->heap_len)] = max_code = n;
-            s->depth[n] = 0;
-        } else {
-            tree[n].Len = 0;
-        }
-    }
-
-    /* The pkzip format requires that at least one distance code exists,
-     * and that at least one bit should be sent even if there is only one
-     * possible code. So to avoid special checks later on we force at least
-     * two codes of non zero frequency.
-     */
-    while (s->heap_len < 2) {
-        node = s->heap[++(s->heap_len)] = (max_code < 2 ? ++max_code : 0);
-        tree[node].Freq = 1;
-        s->depth[node] = 0;
-        s->opt_len--; if (stree) s->static_len -= stree[node].Len;
-        /* node is 0 or 1 so it does not have extra bits */
-    }
-    desc->max_code = max_code;
-
-    /* The elements heap[heap_len/2+1 .. heap_len] are leaves of the tree,
-     * establish sub-heaps of increasing lengths:
-     */
-    for (n = s->heap_len/2; n >= 1; n--) pqdownheap(s, tree, n);
-
-    /* Construct the Huffman tree by repeatedly combining the least two
-     * frequent nodes.
-     */
-    node = elems;              /* next internal node of the tree */
-    do {
-        pqremove(s, tree, n);  /* n = node of least frequency */
-        m = s->heap[SMALLEST]; /* m = node of next least frequency */
-
-        s->heap[--(s->heap_max)] = n; /* keep the nodes sorted by frequency */
-        s->heap[--(s->heap_max)] = m;
-
-        /* Create a new node father of n and m */
-        tree[node].Freq = tree[n].Freq + tree[m].Freq;
-        s->depth[node] = (uch)((s->depth[n] >= s->depth[m] ?
-                                s->depth[n] : s->depth[m]) + 1);
-        tree[n].Dad = tree[m].Dad = (ush)node;
-#ifdef DUMP_BL_TREE
-        if (tree == s->bl_tree) {
-            fprintf(stderr,"\nnode %d(%d), sons %d(%d) %d(%d)",
-                    node, tree[node].Freq, n, tree[n].Freq, m, tree[m].Freq);
-        }
-#endif
-        /* and insert the new node in the heap */
-        s->heap[SMALLEST] = node++;
-        pqdownheap(s, tree, SMALLEST);
-
-    } while (s->heap_len >= 2);
-
-    s->heap[--(s->heap_max)] = s->heap[SMALLEST];
-
-    /* At this point, the fields freq and dad are set. We can now
-     * generate the bit lengths.
-     */
-    gen_bitlen(s, (tree_desc *)desc);
-
-    /* The field len is now set, we can generate the bit codes */
-    gen_codes ((ct_data *)tree, max_code, s->bl_count);
-}
-
-/* ===========================================================================
- * Scan a literal or distance tree to determine the frequencies of the codes
- * in the bit length tree.
- */
-local void scan_tree (s, tree, max_code)
-    deflate_state *s;
-    ct_data *tree;   /* the tree to be scanned */
-    int max_code;    /* and its largest code of non zero frequency */
-{
-    int n;                     /* iterates over all tree elements */
-    int prevlen = -1;          /* last emitted length */
-    int curlen;                /* length of current code */
-    int nextlen = tree[0].Len; /* length of next code */
-    int count = 0;             /* repeat count of the current code */
-    int max_count = 7;         /* max repeat count */
-    int min_count = 4;         /* min repeat count */
-
-    if (nextlen == 0) max_count = 138, min_count = 3;
-    tree[max_code+1].Len = (ush)0xffff; /* guard */
-
-    for (n = 0; n <= max_code; n++) {
-        curlen = nextlen; nextlen = tree[n+1].Len;
-        if (++count < max_count && curlen == nextlen) {
-            continue;
-        } else if (count < min_count) {
-            s->bl_tree[curlen].Freq += count;
-        } else if (curlen != 0) {
-            if (curlen != prevlen) s->bl_tree[curlen].Freq++;
-            s->bl_tree[REP_3_6].Freq++;
-        } else if (count <= 10) {
-            s->bl_tree[REPZ_3_10].Freq++;
-        } else {
-            s->bl_tree[REPZ_11_138].Freq++;
-        }
-        count = 0; prevlen = curlen;
-        if (nextlen == 0) {
-            max_count = 138, min_count = 3;
-        } else if (curlen == nextlen) {
-            max_count = 6, min_count = 3;
-        } else {
-            max_count = 7, min_count = 4;
-        }
-    }
-}
-
-/* ===========================================================================
- * Send a literal or distance tree in compressed form, using the codes in
- * bl_tree.
- */
-local void send_tree (s, tree, max_code)
-    deflate_state *s;
-    ct_data *tree; /* the tree to be scanned */
-    int max_code;       /* and its largest code of non zero frequency */
-{
-    int n;                     /* iterates over all tree elements */
-    int prevlen = -1;          /* last emitted length */
-    int curlen;                /* length of current code */
-    int nextlen = tree[0].Len; /* length of next code */
-    int count = 0;             /* repeat count of the current code */
-    int max_count = 7;         /* max repeat count */
-    int min_count = 4;         /* min repeat count */
-
-    /* tree[max_code+1].Len = -1; */  /* guard already set */
-    if (nextlen == 0) max_count = 138, min_count = 3;
-
-    for (n = 0; n <= max_code; n++) {
-        curlen = nextlen; nextlen = tree[n+1].Len;
-        if (++count < max_count && curlen == nextlen) {
-            continue;
-        } else if (count < min_count) {
-            do { send_code(s, curlen, s->bl_tree); } while (--count != 0);
-
-        } else if (curlen != 0) {
-            if (curlen != prevlen) {
-                send_code(s, curlen, s->bl_tree); count--;
-            }
-            Assert(count >= 3 && count <= 6, " 3_6?");
-            send_code(s, REP_3_6, s->bl_tree); send_bits(s, count-3, 2);
-
-        } else if (count <= 10) {
-            send_code(s, REPZ_3_10, s->bl_tree); send_bits(s, count-3, 3);
-
-        } else {
-            send_code(s, REPZ_11_138, s->bl_tree); send_bits(s, count-11, 7);
-        }
-        count = 0; prevlen = curlen;
-        if (nextlen == 0) {
-            max_count = 138, min_count = 3;
-        } else if (curlen == nextlen) {
-            max_count = 6, min_count = 3;
-        } else {
-            max_count = 7, min_count = 4;
-        }
-    }
-}
-
-/* ===========================================================================
- * Construct the Huffman tree for the bit lengths and return the index in
- * bl_order of the last bit length code to send.
- */
-local int build_bl_tree(s)
-    deflate_state *s;
-{
-    int max_blindex;  /* index of last bit length code of non zero freq */
-
-    /* Determine the bit length frequencies for literal and distance trees */
-    scan_tree(s, (ct_data *)s->dyn_ltree, s->l_desc.max_code);
-    scan_tree(s, (ct_data *)s->dyn_dtree, s->d_desc.max_code);
-
-    /* Build the bit length tree: */
-    build_tree(s, (tree_desc *)(&(s->bl_desc)));
-    /* opt_len now includes the length of the tree representations, except
-     * the lengths of the bit lengths codes and the 5+5+4 bits for the counts.
-     */
-
-    /* Determine the number of bit length codes to send. The pkzip format
-     * requires that at least 4 bit length codes be sent. (appnote.txt says
-     * 3 but the actual value used is 4.)
-     */
-    for (max_blindex = BL_CODES-1; max_blindex >= 3; max_blindex--) {
-        if (s->bl_tree[bl_order[max_blindex]].Len != 0) break;
-    }
-    /* Update opt_len to include the bit length tree and counts */
-    s->opt_len += 3*(max_blindex+1) + 5+5+4;
-    Tracev((stderr, "\ndyn trees: dyn %d, stat %d",
-            s->opt_len, s->static_len));
-
-    return max_blindex;
-}
-
-/* ===========================================================================
- * Send the header for a block using dynamic Huffman trees: the counts, the
- * lengths of the bit length codes, the literal tree and the distance tree.
- * IN assertion: lcodes >= 257, dcodes >= 1, blcodes >= 4.
- */
-local void send_all_trees(s, lcodes, dcodes, blcodes)
-    deflate_state *s;
-    int lcodes, dcodes, blcodes; /* number of codes for each tree */
-{
-    int rank;                    /* index in bl_order */
-
-    Assert (lcodes >= 257 && dcodes >= 1 && blcodes >= 4, "not enough codes");
-    Assert (lcodes <= L_CODES && dcodes <= D_CODES && blcodes <= BL_CODES,
-            "too many codes");
-    Tracev((stderr, "\nbl counts: "));
-    send_bits(s, lcodes-257, 5); /* not +255 as stated in appnote.txt */
-    send_bits(s, dcodes-1,   5);
-    send_bits(s, blcodes-4,  4); /* not -3 as stated in appnote.txt */
-    for (rank = 0; rank < blcodes; rank++) {
-        Tracev((stderr, "\nbl code %2d ", bl_order[rank]));
-        send_bits(s, s->bl_tree[bl_order[rank]].Len, 3);
-    }
-    Tracev((stderr, "\nbl tree: sent %d", s->bits_sent));
-
-    send_tree(s, (ct_data *)s->dyn_ltree, lcodes-1); /* literal tree */
-    Tracev((stderr, "\nlit tree: sent %d", s->bits_sent));
-
-    send_tree(s, (ct_data *)s->dyn_dtree, dcodes-1); /* distance tree */
-    Tracev((stderr, "\ndist tree: sent %d", s->bits_sent));
-}
-
-/* ===========================================================================
- * Send a stored block
- */
-void _tr_stored_block(s, buf, stored_len, eof)
-    deflate_state *s;
-    charf *buf;       /* input block */
-    ulg stored_len;   /* length of input block */
-    int eof;          /* true if this is the last block for a file */
-{
-    send_bits(s, (STORED_BLOCK<<1)+eof, 3);  /* send block type */
-#ifdef DEBUG
-    s->compressed_len = (s->compressed_len + 3 + 7) & (ulg)~7L;
-    s->compressed_len += (stored_len + 4) << 3;
-#endif
-    copy_block(s, buf, (unsigned)stored_len, 1); /* with header */
-}
-
-/* ===========================================================================
- * Send one empty static block to give enough lookahead for inflate.
- * This takes 10 bits, of which 7 may remain in the bit buffer.
- * The current inflate code requires 9 bits of lookahead. If the
- * last two codes for the previous block (real code plus EOB) were coded
- * on 5 bits or less, inflate may have only 5+3 bits of lookahead to decode
- * the last real code. In this case we send two empty static blocks instead
- * of one. (There are no problems if the previous block is stored or fixed.)
- * To simplify the code, we assume the worst case of last real code encoded
- * on one bit only.
- */
-void _tr_align(s)
-    deflate_state *s;
-{
-    send_bits(s, STATIC_TREES<<1, 3);
-    send_code(s, END_BLOCK, static_ltree);
-#ifdef DEBUG
-    s->compressed_len += 10L; /* 3 for block type, 7 for EOB */
-#endif
-    bi_flush(s);
-    /* Of the 10 bits for the empty block, we have already sent
-     * (10 - bi_valid) bits. The lookahead for the last real code (before
-     * the EOB of the previous block) was thus at least one plus the length
-     * of the EOB plus what we have just sent of the empty static block.
-     */
-    if (1 + s->last_eob_len + 10 - s->bi_valid < 9) {
-        send_bits(s, STATIC_TREES<<1, 3);
-        send_code(s, END_BLOCK, static_ltree);
-#ifdef DEBUG
-        s->compressed_len += 10L;
-#endif
-        bi_flush(s);
-    }
-    s->last_eob_len = 7;
-}
-
-/* ===========================================================================
- * Determine the best encoding for the current block: dynamic trees, static
- * trees or store, and output the encoded block to the zip file.
- */
-void _tr_flush_block(s, buf, stored_len, eof)
-    deflate_state *s;
-    charf *buf;       /* input block, or NULL if too old */
-    ulg stored_len;   /* length of input block */
-    int eof;          /* true if this is the last block for a file */
-{
-    ulg opt_lenb, static_lenb; /* opt_len and static_len in bytes */
-    int max_blindex = 0;  /* index of last bit length code of non zero freq */
-
-    /* Build the Huffman trees unless a stored block is forced */
-    if (s->level > 0) {
-
-        /* Check if the file is binary or text */
-        if (stored_len > 0 && s->strm->data_type == Z_UNKNOWN)
-            set_data_type(s);
-
-        /* Construct the literal and distance trees */
-        build_tree(s, (tree_desc *)(&(s->l_desc)));
-        Tracev((stderr, "\nlit data: dyn %d, stat %d", s->opt_len,
-                s->static_len));
-
-        build_tree(s, (tree_desc *)(&(s->d_desc)));
-        Tracev((stderr, "\ndist data: dyn %d, stat %d", s->opt_len,
-                s->static_len));
-        /* At this point, opt_len and static_len are the total bit lengths of
-         * the compressed block data, excluding the tree representations.
-         */
-
-        /* Build the bit length tree for the above two trees, and get the index
-         * in bl_order of the last bit length code to send.
-         */
-        max_blindex = build_bl_tree(s);
-
-        /* Determine the best encoding. Compute the block lengths in bytes. */
-        opt_lenb = (s->opt_len+3+7)>>3;
-        static_lenb = (s->static_len+3+7)>>3;
-
-        Tracev((stderr, "\nopt %u(%u) stat %u(%u) stored %u lit %u ",
-                opt_lenb, s->opt_len, static_lenb, s->static_len, stored_len,
-                s->last_lit));
-
-        if (static_lenb <= opt_lenb) opt_lenb = static_lenb;
-
-    } else {
-        Assert(buf != (char*)0, "lost buf");
-        opt_lenb = static_lenb = stored_len + 5; /* force a stored block */
-    }
-
-#ifdef FORCE_STORED
-    if (buf != (char*)0) { /* force stored block */
-#else
-    if (stored_len+4 <= opt_lenb && buf != (char*)0) {
-                       /* 4: two words for the lengths */
-#endif
-        /* The test buf != NULL is only necessary if LIT_BUFSIZE > WSIZE.
-         * Otherwise we can't have processed more than WSIZE input bytes since
-         * the last block flush, because compression would have been
-         * successful. If LIT_BUFSIZE <= WSIZE, it is never too late to
-         * transform a block into a stored block.
-         */
-        _tr_stored_block(s, buf, stored_len, eof);
-
-#ifdef FORCE_STATIC
-    } else if (static_lenb >= 0) { /* force static trees */
-#else
-    } else if (s->strategy == Z_FIXED || static_lenb == opt_lenb) {
-#endif
-        send_bits(s, (STATIC_TREES<<1)+eof, 3);
-        compress_block(s, (ct_data *)static_ltree, (ct_data *)static_dtree);
-#ifdef DEBUG
-        s->compressed_len += 3 + s->static_len;
-#endif
-    } else {
-        send_bits(s, (DYN_TREES<<1)+eof, 3);
-        send_all_trees(s, s->l_desc.max_code+1, s->d_desc.max_code+1,
-                       max_blindex+1);
-        compress_block(s, (ct_data *)s->dyn_ltree, (ct_data *)s->dyn_dtree);
-#ifdef DEBUG
-        s->compressed_len += 3 + s->opt_len;
-#endif
-    }
-    Assert (s->compressed_len == s->bits_sent, "bad compressed size");
-    /* The above check is made mod 2^32, for files larger than 512 MB
-     * and uLong implemented on 32 bits.
-     */
-    init_block(s);
-
-    if (eof) {
-        bi_windup(s);
-#ifdef DEBUG
-        s->compressed_len += 7;  /* align on byte boundary */
-#endif
-    }
-    Tracev((stderr,"\ncomprlen %u(%u) ", s->compressed_len>>3,
-           s->compressed_len-7*eof));
-}
-
-/* ===========================================================================
- * Save the match info and tally the frequency counts. Return true if
- * the current block must be flushed.
- */
-int _tr_tally (s, dist, lc)
-    deflate_state *s;
-    unsigned dist;  /* distance of matched string */
-    unsigned lc;    /* match length-MIN_MATCH or unmatched char (if dist==0) */
-{
-    s->d_buf[s->last_lit] = (ush)dist;
-    s->l_buf[s->last_lit++] = (uch)lc;
-    if (dist == 0) {
-        /* lc is the unmatched char */
-        s->dyn_ltree[lc].Freq++;
-    } else {
-        s->matches++;
-        /* Here, lc is the match length - MIN_MATCH */
-        dist--;             /* dist = match distance - 1 */
-        Assert((ush)dist < (ush)MAX_DIST(s) &&
-               (ush)lc <= (ush)(MAX_MATCH-MIN_MATCH) &&
-               (ush)d_code(dist) < (ush)D_CODES,  "_tr_tally: bad match");
-
-        s->dyn_ltree[_length_code[lc]+LITERALS+1].Freq++;
-        s->dyn_dtree[d_code(dist)].Freq++;
-    }
-
-#ifdef TRUNCATE_BLOCK
-    /* Try to guess if it is profitable to stop the current block here */
-    if ((s->last_lit & 0x1fff) == 0 && s->level > 2) {
-        /* Compute an upper bound for the compressed length */
-        ulg out_length = (ulg)s->last_lit*8L;
-        ulg in_length = (ulg)((int)s->strstart - s->block_start);
-        int dcode;
-        for (dcode = 0; dcode < D_CODES; dcode++) {
-            out_length += (ulg)s->dyn_dtree[dcode].Freq *
-                (5L+extra_dbits[dcode]);
-        }
-        out_length >>= 3;
-        Tracev((stderr,"\nlast_lit %u, in %d, out ~%d(%d%%) ",
-               s->last_lit, in_length, out_length,
-               100L - out_length*100L/in_length));
-        if (s->matches < s->last_lit/2 && out_length < in_length/2) return 1;
-    }
-#endif
-    return (s->last_lit == s->lit_bufsize-1);
-    /* We avoid equality with lit_bufsize because of wraparound at 64K
-     * on 16 bit machines and because stored blocks are restricted to
-     * 64K-1 bytes.
-     */
-}
-
-/* ===========================================================================
- * Send the block data compressed using the given Huffman trees
- */
-local void compress_block(s, ltree, dtree)
-    deflate_state *s;
-    ct_data *ltree; /* literal tree */
-    ct_data *dtree; /* distance tree */
-{
-    unsigned dist;      /* distance of matched string */
-    int lc;             /* match length or unmatched char (if dist == 0) */
-    unsigned lx = 0;    /* running index in l_buf */
-    unsigned code;      /* the code to send */
-    int extra;          /* number of extra bits to send */
-
-    if (s->last_lit != 0) do {
-        dist = s->d_buf[lx];
-        lc = s->l_buf[lx++];
-        if (dist == 0) {
-            send_code(s, lc, ltree); /* send a literal byte */
-            Tracecv(isgraph(lc), (stderr," '%c' ", lc));
-        } else {
-            /* Here, lc is the match length - MIN_MATCH */
-            code = _length_code[lc];
-            send_code(s, code+LITERALS+1, ltree); /* send the length code */
-            extra = extra_lbits[code];
-            if (extra != 0) {
-                lc -= base_length[code];
-                send_bits(s, lc, extra);       /* send the extra length bits */
-            }
-            dist--; /* dist is now the match distance - 1 */
-            code = d_code(dist);
-            Assert (code < D_CODES, "bad d_code");
-
-            send_code(s, code, dtree);       /* send the distance code */
-            extra = extra_dbits[code];
-            if (extra != 0) {
-                dist -= base_dist[code];
-                send_bits(s, dist, extra);   /* send the extra distance bits */
-            }
-        } /* literal or match pair ? */
-
-        /* Check that the overlay between pending_buf and d_buf+l_buf is ok: */
-        Assert((uInt)(s->pending) < s->lit_bufsize + 2*lx,
-               "pendingBuf overflow");
-
-    } while (lx < s->last_lit);
-
-    send_code(s, END_BLOCK, ltree);
-    s->last_eob_len = ltree[END_BLOCK].Len;
-}
-
-/* ===========================================================================
- * Set the data type to BINARY or TEXT, using a crude approximation:
- * set it to Z_TEXT if all symbols are either printable characters (33 to 255)
- * or white spaces (9 to 13, or 32); or set it to Z_BINARY otherwise.
- * IN assertion: the fields Freq of dyn_ltree are set.
- */
-local void set_data_type(s)
-    deflate_state *s;
-{
-    int n;
-
-    for (n = 0; n < 9; n++)
-        if (s->dyn_ltree[n].Freq != 0)
-            break;
-    if (n == 9)
-        for (n = 14; n < 32; n++)
-            if (s->dyn_ltree[n].Freq != 0)
-                break;
-    s->strm->data_type = (n == 32) ? Z_TEXT : Z_BINARY;
-}
-
-/* ===========================================================================
- * Reverse the first len bits of a code, using straightforward code (a faster
- * method would use a table)
- * IN assertion: 1 <= len <= 15
- */
-local unsigned bi_reverse(code, len)
-    unsigned code; /* the value to invert */
-    int len;       /* its bit length */
-{
-    register unsigned res = 0;
-    do {
-        res |= code & 1;
-        code >>= 1, res <<= 1;
-    } while (--len > 0);
-    return res >> 1;
-}
-
-/* ===========================================================================
- * Flush the bit buffer, keeping at most 7 bits in it.
- */
-local void bi_flush(s)
-    deflate_state *s;
-{
-    if (s->bi_valid == 16) {
-        put_short(s, s->bi_buf);
-        s->bi_buf = 0;
-        s->bi_valid = 0;
-    } else if (s->bi_valid >= 8) {
-        put_byte(s, (Byte)s->bi_buf);
-        s->bi_buf >>= 8;
-        s->bi_valid -= 8;
-    }
-}
-
-/* ===========================================================================
- * Flush the bit buffer and align the output on a byte boundary
- */
-local void bi_windup(s)
-    deflate_state *s;
-{
-    if (s->bi_valid > 8) {
-        put_short(s, s->bi_buf);
-    } else if (s->bi_valid > 0) {
-        put_byte(s, (Byte)s->bi_buf);
-    }
-    s->bi_buf = 0;
-    s->bi_valid = 0;
-#ifdef DEBUG
-    s->bits_sent = (s->bits_sent+7) & ~7;
-#endif
-}
-
-/* ===========================================================================
- * Copy a stored block, storing first the length and its
- * one's complement if requested.
- */
-local void copy_block(s, buf, len, header)
-    deflate_state *s;
-    charf    *buf;    /* the input data */
-    unsigned len;     /* its length */
-    int      header;  /* true if block header must be written */
-{
-    bi_windup(s);        /* align on byte boundary */
-    s->last_eob_len = 8; /* enough lookahead for inflate */
-
-    if (header) {
-        put_short(s, (ush)len);
-        put_short(s, (ush)~len);
-#ifdef DEBUG
-        s->bits_sent += 2*16;
-#endif
-    }
-#ifdef DEBUG
-    s->bits_sent += (ulg)len<<3;
-#endif
-    while (len--) {
-        put_byte(s, *buf++);
-    }
-}
diff --git a/surface/src/3rdparty/opennurbs/uncompr.c b/surface/src/3rdparty/opennurbs/uncompr.c
deleted file mode 100644 (file)
index 2195560..0000000
+++ /dev/null
@@ -1,61 +0,0 @@
-/* uncompr.c -- decompress a memory buffer
- * Copyright (C) 1995-2003 Jean-loup Gailly.
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* @(#) $Id$ */
-
-#define ZLIB_INTERNAL
-#include "pcl/surface/3rdparty/opennurbs/zlib.h"
-
-/* ===========================================================================
-     Decompresses the source buffer into the destination buffer.  sourceLen is
-   the byte length of the source buffer. Upon entry, destLen is the total
-   size of the destination buffer, which must be large enough to hold the
-   entire uncompressed data. (The size of the uncompressed data must have
-   been saved previously by the compressor and transmitted to the decompressor
-   by some mechanism outside the scope of this compression library.)
-   Upon exit, destLen is the actual size of the compressed buffer.
-     This function can be used to decompress a whole file at once if the
-   input file is mmap'ed.
-
-     uncompress returns Z_OK if success, Z_MEM_ERROR if there was not
-   enough memory, Z_BUF_ERROR if there was not enough room in the output
-   buffer, or Z_DATA_ERROR if the input data was corrupted.
-*/
-int ZEXPORT uncompress (dest, destLen, source, sourceLen)
-    Bytef *dest;
-    uLongf *destLen;
-    const Bytef *source;
-    uLong sourceLen;
-{
-    z_stream stream;
-    int err;
-
-    stream.next_in = (Bytef*)source;
-    stream.avail_in = (uInt)sourceLen;
-    /* Check for source > 64K on 16-bit machine: */
-    if ((uLong)stream.avail_in != sourceLen) return Z_BUF_ERROR;
-
-    stream.next_out = dest;
-    stream.avail_out = (uInt)*destLen;
-    if ((uLong)stream.avail_out != *destLen) return Z_BUF_ERROR;
-
-    stream.zalloc = (alloc_func)0;
-    stream.zfree = (free_func)0;
-
-    err = inflateInit(&stream);
-    if (err != Z_OK) return err;
-
-    err = inflate(&stream, Z_FINISH);
-    if (err != Z_STREAM_END) {
-        inflateEnd(&stream);
-        if (err == Z_NEED_DICT || (err == Z_BUF_ERROR && stream.avail_in == 0))
-            return Z_DATA_ERROR;
-        return err;
-    }
-    *destLen = stream.total_out;
-
-    err = inflateEnd(&stream);
-    return err;
-}
diff --git a/surface/src/3rdparty/opennurbs/zlib.cmake b/surface/src/3rdparty/opennurbs/zlib.cmake
new file mode 100644 (file)
index 0000000..d730f22
--- /dev/null
@@ -0,0 +1,26 @@
+set(ZLIB_INCLUDES
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/crc32.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/deflate.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffast.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffixed.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inflate.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inftrees.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/trees.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zconf.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zlib.h
+    include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zutil.h
+)
+
+set(ZLIB_SOURCES
+    src/3rdparty/opennurbs/adler32.c
+    src/3rdparty/opennurbs/compress.c
+    src/3rdparty/opennurbs/crc32.c
+    src/3rdparty/opennurbs/deflate.c
+    src/3rdparty/opennurbs/infback.c
+    src/3rdparty/opennurbs/inffast.c
+    src/3rdparty/opennurbs/inflate.c
+    src/3rdparty/opennurbs/inftrees.c
+    src/3rdparty/opennurbs/trees.c
+    src/3rdparty/opennurbs/uncompr.c
+    src/3rdparty/opennurbs/zutil.c
+)
diff --git a/surface/src/3rdparty/opennurbs/zutil.c b/surface/src/3rdparty/opennurbs/zutil.c
deleted file mode 100644 (file)
index 8067497..0000000
+++ /dev/null
@@ -1,318 +0,0 @@
-/* zutil.c -- target dependent utility functions for the compression library
- * Copyright (C) 1995-2005 Jean-loup Gailly.
- * For conditions of distribution and use, see copyright notice in zlib.h
- */
-
-/* @(#) $Id$ */
-
-#include "pcl/surface/3rdparty/opennurbs/zutil.h"
-
-#ifndef NO_DUMMY_DECL
-struct internal_state      {int dummy;}; /* for buggy compilers */
-#endif
-
-const char * const z_errmsg[10] = {
-"need dictionary",     /* Z_NEED_DICT       2  */
-"stream end",          /* Z_STREAM_END      1  */
-"",                    /* Z_OK              0  */
-"file error",          /* Z_ERRNO         (-1) */
-"stream error",        /* Z_STREAM_ERROR  (-2) */
-"data error",          /* Z_DATA_ERROR    (-3) */
-"insufficient memory", /* Z_MEM_ERROR     (-4) */
-"buffer error",        /* Z_BUF_ERROR     (-5) */
-"incompatible version",/* Z_VERSION_ERROR (-6) */
-""};
-
-
-const char * ZEXPORT zlibVersion()
-{
-    return ZLIB_VERSION;
-}
-
-uLong ZEXPORT zlibCompileFlags()
-{
-    uLong flags;
-
-    flags = 0;
-    switch (sizeof(uInt)) {
-    case 2:     break;
-    case 4:     flags += 1;     break;
-    case 8:     flags += 2;     break;
-    default:    flags += 3;
-    }
-    switch (sizeof(uLong)) {
-    case 2:     break;
-    case 4:     flags += 1 << 2;        break;
-    case 8:     flags += 2 << 2;        break;
-    default:    flags += 3 << 2;
-    }
-    switch (sizeof(voidpf)) {
-    case 2:     break;
-    case 4:     flags += 1 << 4;        break;
-    case 8:     flags += 2 << 4;        break;
-    default:    flags += 3 << 4;
-    }
-    switch (sizeof(z_off_t)) {
-    case 2:     break;
-    case 4:     flags += 1 << 6;        break;
-    case 8:     flags += 2 << 6;        break;
-    default:    flags += 3 << 6;
-    }
-#ifdef DEBUG
-    flags += 1 << 8;
-#endif
-#if defined(ASMV) || defined(ASMINF)
-    flags += 1 << 9;
-#endif
-#ifdef ZLIB_WINAPI
-    flags += 1 << 10;
-#endif
-#ifdef BUILDFIXED
-    flags += 1 << 12;
-#endif
-#ifdef DYNAMIC_CRC_TABLE
-    flags += 1 << 13;
-#endif
-#ifdef NO_GZCOMPRESS
-    flags += 1L << 16;
-#endif
-#ifdef NO_GZIP
-    flags += 1L << 17;
-#endif
-#ifdef PKZIP_BUG_WORKAROUND
-    flags += 1L << 20;
-#endif
-#ifdef FASTEST
-    flags += 1L << 21;
-#endif
-#ifdef STDC
-#  ifdef NO_vsnprintf
-        flags += 1L << 25;
-#    ifdef HAS_vsprintf_void
-        flags += 1L << 26;
-#    endif
-#  else
-#    ifdef HAS_vsnprintf_void
-        flags += 1L << 26;
-#    endif
-#  endif
-#else
-        flags += 1L << 24;
-#  ifdef NO_snprintf
-        flags += 1L << 25;
-#    ifdef HAS_sprintf_void
-        flags += 1L << 26;
-#    endif
-#  else
-#    ifdef HAS_snprintf_void
-        flags += 1L << 26;
-#    endif
-#  endif
-#endif
-    return flags;
-}
-
-#ifdef DEBUG
-
-#  ifndef verbose
-#    define verbose 0
-#  endif
-int z_verbose = verbose;
-
-void z_error (m)
-    char *m;
-{
-    fprintf(stderr, "%s\n", m);
-    exit(1);
-}
-#endif
-
-/* exported to allow conversion of error code to string for compress() and
- * uncompress()
- */
-const char * ZEXPORT zError(err)
-    int err;
-{
-    return ERR_MSG(err);
-}
-
-#if defined(_WIN32_WCE)
-    /* The Microsoft C Run-Time Library for Windows CE doesn't have
-     * errno.  We define it as a global variable to simplify porting.
-     * Its value is always 0 and should not be used.
-     */
-    int errno = 0;
-#endif
-
-#ifndef HAVE_MEMCPY
-
-void zmemcpy(dest, source, len)
-    Bytef* dest;
-    const Bytef* source;
-    uInt  len;
-{
-    if (len == 0) return;
-    do {
-        *dest++ = *source++; /* ??? to be unrolled */
-    } while (--len != 0);
-}
-
-int zmemcmp(s1, s2, len)
-    const Bytef* s1;
-    const Bytef* s2;
-    uInt  len;
-{
-    uInt j;
-
-    for (j = 0; j < len; j++) {
-        if (s1[j] != s2[j]) return 2*(s1[j] > s2[j])-1;
-    }
-    return 0;
-}
-
-void zmemzero(dest, len)
-    Bytef* dest;
-    uInt  len;
-{
-    if (len == 0) return;
-    do {
-        *dest++ = 0;  /* ??? to be unrolled */
-    } while (--len != 0);
-}
-#endif
-
-
-#ifdef SYS16BIT
-
-#ifdef __TURBOC__
-/* Turbo C in 16-bit mode */
-
-#  define MY_ZCALLOC
-
-/* Turbo C malloc() does not allow dynamic allocation of 64K bytes
- * and farmalloc(64K) returns a pointer with an offset of 8, so we
- * must fix the pointer. Warning: the pointer must be put back to its
- * original form in order to free it, use zcfree().
- */
-
-#define MAX_PTR 10
-/* 10*64K = 640K */
-
-local int next_ptr = 0;
-
-typedef struct ptr_table_s {
-    voidpf org_ptr;
-    voidpf new_ptr;
-} ptr_table;
-
-local ptr_table table[MAX_PTR];
-/* This table is used to remember the original form of pointers
- * to large buffers (64K). Such pointers are normalized with a zero offset.
- * Since MSDOS is not a preemptive multitasking OS, this table is not
- * protected from concurrent access. This hack doesn't work anyway on
- * a protected system like OS/2. Use Microsoft C instead.
- */
-
-voidpf zcalloc (voidpf opaque, unsigned items, unsigned size)
-{
-    voidpf buf = opaque; /* just to make some compilers happy */
-    ulg bsize = (ulg)items*size;
-
-    /* If we allocate less than 65520 bytes, we assume that farmalloc
-     * will return a usable pointer which doesn't have to be normalized.
-     */
-    if (bsize < 65520L) {
-        buf = farmalloc(bsize);
-        if (*(ush*)&buf != 0) return buf;
-    } else {
-        buf = farmalloc(bsize + 16L);
-    }
-    if (buf == 0 || next_ptr >= MAX_PTR) return 0;
-    table[next_ptr].org_ptr = buf;
-
-    /* Normalize the pointer to seg:0 */
-    *((ush*)&buf+1) += ((ush)((uch*)buf-0) + 15) >> 4;
-    *(ush*)&buf = 0;
-    table[next_ptr++].new_ptr = buf;
-    return buf;
-}
-
-void  zcfree (voidpf opaque, voidpf ptr)
-{
-    int n;
-    if (*(ush*)&ptr != 0) { /* object < 64K */
-        farfree(ptr);
-        return;
-    }
-    /* Find the original pointer */
-    for (n = 0; n < next_ptr; n++) {
-        if (ptr != table[n].new_ptr) continue;
-
-        farfree(table[n].org_ptr);
-        while (++n < next_ptr) {
-            table[n-1] = table[n];
-        }
-        next_ptr--;
-        return;
-    }
-    ptr = opaque; /* just to make some compilers happy */
-    Assert(0, "zcfree: ptr not found");
-}
-
-#endif /* __TURBOC__ */
-
-
-#ifdef M_I86
-/* Microsoft C in 16-bit mode */
-
-#  define MY_ZCALLOC
-
-#if (!defined(_MSC_VER) || (_MSC_VER <= 600))
-#  define _halloc  halloc
-#  define _hfree   hfree
-#endif
-
-voidpf zcalloc (voidpf opaque, unsigned items, unsigned size)
-{
-    if (opaque) opaque = 0; /* to make compiler happy */
-    return _halloc((int)items, size);
-}
-
-void  zcfree (voidpf opaque, voidpf ptr)
-{
-    if (opaque) opaque = 0; /* to make compiler happy */
-    _hfree(ptr);
-}
-
-#endif /* M_I86 */
-
-#endif /* SYS16BIT */
-
-
-#ifndef MY_ZCALLOC /* Any system without a special alloc function */
-
-#ifndef STDC
-extern voidp  malloc OF((uInt size));
-extern voidp  calloc OF((uInt items, uInt size));
-extern void   free   OF((voidpf ptr));
-#endif
-
-voidpf zcalloc (opaque, items, size)
-    voidpf opaque;
-    unsigned items;
-    unsigned size;
-{
-    if (opaque) items += size - size; /* make compiler happy */
-    return sizeof(uInt) > 2 ? (voidpf)malloc(items * size) :
-                              (voidpf)calloc(items, size);
-}
-
-void  zcfree (opaque, ptr)
-    voidpf opaque;
-    voidpf ptr;
-{
-    free(ptr);
-    if (opaque) return; /* make compiler happy */
-}
-
-#endif /* MY_ZCALLOC */
index 7c19a76c7e81734067d82871e1bafcc5fed390fb..922d5a3963843eb15ddb1ade0a13dec656383530 100644 (file)
@@ -44,7 +44,7 @@ BSplineElements<1>::upSample(BSplineElements<1>& high) const
 {
   high.resize(size() * 2);
   high.assign(high.size(), BSplineElementCoefficients<1>());
-  for (int i = 0; i < int(size()); i++) {
+  for (int i = 0; i < static_cast<int>(size()); i++) {
     high[2 * i + 0][0] += 1 * (*this)[i][0];
     high[2 * i + 0][1] += 0 * (*this)[i][0];
     high[2 * i + 1][0] += 2 * (*this)[i][0];
@@ -71,7 +71,7 @@ BSplineElements<2>::upSample(BSplineElements<2>& high) const
 
   high.resize(size() * 2);
   high.assign(high.size(), BSplineElementCoefficients<2>());
-  for (int i = 0; i < int(size()); i++) {
+  for (int i = 0; i < static_cast<int>(size()); i++) {
     high[2 * i + 0][0] += 1 * (*this)[i][0];
     high[2 * i + 0][1] += 0 * (*this)[i][0];
     high[2 * i + 0][2] += 0 * (*this)[i][0];
index 75c97caf2339cfc591139a323cd09aef6ecd3b23..dda5573fc7880ccd5f91ef393e4ec4447064490b 100644 (file)
@@ -45,19 +45,19 @@ namespace pcl
     void CoredVectorMeshData::resetIterator ( ) { oocPointIndex = polygonIndex = 0; }
     int CoredVectorMeshData::addOutOfCorePoint(const Point3D<float>& p){
       oocPoints.push_back(p);
-      return int(oocPoints.size())-1;
+      return static_cast<int>(oocPoints.size())-1;
     }
     int CoredVectorMeshData::addPolygon( const std::vector< CoredVertexIndex >& vertices )
     {
       std::vector< int > polygon( vertices.size() );
-      for( int i=0 ; i<int(vertices.size()) ; i++ )
+      for( int i=0 ; i<static_cast<int>(vertices.size()) ; i++ )
         if( vertices[i].inCore ) polygon[i] =  vertices[i].idx;
         else                     polygon[i] = -vertices[i].idx-1;
       polygons.push_back( polygon );
-      return int( polygons.size() )-1;
+      return static_cast<int>( polygons.size() )-1;
     }
     int CoredVectorMeshData::nextOutOfCorePoint(Point3D<float>& p){
-      if(oocPointIndex<int(oocPoints.size())){
+      if(oocPointIndex<static_cast<int>(oocPoints.size())){
         p=oocPoints[oocPointIndex++];
         return 1;
       }
@@ -65,19 +65,19 @@ namespace pcl
     }
     int CoredVectorMeshData::nextPolygon( std::vector< CoredVertexIndex >& vertices )
     {
-      if( polygonIndex<int( polygons.size() ) )
+      if( polygonIndex<static_cast<int>( polygons.size() ) )
       {
         std::vector< int >& polygon = polygons[ polygonIndex++ ];
         vertices.resize( polygon.size() );
-        for( int i=0 ; i<int(polygon.size()) ; i++ )
+        for( int i=0 ; i<static_cast<int>(polygon.size()) ; i++ )
           if( polygon[i]<0 ) vertices[i].idx = -polygon[i]-1 , vertices[i].inCore = false;
           else               vertices[i].idx =  polygon[i]   , vertices[i].inCore = true;
         return 1;
       }
       else return 0;
     }
-    int CoredVectorMeshData::outOfCorePointCount(){return int(oocPoints.size());}
-    int CoredVectorMeshData::polygonCount( ) { return int( polygons.size() ); }
+    int CoredVectorMeshData::outOfCorePointCount(){return static_cast<int>(oocPoints.size());}
+    int CoredVectorMeshData::polygonCount( ) { return static_cast<int>( polygons.size() ); }
 
     /////////////////////////
     // CoredVectorMeshData //
@@ -87,20 +87,20 @@ namespace pcl
     int CoredVectorMeshData2::addOutOfCorePoint( const CoredMeshData2::Vertex& v )
     {
       oocPoints.push_back( v );
-      return int(oocPoints.size())-1;
+      return static_cast<int>(oocPoints.size())-1;
     }
     int CoredVectorMeshData2::addPolygon( const std::vector< CoredVertexIndex >& vertices )
     {
       std::vector< int > polygon( vertices.size() );
-      for( int i=0 ; i<int(vertices.size()) ; i++ )
+      for( int i=0 ; i<static_cast<int>(vertices.size()) ; i++ )
         if( vertices[i].inCore ) polygon[i] =  vertices[i].idx;
         else                     polygon[i] = -vertices[i].idx-1;
       polygons.push_back( polygon );
-      return int( polygons.size() )-1;
+      return static_cast<int>( polygons.size() )-1;
     }
     int CoredVectorMeshData2::nextOutOfCorePoint( CoredMeshData2::Vertex& v )
     {
-      if(oocPointIndex<int(oocPoints.size()))
+      if(oocPointIndex<static_cast<int>(oocPoints.size()))
       {
         v = oocPoints[oocPointIndex++];
         return 1;
@@ -109,19 +109,19 @@ namespace pcl
     }
     int CoredVectorMeshData2::nextPolygon( std::vector< CoredVertexIndex >& vertices )
     {
-      if( polygonIndex<int( polygons.size() ) )
+      if( polygonIndex<static_cast<int>( polygons.size() ) )
       {
         std::vector< int >& polygon = polygons[ polygonIndex++ ];
         vertices.resize( polygon.size() );
-        for( int i=0 ; i<int(polygon.size()) ; i++ )
+        for( int i=0 ; i<static_cast<int>(polygon.size()) ; i++ )
           if( polygon[i]<0 ) vertices[i].idx = -polygon[i]-1 , vertices[i].inCore = false;
           else               vertices[i].idx =  polygon[i]   , vertices[i].inCore = true;
         return 1;
       }
       else return 0;
     }
-    int CoredVectorMeshData2::outOfCorePointCount(){return int(oocPoints.size());}
-    int CoredVectorMeshData2::polygonCount( ) { return int( polygons.size() ); }
+    int CoredVectorMeshData2::outOfCorePointCount(){return static_cast<int>(oocPoints.size());}
+    int CoredVectorMeshData2::polygonCount( ) { return static_cast<int>( polygons.size() ); }
 
   }
 }
index ba2fd655300517321e7e02e41f15c8ef1d77c9ed..c948f4d19e1e31d3c538ab55f98fcbbffbb11451 100644 (file)
@@ -80,6 +80,15 @@ pcl::MLSResult::calculatePrincipalCurvatures (const double u, const double v) co
   PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal))
                                               ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal)))
 #else
-  PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, (PCL_XYZ_POINT_TYPES)(PCL_XYZ_POINT_TYPES))
+  // PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, (PCL_XYZ_POINT_TYPES)(PCL_XYZ_POINT_TYPES))
+  // All instantiations that are available with PCL_ONLY_CORE_POINT_TYPES, plus instantiations for all XYZ types where PointInT and PointOutT are the same
+  #define PCL_INSTANTIATE_MovingLeastSquaresSameInAndOut(T) template class PCL_EXPORTS pcl::MovingLeastSquares<T,T>;
+  PCL_INSTANTIATE(MovingLeastSquaresSameInAndOut, PCL_XYZ_POINT_TYPES)
+  PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZ))((pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal)))
+  PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZI))((pcl::PointXYZ)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal)))
+  PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZRGB))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal)))
+  PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZRGBA))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBNormal)(pcl::PointNormal)))
+  PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZRGBNormal))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointNormal)))
+  PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointNormal))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)))
 #endif
 #endif    // PCL_NO_PRECOMPILE
index 0c28bf60fcbb75e619153dfe34a2af90ec677e81..9ed63491673c471f20a6e9af4923bf2786b36c86 100644 (file)
@@ -136,7 +136,7 @@ NurbsSolve::solve ()
 {
   //  m_xeig = m_Keig.colPivHouseholderQr().solve(m_feig);
   //  Eigen::MatrixXd x = A.householderQr().solve(b);
-  m_xeig = m_Keig.jacobiSvd (Eigen::ComputeThinU | Eigen::ComputeThinV).solve (m_feig);
+  m_xeig = m_Keig.completeOrthogonalDecomposition().solve (m_feig);
 
   return true;
 }
index 49bb6b511b16fc389d762a7c78c199e93a1f3b20..10433490aef92820ce21f3738e837335782ad888 100644 (file)
@@ -177,7 +177,7 @@ SequentialFitter::project (const Eigen::Vector3d &pt)
     pr (0) = -pr (0);
     pr (1) = -pr (1);
   }
-  return Eigen::Vector2d (pr (0), pr (1));
+  return {pr(0), pr(1)};
 }
 
 bool
@@ -493,7 +493,6 @@ SequentialFitter::grow (float max_dist, float max_angle, unsigned min_length, un
   }
 
   float angle = std::cos (max_angle);
-  unsigned bnd_moved (0);
 
   for (unsigned i = 0; i < num_bnd; i++)
   {
@@ -584,7 +583,6 @@ SequentialFitter::grow (float max_dist, float max_angle, unsigned min_length, un
       this->m_data.boundary[i] (0) = point.x;
       this->m_data.boundary[i] (1) = point.y;
       this->m_data.boundary[i] (2) = point.z;
-      bnd_moved++;
     }
 
   } // i
index 2277ba1a6a389c1a3cf3cb99b6436ce91da6bfa4..c271b5eaa63b54d4153670aad8960fd1e383d73e 100644 (file)
 #include <vtkQuadricDecimation.h>
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-pcl::MeshQuadricDecimationVTK::MeshQuadricDecimationVTK ()
-  : target_reduction_factor_ (0.5f)
-{
-}
+pcl::MeshQuadricDecimationVTK::MeshQuadricDecimationVTK () = default;
 
 
 //////////////////////////////////////////////////////////////////////////////////////////////
index 5ff489a9803d9d441f41bc186841ccd01ca1c12e..6b78214c08ce7e1e6aa5c57004d12b4e1afc5771 100644 (file)
 
 
 //////////////////////////////////////////////////////////////////////////////////////////////
-pcl::MeshSubdivisionVTK::MeshSubdivisionVTK ()
-  : filter_type_ (LINEAR)
-{
-}
+pcl::MeshSubdivisionVTK::MeshSubdivisionVTK () = default;
 
 
 //////////////////////////////////////////////////////////////////////////////////////////////
index ae85bf3a86cf00056dfbc7ef238a45853a5f5bff..3bcf78a35fed426edd628c11bdbd84d15d19eda2 100644 (file)
@@ -212,7 +212,7 @@ pcl::VTKUtils::mesh2vtk (const pcl::PolygonMesh& mesh, vtkSmartPointer<vtkPolyDa
     Eigen::Array4i xyz_offset (mesh.cloud.fields[idx_x].offset, mesh.cloud.fields[idx_y].offset, mesh.cloud.fields[idx_z].offset, 0);
     for (vtkIdType cp = 0; cp < nr_points; ++cp, xyz_offset += mesh.cloud.point_step)
     {
-      memcpy(&pt[0], &mesh.cloud.data[xyz_offset[0]], sizeof(float));
+      memcpy(&pt[0], &mesh.cloud.data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer)
       memcpy(&pt[1], &mesh.cloud.data[xyz_offset[1]], sizeof(float));
       memcpy(&pt[2], &mesh.cloud.data[xyz_offset[2]], sizeof(float));
       vtk_mesh_points->InsertPoint(cp, pt[0], pt[1], pt[2]);
index a87782a83d2808f1d88dbb7a4ab57a8c5679c521..93e3b5a370c84cc56ed31d07ad277401cd3681df 100644 (file)
@@ -837,6 +837,140 @@ TEST (PCL, computeMeanAndCovariance)
   EXPECT_EQ (covariance_matrix (2, 2), 1);
 }
 
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+TEST (PCL, computeCentroidAndOBB)
+{
+  PointCloud<PointXYZ> cloud;
+  PointXYZ point;
+  Indices indices;
+  Eigen::Vector3f centroid = Eigen::Vector3f::Random();
+  Eigen::Vector3f major_axis;
+  Eigen::Vector3f middle_axis;
+  Eigen::Vector3f minor_axis;
+  Eigen::Matrix<float, 3, 1> obb_position;
+  Eigen::Matrix<float, 3, 1> obb_dimensions;
+  Eigen::Matrix3f obb_rotational_matrix= Eigen::Matrix3f::Random();
+
+  const Eigen::Vector3f old_centroid = centroid;
+  const Eigen::Matrix3f old_obb_rotational_matrix= obb_rotational_matrix;
+
+  // test empty cloud which is dense
+  cloud.is_dense = true;
+  EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0);
+  EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged
+  EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged
+
+  // test empty cloud non_dense
+  cloud.is_dense = false;
+  EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0);
+  EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged
+  EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged
+
+  // test non-empty cloud non_dense with no valid points
+  point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
+  cloud.push_back (point);
+  EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0);
+  EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged
+  EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged
+
+  // test non-empty cloud non_dense with no valid points
+  point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
+  cloud.push_back (point);
+  indices.push_back (1);
+  EXPECT_EQ (computeCentroidAndOBB (cloud, indices, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0);
+  EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged
+  EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged
+
+  cloud.clear ();
+  indices.clear ();
+  // -1 -1 -1 / -1 -1 1 / -1 1 -1 / -1 1 1 / 1 -1 -1 / 1 -1 1 / 1 1 -1 / 1 1 1
+  for (point.x = -1; point.x < 2; point.x += 2)
+  {
+    for (point.y = -1; point.y < 2; point.y += 2)
+    {
+      for (point.z = -1; point.z < 2; point.z += 2)
+      {
+        cloud.push_back (point);
+      }
+    }
+  }
+  cloud.is_dense = true;
+
+  // eight points with (0, 0, 0) as centroid
+
+  centroid [0] = -100;
+  centroid [1] = -101;
+  centroid [2] = -102;
+  EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 8);
+  EXPECT_EQ (centroid [0], 0);
+  EXPECT_EQ (centroid [1], 0);
+  EXPECT_EQ (centroid [2], 0);
+  EXPECT_NEAR (obb_position(0), 0, 0.01);
+  EXPECT_NEAR (obb_position(1), 0, 0.01);
+  EXPECT_NEAR (obb_position(2), 0, 0.01);
+  EXPECT_NEAR (obb_dimensions(0), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(1), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(2), 2, 0.01);
+
+
+  indices.resize (4); // only positive y values
+  indices [0] = 2;
+  indices [1] = 3;
+  indices [2] = 6;
+  indices [3] = 7;
+  centroid [0] = -100;
+  centroid [1] = -101;
+  centroid [2] = -102;
+
+  EXPECT_EQ (computeCentroidAndOBB (cloud, indices, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 4);
+  EXPECT_EQ (centroid [0], 0);
+  EXPECT_NEAR (centroid [1], 1, 0.001);
+  EXPECT_EQ (centroid [2], 0);
+  EXPECT_NEAR (obb_position(0), 0, 0.01);
+  EXPECT_NEAR (obb_position(1), 1, 0.01);
+  EXPECT_NEAR (obb_position(2), 0, 0.01);
+  EXPECT_NEAR (obb_dimensions(0), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(1), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(2), 0, 0.01);
+
+
+  point.x = point.y = point.z = std::numeric_limits<float>::quiet_NaN ();
+  cloud.push_back (point);
+  cloud.is_dense = false;
+  centroid [0] = -100;
+  centroid [1] = -101;
+  centroid [2] = -102;
+  EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 8);
+  EXPECT_EQ (centroid [0], 0);
+  EXPECT_EQ (centroid [1], 0);
+  EXPECT_EQ (centroid [2], 0);
+  EXPECT_NEAR (obb_position(0), 0, 0.01);
+  EXPECT_NEAR (obb_position(1), 0, 0.01);
+  EXPECT_NEAR (obb_position(2), 0, 0.01);
+  EXPECT_NEAR (obb_dimensions(0), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(1), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(2), 2, 0.01);
+
+
+  indices.push_back (8); // add the NaN
+  centroid [0] = -100;
+  centroid [1] = -101;
+  centroid [2] = -102;
+
+  EXPECT_EQ (computeCentroidAndOBB (cloud, indices, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 4);
+  EXPECT_EQ (centroid [0], 0);
+  EXPECT_NEAR (centroid [1], 1, 0.001);
+  EXPECT_EQ (centroid [2], 0);
+  EXPECT_NEAR (obb_position(0), 0, 0.01);
+  EXPECT_NEAR (obb_position(1), 1, 0.01);
+  EXPECT_NEAR (obb_position(2), 0, 0.01);
+  EXPECT_NEAR (obb_dimensions(0), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(1), 2, 0.01);
+  EXPECT_NEAR (obb_dimensions(2), 0, 0.01);
+
+}
+
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST (PCL, CentroidPoint)
 {
index 1ecebc9d51c21711c7c9ca901fb5366ed589a374..6bcc4ae1ae882d23734f4b2c759e9086fc2f0039 100644 (file)
@@ -65,14 +65,14 @@ TEST (PCL, InverseGeneral3x3f)
   CMatrix c_inverse = CMatrix::Zero ();
   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
-  const Scalar epsilon = 1e-5f;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 1e-5f;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
   {
     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
-      r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng));
+      r_matrix.coeffRef (elIdx) = static_cast<Scalar>(rand_double (rng));
 
     c_matrix = r_matrix;
 
@@ -124,15 +124,15 @@ TEST (PCL, InverseGeneral3x3d)
   CMatrix c_inverse = CMatrix::Zero ();
   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
-  const Scalar epsilon = 1e-13;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 1e-13;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
   {
     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
     {
-      r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng));
+      r_matrix.coeffRef (elIdx) = static_cast<Scalar>(rand_double (rng));
     }
     c_matrix = r_matrix;
     // test row-major -> row-major
@@ -183,14 +183,14 @@ TEST (PCL, InverseSymmetric3x3f)
   CMatrix c_inverse = CMatrix::Zero ();
   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
-  const Scalar epsilon = 1e-5f;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 1e-5f;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
   {
     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
-      r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng));
+      r_matrix.coeffRef (elIdx) = static_cast<Scalar>(rand_double (rng));
 
     r_matrix.coeffRef (3) = r_matrix.coeffRef (1);
     r_matrix.coeffRef (6) = r_matrix.coeffRef (2);
@@ -248,14 +248,14 @@ TEST (PCL, InverseSymmetric3x3d)
   CMatrix c_inverse = CMatrix::Zero ();
   Eigen::Matrix<Scalar, 3, 3> result = Eigen::Matrix<Scalar, 3, 3>::Zero ();
   Eigen::Matrix<Scalar, 3, 3> error = Eigen::Matrix<Scalar, 3, 3>::Zero ();
-  const Scalar epsilon = 1e-13;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 1e-13;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
   {
     for (unsigned elIdx = 0; elIdx < 9; ++elIdx)
-      r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng));
+      r_matrix.coeffRef (elIdx) = static_cast<Scalar>(rand_double (rng));
 
     r_matrix.coeffRef (3) = r_matrix.coeffRef (1);
     r_matrix.coeffRef (6) = r_matrix.coeffRef (2);
@@ -314,14 +314,14 @@ TEST (PCL, Inverse2x2f)
   CMatrix c_inverse = CMatrix::Zero ();
   Eigen::Matrix<Scalar, 2, 2> result = Eigen::Matrix<Scalar, 2, 2>::Zero ();
   Eigen::Matrix<Scalar, 2, 2> error = Eigen::Matrix<Scalar, 2, 2>::Zero ();
-  const Scalar epsilon = 1e-6f;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 1e-6f;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
   {
     for (unsigned elIdx = 0; elIdx < 4; ++elIdx)
-      r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng));
+      r_matrix.coeffRef (elIdx) = static_cast<Scalar>(rand_double (rng));
 
     c_matrix = r_matrix;
     // test row-major -> row-major
@@ -372,14 +372,14 @@ TEST (PCL, Inverse2x2d)
   CMatrix c_inverse = CMatrix::Zero ();
   Eigen::Matrix<Scalar, 2, 2> result;
   Eigen::Matrix<Scalar, 2, 2> error;
-  const Scalar epsilon = 1e-15;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 1e-15;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
   {
     for (unsigned elIdx = 0; elIdx < 4; ++elIdx)
-      r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng));
+      r_matrix.coeffRef (elIdx) = static_cast<Scalar>(rand_double (rng));
 
     c_matrix = r_matrix;
     // test row-major -> row-major
@@ -425,8 +425,8 @@ inline void generateSymPosMatrix2x2 (Matrix& matrix)
 
   unsigned test_case = rand_uint (rng) % 10;
 
-  Scalar val1 = Scalar (rand_double (rng));
-  Scalar val2 = Scalar (rand_double (rng));
+  Scalar val1 = static_cast<Scalar> (rand_double (rng));
+  Scalar val2 = static_cast<Scalar> (rand_double (rng));
 
   // 10% of test cases include equal eigenvalues
   if (test_case == 0)
@@ -446,8 +446,8 @@ inline void generateSymPosMatrix2x2 (Matrix& matrix)
   {
     do
     {
-      eigenvectors.col (0)[0] = Scalar (rand_double (rng));
-      eigenvectors.col (0)[1] = Scalar (rand_double (rng));
+      eigenvectors.col (0)[0] = static_cast<Scalar> (rand_double (rng));
+      eigenvectors.col (0)[1] = static_cast<Scalar> (rand_double (rng));
       sqrNorm = eigenvectors.col (0).squaredNorm ();
     } while (sqrNorm == 0);
     eigenvectors.col (0) /= sqrt (sqrNorm);
@@ -479,8 +479,8 @@ TEST (PCL, eigen22d)
   Eigen::Matrix<Scalar, 2, 2> c_result;
   Eigen::Matrix<Scalar, 2, 2> c_error;
 
-  const Scalar epsilon = 1.25e-14;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 1.25e-14;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
@@ -537,8 +537,8 @@ TEST (PCL, eigen22f)
   Eigen::Matrix<Scalar, 2, 2> c_result;
   Eigen::Matrix<Scalar, 2, 2> c_error;
 
-  const Scalar epsilon = 3.1e-5f;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 3.1e-5f;
+  constexpr unsigned iterations = 1000000;
 
   // test floating point row-major : row-major
   for (unsigned idx = 0; idx < iterations; ++idx)
@@ -592,9 +592,9 @@ inline void generateSymPosMatrix3x3 (Matrix& matrix)
 
   unsigned test_case = rand_uint (rng);
 
-  Scalar val1 = Scalar (rand_double (rng));
-  Scalar val2 = Scalar (rand_double (rng));
-  Scalar val3 = Scalar (rand_double (rng));
+  Scalar val1 = static_cast<Scalar> (rand_double (rng));
+  Scalar val2 = static_cast<Scalar> (rand_double (rng));
+  Scalar val3 = static_cast<Scalar> (rand_double (rng));
 
   // 1%: all three values are equal and non-zero
   if (test_case == 0)
@@ -635,12 +635,12 @@ inline void generateSymPosMatrix3x3 (Matrix& matrix)
 
   do
   {
-    eigenvectors.col (0)[0] = Scalar (rand_double (rng));
-    eigenvectors.col (0)[1] = Scalar (rand_double (rng));
-    eigenvectors.col (0)[2] = Scalar (rand_double (rng));
-    eigenvectors.col (1)[0] = Scalar (rand_double (rng));
-    eigenvectors.col (1)[1] = Scalar (rand_double (rng));
-    eigenvectors.col (1)[2] = Scalar (rand_double (rng));
+    eigenvectors.col (0)[0] = static_cast<Scalar> (rand_double (rng));
+    eigenvectors.col (0)[1] = static_cast<Scalar> (rand_double (rng));
+    eigenvectors.col (0)[2] = static_cast<Scalar> (rand_double (rng));
+    eigenvectors.col (1)[0] = static_cast<Scalar> (rand_double (rng));
+    eigenvectors.col (1)[1] = static_cast<Scalar> (rand_double (rng));
+    eigenvectors.col (1)[2] = static_cast<Scalar> (rand_double (rng));
     eigenvectors.col (2) = eigenvectors.col (0).cross (eigenvectors.col (1));
 
     sqrNorm = eigenvectors.col (2).squaredNorm ();
@@ -676,8 +676,8 @@ TEST (PCL, eigen33d)
   Eigen::Matrix<Scalar, 3, 3> c_result;
   Eigen::Matrix<Scalar, 3, 3> c_error;
 
-  const Scalar epsilon = 2e-5;
-  const unsigned iterations = 1000000;
+  constexpr Scalar epsilon = 2e-5;
+  constexpr unsigned iterations = 1000000;
 
   // special case
   r_matrix = Eigen::Matrix<Scalar, 3, 1>(3, 2, 1).asDiagonal();
@@ -751,7 +751,7 @@ TEST (PCL, eigen33f)
   Eigen::Matrix<Scalar, 3, 3> c_result;
   Eigen::Matrix<Scalar, 3, 3> c_error;
 
-  const Scalar epsilon = 1e-3f;
+  constexpr Scalar epsilon = 1e-3f;
   constexpr unsigned iterations = 1000000;
   unsigned r_fail_count = 0;
 
@@ -828,8 +828,8 @@ TEST (PCL, transformLine)
   // Simple rotation
   transformation = Eigen::Affine3f::Identity ();
   transformationd = Eigen::Affine3d::Identity ();
-  transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ());
-  transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ());
+  transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ()));
+  transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ()));
 
   line << 1, 2, 3, 0, 1, 0;
   lined << 1, 2, 3, 0, 1, 0;
@@ -849,9 +849,9 @@ TEST (PCL, transformLine)
   transformationd = Eigen::Affine3d::Identity ();
   transformation.translation() << 25.97, -2.45, 0.48941;
   transformationd.translation() << 25.97, -2.45, 0.48941;
-  transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/5, Eigen::Vector3f::UnitX())
+  transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/5, Eigen::Vector3f::UnitX()))
   * Eigen::AngleAxisf(M_PI/3, Eigen::Vector3f::UnitY());
-  transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/5, Eigen::Vector3d::UnitX())
+  transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/5, Eigen::Vector3d::UnitX()))
   * Eigen::AngleAxisd(M_PI/3, Eigen::Vector3d::UnitY());
 
   line << -1, 9, 3, 1.5, 2.0, 0.2;
@@ -901,8 +901,8 @@ TEST (PCL, transformPlane)
   // Simple rotation
   transformation.translation() << 0, 0, 0;
   transformationd.translation() << 0, 0, 0;
-  transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ());
-  transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ());
+  transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ()));
+  transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ()));
   test << 0, 1, 0, -2;
   tolerance = 1e-6;
 
@@ -925,9 +925,9 @@ TEST (PCL, transformPlane)
   // Random transformation
   transformation.translation() << 12.5, -5.4, 0.1;
   transformationd.translation() << 12.5, -5.4, 0.1;
-  transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/7, Eigen::Vector3f::UnitY())
+  transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/7, Eigen::Vector3f::UnitY()))
   * Eigen::AngleAxisf(M_PI/4, Eigen::Vector3f::UnitZ());
-  transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/7, Eigen::Vector3d::UnitY())
+  transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/7, Eigen::Vector3d::UnitY()))
   * Eigen::AngleAxisd(M_PI/4, Eigen::Vector3d::UnitZ());
   test << 5.35315, 2.89914, 0.196848, -49.2788;
   test /= test.head<3> ().norm ();
@@ -1128,9 +1128,9 @@ TEST (PCL, getTransFromUnitVectors)
 
 TEST (PCL, getTransformation)
 {
-  const float rot_x = 2.8827f;
-  const float rot_y = -0.31190f;
-  const float rot_z = -0.93058f;
+  constexpr float rot_x = 2.8827f;
+  constexpr float rot_y = -0.31190f;
+  constexpr float rot_z = -0.93058f;
 
   Eigen::Affine3f affine;
   pcl::getTransformation (0, 0, 0, rot_x, rot_y, rot_z, affine);
@@ -1142,12 +1142,12 @@ TEST (PCL, getTransformation)
 
 TEST (PCL, getTranslationAndEulerAngles)
 {
-  const float trans_x = 0.1f;
-  const float trans_y = 0.2f;
-  const float trans_z = 0.3f;
-  const float rot_x = 2.8827f;
-  const float rot_y = -0.31190f;
-  const float rot_z = -0.93058f;
+  constexpr float trans_x = 0.1f;
+  constexpr float trans_y = 0.2f;
+  constexpr float trans_z = 0.3f;
+  constexpr float rot_x = 2.8827f;
+  constexpr float rot_y = -0.31190f;
+  constexpr float rot_z = -0.93058f;
 
   Eigen::Affine3f affine;
   pcl::getTransformation (trans_x, trans_y, trans_z, rot_x, rot_y, rot_z, affine);
index efdc8245b7b2cc86afe67ecb1e8f53df9eed3451..e5d742ad74931643192990850b87cacb3a369d51 100644 (file)
@@ -51,29 +51,6 @@ PointXYZRGBA pt_xyz_rgba, pt_xyz_rgba2;
 PointXYZRGB pt_xyz_rgb;
 PointXYZ pt_xyz;
 
-///////////////////////////////////////////////////////////////////////////////////////////
-TEST (PCL, concatenateFields)
-{
-  bool status = isSamePointType<PointXYZ, PointXYZ> ();
-  EXPECT_TRUE (status);
-  status = isSamePointType<PointXYZ, PointXY> ();
-  EXPECT_FALSE (status);
-  status = isSamePointType<PointXY, PointXYZ> ();
-  EXPECT_FALSE (status);
-  status = isSamePointType<PointNormal, PointNormal> ();
-  EXPECT_TRUE (status);
-  status = isSamePointType<PointNormal, PointXYZRGBNormal> ();
-  EXPECT_FALSE (status);
-  status = isSamePointType<PointXYZRGB, PointXYZRGB> ();
-  EXPECT_TRUE (status);
-  
-  // Even though it's the "same" type, rgb != rgba
-  status = isSamePointType<PointXYZRGB, PointXYZRGBA> ();
-  EXPECT_FALSE (status);
-  status = isSamePointType<PointXYZRGBA, PointXYZRGB> ();
-  EXPECT_FALSE (status);
-}
-
 ///////////////////////////////////////////////////////////////////////////////////////////
 TEST (PCL, copyPointCloud)
 {
@@ -153,12 +130,12 @@ TEST (PCL, concatenatePointCloud2)
   pcl::fromPCLPointCloud2 (cloud_out, cloud_all);
 
   EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ());
-  for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i)
+  for (int i = 0; i < static_cast<int>(cloud_xyz_rgba.size ()); ++i)
   {
     EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]);
     EXPECT_RGBA_EQ (cloud_all[i], cloud_xyz_rgba[i]);
   }
-  for (int i = 0; i < int (cloud_xyz_rgba2.size ()); ++i)
+  for (int i = 0; i < static_cast<int>(cloud_xyz_rgba2.size ()); ++i)
   {
     EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgba2[i]);
     EXPECT_RGBA_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgba2[i]);
@@ -175,12 +152,12 @@ TEST (PCL, concatenatePointCloud2)
   pcl::fromPCLPointCloud2 (cloud_out2, cloud_all);
 
   EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ());
-  for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i)
+  for (int i = 0; i < static_cast<int>(cloud_xyz_rgba.size ()); ++i)
   {
     EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]);
     EXPECT_RGBA_EQ (cloud_all[i], cloud_xyz_rgba[i]);
   }
-  for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i)
+  for (int i = 0; i < static_cast<int>(cloud_xyz_rgb.size ()); ++i)
   {
     EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]);
     EXPECT_RGBA_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]);
@@ -209,13 +186,13 @@ TEST (PCL, concatenatePointCloud2)
   pcl::fromPCLPointCloud2 (cloud_out3, cloud_all);
 
   EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgb.size ());
-  for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i)
+  for (int i = 0; i < static_cast<int>(cloud_xyz_rgba.size ()); ++i)
   {
     EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]);
     // Data doesn't get modified
     EXPECT_RGBA_EQ (cloud_all[i], cloud_xyz_rgba[i]);
   }
-  for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i)
+  for (int i = 0; i < static_cast<int>(cloud_xyz_rgb.size ()); ++i)
   {
     EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]);
     EXPECT_RGBA_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]);
index 7fc62e70cb39c3220a997309d7dad428effe7ee7..018ce2797ec9a5ace4174c16cd3a121f81b6a28b 100644 (file)
@@ -67,7 +67,7 @@ TEST(MACROS, expect_near_vectors_macro)
 {
   v1.clear ();
   v2.clear ();
-  const static float epsilon = 1e-5f;
+  constexpr float epsilon = 1e-5f;
   for (std::size_t i = 0; i < 3; i++)
   {
     float val = static_cast<float> (i) * 1.5f;
index 7ec6da1d038cd311f756592bf490fbe4ebb0117f..b529562a84d9d57778109118ece646ea01eca020 100644 (file)
@@ -51,7 +51,7 @@ TEST (PCL, parse_double)
   const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr};
   const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr};
   const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr};
-  const int argc = static_cast<int> (sizeof (argv_1)/sizeof (argv_1[0])) - 1;
+  constexpr int argc = static_cast<int> (sizeof (argv_1)/sizeof (argv_1[0])) - 1;
 
   int index = -1;
   double value = 0;
@@ -79,7 +79,7 @@ TEST (PCL, parse_float)
   const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr};
   const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr};
   const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr};
-  const int argc = static_cast<int> (sizeof (argv_1)/sizeof (argv_1[0])) - 1;
+  constexpr int argc = static_cast<int>(sizeof(argv_1) / sizeof(argv_1[0])) - 1;
 
   int index = -1;
   float value = 0;
@@ -107,7 +107,7 @@ TEST (PCL, parse_longint)
   const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr};
   const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr};
   const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr};
-  const int argc = static_cast<int> (sizeof (argv_1)/sizeof (argv_1[0])) - 1;
+  constexpr int argc = static_cast<int>(sizeof(argv_1) / sizeof(argv_1[0])) - 1;
 
   int index = -1;
   long int value = 0;
@@ -135,7 +135,7 @@ TEST (PCL, parse_unsignedint)
   const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr};
   const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr};
   const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr};
-  const int argc = static_cast<int> (sizeof (argv_1)/sizeof (argv_1[0])) - 1;
+  constexpr int argc = static_cast<int>(sizeof(argv_1) / sizeof(argv_1[0])) - 1;
 
   int index = -1;
   unsigned int value = 53;
@@ -163,7 +163,7 @@ TEST (PCL, parse_int)
   const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr};
   const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr};
   const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr};
-  const int argc = static_cast<int> (sizeof (argv_1)/sizeof (argv_1[0])) - 1;
+  constexpr int argc = static_cast<int>(sizeof(argv_1) / sizeof(argv_1[0])) - 1;
 
   int index = -1;
   int value = 0;
index cb0ee8c5bea53c42eea8ffb8bc9d1c9e956c9d91..ec8425410dbebcd01ee52dfc5a3f46a7aca5fa5d 100644 (file)
@@ -169,8 +169,8 @@ TEST (PCL, lineWithLineIntersection)
   Eigen::Vector4f point_mod_case_2;
   double sqr_mod_case_2 = 1e-1;
 
-  Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (&line_a_mod_2.values[0], line_a_mod_2.values.size ());
-  Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (&line_b_mod_2.values[0], line_b_mod_2.values.size ());
+  Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (line_a_mod_2.values.data(), line_a_mod_2.values.size ());
+  Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (line_b_mod_2.values.data(), line_b_mod_2.values.size ());
 
   Eigen::Vector4f p1_mod, p2_mod;
   lineToLineSegment (coeff1, coeff2, p1_mod, p2_mod);
index d03038ab19250a99c385aabe1f9182b6b00c17c0..f97c1a6807dcdf64ae0f0595f6cb6f945956bc54 100644 (file)
@@ -66,7 +66,7 @@ TEST(PolygonMesh, concatenate_header)
 TEST(PolygonMesh, concatenate_cloud)
 {
     PointCloud<PointXYZ> cloud_template;
-    const std::size_t size = 10 * 480;
+    constexpr std::size_t size = 10 * 480;
 
     cloud_template.width = 10;
     cloud_template.height = 480;
@@ -91,7 +91,7 @@ TEST(PolygonMesh, concatenate_cloud)
 
 TEST(PolygonMesh, concatenate_vertices)
 {
-    const std::size_t size = 15;
+    constexpr std::size_t size = 15;
 
     PolygonMesh test, dummy;
     // The algorithm works regardless of the organization.
index ffb1de669e708e935ce0e94176090b6b27eb7cd6..f1474df076e22b2785de72bf6032ee573dda6cea 100644 (file)
@@ -44,8 +44,8 @@ using namespace pcl;
 using namespace pcl::test;
 
 PointCloud<PointXYZ>::Ptr cloud_ptr (new PointCloud<PointXYZ> (4, 5));
-const std::size_t size = 5 * 4;
-const int amount = 2;
+constexpr std::size_t size = 5 * 4;
+constexpr int amount = 2;
 
 // TEST (PointCloudSpring, vertical)
 // {
index 9b131c0a98638b0372c66866543bd21a1ce54d60..cfac20d67009ed6bfe3705fc0fb94b0f8f5bd5f9 100644 (file)
@@ -61,10 +61,7 @@ class Transforms : public ::testing::Test
 {
  public:
   using Scalar = typename Transform::Scalar;
-
   Transforms ()
-  : ABS_ERROR (std::numeric_limits<Scalar>::epsilon () * 10)
-  , CLOUD_SIZE (100)
   {
     Eigen::Matrix<Scalar, 6, 1> r = Eigen::Matrix<Scalar, 6, 1>::Random ();
     Eigen::Transform<Scalar, 3, Eigen::Affine> transform;
@@ -93,9 +90,8 @@ class Transforms : public ::testing::Test
       indices[i] = i * 2;
   }
 
-  const Scalar ABS_ERROR;
-  const std::size_t CLOUD_SIZE;
-
+  const Scalar ABS_ERROR{std::numeric_limits<Scalar>::epsilon () * 10};
+  const std::size_t CLOUD_SIZE{100};
   Transform tf;
 
   // Random point clouds and their expected transformed versions
@@ -105,7 +101,7 @@ class Transforms : public ::testing::Test
   // Indices, every second point
   Indices indices;
 
-  PCL_MAKE_ALIGNED_OPERATOR_NEW;
+  PCL_MAKE_ALIGNED_OPERATOR_NEW
 };
 
 TYPED_TEST_SUITE (Transforms, TransformTypes);
index c446487472bbb5cb11ccf4e0721ecc782f4602c4..676f92cdd256b082dc11b85525b5244e3d03303e 100644 (file)
@@ -46,7 +46,7 @@ using namespace pcl;
 using namespace pcl::test;
 
 PointCloud<PointXYZ> cloud;
-const std::size_t size = 10 * 480;
+constexpr std::size_t size = 10 * 480;
 
 TEST (PointCloud, size)
 {
index ea23214a76af9a4b7978f934804bc7d5168844e8..d0717a2c6e6cf253a56e7b02addf470a1d4d94d1 100644 (file)
@@ -86,23 +86,23 @@ TEST (PCL, BoundaryEstimation)
 
   // isBoundaryPoint (indices)
   bool pt = false;
-  pt = b.isBoundaryPoint (cloud, 0, indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, 0, indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_FALSE (pt);
-  pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 3, indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 3, indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_FALSE (pt);
-  pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 2, indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 2, indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_FALSE (pt);
-  pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) - 1, indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) - 1, indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_TRUE (pt);
 
   // isBoundaryPoint (points)
-  pt = b.isBoundaryPoint (cloud, cloud[0], indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, cloud[0], indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_FALSE (pt);
-  pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 3], indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 3], indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_FALSE (pt);
-  pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 2], indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 2], indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_FALSE (pt);
-  pt = b.isBoundaryPoint (cloud, cloud[indices.size () - 1], indices, u, v, float (M_PI) / 2.0);
+  pt = b.isBoundaryPoint (cloud, cloud[indices.size () - 1], indices, u, v, static_cast<float>(M_PI) / 2.0);
   EXPECT_TRUE (pt);
 
   // Object
index 93bb31ea55d8244e9ad151d9eeb1ed1b63c924a3..c4405f1725776c4f608dee6abf66b09b010c511b 100644 (file)
@@ -70,8 +70,8 @@ TEST (PCL, BRISK_2D)
 
   //io::savePCDFileBinary ("brisk_keypoints.pcd", *cloud_keypoints);
 
-  const int num_of_keypoints = int (cloud_keypoints->size ());
-  const int num_of_keypoints_gt = int (cloud_keypoints_gt->size ());
+  const int num_of_keypoints = static_cast<int>(cloud_keypoints->size ());
+  const int num_of_keypoints_gt = static_cast<int>(cloud_keypoints_gt->size ());
   EXPECT_EQ (num_of_keypoints_gt, num_of_keypoints);
 
 
@@ -96,8 +96,8 @@ TEST (PCL, BRISK_2D)
   cloud_descriptors.reset (new PointCloud<BRISKSignature512>);
   brisk_descriptor_estimation.compute (*cloud_descriptors);
 
-  const int num_of_descriptors = int (cloud_descriptors->size ());
-  const int num_of_descriptors_gt = int (cloud_descriptors_gt->size ());
+  const int num_of_descriptors = static_cast<int>(cloud_descriptors->size ());
+  const int num_of_descriptors_gt = static_cast<int>(cloud_descriptors_gt->size ());
   EXPECT_EQ (num_of_descriptors_gt, num_of_descriptors);
 
 
@@ -111,7 +111,7 @@ TEST (PCL, BRISK_2D)
     float sqr_dist = 0.0f;
     for (std::size_t index = 0; index < 33; ++index)
     {
-      const float dist = float (descriptor.descriptor[index] - descriptor_gt.descriptor[index]);
+      const float dist = static_cast<float>(descriptor.descriptor[index] - descriptor_gt.descriptor[index]);
       sqr_dist += dist * dist;
     }
 
index 7e9746ca256eb029254b66d7916c18a5d8d3727c..5a60c2d7a94e040d43e8881ce4adfa3f18c058dc 100644 (file)
@@ -62,7 +62,7 @@ TEST (PCL, FLARELocalReferenceFrameEstimation)
   pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal> ());
   pcl::PointCloud<pcl::ReferenceFrame> bunny_LRF;
 
-  const float mesh_res = 0.005f;
+  constexpr float mesh_res = 0.005f;
 
   // Compute normals
   pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
@@ -159,13 +159,13 @@ main (int argc, char** argv)
   tree->setInputCloud (cloud);
 
   //create and set sampled point cloud for computation of X axis
-  const float sampling_perc = 0.2f;
-  const float sampling_incr = 1.0f / sampling_perc;
+  constexpr float sampling_perc = 0.2f;
+  constexpr float sampling_incr = 1.0f / sampling_perc;
 
   sampled_cloud.reset (new pcl::PointCloud<pcl::PointXYZ> ());
 
   pcl::Indices sampled_indices;
-  for (float sa = 0.0f; sa < (float)cloud->size (); sa += sampling_incr)
+  for (float sa = 0.0f; sa < static_cast<float>(cloud->size ()); sa += sampling_incr)
     sampled_indices.push_back (static_cast<int> (sa));
   copyPointCloud (*cloud, sampled_indices, *sampled_cloud);
 
index 0b000cbcabe6d432fc2279e5c8fc61b37f4e7d38..13c1cb77c53869a9dfce5010e8779c02f5aee9b4 100644 (file)
@@ -114,7 +114,7 @@ TEST (PCL, GASDShapeEstimationNoInterp)
     0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
 
   EXPECT_EQ (descriptor.size (), 1);
-  for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i)
+  for (std::size_t i = 0; i < static_cast<std::size_t>(descriptor[0].descriptorSize ()); ++i)
   {
     EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5);
   }
@@ -158,7 +158,7 @@ TEST(PCL, GASDShapeEstimationTrilinearInterp)
     0, 0, 0, 0, 0, 0, 0, 0};
 
   EXPECT_EQ (descriptor.size (), 1);
-  for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i)
+  for (std::size_t i = 0; i < static_cast<std::size_t>(descriptor[0].descriptorSize ()); ++i)
   {
     EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5);
   }
@@ -217,7 +217,7 @@ TEST (PCL, GASDShapeAndColorEstimationNoInterp)
     0, 0, 0, 0, 0, 0, 0, 0};
 
   EXPECT_EQ (descriptor.size (), 1);
-  for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i)
+  for (std::size_t i = 0; i < static_cast<std::size_t>(descriptor[0].descriptorSize ()); ++i)
   {
     EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5);
   }
@@ -304,7 +304,7 @@ TEST(PCL, GASDShapeAndColorEstimationQuadrilinearInterp)
     0, 0, 0, 0, 0, 0, 0, 0};
 
   EXPECT_EQ (descriptor.size (), 1);
-  for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i)
+  for (std::size_t i = 0; i < static_cast<std::size_t>( descriptor[0].descriptorSize ()); ++i)
   {
     EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5);
   }
index 7127c13b0634a6883a455e5185bc1cb2c218ce3b..589b42fb883d549557cb5cc2d9101ebab0f2d310 100644 (file)
@@ -113,7 +113,7 @@ TEST (PCL, IntensityGradientEstimation)
     float gz = (-nz * nx) * tmpx + (-nz * ny) * tmpy + (1 - nz * nz) * tmpz;
 
     // Compare the estimates to the derived values.
-    const float tolerance = 0.11f;
+    constexpr float tolerance = 0.11f;
     EXPECT_NEAR (g_est[0], gx, tolerance);
     EXPECT_NEAR (g_est[1], gy, tolerance);
     EXPECT_NEAR (g_est[2], gz, tolerance);
index 7345032979278f4543c29207e064d213c43f4302..914def1f8cbc3a52af3908a2750edbf5db9dbdaa 100644 (file)
@@ -55,10 +55,10 @@ IntegralImageNormalEstimation<PointXYZ, Normal> ne;
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST(PCL, IntegralImage1D)
 {
-  const unsigned width = 640;
-  const unsigned height = 480;
-  const unsigned max_window_size = 5;
-  const unsigned min_window_size = 1;
+  constexpr unsigned width = 640;
+  constexpr unsigned height = 480;
+  constexpr unsigned max_window_size = 5;
+  constexpr unsigned min_window_size = 1;
   IntegralImage2D<float,1> integral_image1(true); // calculate second order
   IntegralImage2D<float,1> integral_image2(false);// calculate just first order (other if branch)
 
@@ -268,10 +268,10 @@ TEST(PCL, IntegralImage1D)
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST(PCL, IntegralImage3D)
 {
-  const unsigned width = 640;
-  const unsigned height = 480;
-  const unsigned max_window_size = 5;
-  const unsigned min_window_size = 1;
+  constexpr unsigned width = 640;
+  constexpr unsigned height = 480;
+  constexpr unsigned max_window_size = 5;
+  constexpr unsigned min_window_size = 1;
   IntegralImage2D<float, 3> integral_image3(true);
   unsigned element_stride = 4;
   unsigned row_stride = width * element_stride + 1;
index c93f910d8c46e5524971ef82ef74f4fc8b7ab220..558ab31299108a952fc93c1a5f920f25854592fa 100644 (file)
@@ -166,7 +166,7 @@ TEST (PCL, NormalEstimation)
   n.setSearchSurface (surfaceptr);
   EXPECT_EQ (n.getSearchSurface (), surfaceptr);
 
-  // Additional test for searchForNeigbhors
+  // Additional test for searchForNeighbors
   surfaceptr.reset (new PointCloud<PointXYZ>);
   *surfaceptr = *cloudptr;
   surfaceptr->points.resize (640 * 480);
@@ -191,10 +191,10 @@ TEST (PCL, TranslatedNormalEstimation)
   NormalEstimation<PointXYZ, Normal> n;
 
   PointCloud<PointXYZ> translatedCloud(cloud);
-  for(size_t i = 0; i < translatedCloud.size(); ++i) {
-    translatedCloud[i].x += 100;
-    translatedCloud[i].y += 100;
-    translatedCloud[i].z += 100;
+  for(auto & i : translatedCloud) {
+    i.x += 100;
+    i.y += 100;
+    i.z += 100;
   }
 
   // computePointNormal (indices, Vector)
@@ -267,7 +267,7 @@ TEST (PCL, TranslatedNormalEstimation)
   n.setSearchSurface (surfaceptr);
   EXPECT_EQ (n.getSearchSurface (), surfaceptr);
 
-  // Additional test for searchForNeigbhors
+  // Additional test for searchForNeighbors
   surfaceptr.reset (new PointCloud<PointXYZ>);
   *surfaceptr = *cloudptr;
   surfaceptr->points.resize (640 * 480);
@@ -430,7 +430,7 @@ TEST (PCL, IntegralImageNormalEstimationIndexingIssue)
       double y = ypos;
       double x = xpos;
 
-      (*cloudptr)[idx++] = PointXYZ(float(x), float(y), float(z));
+      (*cloudptr)[idx++] = PointXYZ(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z));
     }
   }
 
index 98673c4139a19f67ebbdb129efa3ff2c5c79dcc7..3575a5b05f1508e66475db3ce239edcd28a158df 100644 (file)
@@ -476,7 +476,7 @@ TEST (PCL, GFPFH)
 
   PointCloud<PointXYZL>::Ptr cloud (new PointCloud<PointXYZL>());
 
-  const unsigned num_classes = 3;
+  constexpr unsigned num_classes = 3;
 
   // Build a cubic shape with a hole and changing labels.
   for (int z = -10; z < 10; ++z)
@@ -504,10 +504,10 @@ TEST (PCL, GFPFH)
   PointCloud<GFPFHSignature16> descriptor;
   gfpfh.compute (descriptor);
 
-  const float ref_values[] = { 1877, 6375, 5361, 14393, 6674, 2471, 2248, 2753, 3117, 4585, 14388, 32407, 15122, 3061, 3202, 794 };
+  const float ref_values[] = { 1881, 6378, 5343, 14406, 6726, 2379, 2295, 2724, 3177, 4518, 14283, 32341, 15131, 3195, 3238, 813 };
 
   EXPECT_EQ (descriptor.size (), 1);
-  for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i)
+  for (std::size_t i = 0; i < static_cast<std::size_t>(descriptor[0].descriptorSize ()); ++i)
   {
     EXPECT_EQ (descriptor[0].histogram[i], ref_values[i]);
   }
index 46f82e48e90e042fe92e9c2ec8acb4bf2cf42c41..58d388f498c56f09ba40bee18c9d31668acff2d0 100644 (file)
@@ -95,13 +95,13 @@ TEST (BoxClipper3D, Filters)
   EXPECT_EQ (int (indices.size ()), 5);
 
   // ... then rotate points +45 in Y-Axis
-  t.rotate (AngleAxisf (45.0f * float (M_PI) / 180.0f, Vector3f::UnitY ()));
+  t.rotate (AngleAxisf (45.0f * static_cast<float>(M_PI) / 180.0f, Vector3f::UnitY ()));
   boxClipper3D.setTransformation (t);
   boxClipper3D.clipPointCloud3D (*input, indices);
   EXPECT_EQ (int (indices.size ()), 1);
 
   // ... then rotate points -45 in Z-axis
-  t.rotate (AngleAxisf (-45.0f * float (M_PI) / 180.0f, Vector3f::UnitZ ()));
+  t.rotate (AngleAxisf (-45.0f * static_cast<float>(M_PI) / 180.0f, Vector3f::UnitZ ()));
   boxClipper3D.setTransformation (t);
   boxClipper3D.clipPointCloud3D (*input, indices);
   EXPECT_EQ (int (indices.size ()), 3);
@@ -210,7 +210,7 @@ TEST (CropBox, Filters)
   cropBoxFilter.filter (cloud_out);
 
   // Rotate crop box up by 45
-  cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f));
+  cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast<float>(M_PI) / 180.0f, 0.0f));
   cropBoxFilter.filter (indices);
   cropBoxFilter.filter (cloud_out);
 
@@ -234,7 +234,7 @@ TEST (CropBox, Filters)
   cropBoxFilter.filter (cloud_out);
 
   // Rotate point cloud by -45
-  cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f));
+  cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast<float>(M_PI) / 180.0f));
   cropBoxFilter.filter (indices);
   cropBoxFilter.filter (cloud_out);
 
@@ -258,7 +258,7 @@ TEST (CropBox, Filters)
   cropBoxFilter.filter (cloud_out);
 
   // Translate point cloud down by -1
-  cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * float (M_PI) / 180.0));
+  cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * static_cast<float>(M_PI) / 180.0));
   cropBoxFilter.filter (indices);
   cropBoxFilter.filter (cloud_out);
 
@@ -366,7 +366,7 @@ TEST (CropBox, Filters)
   cropBoxFilter.filter (cloud_out);
 
   // Rotate crop box up by 45
-  cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f));
+  cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast<float>(M_PI) / 180.0f, 0.0f));
   cropBoxFilter.filter (indices);
   cropBoxFilter.filter (cloud_out);
 
@@ -391,7 +391,7 @@ TEST (CropBox, Filters)
   cropBoxFilter.filter (cloud_out);
 
   // Rotate point cloud by -45
-  cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f));
+  cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast<float>(M_PI) / 180.0f));
   cropBoxFilter.filter (indices);
   cropBoxFilter.filter (cloud_out);
 
@@ -418,7 +418,7 @@ TEST (CropBox, Filters)
   cropBoxFilter.filter (cloud_out);
 
   // Translate point cloud down by -1
-  cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * float (M_PI) / 180.0));
+  cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * static_cast<float>(M_PI) / 180.0));
   cropBoxFilter.filter (indices);
   cropBoxFilter.filter (cloud_out);
 
@@ -533,7 +533,7 @@ TEST (CropBox, Filters)
   cropBoxFilter2.filter (cloud_out2);
 
   // Rotate crop box up by 45
-  cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f));
+  cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast<float>(M_PI) / 180.0f, 0.0f));
   cropBoxFilter2.filter (indices2);
   cropBoxFilter2.filter (cloud_out2);
 
@@ -541,7 +541,7 @@ TEST (CropBox, Filters)
   EXPECT_EQ (int (indices2.size ()), int (cloud_out2.width * cloud_out2.height));
 
   // Rotate point cloud by -45
-  cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f));
+  cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast<float>(M_PI) / 180.0f));
   cropBoxFilter2.filter (indices2);
   cropBoxFilter2.filter (cloud_out2);
 
@@ -563,7 +563,7 @@ TEST (CropBox, Filters)
   cropBoxFilter2.filter (cloud_out2);
 
   // Translate point cloud down by -1
-  cropBoxFilter2.setTransform (getTransformation (0.0f, -1.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f));
+  cropBoxFilter2.setTransform (getTransformation (0.0f, -1.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast<float>(M_PI) / 180.0f));
   cropBoxFilter2.filter (indices2);
   cropBoxFilter2.filter (cloud_out2);
 
@@ -669,7 +669,7 @@ TEST (CropBox, Filters)
     cropBoxFilter2.filter (cloud_out2);
 
     // Rotate crop box up by 45
-    cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f));
+    cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast<float>(M_PI) / 180.0f, 0.0f));
     cropBoxFilter2.filter (indices2);
     cropBoxFilter2.filter (cloud_out2);
 
@@ -694,7 +694,7 @@ TEST (CropBox, Filters)
     cropBoxFilter2.filter (cloud_out2);
 
     // Rotate point cloud by -45
-    cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f));
+    cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast<float>(M_PI) / 180.0f));
     cropBoxFilter2.filter (indices2);
     cropBoxFilter2.filter (cloud_out2);
 
@@ -720,7 +720,7 @@ TEST (CropBox, Filters)
     cropBoxFilter2.filter (cloud_out2);
 
     // Translate point cloud down by -1
-    cropBoxFilter2.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * float (M_PI) / 180.0));
+    cropBoxFilter2.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * static_cast<float>(M_PI) / 180.0));
     cropBoxFilter2.filter (indices2);
     cropBoxFilter2.filter (cloud_out2);
 
index 2bae7ae0bd41bb562e2b783891fbd45d98d4a4bd..f0d1ece311bb81583df1d9ff2d2015acb729f7b4 100644 (file)
@@ -68,11 +68,11 @@ RGB interpolate_color(float lower_bound, float upper_bound, float value)
   auto interpolate = [](std::uint8_t lower, std::uint8_t upper, float step_size, float value) {
     return (lower == upper) ? lower : static_cast<std::uint8_t>(static_cast<float>(lower) + ((static_cast<float>(upper) - static_cast<float>(lower)) / step_size) * value);
   };
-  return RGB(
+  return {
     interpolate(colormap[lower_index].r, colormap[lower_index + 1].r, step_size, value),
     interpolate(colormap[lower_index].g, colormap[lower_index + 1].g, step_size, value),
     interpolate(colormap[lower_index].b, colormap[lower_index + 1].b, step_size, value)
-  );
+  };
 }
 
 TEST (Convolution, convolveRowsXYZI)
@@ -193,10 +193,10 @@ TEST (Convolution, convolveRowsRGB)
   for (std::uint32_t r = 0; r < input->height; r++)
     for (std::uint32_t c = 0; c < input->width; c++)
     {
-      float x1 = -2.0f + (4.0f / (float)input->width) * (float)c;
-      float y1 = -2.0f + (4.0f / (float)input->height) * (float)r;
-      float x2 = -M_PI + (2.0f * M_PI / (float)input->width) * (float)c;
-      float y2 = -2.0f + (4.0f / (float)input->height) * (float)r;
+      float x1 = -2.0f + (4.0f / static_cast<float>(input->width)) * static_cast<float>(c);
+      float y1 = -2.0f + (4.0f / static_cast<float>(input->height)) * static_cast<float>(r);
+      float x2 = -M_PI + (2.0f * M_PI / static_cast<float>(input->width)) * static_cast<float>(c);
+      float y2 = -2.0f + (4.0f / static_cast<float>(input->height)) * static_cast<float>(r);
       float z = x1 * std::exp(-(x1 * x1 + y1 * y1)) * 2.5f + std::sin(x2) * std::sin(y2);
       (*input) (c, r) = interpolate_color(-1.6f, 1.6f, z);
     }
@@ -302,18 +302,18 @@ TEST (Convolution, convolveRowsXYZRGB)
   for (std::uint32_t r = 0; r < input->height; r++)
     for (std::uint32_t c = 0; c < input->width; c++)
     {
-      float x1 = -2.0f + (4.0f / (float)input->width) * (float)c;
-      float y1 = -2.0f + (4.0f / (float)input->height) * (float)r;
-      float x2 = -M_PI + (2.0f * M_PI / (float)input->width) * (float)c;
-      float y2 = -2.0f + (4.0f / (float)input->height) * (float)r;
+      float x1 = -2.0f + (4.0f / static_cast<float>(input->width)) * static_cast<float>(c);
+      float y1 = -2.0f + (4.0f / static_cast<float>(input->height)) * static_cast<float>(r);
+      float x2 = -M_PI + (2.0f * M_PI / static_cast<float>(input->width)) * static_cast<float>(c);
+      float y2 = -2.0f + (4.0f / static_cast<float>(input->height)) * static_cast<float>(r);
       float z = x1 * std::exp(-(x1 * x1 + y1 * y1)) * 2.5f + std::sin(x2) * std::sin(y2);
       RGB color = interpolate_color(-1.6f, 1.6f, z);
       (*input) (c, r).x = x1;
       (*input) (c, r).y = y1;
       (*input) (c, r).z = z;
-      (*input) (c, r).r = (uint8_t)(255.0f * color.r);
-      (*input) (c, r).g = (uint8_t)(255.0f * color.g);
-      (*input) (c, r).b = (uint8_t)(255.0f * color.b);
+      (*input) (c, r).r = static_cast<uint8_t>(255.0f * color.r);
+      (*input) (c, r).g = static_cast<uint8_t>(255.0f * color.g);
+      (*input) (c, r).b = static_cast<uint8_t>(255.0f * color.b);
     }
 
   // filter
@@ -396,12 +396,14 @@ TEST (Convolution, convolveRowsXYZRGB)
   // check result
   for (std::uint32_t i = 0; i < output->width ; ++i)
   {
+#ifndef __i386__
     EXPECT_EQ ((*output) (i, 0).r, output_results[i * 2 + 0].r);
     EXPECT_EQ ((*output) (i, 0).g, output_results[i * 2 + 0].g);
     EXPECT_EQ ((*output) (i, 0).b, output_results[i * 2 + 0].b);
     EXPECT_EQ ((*output) (i, 47).r, output_results[i * 2 + 1].r);
     EXPECT_EQ ((*output) (i, 47).g, output_results[i * 2 + 1].g);
     EXPECT_EQ ((*output) (i, 47).b, output_results[i * 2 + 1].b);
+#endif
   }
 }
 
index ebe169ae65cdf41e476e634dd50810469b913a79..17e87e06f0eaa12bb79ccac1f65f230896a654ab 100644 (file)
@@ -58,7 +58,7 @@ createTestDataSuite(
     std::function<pcl::PointXYZ()> outside_point_generator)
 {
   std::vector<TestData> test_data_suite;
-  size_t const chunk_size = 1000;
+  constexpr size_t chunk_size = 1000;
   pcl::PointCloud<pcl::PointXYZ>::Ptr inside_cloud(new pcl::PointCloud<pcl::PointXYZ>);
   pcl::PointCloud<pcl::PointXYZ>::Ptr outside_cloud(new pcl::PointCloud<pcl::PointXYZ>);
   pcl::PointCloud<pcl::PointXYZ>::Ptr mixed_cloud(new pcl::PointCloud<pcl::PointXYZ>);
index 9606c07eb7e87f749e52b8038ef95f34c8360960..e1d0a96199341bad44c3a753342c11f27aeb6392 100644 (file)
@@ -19,8 +19,8 @@
 
 using namespace pcl;
 PointCloud<PointXYZ>::Ptr cloud_in (new PointCloud<PointXYZ>);
-const static int CLOUD_SIZE = 10;
-const static int SAMPLE_SIZE = CLOUD_SIZE -1;
+constexpr int CLOUD_SIZE = 10;
+constexpr int SAMPLE_SIZE = CLOUD_SIZE - 1;
 std::vector<float> x_values;
 
 TEST (FarthestPointSampling, farthest_point_sampling)
index 4932be95afe3596429c22137ed6ee67acc6c01f0..2cc5b88361ebacbd64f1ecd487351b44139891b1 100644 (file)
@@ -1972,9 +1972,9 @@ TEST (FrustumCulling, Filters)
       for (int k = 0; k < 5; k++)
       {
         pcl::PointXYZ pt;
-        pt.x = float (i);
-        pt.y = float (j);
-        pt.z = float (k);
+        pt.x = static_cast<float>(i);
+        pt.y = static_cast<float>(j);
+        pt.z = static_cast<float>(k);
         input->push_back (pt);
       }
     }
@@ -2126,7 +2126,7 @@ TEST (ConditionalRemovalTfQuadraticXYZComparison, Filters)
   EXPECT_EQ ((*input)[9].z, output[9].z);
 
   // rotate cylinder comparison along z-axis by PI/2
-  cyl_comp->transformComparison (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, float (M_PI) / 2.0f).inverse ());
+  cyl_comp->transformComparison (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, static_cast<float>(M_PI) / 2.0f).inverse ());
 
   condrem.filter (output);
 
@@ -2302,7 +2302,7 @@ TEST (NormalRefinement, Filters)
   const float vp_z = cloud_organized_nonan.sensor_origin_[2];
 
   // Search parameters
-  const int k = 5;
+  constexpr int k = 5;
   std::vector<pcl::Indices> k_indices;
   std::vector<std::vector<float> > k_sqr_distances;
 
index dc69cca82b2df03f3018adecc5d55e2ab5e74062..3bc10cd6c8de97d08970966a5a00fa8128e3f418 100644 (file)
 
 using namespace pcl;
 
-PointCloud<PointXYZ> cloud;
-
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST (Filters, LocalMaximum)
 {
   PointCloud<PointXYZ> cloud_in, cloud_out;
 
   cloud_in.height = 1;
-  cloud_in.width = 3;
+  cloud_in.width = 4;
   cloud_in.is_dense = true;
   cloud_in.resize (4);
 
@@ -73,6 +71,31 @@ TEST (Filters, LocalMaximum)
   EXPECT_EQ (3, cloud_out.size ());
 }
 
+TEST (Filters, LocalMaximum2) // Same as the "LocalMaximum" test above, but the points have a different order
+{
+  PointCloud<PointXYZ> cloud_in, cloud_out;
+
+  cloud_in.height = 1;
+  cloud_in.width = 4;
+  cloud_in.is_dense = true;
+  cloud_in.resize (4);
+
+  cloud_in[0].x = 0.5;  cloud_in[0].y = 0.5;  cloud_in[0].z = 1; // this one should be removed
+  cloud_in[1].x = 0;    cloud_in[1].y = 0;    cloud_in[1].z = 0.25;
+  cloud_in[2].x = 0.25; cloud_in[2].y = 0.25; cloud_in[2].z = 0.5;
+  cloud_in[3].x = 5;    cloud_in[3].y = 5;    cloud_in[3].z = 2;
+
+  LocalMaximum<PointXYZ> lm;
+  lm.setInputCloud (cloud_in.makeShared ());
+  lm.setRadius (1.0f);
+  lm.filter (cloud_out);
+
+  EXPECT_EQ (0.25f, cloud_out[0].z);
+  EXPECT_EQ (0.50f, cloud_out[1].z);
+  EXPECT_EQ (2.00f, cloud_out[2].z);
+  EXPECT_EQ (3, cloud_out.size ());
+}
+
 /* ---[ */
 int
 main (int argc, char** argv)
index f9410a9e04dd0d39bfd7dc2077faaca9a8769d76..50a3446c0368c9415bba6ae5015e426c7bbbfead 100644 (file)
@@ -44,7 +44,7 @@
 TEST(UniformSampling, extractRemovedIndices)
 {
   using namespace pcl::common;
-  const int SEED = 1234;
+  constexpr int SEED = 1234;
   CloudGenerator<pcl::PointXYZ, UniformGenerator<float>> generator;
   UniformGenerator<float>::Parameters x_params(0, 1, SEED + 1);
   generator.setParametersForX(x_params);
index 0ff5cbc63951321d38f94fe410bfe2a6c15081f3..df91318689eb41e8fcc1bb9f1eceed0e97cfe5d7 100644 (file)
@@ -51,8 +51,8 @@ void checkSimpleLine8 (unsigned x_start, unsigned y_start, unsigned x_end, unsig
     for (unsigned xIdx = 0; xIdx < cloud.width; ++xIdx)
     {
       PointT& point = cloud.points [yIdx * cloud.width + xIdx];
-      point.x = float(xIdx);
-      point.y = float(yIdx);
+      point.x = static_cast<float>(xIdx);
+      point.y = static_cast<float>(yIdx);
       point.z = 0.0f;
     }
   }
@@ -132,8 +132,8 @@ void checkGeneralLine (unsigned x_start, unsigned y_start, unsigned x_end, unsig
     for (unsigned xIdx = 0; xIdx < cloud.width; ++xIdx)
     {
       PointT& point = cloud.points [yIdx * cloud.width + xIdx];
-      point.x = float(xIdx);
-      point.y = float(yIdx);
+      point.x = static_cast<float>(xIdx);
+      point.y = static_cast<float>(yIdx);
       point.z = 0.0f;
     }
   }
@@ -168,27 +168,27 @@ void checkGeneralLine (unsigned x_start, unsigned y_start, unsigned x_end, unsig
   else
     EXPECT_EQ (std::abs(dx) + std::abs(dy), idx);
   
-  float length = std::sqrt (float (dx * dx + dy * dy));
-  float dir_x = float (dx) / length;
-  float dir_y = float (dy) / length;
+  float length = std::sqrt (static_cast<float>(dx * dx + dy * dy));
+  float dir_x = static_cast<float>(dx) / length;
+  float dir_y = static_cast<float>(dy) / length;
   
   // now all z-values should be 0 again!
-  for (int yIdx = 0; yIdx < int(cloud.height); ++yIdx)
+  for (int yIdx = 0; yIdx < static_cast<int>(cloud.height); ++yIdx)
   {
-    for (int xIdx = 0; xIdx < int(cloud.width); ++xIdx)
+    for (int xIdx = 0; xIdx < static_cast<int>(cloud.width); ++xIdx)
     {
       PointT& point = cloud.points [yIdx * cloud.width + xIdx];
       if (point.z != 0)
       {
         // point need to be close to line
-        float distance = dir_x * float(yIdx - int(y_start)) - dir_y * float(xIdx - int(x_start));
+        float distance = dir_x * static_cast<float>(yIdx - static_cast<int>(y_start)) - dir_y * static_cast<float>(xIdx - static_cast<int>(x_start));
         if (neighorhood)        
           EXPECT_LE (std::fabs(distance), 0.5f);
         else
           EXPECT_LE (std::fabs(distance), 0.70711f);
         
         // and within the endpoints
-        float lambda = dir_y * float(yIdx - int(y_start)) + dir_x * float(xIdx - int(x_start));
+        float lambda = dir_y * static_cast<float>(yIdx - static_cast<int>(y_start)) + dir_x * static_cast<float>(xIdx - static_cast<int>(x_start));
         EXPECT_LE (lambda, length);
         EXPECT_GE (lambda, 0.0f);
       }
@@ -245,12 +245,12 @@ TEST (PCL, LineIterator8NeighborsGeneral)
   unsigned center_y = 50;
   unsigned length = 45;
   
-  const unsigned angular_resolution = 180;
-  float d_alpha = float(M_PI / angular_resolution);
+  constexpr unsigned angular_resolution = 180;
+  constexpr float d_alpha = static_cast<float>(M_PI / angular_resolution);
   for (unsigned idx = 0; idx < angular_resolution; ++idx)
   {
-    auto x_end = unsigned (length * std::cos (float(idx) * d_alpha) + center_x + 0.5);
-    auto y_end = unsigned (length * std::sin (float(idx) * d_alpha) + center_y + 0.5);
+    auto x_end = static_cast<unsigned>(length * std::cos (static_cast<float>(idx) * d_alpha) + center_x + 0.5);
+    auto y_end = static_cast<unsigned>(length * std::sin (static_cast<float>(idx) * d_alpha) + center_y + 0.5);
     
     // right
     checkGeneralLine (center_x, center_y, x_end, y_end, cloud, true);
@@ -269,12 +269,12 @@ TEST (PCL, LineIterator4NeighborsGeneral)
   unsigned center_y = 50;
   unsigned length = 45;
   
-  const unsigned angular_resolution = 360;
-  float d_alpha = float(2.0 * M_PI / angular_resolution);
+  constexpr unsigned angular_resolution = 360;
+  constexpr float d_alpha = static_cast<float>(2.0 * M_PI / angular_resolution);
   for (unsigned idx = 0; idx < angular_resolution; ++idx)
   {
-    auto x_end = unsigned (length * std::cos (float(idx) * d_alpha) + center_x + 0.5);
-    auto y_end = unsigned (length * std::sin (float(idx) * d_alpha) + center_y + 0.5);
+    auto x_end = static_cast<unsigned>(length * std::cos (static_cast<float>(idx) * d_alpha) + center_x + 0.5);
+    auto y_end = static_cast<unsigned>(length * std::sin (static_cast<float>(idx) * d_alpha) + center_y + 0.5);
     
     // right
     checkGeneralLine (center_x, center_y, x_end, y_end, cloud, false);
index f61ed0a86a758daeead202817176106830c24ab2..5f3d42f5f2b189ebbf2d043b1c8c9fde9e0852ad 100644 (file)
@@ -46,8 +46,8 @@
 ////////////////////////////////////////////////////////////////////////////////
 
 // Abort circulating if the number of evaluations is too damn high.
-const unsigned int max_number_polygon_vertices  = 100;
-const unsigned int max_number_boundary_vertices = 100;
+constexpr unsigned int max_number_polygon_vertices = 100;
+constexpr unsigned int max_number_boundary_vertices = 100;
 
 ////////////////////////////////////////////////////////////////////////////////
 
@@ -65,7 +65,7 @@ hasFaces (const MeshT& mesh, const std::vector <typename MeshT::VertexIndices> &
     {
       std::cerr << "Incorrect number of faces: " << mesh.sizeFaces () << " != " << faces.size () << "\n";
     }
-    return (false);
+    return false;
   }
 
   VertexIndices vi;
@@ -84,7 +84,7 @@ hasFaces (const MeshT& mesh, const std::vector <typename MeshT::VertexIndices> &
       if (++counter > max_number_polygon_vertices)
       {
         if (verbose) std::cerr << "... Infinite loop aborted.\n";
-        return (false);
+        return false;
       }
       vi.push_back (circ.getTargetIndex ());
     } while (++circ != circ_end);
@@ -92,7 +92,7 @@ hasFaces (const MeshT& mesh, const std::vector <typename MeshT::VertexIndices> &
     if (vi.size () != faces [i].size ())
     {
       std::cerr << "Wrong size!\n";
-      return (false);
+      return false;
     }
     if (verbose) std::cerr << "\texpected: ";
     for (std::size_t j = 0; j < vi.size (); ++j)
@@ -100,12 +100,12 @@ hasFaces (const MeshT& mesh, const std::vector <typename MeshT::VertexIndices> &
       if (verbose) std::cerr << std::setw (2) << faces [i][j] << " ";
       if (vi [j] != faces [i][j])
       {
-        return (false);
+        return false;
       }
     }
     if (verbose) std::cerr << "\n";
   }
-  return (true);
+  return true;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -126,7 +126,7 @@ hasFaces (const MeshT& mesh, const std::vector <std::vector <int> > &faces, cons
     {
       std::cerr << "Incorrect number of faces: " << mesh.sizeFaces () << " != " << faces.size () << "\n";
     }
-    return (false);
+    return false;
   }
 
   const VertexDataCloud& vdc = mesh.getVertexDataCloud ();
@@ -146,7 +146,7 @@ hasFaces (const MeshT& mesh, const std::vector <std::vector <int> > &faces, cons
       if (++counter > max_number_polygon_vertices)
       {
         if (verbose) std::cerr << "... Infinite loop aborted.\n";
-        return (false);
+        return false;
       }
       vv.push_back (vdc [circ.getTargetIndex ().get ()]);
     } while (++circ != circ_end);
@@ -154,7 +154,7 @@ hasFaces (const MeshT& mesh, const std::vector <std::vector <int> > &faces, cons
     if (vv.size () != faces [i].size ())
     {
       std::cerr << "Wrong size!\n";
-      return (false);
+      return false;
     }
     if (verbose) std::cerr << "\texpected: ";
     for (std::size_t j=0; j<vv.size (); ++j)
@@ -163,12 +163,12 @@ hasFaces (const MeshT& mesh, const std::vector <std::vector <int> > &faces, cons
       if (vv [j] != faces [i][j])
       {
         if (verbose) std::cerr << "\n";
-        return (false);
+        return false;
       }
     }
     if (verbose) std::cerr << "\n";
   }
-  return (true);
+  return true;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -187,7 +187,7 @@ getBoundaryVertices (const MeshT& mesh, const typename MeshT::VertexIndex& first
     if (verbose) std::cerr << "Vertex " << first << "with outgoing half_edge "
                            << mesh.getOriginatingVertexIndex (boundary_he) << "-"
                            << mesh.getTerminatingVertexIndex (boundary_he) << " is not on the boundary!\n";
-    return (VertexIndices ());
+    return {};
   }
 
   VAFC       circ     = mesh.getVertexAroundFaceCirculator (boundary_he);
@@ -203,12 +203,12 @@ getBoundaryVertices (const MeshT& mesh, const typename MeshT::VertexIndex& first
     if (++counter > max_number_boundary_vertices)
     {
       if (verbose) std::cerr << "... Infinite loop aborted.\n";
-      return (VertexIndices ());
+      return {};
     }
     boundary_vertices.push_back (circ.getTargetIndex ());
   } while (++circ != circ_end);
   if (verbose) std::cerr << "\n";
-  return (boundary_vertices);
+  return boundary_vertices;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -227,7 +227,7 @@ getBoundaryVertices (const MeshT& mesh, const int first, const bool verbose = fa
     if (verbose) std::cerr << "Vertex " << first << "with outgoing half_edge "
                            << mesh.getOriginatingVertexIndex (boundary_he) << "-"
                            << mesh.getTerminatingVertexIndex (boundary_he) << " is not on the boundary!\n";
-    return (std::vector <int> ());
+    return {};
   }
 
   VAFC       circ     = mesh.getVertexAroundFaceCirculator (boundary_he);
@@ -243,12 +243,12 @@ getBoundaryVertices (const MeshT& mesh, const int first, const bool verbose = fa
     if (++counter > max_number_boundary_vertices)
     {
       if (verbose) std::cerr << "... Infinite loop aborted.\n";
-      return (std::vector <int> ());
+      return {};
     }
     boundary_vertices.push_back (mesh.getVertexDataCloud () [circ.getTargetIndex ().get ()]);
   } while (++circ != circ_end);
   if (verbose) std::cerr << "\n";
-  return (boundary_vertices);
+  return boundary_vertices;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -264,7 +264,7 @@ isCircularPermutation (const ContainerT& expected, const ContainerT& actual, con
   if (n != actual.size ())
   {
     if (verbose) std::cerr << "expected.size () != actual.size (): " << n << " != " << actual.size () << "\n";
-    return (false);
+    return false;
   }
 
   for (unsigned int i=0; i<n; ++i)
@@ -282,11 +282,11 @@ isCircularPermutation (const ContainerT& expected, const ContainerT& actual, con
     if (all_equal)
     {
       if (verbose) std::cerr << " SUCCESS\n";
-      return (true);
+      return true;
     }
     if (verbose) std::cerr << "\n";
   }
-  return (false);
+  return false;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -300,7 +300,7 @@ isCircularPermutationVec (const std::vector <ContainerT> &expected, const std::v
   if (n != actual.size ())
   {
     if (verbose) std::cerr << "expected.size () != actual.size (): " << n << " != " << actual.size () << "\n";
-    return (false);
+    return false;
   }
 
   for (unsigned int i=0; i<n; ++i)
@@ -317,10 +317,10 @@ isCircularPermutationVec (const std::vector <ContainerT> &expected, const std::v
     if (verbose) std::cerr << "\n";
     if (all_equal)
     {
-      return (true);
+      return true;
     }
   }
-  return (false);
+  return false;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -333,12 +333,11 @@ findHalfEdge (const MeshT&                       mesh,
               const typename MeshT::VertexIndex& idx_v_0,
               const typename MeshT::VertexIndex& idx_v_1)
 {
-  using HalfEdgeIndex = typename MeshT::HalfEdgeIndex;
   using VAVC = typename MeshT::VertexAroundVertexCirculator;
 
   if (mesh.isIsolated (idx_v_0) || mesh.isIsolated (idx_v_1))
   {
-    return (HalfEdgeIndex ());
+    return {};
   }
 
   VAVC       circ     = mesh.getVertexAroundVertexCirculator (idx_v_0);
@@ -352,7 +351,7 @@ findHalfEdge (const MeshT&                       mesh,
     }
   } while (++circ != circ_end);
 
-  return (HalfEdgeIndex ());
+  return {};
 }
 
 ////////////////////////////////////////////////////////////////////////////////
@@ -364,9 +363,9 @@ checkHalfEdge (const MeshT&                        mesh,
                const typename MeshT::VertexIndex   ind_v_a,
                const typename MeshT::VertexIndex   ind_v_b)
 {
-  if (mesh.getOriginatingVertexIndex (ind_he_ab) != ind_v_a) return (false);
-  if (mesh.getTerminatingVertexIndex (ind_he_ab) != ind_v_b) return (false);
-  return (true);
+  if (mesh.getOriginatingVertexIndex (ind_he_ab) != ind_v_a) return false;
+  if (mesh.getTerminatingVertexIndex (ind_he_ab) != ind_v_b) return false;
+  return true;
 }
 
 ////////////////////////////////////////////////////////////////////////////////
index 0a958f6e215dfba3079d8098c78cdc85e2f9ade7..3bafedb1827620297a92dba8cda78d5dad9fd544 100644 (file)
@@ -221,7 +221,7 @@ TYPED_TEST (TestQuadMesh, OneQuad)
 TYPED_TEST (TestQuadMesh, NineQuads)
 {
   using Mesh = typename TestFixture::Mesh;
-  const int int_max = std::numeric_limits <int>::max ();
+  constexpr int int_max = std::numeric_limits<int>::max();
 
   // Order
   //    -   -   -   //
index 0c0ead83fb20fcaa8c1e1df2968155edf970eafc..d351641a035dcfd0d37db8c33a7587c0c0624d0f 100644 (file)
@@ -12,7 +12,7 @@ if(NOT build)
   return()
 endif()
 
-PCL_ADD_TEST(gpu_octree_performance test_gpu_octree_perfomance FILES perfomance.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree)
+PCL_ADD_TEST(gpu_octree_performance test_gpu_octree_performance FILES performance.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree)
 PCL_ADD_TEST(gpu_octree_approx_nearest test_gpu_approx_nearest FILES test_approx_nearest.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree pcl_gpu_utils)
 PCL_ADD_TEST(gpu_octree_bfrs test_gpu_bfrs FILES test_bfrs_gpu.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree)
 PCL_ADD_TEST(gpu_octree_host_radius test_gpu_host_radius_search FILES test_host_radius_search.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree)
diff --git a/test/gpu/octree/perfomance.cpp b/test/gpu/octree/perfomance.cpp
deleted file mode 100644 (file)
index 0d72a55..0000000
+++ /dev/null
@@ -1,267 +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)
- */
-
-#if defined _MSC_VER
-    #pragma warning (disable : 4996 4530)
-#endif
-
-#include <gtest/gtest.h>
-
-#include<iostream>
-#include<algorithm>
-
-#if defined _MSC_VER
-    #pragma warning (disable: 4521)
-#endif
-    
-#include <pcl/point_cloud.h>
-#include <pcl/octree/octree.h>
-
-#if defined _MSC_VER
-    #pragma warning (default: 4521)
-#endif
-    
-
-#include <pcl/gpu/octree/octree.hpp>
-#include <pcl/gpu/containers/device_array.h>
-#include <pcl/common/time.h>
-#include "data_source.hpp"
-
-using namespace pcl::gpu;
-
-using pcl::ScopeTime;
-
-#if defined HAVE_OPENCV
-    #include "opencv2/contrib/contrib.hpp"
-#endif
-
-//TEST(PCL_OctreeGPU, DISABLED_performance)
-TEST(PCL_OctreeGPU, performance)
-{
-    DataGenerator data;
-    data.data_size = 871000;
-    data.tests_num = 10000;
-    data.cube_size = 1024.f;
-    data.max_radius    = data.cube_size/15.f;
-    data.shared_radius = data.cube_size/15.f;
-    data.printParams();
-
-    //const int k = 32;
-
-    std::cout << "sizeof(pcl::gpu::Octree::PointType): " << sizeof(pcl::gpu::Octree::PointType) << std::endl;    
-    //std::cout << "k = " << k << std::endl;
-    //generate data
-    data();
-
-    //prepare device cloud
-    pcl::gpu::Octree::PointCloud cloud_device;
-    cloud_device.upload(data.points);
-
-    //prepare queries_device
-    pcl::gpu::Octree::Queries queries_device;
-    pcl::gpu::Octree::Radiuses radiuses_device;
-     queries_device.upload(data.queries);  
-    radiuses_device.upload(data.radiuses);
-
-    //prepare host cloud
-    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_host(new pcl::PointCloud<pcl::PointXYZ>);        
-    cloud_host->width = data.points.size();
-    cloud_host->height = 1;
-    cloud_host->resize (cloud_host->width * cloud_host->height);    
-    std::transform(data.points.cbegin(), data.points.cend(), cloud_host->begin(), DataGenerator::ConvPoint<pcl::PointXYZ>());
-
-    float host_octree_resolution = 25.f;    
-    
-    std::cout << "[!] Host octree resolution: " << host_octree_resolution << std::endl << std::endl;    
-
-    std::cout << "======  Build performance =====" << std::endl;
-    // build device octree
-    pcl::gpu::Octree octree_device;                
-    octree_device.setCloud(cloud_device);          
-    {        
-        ScopeTime up("gpu-build");                     
-        octree_device.build();
-    }    
-    {
-        ScopeTime up("gpu-download");  
-        octree_device.internalDownload();
-    }
-
-    //build host octree
-    pcl::octree::OctreePointCloudSearch<pcl::PointXYZ> octree_host(host_octree_resolution);
-    octree_host.setInputCloud (cloud_host);
-    {
-        ScopeTime t("host-build");             
-        octree_host.addPointsFromInputCloud();
-    }
-
-    // build opencv octree
-#ifdef HAVE_OPENCV
-    cv::Octree octree_opencv;
-    const static int opencv_octree_points_per_leaf = 32;    
-    std::vector<cv::Point3f> opencv_points(data.size());
-    std::transform(data.cbegin(), data.cend(), opencv_points.begin(), DataGenerator::ConvPoint<cv::Point3f>());
-        
-    {        
-        ScopeTime t("opencv-build");           
-        octree_opencv.buildTree(opencv_points, 10, opencv_octree_points_per_leaf); 
-    }
-#endif
-    
-    //// Radius search performance ///
-
-    const int max_answers = 500;
-    float dist;
-
-    //host buffers
-    std::vector<int> indices;
-    pcl::Indices indices_host;
-    std::vector<float> pointRadiusSquaredDistance;
-#ifdef HAVE_OPENCV  
-    std::vector<cv::Point3f> opencv_results;
-#endif
-
-    //reserve
-    indices.reserve(data.data_size);
-    indices_host.reserve(data.data_size);
-    pointRadiusSquaredDistance.reserve(data.data_size);
-#ifdef HAVE_OPENCV
-    opencv_results.reserve(data.data_size);
-#endif
-
-    //device buffers
-    pcl::gpu::DeviceArray<int> bruteforce_results_device, buffer(cloud_device.size());    
-    pcl::gpu::NeighborIndices result_device(queries_device.size(), max_answers);
-    
-    //pcl::gpu::Octree::BatchResult          distsKNN_device(queries_device.size() * k);
-    //pcl::gpu::Octree::BatchResultSqrDists  indsKNN_device(queries_device.size() * k);
-        
-    std::cout << "======  Separate radius for each query =====" << std::endl;
-
-    {
-        ScopeTime up("gpu--radius-search-batch-all");          
-        octree_device.radiusSearch(queries_device, radiuses_device, max_answers, result_device);
-    }
-
-    {
-        ScopeTime up("gpu-radius-search-{host}-all");  
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            octree_device.radiusSearchHost(data.queries[i], data.radiuses[i], indices, max_answers);
-    }
-
-    {                
-        ScopeTime up("host-radius-search-all");        
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            octree_host.radiusSearch(pcl::PointXYZ(data.queries[i].x, data.queries[i].y, data.queries[i].z), 
-                data.radiuses[i], indices_host, pointRadiusSquaredDistance, max_answers);
-    }
-     
-    {
-        ScopeTime up("gpu_bruteforce-radius-search-all");               
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            pcl::gpu::bruteForceRadiusSearchGPU(cloud_device, data.queries[i], data.radiuses[i], bruteforce_results_device, buffer);
-    }
-
-    std::cout << "======  Shared radius (" << data.shared_radius << ") =====" << std::endl;
-    
-    {
-        ScopeTime up("gpu-radius-search-batch-all");           
-        octree_device.radiusSearch(queries_device, data.shared_radius, max_answers, result_device);                        
-    }
-
-    {
-        ScopeTime up("gpu-radius-search-{host}-all");
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            octree_device.radiusSearchHost(data.queries[i], data.shared_radius, indices, max_answers);
-    }
-
-    {                
-        ScopeTime up("host-radius-search-all");        
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            octree_host.radiusSearch(pcl::PointXYZ(data.queries[i].x, data.queries[i].y, data.queries[i].z), 
-                data.radiuses[i], indices_host, pointRadiusSquaredDistance, max_answers);
-    }
-     
-    {
-        ScopeTime up("gpu-radius-bruteforce-search-all");               
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            pcl::gpu::bruteForceRadiusSearchGPU(cloud_device, data.queries[i], data.shared_radius, bruteforce_results_device, buffer);
-    }
-
-    std::cout << "======  Approx nearest search =====" << std::endl;
-
-    {
-        ScopeTime up("gpu-approx-nearest-batch-all");         
-        pcl::gpu::Octree::ResultSqrDists sqr_distance;
-        octree_device.approxNearestSearch(queries_device, result_device, sqr_distance);
-    }
-
-    {        
-        int inds;
-        ScopeTime up("gpu-approx-nearest-search-{host}-all");
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            octree_device.approxNearestSearchHost(data.queries[i], inds, dist);                        
-    }
-
-    {                
-        pcl::index_t inds;
-        ScopeTime up("host-approx-nearest-search-all");        
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            octree_host.approxNearestSearch(data.queries[i], inds, dist);
-    }
-
- /*   std::cout << "======  knn search ( k fixed to " << k << " ) =====" << std::endl;    
-    {
-        ScopeTime up("gpu-knn-batch-all");             
-        octree_device.nearestKSearchBatch(queries_device, k, distsKNN_device, indsKNN_device);                        
-    }    
-
-    {                
-        ScopeTime up("host-knn-search-all");   
-        for(std::size_t i = 0; i < data.tests_num; ++i)
-            octree_host.nearestKSearch(data.queries[i], k, indices, pointRadiusSquaredDistance);
-    }*/
-}
-
-/* ---[ */
-int
-main (int argc, char** argv)
-{
-  testing::InitGoogleTest (&argc, argv);
-  return (RUN_ALL_TESTS ());
-}
-/* ]--- */
-
diff --git a/test/gpu/octree/performance.cpp b/test/gpu/octree/performance.cpp
new file mode 100644 (file)
index 0000000..794f5e1
--- /dev/null
@@ -0,0 +1,267 @@
+/*
+ * 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)
+ */
+
+#if defined _MSC_VER
+    #pragma warning (disable : 4996 4530)
+#endif
+
+#include <gtest/gtest.h>
+
+#include<iostream>
+#include<algorithm>
+
+#if defined _MSC_VER
+    #pragma warning (disable: 4521)
+#endif
+    
+#include <pcl/point_cloud.h>
+#include <pcl/octree/octree.h>
+
+#if defined _MSC_VER
+    #pragma warning (default: 4521)
+#endif
+    
+
+#include <pcl/gpu/octree/octree.hpp>
+#include <pcl/gpu/containers/device_array.h>
+#include <pcl/common/time.h>
+#include "data_source.hpp"
+
+using namespace pcl::gpu;
+
+using pcl::ScopeTime;
+
+#if defined HAVE_OPENCV
+    #include "opencv2/contrib/contrib.hpp"
+#endif
+
+//TEST(PCL_OctreeGPU, DISABLED_performance)
+TEST(PCL_OctreeGPU, performance)
+{
+    DataGenerator data;
+    data.data_size = 871000;
+    data.tests_num = 10000;
+    data.cube_size = 1024.f;
+    data.max_radius    = data.cube_size/15.f;
+    data.shared_radius = data.cube_size/15.f;
+    data.printParams();
+
+    //const int k = 32;
+
+    std::cout << "sizeof(pcl::gpu::Octree::PointType): " << sizeof(pcl::gpu::Octree::PointType) << std::endl;    
+    //std::cout << "k = " << k << std::endl;
+    //generate data
+    data();
+
+    //prepare device cloud
+    pcl::gpu::Octree::PointCloud cloud_device;
+    cloud_device.upload(data.points);
+
+    //prepare queries_device
+    pcl::gpu::Octree::Queries queries_device;
+    pcl::gpu::Octree::Radiuses radiuses_device;
+     queries_device.upload(data.queries);  
+    radiuses_device.upload(data.radiuses);
+
+    //prepare host cloud
+    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_host(new pcl::PointCloud<pcl::PointXYZ>);        
+    cloud_host->width = data.points.size();
+    cloud_host->height = 1;
+    cloud_host->resize (cloud_host->width * cloud_host->height);    
+    std::transform(data.points.cbegin(), data.points.cend(), cloud_host->begin(), DataGenerator::ConvPoint<pcl::PointXYZ>());
+
+    float host_octree_resolution = 25.f;    
+    
+    std::cout << "[!] Host octree resolution: " << host_octree_resolution << std::endl << std::endl;    
+
+    std::cout << "======  Build performance =====" << std::endl;
+    // build device octree
+    pcl::gpu::Octree octree_device;                
+    octree_device.setCloud(cloud_device);          
+    {        
+        ScopeTime up("gpu-build");                     
+        octree_device.build();
+    }    
+    {
+        ScopeTime up("gpu-download");  
+        octree_device.internalDownload();
+    }
+
+    //build host octree
+    pcl::octree::OctreePointCloudSearch<pcl::PointXYZ> octree_host(host_octree_resolution);
+    octree_host.setInputCloud (cloud_host);
+    {
+        ScopeTime t("host-build");             
+        octree_host.addPointsFromInputCloud();
+    }
+
+    // build opencv octree
+#ifdef HAVE_OPENCV
+    cv::Octree octree_opencv;
+    constexpr int opencv_octree_points_per_leaf = 32;    
+    std::vector<cv::Point3f> opencv_points(data.size());
+    std::transform(data.cbegin(), data.cend(), opencv_points.begin(), DataGenerator::ConvPoint<cv::Point3f>());
+        
+    {        
+        ScopeTime t("opencv-build");           
+        octree_opencv.buildTree(opencv_points, 10, opencv_octree_points_per_leaf); 
+    }
+#endif
+    
+    //// Radius search performance ///
+
+    constexpr int max_answers = 500;
+    float dist;
+
+    //host buffers
+    std::vector<int> indices;
+    pcl::Indices indices_host;
+    std::vector<float> pointRadiusSquaredDistance;
+#ifdef HAVE_OPENCV  
+    std::vector<cv::Point3f> opencv_results;
+#endif
+
+    //reserve
+    indices.reserve(data.data_size);
+    indices_host.reserve(data.data_size);
+    pointRadiusSquaredDistance.reserve(data.data_size);
+#ifdef HAVE_OPENCV
+    opencv_results.reserve(data.data_size);
+#endif
+
+    //device buffers
+    pcl::gpu::DeviceArray<int> bruteforce_results_device, buffer(cloud_device.size());    
+    pcl::gpu::NeighborIndices result_device(queries_device.size(), max_answers);
+    
+    //pcl::gpu::Octree::BatchResult          distsKNN_device(queries_device.size() * k);
+    //pcl::gpu::Octree::BatchResultSqrDists  indsKNN_device(queries_device.size() * k);
+        
+    std::cout << "======  Separate radius for each query =====" << std::endl;
+
+    {
+        ScopeTime up("gpu--radius-search-batch-all");          
+        octree_device.radiusSearch(queries_device, radiuses_device, max_answers, result_device);
+    }
+
+    {
+        ScopeTime up("gpu-radius-search-{host}-all");  
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            octree_device.radiusSearchHost(data.queries[i], data.radiuses[i], indices, max_answers);
+    }
+
+    {                
+        ScopeTime up("host-radius-search-all");        
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            octree_host.radiusSearch(pcl::PointXYZ(data.queries[i].x, data.queries[i].y, data.queries[i].z), 
+                data.radiuses[i], indices_host, pointRadiusSquaredDistance, max_answers);
+    }
+     
+    {
+        ScopeTime up("gpu_bruteforce-radius-search-all");               
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            pcl::gpu::bruteForceRadiusSearchGPU(cloud_device, data.queries[i], data.radiuses[i], bruteforce_results_device, buffer);
+    }
+
+    std::cout << "======  Shared radius (" << data.shared_radius << ") =====" << std::endl;
+    
+    {
+        ScopeTime up("gpu-radius-search-batch-all");           
+        octree_device.radiusSearch(queries_device, data.shared_radius, max_answers, result_device);                        
+    }
+
+    {
+        ScopeTime up("gpu-radius-search-{host}-all");
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            octree_device.radiusSearchHost(data.queries[i], data.shared_radius, indices, max_answers);
+    }
+
+    {                
+        ScopeTime up("host-radius-search-all");        
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            octree_host.radiusSearch(pcl::PointXYZ(data.queries[i].x, data.queries[i].y, data.queries[i].z), 
+                data.radiuses[i], indices_host, pointRadiusSquaredDistance, max_answers);
+    }
+     
+    {
+        ScopeTime up("gpu-radius-bruteforce-search-all");               
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            pcl::gpu::bruteForceRadiusSearchGPU(cloud_device, data.queries[i], data.shared_radius, bruteforce_results_device, buffer);
+    }
+
+    std::cout << "======  Approx nearest search =====" << std::endl;
+
+    {
+        ScopeTime up("gpu-approx-nearest-batch-all");         
+        pcl::gpu::Octree::ResultSqrDists sqr_distance;
+        octree_device.approxNearestSearch(queries_device, result_device, sqr_distance);
+    }
+
+    {        
+        int inds;
+        ScopeTime up("gpu-approx-nearest-search-{host}-all");
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            octree_device.approxNearestSearchHost(data.queries[i], inds, dist);                        
+    }
+
+    {                
+        pcl::index_t inds;
+        ScopeTime up("host-approx-nearest-search-all");        
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            octree_host.approxNearestSearch(data.queries[i], inds, dist);
+    }
+
+ /*   std::cout << "======  knn search ( k fixed to " << k << " ) =====" << std::endl;    
+    {
+        ScopeTime up("gpu-knn-batch-all");             
+        octree_device.nearestKSearchBatch(queries_device, k, distsKNN_device, indsKNN_device);                        
+    }    
+
+    {                
+        ScopeTime up("host-knn-search-all");   
+        for(std::size_t i = 0; i < data.tests_num; ++i)
+            octree_host.nearestKSearch(data.queries[i], k, indices, pointRadiusSquaredDistance);
+    }*/
+}
+
+/* ---[ */
+int
+main (int argc, char** argv)
+{
+  testing::InitGoogleTest (&argc, argv);
+  return (RUN_ALL_TESTS ());
+}
+/* ]--- */
+
index a16c6d59a23a7f7ff4d0b960b2aa772f38f73aa9..2fd7b175c2fb24a759d11ad3d98d43ef2ac8488f 100644 (file)
@@ -136,7 +136,7 @@ TEST(PCL_OctreeGPU, hostRadiusSearch)
 
 int main (int argc, char** argv)
 {
-    const int device = 0;
+    constexpr int device = 0;
     pcl::gpu::setDevice(device);
     pcl::gpu::printShortCudaDeviceInfo(device);        
     testing::InitGoogleTest (&argc, argv);
index c21ba65c640e2f959ec7dd5ea90f6d6e89e8f33e..d5c5a36c99aea0ba1c7d39fd261ea5bd438cfa63 100644 (file)
@@ -81,8 +81,8 @@ TEST(PCL_OctreeGPU, exactNeighbourSearch)
     data.shared_radius = data.cube_size/30.f;
     data.printParams();
 
-    const float host_octree_resolution = 25.f;
-    const int k = 1; // only this is supported
+    constexpr float host_octree_resolution = 25.f;
+    constexpr int k = 1; // only this is supported
 
     //generate
     data();
index 9288760311a370171bfad5007bd84d1c50dcd1e8..c9ad5caecab1af44fea52c6e65e768d16edc18b4 100644 (file)
@@ -68,7 +68,7 @@ TEST(PCL_OctreeGPU, batchRadiusSearch)
     data.shared_radius = data.cube_size/30.f;
     data.printParams();
 
-    const int max_answers = 333;
+    constexpr int max_answers = 333;
 
     //generate
     data();
index 82fe839e492ba8e20714e5a3c473b607056f6c0f..6a57a6826625aa8d69691877aa4788ac5e4badf0 100644 (file)
@@ -12,6 +12,10 @@ if(NOT build)
   return()
 endif()
 
+PCL_ADD_TEST(timestamp test_timestamp
+              FILES test_timestamp.cpp
+              LINK_WITH pcl_gtest pcl_io)
+
 PCL_ADD_TEST(io_io test_io
               FILES test_io.cpp
               LINK_WITH pcl_gtest pcl_io)
index a7c794aad000a61d0350c11d3ce2c31906e0ac33..09185f9f8d23d4401b9f26aaa647079724ff4827 100644 (file)
@@ -522,7 +522,7 @@ int
   boost::filesystem::directory_iterator end_itr;
   for (boost::filesystem::directory_iterator itr (pcd_dir_); itr != end_itr; ++itr)
   {
-    if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+    if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
     {
       pcd_files_.push_back (itr->path ().string ());
       std::cout << "added: " << itr->path ().string () << std::endl;
index a534c29e677ed3371552581d2c7594e71985e962..53438b2e92f7d54f1eba7eddaddfa5c16f320e9a 100644 (file)
@@ -1379,6 +1379,74 @@ TEST (PCL, LZFExtended)
   remove ("test_pcl_io_compressed.pcd");
 }
 
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+TEST (PCL, WriteBinaryToOStream)
+{
+  PointCloud<PointXYZRGBNormal> cloud;
+  cloud.width  = 640;
+  cloud.height = 480;
+  cloud.resize (cloud.width * cloud.height);
+  cloud.is_dense = true;
+
+  srand (static_cast<unsigned int> (time (nullptr)));
+  const auto nr_p = cloud.size ();
+  // Randomly create a new point cloud
+  for (std::size_t i = 0; i < nr_p; ++i)
+  {
+    cloud[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].normal_x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].normal_y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].normal_z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].rgb = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+  }
+
+  pcl::PCLPointCloud2 blob;
+  pcl::toPCLPointCloud2 (cloud, blob);
+
+  std::ostringstream oss;
+  PCDWriter writer;
+  int res = writer.writeBinary (oss, blob);
+  EXPECT_EQ (res, 0);
+  std::string pcd_str = oss.str ();
+
+  Eigen::Vector4f origin;
+  Eigen::Quaternionf orientation;
+  int pcd_version = -1;
+  int data_type = -1;
+  unsigned int data_idx = 0;
+  std::istringstream iss (pcd_str, std::ios::binary);
+  PCDReader reader;
+  pcl::PCLPointCloud2 blob2;
+  res = reader.readHeader (iss, blob2, origin, orientation, pcd_version, data_type, data_idx);
+  EXPECT_EQ (res, 0);
+  EXPECT_EQ (blob2.width, blob.width);
+  EXPECT_EQ (blob2.height, blob.height);
+  EXPECT_EQ (data_type, 1); // since it was written by writeBinary (), it should be uncompressed.
+
+  const auto *data = reinterpret_cast<const unsigned char *> (pcd_str.data ());
+  res = reader.readBodyBinary (data, blob2, pcd_version, data_type == 2, data_idx);
+  PointCloud<PointXYZRGBNormal> cloud2;
+  pcl::fromPCLPointCloud2 (blob2, cloud2);
+  EXPECT_EQ (res, 0);
+  EXPECT_EQ (cloud2.width, blob.width);
+  EXPECT_EQ (cloud2.height, blob.height);
+  EXPECT_EQ (cloud2.is_dense, cloud.is_dense);
+  EXPECT_EQ (cloud2.size (), cloud.size ());
+
+  for (std::size_t i = 0; i < cloud2.size (); ++i)
+  {
+    EXPECT_EQ (cloud2[i].x, cloud[i].x);
+    EXPECT_EQ (cloud2[i].y, cloud[i].y);
+    EXPECT_EQ (cloud2[i].z, cloud[i].z);
+    EXPECT_EQ (cloud2[i].normal_x, cloud[i].normal_x);
+    EXPECT_EQ (cloud2[i].normal_y, cloud[i].normal_y);
+    EXPECT_EQ (cloud2[i].normal_z, cloud[i].normal_z);
+    EXPECT_EQ (cloud2[i].rgb, cloud[i].rgb);
+  }
+}
+
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST (PCL, LZFInMem)
 {
@@ -1451,27 +1519,29 @@ TEST (PCL, LZFInMem)
 TEST (PCL, Locale)
 {
 #ifndef __APPLE__
+  PointCloud<PointXYZ> cloud, cloud2, cloud3;
+  cloud.width  = 640;
+  cloud.height = 480;
+  cloud.resize (cloud.width * cloud.height);
+  cloud.is_dense = true;
+
+  srand (static_cast<unsigned int> (time (nullptr)));
+  const auto nr_p = cloud.size ();
+  // Randomly create a new point cloud
+  cloud[0].x = std::numeric_limits<float>::quiet_NaN ();
+  cloud[0].y = std::numeric_limits<float>::quiet_NaN ();
+  cloud[0].z = std::numeric_limits<float>::quiet_NaN ();
+
+  for (std::size_t i = 1; i < nr_p; ++i)
+  {
+    cloud[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+    cloud[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
+  }
+
+  // First write with German locale, then read with English locale
   try
   {
-    PointCloud<PointXYZ> cloud, cloud2;
-    cloud.width  = 640;
-    cloud.height = 480;
-    cloud.resize (cloud.width * cloud.height);
-    cloud.is_dense = true;
-
-    srand (static_cast<unsigned int> (time (nullptr)));
-    const auto nr_p = cloud.size ();
-    // Randomly create a new point cloud
-    cloud[0].x = std::numeric_limits<float>::quiet_NaN ();
-    cloud[0].y = std::numeric_limits<float>::quiet_NaN ();
-    cloud[0].z = std::numeric_limits<float>::quiet_NaN ();
-  
-    for (std::size_t i = 1; i < nr_p; ++i)
-    {
-      cloud[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
-      cloud[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
-      cloud[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
-    }
     PCDWriter writer;
     try
     {
@@ -1524,6 +1594,56 @@ TEST (PCL, Locale)
   }
 
   remove ("test_pcl_io_ascii_locale.pcd");
+
+  // Now write with English locale, then read with German locale
+  try
+  {
+#ifdef _WIN32
+    std::locale::global (std::locale ("English_US"));
+#else
+    std::locale::global (std::locale ("en_US.UTF-8"));
+#endif
+  }
+  catch (const std::runtime_error&)
+  {
+    PCL_WARN ("Failed to set locale, skipping test.\n");
+  }
+  PCDWriter writer;
+  int res = writer.writeASCII<PointXYZ> ("test_pcl_io_ascii_locale.pcd", cloud);
+  EXPECT_EQ (res, 0);
+
+  PCDReader reader;
+  try
+  {
+#ifdef _WIN32
+    std::locale::global (std::locale ("German_germany"));
+#else
+    std::locale::global (std::locale ("de_DE.UTF-8"));
+#endif
+  }
+  catch (const std::runtime_error&)
+  {
+    PCL_WARN ("Failed to set locale, skipping test.\n");
+  }
+  reader.read<PointXYZ> ("test_pcl_io_ascii_locale.pcd", cloud3);
+  std::locale::global (std::locale::classic ());
+
+  EXPECT_EQ (cloud3.width, cloud.width);
+  EXPECT_EQ (cloud3.height, cloud.height);
+  EXPECT_FALSE (cloud3.is_dense);
+  EXPECT_EQ (cloud3.size (), cloud.size ());
+
+  EXPECT_TRUE (std::isnan(cloud3[0].x));
+  EXPECT_TRUE (std::isnan(cloud3[0].y));
+  EXPECT_TRUE (std::isnan(cloud3[0].z));
+  for (std::size_t i = 1; i < cloud3.size (); ++i)
+  {
+    ASSERT_FLOAT_EQ (cloud3[i].x, cloud[i].x);
+    ASSERT_FLOAT_EQ (cloud3[i].y, cloud[i].y);
+    ASSERT_FLOAT_EQ (cloud3[i].z, cloud[i].z);
+  }
+
+  remove ("test_pcl_io_ascii_locale.pcd");
 #endif
 }
 
index c44cbd564bea8fe329f3204d2b16840addde9a22..d09c71e8ec2a5ea42ebd9c122ce70094067f5ab1 100644 (file)
@@ -59,7 +59,9 @@ TEST (PCL, Iterators)
 {
   Point mean (0,0,0);
 
-  for (auto it = cloud.begin(); it != cloud.end(); ++it) 
+  // Disable lint since this test is testing begin() and end()
+  // NOLINTNEXTLINE(modernize-loop-convert)
+  for (auto it = cloud.begin(); it != cloud.end(); ++it)
   {
     for (int i=0;i<3;i++) mean.data[i] += it->data[i];
   }
index 091e8ed82f0a0850bf9b3900b664fa005b8cce26..a044a33b07f0325b60c9b4b8a11b645a2840a43e 100644 (file)
@@ -53,19 +53,19 @@ char* pcd_file;
 template<typename PointT> inline PointT generateRandomPoint(const float MAX_XYZ);
 
 template<> inline pcl::PointXYZRGBA generateRandomPoint(const float MAX_XYZ) {
-  return pcl::PointXYZRGBA(static_cast<float> (MAX_XYZ * rand() / RAND_MAX),
+  return {static_cast<float> (MAX_XYZ * rand() / RAND_MAX),
                            static_cast<float> (MAX_XYZ * rand() / RAND_MAX),
                            static_cast<float> (MAX_XYZ * rand() / RAND_MAX),
-                           static_cast<int> (MAX_COLOR * rand() / RAND_MAX),
-                           static_cast<int> (MAX_COLOR * rand() / RAND_MAX),
-                           static_cast<int> (MAX_COLOR * rand() / RAND_MAX),
-                           static_cast<int> (MAX_COLOR * rand() / RAND_MAX));
+                           static_cast<std::uint8_t> (MAX_COLOR * rand() / RAND_MAX),
+                           static_cast<std::uint8_t> (MAX_COLOR * rand() / RAND_MAX),
+                           static_cast<std::uint8_t> (MAX_COLOR * rand() / RAND_MAX),
+                           static_cast<std::uint8_t> (MAX_COLOR * rand() / RAND_MAX)};
 }
 
 template<> inline pcl::PointXYZ generateRandomPoint(const float MAX_XYZ) {
-  return pcl::PointXYZ(static_cast<float> (MAX_XYZ * rand() / RAND_MAX),
+  return {static_cast<float> (MAX_XYZ * rand() / RAND_MAX),
                        static_cast<float> (MAX_XYZ * rand() / RAND_MAX),
-                       static_cast<float> (MAX_XYZ * rand() / RAND_MAX));
+                       static_cast<float> (MAX_XYZ * rand() / RAND_MAX)};
 }
 
 template<typename PointT> inline
@@ -94,7 +94,7 @@ TYPED_TEST (OctreeDeCompressionTest, RandomClouds)
     for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR;
       compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) {
       // instantiate point cloud compression encoder/decoder
-      pcl::io::OctreePointCloudCompression<TypeParam> pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false);
+      pcl::io::OctreePointCloudCompression<TypeParam> pointcloud_encoder(static_cast<pcl::io::compression_Profiles_e>(compression_profile), false);
       pcl::io::OctreePointCloudCompression<TypeParam> pointcloud_decoder;
       typename pcl::PointCloud<TypeParam>::Ptr cloud_out(new pcl::PointCloud<TypeParam>());
       // iterate over runs
@@ -124,13 +124,13 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBASameCloud)
 {
   // Generate a random cloud. Put it into the encoder several times and make
   // sure that the decoded cloud has correct width and height each time.
-  const double MAX_XYZ = 1.0;
+  constexpr double MAX_XYZ = 1.0;
   srand(static_cast<unsigned int> (time(nullptr)));
   // iterate over all pre-defined compression profiles
   for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR;
     compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) {
     // instantiate point cloud compression encoder/decoder
-    pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA> pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false);
+    pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA> pointcloud_encoder(static_cast<pcl::io::compression_Profiles_e>(compression_profile), false);
     pcl::io::OctreePointCloudCompression<pcl::PointXYZRGBA> pointcloud_decoder;
 
     auto cloud = generateRandomCloud<pcl::PointXYZRGBA>(MAX_XYZ);
@@ -173,12 +173,12 @@ TEST(PCL, OctreeDeCompressionFile)
   for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR;
        compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) {
     // instantiate point cloud compression encoder/decoder
-    pcl::io::OctreePointCloudCompression<pcl::PointXYZRGB> PointCloudEncoder((pcl::io::compression_Profiles_e) compression_profile, false);
+    pcl::io::OctreePointCloudCompression<pcl::PointXYZRGB> PointCloudEncoder(static_cast<pcl::io::compression_Profiles_e>(compression_profile), false);
     pcl::io::OctreePointCloudCompression<pcl::PointXYZRGB> PointCloudDecoder;
 
     // iterate over various voxel sizes
-    for (std::size_t i = 0; i < sizeof(voxel_sizes)/sizeof(voxel_sizes[0]); i++) {
-      pcl::octree::OctreePointCloud<pcl::PointXYZRGB> octree(voxel_sizes[i]);
+    for (const float& voxel_size : voxel_sizes) {
+      pcl::octree::OctreePointCloud<pcl::PointXYZRGB> octree(voxel_size);
       pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_out(new pcl::PointCloud<pcl::PointXYZRGB>());
       octree.setInputCloud((*input_cloud_ptr).makeShared());
       octree.addPointsFromInputCloud();
index 40bb4f2a0ab38e9bccb40394961e4b34e5cbdc71..c6472e245802aa327a79a3baa7fcc6a8bd940375 100644 (file)
@@ -80,10 +80,22 @@ TEST (PCL, PLYReaderWriter)
 
   // test for toPCLPointCloud2 ()
   pcl::PLYWriter writer;
-  writer.write ("test_pcl_io.ply", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), true, true);
+  const Eigen::Vector4f origin (0.0f, 0.5f, -1.0f, 0.0f);
+  const Eigen::Quaternionf orientation(std::sqrt(0.5f), std::sqrt(0.5f), 0.0f, 0.0f);
+  writer.write ("test_pcl_io.ply", cloud_blob, origin, orientation, true, true);
 
   pcl::PLYReader reader;
-  reader.read ("test_pcl_io.ply", cloud_blob2);
+  Eigen::Vector4f origin2;
+  Eigen::Quaternionf orientation2;
+  int ply_version;
+  reader.read ("test_pcl_io.ply", cloud_blob2, origin2, orientation2, ply_version);
+  EXPECT_NEAR (origin.x(), origin2.x(), 1e-5);
+  EXPECT_NEAR (origin.y(), origin2.y(), 1e-5);
+  EXPECT_NEAR (origin.z(), origin2.z(), 1e-5);
+  EXPECT_NEAR (orientation.x(), orientation2.x(), 1e-5);
+  EXPECT_NEAR (orientation.y(), orientation2.y(), 1e-5);
+  EXPECT_NEAR (orientation.z(), orientation2.z(), 1e-5);
+  EXPECT_NEAR (orientation.w(), orientation2.w(), 1e-5);
   //PLY DOES preserve organiziation
   EXPECT_EQ (cloud_blob.width * cloud_blob.height, cloud_blob2.width * cloud_blob2.height);
   EXPECT_EQ (cloud_blob.is_dense, cloud.is_dense);
@@ -105,6 +117,7 @@ TEST (PCL, PLYReaderWriter)
     EXPECT_FLOAT_EQ (cloud[counter].z, cloud2[counter].z);     // test for fromPCLPointCloud2 ()
     EXPECT_FLOAT_EQ (cloud[counter].intensity, cloud2[counter].intensity);  // test for fromPCLPointCloud2 ()
   }
+  remove ("test_pcl_io.ply");
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -160,25 +173,25 @@ struct PLYColorTest : public PLYTest
           "property list uchar int vertex_indices\n"
           "end_header\n"
           "4.23607 0 1.61803 "
-            << unsigned (clr_1_.r) << ' '
-            << unsigned (clr_1_.g) << ' '
-            << unsigned (clr_1_.b) << ' '
-            << unsigned (clr_1_.a) << "\n"
+            << static_cast<unsigned>(clr_1_.r) << ' '
+            << static_cast<unsigned>(clr_1_.g) << ' '
+            << static_cast<unsigned>(clr_1_.b) << ' '
+            << static_cast<unsigned>(clr_1_.a) << "\n"
           "2.61803 2.61803 2.61803 "
-            << unsigned (clr_2_.r) << ' '
-            << unsigned (clr_2_.g) << ' '
-            << unsigned (clr_2_.b) << ' '
-            << unsigned (clr_2_.a) << "\n"
+            << static_cast<unsigned>(clr_2_.r) << ' '
+            << static_cast<unsigned>(clr_2_.g) << ' '
+            << static_cast<unsigned>(clr_2_.b) << ' '
+            << static_cast<unsigned>(clr_2_.a) << "\n"
           "0 1.61803 4.23607 "
-            << unsigned (clr_3_.r) << ' '
-            << unsigned (clr_3_.g) << ' '
-            << unsigned (clr_3_.b) << ' '
-            << unsigned (clr_3_.a) << "\n"
+            << static_cast<unsigned>(clr_3_.r) << ' '
+            << static_cast<unsigned>(clr_3_.g) << ' '
+            << static_cast<unsigned>(clr_3_.b) << ' '
+            << static_cast<unsigned>(clr_3_.a) << "\n"
           "0 -1.61803 4.23607 "
-            << unsigned (clr_4_.r) << ' '
-            << unsigned (clr_4_.g) << ' '
-            << unsigned (clr_4_.b) << ' '
-            << unsigned (clr_4_.a) << "\n"
+            << static_cast<unsigned>(clr_4_.r) << ' '
+            << static_cast<unsigned>(clr_4_.g) << ' '
+            << static_cast<unsigned>(clr_4_.b) << ' '
+            << static_cast<unsigned>(clr_4_.a) << "\n"
           "3 0 1 2\n"
           "3 1 2 3\n";
     fs.close ();
@@ -567,6 +580,7 @@ TEST_F (PLYTest, Float64Cloud)
 
   // create file
   std::ofstream fs;
+  fs.imbue (std::locale::classic ()); // make sure that floats are printed with decimal point
   fs.open (mesh_file_ply_.c_str ());
   fs << "ply\n"
         "format ascii 1.0\n"
@@ -590,7 +604,7 @@ TEST_F (PLYTest, Float64Cloud)
   }
   for (size_t pointIdx = 0; pointIdx < cloud.size(); ++pointIdx)
   {
-    unsigned char const * ptr = &cloud2.data[0] + pointIdx*cloud2.point_step;
+    unsigned char const * ptr = cloud2.data.data() + pointIdx*cloud2.point_step;
     double xValue, yValue, zValue;
     memcpy(
         reinterpret_cast<char*>(&xValue),
index fae86a9324ffb0474cd4887581940184fbe42462..ab069b81053c422ed5fb96ba8cbf7891b1e32c4f 100644 (file)
@@ -293,9 +293,9 @@ TEST (PCL, PLYPolygonMeshSpecificFieldOrder)
   add_field(mesh.cloud.fields, "rgba", 24, pcl::PCLPointField::PointFieldTypes::UINT32);
   mesh.cloud.height = mesh.cloud.width = 1;
   mesh.cloud.data.resize(28);
-  const float x = 0.0, y = 1.0, z = 2.0, normal_x = 1.0, normal_y = 0.0, normal_z = 0.0;
-  const std::uint32_t rgba = 0x326496;
-  memcpy(&mesh.cloud.data[0], &x, sizeof(float));
+  constexpr float x = 0.0, y = 1.0, z = 2.0, normal_x = 1.0, normal_y = 0.0, normal_z = 0.0;
+  constexpr std::uint32_t rgba = 0x326496;
+  memcpy(&mesh.cloud.data[0], &x, sizeof(float)); // NOLINT(readability-container-data-pointer)
   memcpy(&mesh.cloud.data[4], &y, sizeof(float));
   memcpy(&mesh.cloud.data[8], &z, sizeof(float));
   memcpy(&mesh.cloud.data[12], &normal_x, sizeof(float));
index 5c5e58dc3768591da97be56e20771447c9bf8096..c34c2f8056cef9fd97a03a882454be533564747a 100644 (file)
@@ -178,7 +178,7 @@ TEST (PCL, PointCloudImageExtractorFromLabelFieldMono)
   pcie.setColorMode (pcie.COLORS_MONO);
 
   ASSERT_TRUE (pcie.extract (cloud, image));
-  auto* data = reinterpret_cast<unsigned short*> (&image.data[0]);
+  auto* data = reinterpret_cast<unsigned short*> (image.data.data());
 
   EXPECT_EQ ("mono16", image.encoding);
   EXPECT_EQ (cloud.width, image.width);
@@ -279,7 +279,7 @@ TEST (PCL, PointCloudImageExtractorFromZField)
   PointCloudImageExtractorFromZField<PointT> pcie;
 
   ASSERT_TRUE (pcie.extract (cloud, image));
-  auto* data = reinterpret_cast<unsigned short*> (&image.data[0]);
+  auto* data = reinterpret_cast<unsigned short*> (image.data.data());
 
   EXPECT_EQ ("mono16", image.encoding);
   EXPECT_EQ (cloud.width, image.width);
@@ -309,7 +309,7 @@ TEST (PCL, PointCloudImageExtractorFromCurvatureField)
   PointCloudImageExtractorFromCurvatureField<PointT> pcie;
 
   ASSERT_TRUE (pcie.extract (cloud, image));
-  auto* data = reinterpret_cast<unsigned short*> (&image.data[0]);
+  auto* data = reinterpret_cast<unsigned short*> (image.data.data());
 
   EXPECT_EQ ("mono16", image.encoding);
   EXPECT_EQ (cloud.width, image.width);
@@ -341,7 +341,7 @@ TEST (PCL, PointCloudImageExtractorFromIntensityField)
   PointCloudImageExtractorFromIntensityField<PointT> pcie;
 
   ASSERT_TRUE (pcie.extract (cloud, image));
-  auto* data = reinterpret_cast<unsigned short*> (&image.data[0]);
+  auto* data = reinterpret_cast<unsigned short*> (image.data.data());
 
   EXPECT_EQ ("mono16", image.encoding);
   EXPECT_EQ (cloud.width, image.width);
@@ -412,7 +412,7 @@ TEST (PCL, PointCloudImageExtractorBlackNaNs)
   ASSERT_TRUE (pcie.extract (cloud, image));
 
   {
-    auto* data = reinterpret_cast<unsigned short*> (&image.data[0]);
+    auto* data = reinterpret_cast<unsigned short*> (image.data.data());
     EXPECT_EQ (std::numeric_limits<unsigned short>::max (), data[3]);
   }
 
@@ -421,7 +421,7 @@ TEST (PCL, PointCloudImageExtractorBlackNaNs)
   ASSERT_TRUE (pcie.extract (cloud, image));
 
   {
-    auto* data = reinterpret_cast<unsigned short*> (&image.data[0]);
+    auto* data = reinterpret_cast<unsigned short*> (image.data.data());
     EXPECT_EQ (0, data[3]);
   }
 }
index c17fd738c115ca9d10e7675a7a2d3f23ce95a8a9..543a55ae197db1cf10904e0159c6833904bfb4d4 100644 (file)
@@ -58,7 +58,7 @@ TEST (PCL, Adaptive_Range_Coder_Test)
   unsigned long readByteLen;
 
   // vector size
-  const unsigned int vectorSize = 10000;
+  constexpr unsigned int vectorSize = 10000;
 
   inputData.resize(vectorSize);
   outputData.resize(vectorSize);
index f245e0c762ffb342aa02f00b259b70633aec1d56..f846f7656eb2267f15b782c9489b29ee49e390c2 100644 (file)
@@ -89,9 +89,9 @@ TEST_F (TimGrabberTest, Test1)
     for (std::size_t j = 0; j < correct_clouds_.at(i).size (); j++) {
       PointT const& correct_point = correct_clouds_.at(i).at(j);
       PointT const& answer_point = answer_cloud->at(j);
-      EXPECT_NEAR (correct_point.x, answer_point.x, 1.0e-3);
-      EXPECT_NEAR (correct_point.y, answer_point.y, 1.0e-3);
-      EXPECT_NEAR (correct_point.z, answer_point.z, 1.0e-3);
+      EXPECT_NEAR (correct_point.x, answer_point.x, 2.0e-3);
+      EXPECT_NEAR (correct_point.y, answer_point.y, 2.0e-3);
+      EXPECT_NEAR (correct_point.z, answer_point.z, 2.0e-3);
     }
   }
 }
diff --git a/test/io/test_timestamp.cpp b/test/io/test_timestamp.cpp
new file mode 100644 (file)
index 0000000..a9f3182
--- /dev/null
@@ -0,0 +1,64 @@
+#include <pcl/io/timestamp.h>
+#include <pcl/test/gtest.h>
+
+std::string
+getTimeOffset()
+{
+  // local offset
+  auto offset_hour = std::localtime(new time_t(0))->tm_hour;
+  std::ostringstream ss;
+  ss << std::setfill('0') << std::setw(2) << offset_hour;
+
+  return ss.str();
+}
+
+TEST(PCL, TestTimestampGeneratorZeroFraction)
+{
+  const std::chrono::time_point<std::chrono::system_clock> time;
+
+  const auto timestamp = pcl::getTimestamp(time);
+
+  EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000");
+}
+
+TEST(PCL, TestTimestampGeneratorWithFraction)
+{
+  const std::chrono::microseconds dur(123456);
+  const std::chrono::time_point<std::chrono::system_clock> dt(dur);
+
+  const auto timestamp = pcl::getTimestamp(dt);
+
+  EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.123456");
+}
+
+TEST(PCL, TestTimestampGeneratorWithSmallFraction)
+{
+  const std::chrono::microseconds dur(123);
+  const std::chrono::time_point<std::chrono::system_clock> dt(dur);
+
+  const auto timestamp = pcl::getTimestamp(dt);
+
+  EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.000123");
+}
+
+TEST(PCL, TestParseTimestamp)
+{
+  const std::chrono::time_point<std::chrono::system_clock> timepoint(std::chrono::system_clock::now());
+
+  const auto timestamp = pcl::getTimestamp(timepoint);
+
+  const auto parsedTimepoint = pcl::parseTimestamp(timestamp);
+
+  const auto diff = std::chrono::duration<double,std::milli>(timepoint - parsedTimepoint).count();
+
+  EXPECT_LT(diff, 1e-3);
+}
+
+/* ---[ */
+int
+main(int argc, char** argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  return (RUN_ALL_TESTS());
+}
+/* ]--- */
index 903b889c5ed0ac8e593691df0ca96e95f96869e7..a13ac9d7bcf65c2142417f418eab8834b89cc1aa 100644 (file)
@@ -242,7 +242,7 @@ TEST (PCL, KdTreeFLANN_setPointRepresentation)
   MyPoint p (50.0f, 50.0f, 50.0f);
   
   // Find k nearest neighbors
-  const int k = 10;
+  constexpr int k = 10;
   pcl::Indices k_indices (k);
   std::vector<float> k_distances (k);
   kdtree.nearestKSearch (p, k, k_indices, k_distances);
@@ -310,7 +310,7 @@ TEST (PCL, KdTreeFLANN_32_vs_64_bit)
   for (std::size_t vec_i = 0; vec_i < nn_indices_vector.size (); ++vec_i)
   {
     char str[512];
-    sprintf (str, "point_%d", int (vec_i));
+    sprintf (str, "point_%d", static_cast<int>(vec_i));
     boost::optional<boost::property_tree::ptree&> tree = xml_property_tree.get_child_optional (str);
     if (!tree)
       FAIL ();
@@ -320,7 +320,7 @@ TEST (PCL, KdTreeFLANN_32_vs_64_bit)
 
     for (std::size_t n_i = 0; n_i < nn_indices_vector[vec_i].size (); ++n_i)
     {
-      sprintf (str, "nn_%d", int (n_i));
+      sprintf (str, "nn_%d", static_cast<int>(n_i));
       int neighbor_index = tree.get ().get<int> (str);
       EXPECT_EQ (neighbor_index, nn_indices_vector[vec_i][n_i]);
     }
index eff8cb42c9b60da90fd4a9d877d07407bc6ff2cd..14bbe71772a7c4147203d4eda8efb089dbee2359 100644 (file)
@@ -74,7 +74,7 @@ TEST (PCL, ISSKeypoint3D_WBE)
   //
   // Compare to previously validated output
   //
-  const std::size_t correct_nr_keypoints = 6;
+  constexpr std::size_t correct_nr_keypoints = 6;
   const float correct_keypoints[correct_nr_keypoints][3] =
     {
       // { x,  y,  z}
@@ -130,7 +130,7 @@ TEST (PCL, ISSKeypoint3D_BE)
   //
   // Compare to previously validated output
   //
-  const std::size_t correct_nr_keypoints = 5;
+  constexpr std::size_t correct_nr_keypoints = 5;
   const float correct_keypoints[correct_nr_keypoints][3] =
     {
       // { x,  y,  z}
index a65887826c1e82b9ad25db53add528058deb3166..a845d3969704d20d33283ef39f56a70e3a31b63c 100644 (file)
@@ -99,7 +99,7 @@ TEST (PCL, SIFTKeypoint)
   ASSERT_EQ (keypoints.height, 1);
 
   // Compare to previously validated output
-  const std::size_t correct_nr_keypoints = 5;
+  constexpr std::size_t correct_nr_keypoints = 5;
   const float correct_keypoints[correct_nr_keypoints][4] = 
     { 
       // { x,  y,  z,  scale }
@@ -123,14 +123,14 @@ TEST (PCL, SIFTKeypoint)
 
 TEST (PCL, SIFTKeypoint_radiusSearch)
 {
-  const int nr_scales_per_octave = 3;
-  const float scale = 0.02f;
+  constexpr int nr_scales_per_octave = 3;
+  constexpr float scale = 0.02f;
 
   KdTreeFLANN<PointXYZI>::Ptr tree_ (new KdTreeFLANN<PointXYZI>);
   auto cloud = cloud_xyzi->makeShared ();
 
   ApproximateVoxelGrid<PointXYZI> voxel_grid;
-  const float s = 1.0 * scale;
+  constexpr float s = 1.0 * scale;
   voxel_grid.setLeafSize (s, s, s);
   voxel_grid.setInputCloud (cloud);
   voxel_grid.filter (*cloud);
@@ -138,12 +138,11 @@ TEST (PCL, SIFTKeypoint_radiusSearch)
   
   const PointCloud<PointXYZI> & input = *cloud;
   KdTreeFLANN<PointXYZI> & tree = *tree_;
-  const float base_scale = scale;
 
   std::vector<float> scales (nr_scales_per_octave + 3);
   for (int i_scale = 0; i_scale <= nr_scales_per_octave + 2; ++i_scale)
   {
-    scales[i_scale] = base_scale * std::pow (2.0f, static_cast<float> (i_scale-1) / nr_scales_per_octave);
+    scales[i_scale] = scale * std::pow (2.0f, static_cast<float> (i_scale-1) / nr_scales_per_octave);
   }
   Eigen::MatrixXf diff_of_gauss;
 
@@ -151,9 +150,9 @@ TEST (PCL, SIFTKeypoint_radiusSearch)
   std::vector<float> nn_dist;
   diff_of_gauss.resize (input.size (), scales.size () - 1);
 
-  const float max_radius = 0.10f;
+  constexpr float max_radius = 0.10f;
 
-  const std::size_t i_point = 500;
+  constexpr std::size_t i_point = 500;
   tree.radiusSearch (i_point, max_radius, nn_indices, nn_dist);
 
   // Are they all unique?
index e1502480a5a8dc3fdc57dc63937051be03b11538..7fbd7bb0925947f53d2544d09ab9ae42121b139b 100644 (file)
@@ -555,7 +555,7 @@ TEST (PCL, Octree2Buf_Base_Double_Buffering_Test)
 
   srand (static_cast<unsigned int> (time (nullptr)));
 
-  const unsigned int test_runs = 20;
+  constexpr unsigned int test_runs = 20;
 
   for (unsigned int j = 0; j < test_runs; j++)
   {
@@ -636,7 +636,7 @@ TEST (PCL, Octree2Buf_Base_Double_Buffering_XOR_Test)
 
   srand (static_cast<unsigned int> (time (nullptr)));
 
-  const unsigned int test_runs = 15;
+  constexpr unsigned int test_runs = 15;
 
   for (unsigned int j = 0; j < test_runs; j++)
   {
@@ -1538,7 +1538,7 @@ TEST (PCL, Octree_Pointcloud_Ray_Traversal)
     {
       pt = (*cloudIn)[i];
       d = Eigen::Vector3f (pt.x, pt.y, pt.z) - o;
-      ASSERT_GE (d.norm (), min_dist);
+      ASSERT_GE (d.norm (), 0.999 * min_dist);
     }
   }
 }
@@ -1616,10 +1616,10 @@ TEST (PCL, Octree_Pointcloud_Adjacency)
 
 TEST (PCL, Octree_Pointcloud_Bounds)
 {
-    const double SOME_RESOLUTION (10 + 1/3.0);
-    const int SOME_DEPTH (4);
-    const double DESIRED_MAX = ((1<<SOME_DEPTH) + 0.5)*SOME_RESOLUTION;
-    const double DESIRED_MIN = 0;
+    constexpr double SOME_RESOLUTION (10 + 1/3.0);
+    constexpr int SOME_DEPTH (4);
+    constexpr double DESIRED_MAX = ((1 << SOME_DEPTH) + 0.5) * SOME_RESOLUTION;
+    constexpr double DESIRED_MIN = 0;
 
     OctreePointCloud<PointXYZ> tree (SOME_RESOLUTION);
     tree.defineBoundingBox (DESIRED_MIN, DESIRED_MIN, DESIRED_MIN, DESIRED_MAX, DESIRED_MAX, DESIRED_MAX);
@@ -1630,8 +1630,8 @@ TEST (PCL, Octree_Pointcloud_Bounds)
     ASSERT_GE (max_x, DESIRED_MAX);
     ASSERT_GE (DESIRED_MIN, min_x);
 
-    const double LARGE_MIN = 1e7-45*SOME_RESOLUTION;
-    const double LARGE_MAX = 1e7-5*SOME_RESOLUTION;
+    constexpr double LARGE_MIN = 1e7 - 45 * SOME_RESOLUTION;
+    constexpr double LARGE_MAX = 1e7 - 5 * SOME_RESOLUTION;
     tree.defineBoundingBox (LARGE_MIN, LARGE_MIN, LARGE_MIN, LARGE_MAX, LARGE_MAX, LARGE_MAX);
     tree.getBoundingBox (min_x, min_y, min_z, max_x, max_y, max_z);
     const auto depth = tree.getTreeDepth ();
index 0f91a74aa3c33827be34aaa748b98732b6ce36a7..a7fbb988cdb63e37c17724ecbe89127c3873d81c 100644 (file)
@@ -1259,12 +1259,12 @@ struct OctreePointCloudAdjacencyBeginEndIteratorsTest
 
     // Generate Point Cloud
     typename PointCloudT::Ptr cloud (new PointCloudT (100, 1));
-    const float max_inv = 1.f / float (RAND_MAX);
+    constexpr float max_inv = 1.f / static_cast<float>(RAND_MAX);
     for (std::size_t i = 0; i < 100; ++i)
     {
-      const PointT pt (10.f * (float (std::rand ()) * max_inv - .5f),
-                       10.f * (float (std::rand ()) * max_inv - .5f),
-                       10.f * (float (std::rand ()) * max_inv - .5f));
+      const PointT pt (10.f * (static_cast<float>(std::rand ()) * max_inv - .5f),
+                       10.f * (static_cast<float>(std::rand ()) * max_inv - .5f),
+                       10.f * (static_cast<float>(std::rand ()) * max_inv - .5f));
       (*cloud)[i] = pt;
     }
 
@@ -1467,7 +1467,6 @@ struct OctreePointCloudSierpinskiTest
   // Methods
   OctreePointCloudSierpinskiTest ()
     : oct_ (1)
-    , depth_ (7)
   {}
 
   void SetUp () override
@@ -1484,7 +1483,7 @@ struct OctreePointCloudSierpinskiTest
     std::vector<std::pair<Eigen::Vector3f, Eigen::Vector3f> > voxels (generateSierpinskiVoxelExtremities (v_min, v_max, depth_));
 
     // The number of points in each voxel
-    unsigned int total_nb_pt = 100000;
+    constexpr unsigned int total_nb_pt = 100000;
     unsigned int nb_pt_in_voxel = total_nb_pt / pow (4, depth_);
 
     // Replicable results
@@ -1493,7 +1492,7 @@ struct OctreePointCloudSierpinskiTest
     // Fill the point cloud
     for (const auto& voxel : voxels)
     {
-      const static float eps = std::numeric_limits<float>::epsilon ();
+      constexpr float eps = std::numeric_limits<float>::epsilon ();
       double x_min = voxel.first.x () + eps;
       double y_min = voxel.first.y () + eps;
       double z_min = voxel.first.z () + eps;
@@ -1503,9 +1502,9 @@ struct OctreePointCloudSierpinskiTest
 
       for (unsigned int i = 0; i < nb_pt_in_voxel; ++i)
       {
-        float x = x_min + (rand () / ((float)(RAND_MAX) + 1)) * (x_max - x_min);
-        float y = y_min + (rand () / ((float)(RAND_MAX) + 1)) * (y_max - y_min);
-        float z = z_min + (rand () / ((float)(RAND_MAX) + 1)) * (z_max - z_min);
+        float x = x_min + (rand () / (static_cast<float>(RAND_MAX) + 1)) * (x_max - x_min);
+        float y = y_min + (rand () / (static_cast<float>(RAND_MAX) + 1)) * (y_max - y_min);
+        float z = z_min + (rand () / (static_cast<float>(RAND_MAX) + 1)) * (z_max - z_min);
 
         cloud->points.emplace_back(x, y, z);
       }
@@ -1581,7 +1580,7 @@ struct OctreePointCloudSierpinskiTest
   /** \brief Computes the total number of parent nodes at the specified depth
     *
     * The octree is built such that the number of the leaf nodes is equal to
-    * 4^depth and the number of branch nodes is egal to (4^depth -1)/(4 - 1),
+    * 4^depth and the number of branch nodes is equal to (4^depth -1)/(4 - 1),
     * where depth is the detph of the octree. The details of the expression
     * provided for the number of branch nodes could be found at:
     * https://en.wikipedia.org/wiki/Geometric_progression#Geometric_series
@@ -1597,7 +1596,7 @@ struct OctreePointCloudSierpinskiTest
   // Members
   OctreeT oct_;
 
-  const unsigned depth_;
+  const unsigned depth_{7};
 };
 
 /** \brief Octree test based on a Sierpinski fractal
index 0abba40b02520b6950071af08be47e15b5738ffc..cb5cfff4aca489bf029e8713f175635bad8d1071 100644 (file)
@@ -67,7 +67,7 @@ using namespace pcl::outofcore;
 
 // For doing exhaustive checks this is set low remove those, and this can be
 // set much higher
-const static std::uint64_t numPts (10000);
+constexpr std::uint64_t numPts (10000);
 
 constexpr std::uint32_t rngseed = 0xAAFF33DD;
 
@@ -394,7 +394,7 @@ class OutofcoreTest : public testing::Test
 {
   protected:
 
-    OutofcoreTest () : smallest_voxel_dim () {}
+    OutofcoreTest () = default;
 
     void SetUp () override
     {
@@ -420,7 +420,7 @@ class OutofcoreTest : public testing::Test
 
     }
 
-    double smallest_voxel_dim;
+    double smallest_voxel_dim{3.0f};
 
 };
 
@@ -702,7 +702,7 @@ TEST_F (OutofcoreTest, PointCloud2_Constructors)
   const Eigen::Vector3d min (-100.1, -100.1, -100.1);
   const Eigen::Vector3d max (100.1, 100.1, 100.1);
   
-  const std::uint64_t depth = 2;
+  constexpr std::uint64_t depth = 2;
   
   //create a point cloud
   pcl::PointCloud<PointT>::Ptr test_cloud (new pcl::PointCloud<PointT> ());
@@ -833,7 +833,7 @@ TEST_F (OutofcoreTest, PointCloud2_QueryBoundingBox)
   const Eigen::Vector3d min (-100.1, -100.1, -100.1);
   const Eigen::Vector3d max (100.1, 100.1, 100.1);
   
-  const std::uint64_t depth = 2;
+  constexpr std::uint64_t depth = 2;
 
   //create a point cloud
   pcl::PointCloud<PointT>::Ptr test_cloud (new pcl::PointCloud<PointT> ());
@@ -885,7 +885,7 @@ TEST_F (OutofcoreTest, PointCloud2_Query)
   const Eigen::Vector3d min (-100.1, -100.1, -100.1);
   const Eigen::Vector3d max (100.1, 100.1, 100.1);
   
-  const std::uint64_t depth = 2;
+  constexpr std::uint64_t depth = 2;
   
   //create a point cloud
   pcl::PointCloud<PointT>::Ptr test_cloud (new pcl::PointCloud<PointT> ());
@@ -920,7 +920,7 @@ TEST_F (OutofcoreTest, PointCloud2_Query)
   pcl::PCLPointCloud2::Ptr query_result_a (new pcl::PCLPointCloud2 ());
   pcl::PCLPointCloud2::Ptr query_result_b (new pcl::PCLPointCloud2 ());
 
-  octreeA.queryBBIncludes (min, max, int (octreeA.getDepth ()), query_result_a);
+  octreeA.queryBBIncludes (min, max, static_cast<int>(octreeA.getDepth ()), query_result_a);
   
   EXPECT_EQ (test_cloud->width*test_cloud->height, query_result_a->width*query_result_a->height) << "PCLPointCloud2 Query number of points returned failed\n";
 
index 7fa655c8b97b2c9d8b25a47253adb3fdcf5d65b3..c6208b1440345616959c1ddc477c94f89f05b102 100644 (file)
@@ -93,7 +93,7 @@ computeRmsE (const PointCloud<PointType>::ConstPtr &model, const PointCloud<Poin
   }
 
   if (found_points > 0)
-    return sqrt (sqr_norm_sum / double (transformed_model.size ()));
+    return sqrt (sqr_norm_sum / static_cast<double>(transformed_model.size ()));
 
   return std::numeric_limits<double>::max ();
 }
index 2192f3d78c0e983e3928a6825ebc1a46c2138419..b251dd974c49d74d02a0e0ec438f26a15dc5e4a8 100644 (file)
 #include <pcl/features/normal_3d.h>
 #include <pcl/kdtree/kdtree.h>
 
+#include <utility>
+
+namespace
+{
+
+template <typename PointT>
+PointT makeRandomPoint()
+{
+  return PointT{};
+}
+
+template <>
+pcl::PointXYZ makeRandomPoint()
+{
+  return {static_cast<float>(rand()), static_cast<float>(rand()), static_cast<float>(rand())};
+}
+
+template <>
+pcl::PointXYZI makeRandomPoint()
+{
+  return {static_cast<float>(rand()), static_cast<float>(rand()), static_cast<float>(rand()), static_cast<float>(rand())};
+}
+
+template <typename PointT, typename... Args>
+PointT makePointWithParams(Args... args)
+{
+  return PointT{ args... };
+}
+
+template <>
+pcl::PointXYZ makePointWithParams(float x, float y, float z)
+{
+  return {x, y, z};
+}
+
+template <>
+pcl::PointXYZI makePointWithParams(float x, float y, float z)
+{
+  return {x, y, z, static_cast<float>(rand())};
+}
+
+}
+
+template <typename T>
+class CorrespondenceEstimationTestSuite : public ::testing::Test { };
+
+using PointTypesForCorrespondenceEstimationTest = 
+  ::testing::Types<std::pair<pcl::PointXYZ, pcl::PointXYZ>, std::pair<pcl::PointXYZ, pcl::PointXYZI>>;
+
+TYPED_TEST_SUITE(CorrespondenceEstimationTestSuite, PointTypesForCorrespondenceEstimationTest);
+
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-TEST (CorrespondenceEstimation, CorrespondenceEstimationNormalShooting)
+TYPED_TEST(CorrespondenceEstimationTestSuite, CorrespondenceEstimationNormalShooting)
 {
-  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud1 (new pcl::PointCloud<pcl::PointXYZ> ());
-  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2 (new pcl::PointCloud<pcl::PointXYZ> ());
+  using PointSource = typename TypeParam::first_type;
+  using PointTarget = typename TypeParam::second_type;
+
+  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
-  for (float i = 0.0f; i < 10.0f; i += 0.2f)
+  for (std::size_t i = 0; i < 50; ++i)
   {
-    for (float z = 0.0f; z < 5.0f; z += 0.2f)
+    for (std::size_t j = 0; j < 25; ++j)
     {
-      cloud1->points.emplace_back(i, 0, z);
-      cloud2->points.emplace_back(i, 2, z); // Ideally this should be the corresponding point to the point defined in the previous line
+      cloud1->push_back(makePointWithParams<PointSource>(i * 0.2f, 0.f, j * 0.2f));
+      cloud2->push_back(makePointWithParams<PointTarget>(i * 0.2f, 2.f, j * 0.2f)); // Ideally this should be the corresponding point to the point defined in the previous line
     }
   }
         
-  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
+  pcl::NormalEstimation<PointSource, pcl::Normal> ne;
   ne.setInputCloud (cloud1); 
 
-  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());
+  auto tree (pcl::make_shared<pcl::search::KdTree<PointSource>> ());
   ne.setSearchMethod (tree);
 
-  pcl::PointCloud<pcl::Normal>::Ptr cloud1_normals (new pcl::PointCloud<pcl::Normal>);
+  auto cloud1_normals (pcl::make_shared<pcl::PointCloud<pcl::Normal>> ());
   ne.setKSearch (5);
   ne.compute (*cloud1_normals); // All normals are perpendicular to the plane defined
 
-  pcl::CorrespondencesPtr corr (new pcl::Correspondences);
-  pcl::registration::CorrespondenceEstimationNormalShooting <pcl::PointXYZ, pcl::PointXYZ, pcl::Normal> ce;
+  auto corr (pcl::make_shared<pcl::Correspondences> ());
+  pcl::registration::CorrespondenceEstimationNormalShooting <PointSource, PointTarget, pcl::Normal> ce;
   ce.setInputSource (cloud1);
   ce.setKSearch (10);
   ce.setSourceNormals (cloud1_normals);
@@ -83,23 +137,25 @@ TEST (CorrespondenceEstimation, CorrespondenceEstimationNormalShooting)
 }
 
 //////////////////////////////////////////////////////////////////////////////////////
-TEST (CorrespondenceEstimation, CorrespondenceEstimationSetSearchMethod)
+TYPED_TEST (CorrespondenceEstimationTestSuite, CorrespondenceEstimationSetSearchMethod)
 {
+  using PointSource = typename TypeParam::first_type;
+  using PointTarget = typename TypeParam::second_type;
   // Generating 3 random clouds
-  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud1 (new pcl::PointCloud<pcl::PointXYZ> ());
-  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2 (new pcl::PointCloud<pcl::PointXYZ> ());
-  for ( std::size_t i = 0; i < 50; i++ )
+  auto cloud1 (pcl::make_shared<pcl::PointCloud<PointSource>> ());
+  auto cloud2 (pcl::make_shared<pcl::PointCloud<PointTarget>> ());
+  for (std::size_t i = 0; i < 50; i++)
   {
-    cloud1->points.emplace_back(float (rand()), float (rand()), float (rand()));
-    cloud2->points.emplace_back(float (rand()), float (rand()), float (rand()));
+    cloud1->push_back(makeRandomPoint<PointSource>());
+    cloud2->push_back(makeRandomPoint<PointTarget>());
   }
   // Build a KdTree for each
-  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree1 (new pcl::search::KdTree<pcl::PointXYZ> ());
+  auto tree1 (pcl::make_shared<pcl::search::KdTree<PointSource>> ());
   tree1->setInputCloud (cloud1);
-  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree2 (new pcl::search::KdTree<pcl::PointXYZ> ());
+  auto tree2 (pcl::make_shared<pcl::search::KdTree<PointTarget>> ());
   tree2->setInputCloud (cloud2);
   // Compute correspondences
-  pcl::registration::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ, double> ce;
+  pcl::registration::CorrespondenceEstimation<PointSource, PointTarget, double> ce;
   ce.setInputSource (cloud1);
   ce.setInputTarget (cloud2);
   pcl::Correspondences corr_orig;
index 4a6bc105ee27c68865b272cd7587b162a02abcde..0e06cfb869eb72eac4f4d4fb2e2dc0da16010f1c 100644 (file)
@@ -92,7 +92,7 @@ TEST (CorrespondenceRejectors, CorrespondenceRejectionPoly)
   // Transform the target
   pcl::PointCloud<pcl::PointXYZ>::Ptr target(new pcl::PointCloud<pcl::PointXYZ>);
   Eigen::Vector3f t(0.1f, 0.2f, 0.3f);
-  Eigen::Quaternionf q (float (std::cos (0.5*M_PI_4)), 0.0f, 0.0f, float (std::sin (0.5*M_PI_4)));
+  Eigen::Quaternionf q (static_cast<float>(std::cos (0.5*M_PI_4)), 0.0f, 0.0f, static_cast<float>(std::sin (0.5*M_PI_4)));
   pcl::transformPointCloud (*cloud, *target, t, q);
   
   // Noisify the target with a known seed and N(0, 0.005) using deterministic sampling
@@ -121,8 +121,8 @@ TEST (CorrespondenceRejectors, CorrespondenceRejectionPoly)
   reject.getRemainingCorrespondences (corr, result);
   
   // Ground truth fraction of inliers and estimated fraction of inliers
-  const float ground_truth_frac = float (size-last) / float (size);
-  const float accepted_frac = float (result.size()) / float (size);
+  const float ground_truth_frac = static_cast<float>(size-last) / static_cast<float>(size);
+  const float accepted_frac = static_cast<float>(result.size()) / static_cast<float>(size);
 
   /*
    * Test criterion 1: verify that the method accepts at least 25 % of the input correspondences,
@@ -143,8 +143,8 @@ TEST (CorrespondenceRejectors, CorrespondenceRejectionPoly)
       ++true_positives;
   const std::size_t false_positives = result.size() - true_positives;
 
-  const double precision = double(true_positives) / double(true_positives+false_positives);
-  const double recall = double(true_positives) / double(size-last);
+  const double precision = static_cast<double>(true_positives) / static_cast<double>(true_positives+false_positives);
+  const double recall = static_cast<double>(true_positives) / static_cast<double>(size-last);
   EXPECT_NEAR(precision, 1.0, 0.4);
   EXPECT_NEAR(recall, 1.0, 0.2);
 }
index bd80457df13608b484d2494f0c94619832719390..ec3c8229e495e21989de1d9159b4405a35cf9e77 100644 (file)
@@ -1,9 +1,9 @@
 #pragma once
 
-const int nr_threads = 1;
-const float approx_overlap = 0.9f;
-const float delta = 1.f;
-const int nr_samples = 100;
+constexpr int nr_threads = 1;
+constexpr float approx_overlap = 0.9f;
+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 },
index 3148e2f64f552c3926ddc517647e825f2dbbb368..ed709afc7b09c950b13c920410f7f66b74078a0c 100644 (file)
@@ -73,7 +73,7 @@ TEST (PCL, KFPCSInitialAlignment)
   kfpcs_ia.setScoreThreshold (abort_score);
 
   // repeat alignment 2 times to increase probability to ~99.99%
-  const float max_angle3d = 0.1745f, max_translation3d = 1.f;
+  constexpr float max_angle3d = 0.1745f, max_translation3d = 1.f;
   float angle3d = std::numeric_limits<float>::max(), translation3d = std::numeric_limits<float>::max();
   for (int i = 0; i < 2; i++)
   {
index 59a29d5b8fe9edc0b6786e0ae59a232246ae8201..4b7e8905630b6e222365b586b5537a9a1c7442ba 100644 (file)
@@ -1,9 +1,9 @@
 #pragma once
 
-const int nr_threads = 1;
-const float voxel_size = 0.1f;
-const float approx_overlap = 0.9f;
-const float abort_score = 0.0f;
+constexpr int nr_threads = 1;
+constexpr float voxel_size = 0.1f;
+constexpr float approx_overlap = 0.9f;
+constexpr float abort_score = 0.0f;
 
 const float transformation_office1_office2 [4][4] = {
   { -0.6946f, -0.7194f, -0.0051f, -3.6352f },
index b5a3402b11531e5f487aaa83c02d9063342d7324..0b2d33712aa72cb5f99410b3af2aaae817f72bc4 100644 (file)
@@ -183,7 +183,7 @@ TEST(PCL, ICP_translated)
   pcl::PointCloud<pcl::PointXYZ> Final;
   icp.align(Final);
 
-  // Check that we have sucessfully converged
+  // Check that we have successfully converged
   ASSERT_TRUE(icp.hasConverged());
 
   // Test that the fitness score is below acceptable threshold
@@ -249,10 +249,10 @@ sampleRandomTransform (Eigen::Affine3f &trans, float max_angle, float max_trans)
 {
     srand(0);
     // Sample random transform
-    Eigen::Vector3f axis((float)rand() / RAND_MAX, (float)rand() / RAND_MAX, (float)rand() / RAND_MAX);
+    Eigen::Vector3f axis(static_cast<float>(rand()) / RAND_MAX, static_cast<float>(rand()) / RAND_MAX, static_cast<float>(rand()) / RAND_MAX);
     axis.normalize();
-    float angle = (float)rand() / RAND_MAX * max_angle;
-    Eigen::Vector3f translation((float)rand() / RAND_MAX, (float)rand() / RAND_MAX, (float)rand() / RAND_MAX);
+    float angle = static_cast<float>(rand()) / RAND_MAX * max_angle;
+    Eigen::Vector3f translation(static_cast<float>(rand()) / RAND_MAX, static_cast<float>(rand()) / RAND_MAX, static_cast<float>(rand()) / RAND_MAX);
     translation *= max_trans;
     Eigen::Affine3f rotation(Eigen::AngleAxis<float>(angle, axis));
     trans = Eigen::Translation3f(translation) * rotation;
@@ -585,6 +585,68 @@ TEST (PCL, GeneralizedIterativeClosestPoint)
   EXPECT_LT (reg.getFitnessScore (), 0.0001);
 }
 
+TEST (PCL, GeneralizedIterativeClosestPointBFGS)
+{ // same as above, but uses BFGS optimizer
+  using PointT = PointXYZ;
+  PointCloud<PointT>::Ptr src (new PointCloud<PointT>);
+  copyPointCloud (cloud_source, *src);
+  PointCloud<PointT>::Ptr tgt (new PointCloud<PointT>);
+  copyPointCloud (cloud_target, *tgt);
+  PointCloud<PointT> output;
+
+  GeneralizedIterativeClosestPoint<PointT, PointT> reg;
+  reg.useBFGS ();
+  reg.setInputSource (src);
+  reg.setInputTarget (tgt);
+  reg.setMaximumIterations (50);
+  reg.setTransformationEpsilon (1e-8);
+
+  // Register
+  reg.align (output);
+  EXPECT_EQ (output.size (), cloud_source.size ());
+  EXPECT_LT (reg.getFitnessScore (), 0.0001);
+
+  // Check again, for all possible caching schemes
+  for (int iter = 0; iter < 4; iter++)
+  {
+    bool force_cache = static_cast<bool> (iter/2);
+    bool force_cache_reciprocal = static_cast<bool> (iter%2);
+    pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
+    // Ensure that, when force_cache is not set, we are robust to the wrong input
+    if (force_cache)
+      tree->setInputCloud (tgt);
+    reg.setSearchMethodTarget (tree, force_cache);
+
+    pcl::search::KdTree<PointT>::Ptr tree_recip (new pcl::search::KdTree<PointT>);
+    if (force_cache_reciprocal)
+      tree_recip->setInputCloud (src);
+    reg.setSearchMethodSource (tree_recip, force_cache_reciprocal);
+
+    // Register
+    reg.align (output);
+    EXPECT_EQ (output.size (), cloud_source.size ());
+    EXPECT_LT (reg.getFitnessScore (), 0.001);
+  }
+
+  // Test guess matrix
+  Eigen::Isometry3f transform = Eigen::Isometry3f (Eigen::AngleAxisf (0.25 * M_PI, Eigen::Vector3f::UnitX ())
+                                                 * Eigen::AngleAxisf (0.50 * M_PI, Eigen::Vector3f::UnitY ())
+                                                 * Eigen::AngleAxisf (0.33 * M_PI, Eigen::Vector3f::UnitZ ()));
+  transform.translation () = Eigen::Vector3f (0.1, 0.2, 0.3);
+  PointCloud<PointT>::Ptr transformed_tgt (new PointCloud<PointT>);
+  pcl::transformPointCloud (*tgt, *transformed_tgt, transform.matrix ()); // transformed_tgt is now a copy of tgt with a transformation matrix applied
+
+  GeneralizedIterativeClosestPoint<PointT, PointT> reg_guess;
+  reg_guess.useBFGS ();
+  reg_guess.setInputSource (src);
+  reg_guess.setInputTarget (transformed_tgt);
+  reg_guess.setMaximumIterations (50);
+  reg_guess.setTransformationEpsilon (1e-8);
+  reg_guess.align (output, transform.matrix ());
+  EXPECT_EQ (output.size (), cloud_source.size ());
+  EXPECT_LT (reg.getFitnessScore (), 0.0001);
+}
+
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST (PCL, GeneralizedIterativeClosestPoint6D)
 {
@@ -593,7 +655,7 @@ TEST (PCL, GeneralizedIterativeClosestPoint6D)
   PointCloud<PointT>::Ptr src_full (new PointCloud<PointT>);
   copyPointCloud (cloud_with_color, *src_full);
   PointCloud<PointT>::Ptr tgt_full (new PointCloud<PointT>);
-  sampleRandomTransform (delta_transform, M_PI/0.1, .03);
+  sampleRandomTransform (delta_transform, 0.25*M_PI, .03);
   pcl::transformPointCloud (cloud_with_color, *tgt_full, delta_transform);
   PointCloud<PointT> output;
 
@@ -616,7 +678,7 @@ TEST (PCL, GeneralizedIterativeClosestPoint6D)
   // Register
   reg.align (output);
   EXPECT_EQ (output.size (), src->size ());
-  EXPECT_LT (reg.getFitnessScore (), 0.003);
+  EXPECT_LT (reg.getFitnessScore (), 1e-4);
 
   // Check again, for all possible caching schemes
   for (int iter = 0; iter < 4; iter++)
@@ -637,7 +699,7 @@ TEST (PCL, GeneralizedIterativeClosestPoint6D)
     // Register
     reg.align (output);
     EXPECT_EQ (output.size (), src->size ());
-    EXPECT_LT (reg.getFitnessScore (), 0.003);
+    EXPECT_LT (reg.getFitnessScore (), 1e-4);
   }
 }
 
@@ -724,18 +786,21 @@ TEST (PCL, PyramidFeatureHistogram)
   EXPECT_NEAR (similarity_value3, 0.873699546, 1e-3);
 }
 
-// Suat G: disabled, since the transformation does not look correct.
-// ToDo: update transformation from the ground truth.
-#if 0
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 TEST (PCL, PPFRegistration)
 {
-  // Transform the source cloud by a large amount
-  Eigen::Vector3f initial_offset (100, 0, 0);
-  float angle = M_PI/6;
-  Eigen::Quaternionf initial_rotation (std::cos (angle / 2), 0, 0, sin (angle / 2));
+  Eigen::Matrix4f bun0_to_bun4_groundtruth;
+  bun0_to_bun4_groundtruth <<
+    0.825336f, 0.000000f, -0.564642f, 0.037267f,
+    0.000000f, 1.000000f,  0.000000f, 0.000000f,
+    0.564642f, 0.000000f,  0.825336f, 0.038325f,
+    0.000000f, 0.000000f,  0.000000f, 1.000000f;
+
+  // apply some additional, random transformation to show that the initial point cloud poses do not matter
+  const Eigen::Affine3f additional_transformation = Eigen::Translation3f(-0.515f, 0.260f, -0.845f) *
+      Eigen::AngleAxisf(-1.627f, Eigen::Vector3f(0.354f, 0.878f, -0.806f).normalized());
   PointCloud<PointXYZ> cloud_source_transformed;
-  transformPointCloud (cloud_source, cloud_source_transformed, initial_offset, initial_rotation);
+  transformPointCloud (cloud_source, cloud_source_transformed, additional_transformation);
 
 
   // Create shared pointers
@@ -747,7 +812,7 @@ TEST (PCL, PPFRegistration)
   NormalEstimation<PointXYZ, Normal> normal_estimation;
   search::KdTree<PointXYZ>::Ptr search_tree (new search::KdTree<PointXYZ> ());
   normal_estimation.setSearchMethod (search_tree);
-  normal_estimation.setRadiusSearch (0.05);
+  normal_estimation.setKSearch(30); // nearest-k-search seems to work better than radius-search
   PointCloud<Normal>::Ptr normals_target (new PointCloud<Normal> ()),
       normals_source_transformed (new PointCloud<Normal> ());
   normal_estimation.setInputCloud (cloud_target_ptr);
@@ -769,41 +834,41 @@ TEST (PCL, PPFRegistration)
 
 
   // Train the source cloud - create the hash map search structure
-  PPFHashMapSearch::Ptr hash_map_search (new PPFHashMapSearch (15.0 / 180 * M_PI,
+  PPFHashMapSearch::Ptr hash_map_search (new PPFHashMapSearch (2.0 * M_PI / 36, // divide into 36 steps
                                                                0.05));
   hash_map_search->setInputFeatureCloud (features_source_transformed);
 
   // Finally, do the registration
   PPFRegistration<PointNormal, PointNormal> ppf_registration;
-  ppf_registration.setSceneReferencePointSamplingRate (20);
+  ppf_registration.setSceneReferencePointSamplingRate (5);
   ppf_registration.setPositionClusteringThreshold (0.15);
-  ppf_registration.setRotationClusteringThreshold (45.0 / 180 * M_PI);
+  ppf_registration.setRotationClusteringThreshold (25.0 / 180 * M_PI);
   ppf_registration.setSearchMethod (hash_map_search);
-  ppf_registration.setInputCloud (cloud_source_transformed_with_normals);
+  ppf_registration.setInputSource (cloud_source_transformed_with_normals);
   ppf_registration.setInputTarget (cloud_target_with_normals);
 
   PointCloud<PointNormal> cloud_output;
   ppf_registration.align (cloud_output);
   Eigen::Matrix4f transformation = ppf_registration.getFinalTransformation ();
 
-  EXPECT_NEAR (transformation(0, 0), -0.153768, 1e-4);
-  EXPECT_NEAR (transformation(0, 1), -0.628136, 1e-4);
-  EXPECT_NEAR (transformation(0, 2), 0.762759, 1e-4);
-  EXPECT_NEAR (transformation(0, 3), 15.472, 1e-4);
-  EXPECT_NEAR (transformation(1, 0), 0.967397, 1e-4);
-  EXPECT_NEAR (transformation(1, 1), -0.252918, 1e-4);
-  EXPECT_NEAR (transformation(1, 2), -0.0132578, 1e-4);
-  EXPECT_NEAR (transformation(1, 3), -96.6221, 1e-4);
-  EXPECT_NEAR (transformation(2, 0), 0.201243, 1e-4);
-  EXPECT_NEAR (transformation(2, 1), 0.735852, 1e-4);
-  EXPECT_NEAR (transformation(2, 2), 0.646547, 1e-4);
-  EXPECT_NEAR (transformation(2, 3), -20.134, 1e-4);
-  EXPECT_NEAR (transformation(3, 0), 0.000000, 1e-4);
-  EXPECT_NEAR (transformation(3, 1), 0.000000, 1e-4);
-  EXPECT_NEAR (transformation(3, 2), 0.000000, 1e-4);
-  EXPECT_NEAR (transformation(3, 3), 1.000000, 1e-4);
+  const Eigen::Matrix4f reference_transformation = bun0_to_bun4_groundtruth * additional_transformation.inverse().matrix();
+  EXPECT_NEAR (transformation(0, 0), reference_transformation(0, 0), 0.1);
+  EXPECT_NEAR (transformation(0, 1), reference_transformation(0, 1), 0.1);
+  EXPECT_NEAR (transformation(0, 2), reference_transformation(0, 2), 0.1);
+  EXPECT_NEAR (transformation(0, 3), reference_transformation(0, 3), 0.1);
+  EXPECT_NEAR (transformation(1, 0), reference_transformation(1, 0), 0.1);
+  EXPECT_NEAR (transformation(1, 1), reference_transformation(1, 1), 0.1);
+  EXPECT_NEAR (transformation(1, 2), reference_transformation(1, 2), 0.1);
+  EXPECT_NEAR (transformation(1, 3), reference_transformation(1, 3), 0.1);
+  EXPECT_NEAR (transformation(2, 0), reference_transformation(2, 0), 0.1);
+  EXPECT_NEAR (transformation(2, 1), reference_transformation(2, 1), 0.1);
+  EXPECT_NEAR (transformation(2, 2), reference_transformation(2, 2), 0.1);
+  EXPECT_NEAR (transformation(2, 3), reference_transformation(2, 3), 0.1);
+  EXPECT_NEAR (transformation(3, 0), 0.0f, 1e-6);
+  EXPECT_NEAR (transformation(3, 1), 0.0f, 1e-6);
+  EXPECT_NEAR (transformation(3, 2), 0.0f, 1e-6);
+  EXPECT_NEAR (transformation(3, 3), 1.0f, 1e-6);
 }
-#endif
 
 /* ---[ */
 int
index 5667a8ccdda1484e98e1d312c840403862e06b4c..1aeebb78918bdd361e942bad2f1b8a9fe4414ab4 100644 (file)
@@ -88,7 +88,7 @@ TEST (PCL, CorrespondenceEstimation)
 
   // check for correct order and number of matches
   EXPECT_EQ (int (correspondences->size ()), nr_original_correspondences);
-  if (int (correspondences->size ()) == nr_original_correspondences)
+  if (static_cast<int>(correspondences->size ()) == nr_original_correspondences)
   {
     for (int i = 0; i < nr_original_correspondences; ++i)
     {
@@ -112,7 +112,7 @@ TEST (PCL, CorrespondenceEstimationReciprocal)
 
   // check for correct matches and number of matches
   EXPECT_EQ (int (correspondences->size ()), nr_reciprocal_correspondences);
-  if (int (correspondences->size ()) == nr_reciprocal_correspondences)
+  if (static_cast<int>(correspondences->size ()) == nr_reciprocal_correspondences)
   {
     for (int i = 0; i < nr_reciprocal_correspondences; ++i)
     {
@@ -143,7 +143,7 @@ TEST (PCL, CorrespondenceRejectorDistance)
 
   // check for correct matches and number of matches
   EXPECT_EQ (int (correspondences_result_rej_dist->size ()), nr_correspondences_result_rej_dist);
-  if (int (correspondences_result_rej_dist->size ()) == nr_correspondences_result_rej_dist)
+  if (static_cast<int>(correspondences_result_rej_dist->size ()) == nr_correspondences_result_rej_dist)
   {
     for (int i = 0; i < nr_correspondences_result_rej_dist; ++i)
     {
@@ -176,7 +176,7 @@ TEST (PCL, CorrespondenceRejectorMedianDistance)
   // check for correct matches
   EXPECT_NEAR (corr_rej_median_dist.getMedianDistance (), rej_median_distance, 1e-4);
   EXPECT_EQ (int (correspondences_result_rej_median_dist->size ()), nr_correspondences_result_rej_median_dist);
-  if (int (correspondences_result_rej_median_dist->size ()) == nr_correspondences_result_rej_median_dist)
+  if (static_cast<int>(correspondences_result_rej_median_dist->size ()) == nr_correspondences_result_rej_median_dist)
   {
     for (int i = 0; i < nr_correspondences_result_rej_median_dist; ++i)
     {
@@ -206,7 +206,7 @@ TEST (PCL, CorrespondenceRejectorOneToOne)
 
   // check for correct matches and number of matches
   EXPECT_EQ (int (correspondences_result_rej_one_to_one->size ()), nr_correspondences_result_rej_one_to_one);
-  if (int (correspondences_result_rej_one_to_one->size ()) == nr_correspondences_result_rej_one_to_one)
+  if (static_cast<int>(correspondences_result_rej_one_to_one->size ()) == nr_correspondences_result_rej_one_to_one)
   {
     for (int i = 0; i < nr_correspondences_result_rej_one_to_one; ++i)
     {
@@ -242,7 +242,7 @@ TEST (PCL, CorrespondenceRejectorSampleConsensus)
 
   // check for correct matches and number of matches
   EXPECT_EQ (int (correspondences_result_rej_sac->size ()), nr_correspondences_result_rej_sac);
-  if (int (correspondences_result_rej_sac->size ()) == nr_correspondences_result_rej_sac)
+  if (static_cast<int>(correspondences_result_rej_sac->size ()) == nr_correspondences_result_rej_sac)
   {
     for (int i = 0; i < nr_correspondences_result_rej_sac; ++i)
     {
@@ -302,7 +302,7 @@ TEST (PCL, CorrespondenceRejectorSurfaceNormal)
   corr_rej_surf_norm.getCorrespondences (*correspondences_result_rej_surf_norm);
 
   // check for correct matches
-  if (int (correspondences_result_rej_surf_norm->size ()) == nr_correspondences_result_rej_dist)
+  if (static_cast<int>(correspondences_result_rej_surf_norm->size ()) == nr_correspondences_result_rej_dist)
   {
     for (int i = 0; i < nr_correspondences_result_rej_dist; ++i)
     {
@@ -332,7 +332,7 @@ TEST (PCL, CorrespondenceRejectorTrimmed)
 
   // check for correct matches, number of matches, and for sorting (correspondences should be sorted w.r.t. distance)
   EXPECT_EQ (int (correspondences_result_rej_trimmed->size ()), nr_correspondences_result_rej_trimmed);
-  if (int (correspondences_result_rej_trimmed->size ()) == nr_correspondences_result_rej_trimmed)
+  if (static_cast<int>(correspondences_result_rej_trimmed->size ()) == nr_correspondences_result_rej_trimmed)
   {
     for (int i = 0; i < nr_correspondences_result_rej_trimmed; ++i)
     {
@@ -364,7 +364,7 @@ TEST (PCL, CorrespondenceRejectorVarTrimmed)
   corr_rej_var_trimmed_dist.getCorrespondences(*correspondences_result_rej_var_trimmed_dist);
 
   // check for correct matches
-  if (int (correspondences_result_rej_var_trimmed_dist->size ()) == nr_correspondences_result_rej_dist)
+  if (static_cast<int>(correspondences_result_rej_var_trimmed_dist->size ()) == nr_correspondences_result_rej_dist)
   {
     for (int i = 0; i < nr_correspondences_result_rej_dist; ++i)
     {
index f1a934f3c1367483bc4060898ca0fa7700b90eb5..0386cc4dc32e383e88852bdee38c78b38bcad7a3 100644 (file)
@@ -1,6 +1,6 @@
 #pragma once
 
-const int nr_original_correspondences = 397;
+constexpr int nr_original_correspondences = 397;
 const int correspondences_original[397][2] = {
   { 0, 61 },
   { 1, 50 },
@@ -401,7 +401,7 @@ const int correspondences_original[397][2] = {
   { 396, 353 },
 };
 
-const int nr_reciprocal_correspondences = 53;
+constexpr int nr_reciprocal_correspondences = 53;
 const int correspondences_reciprocal[53][2] = {
   { 1, 50 },
   { 2, 51 },
@@ -458,8 +458,8 @@ const int correspondences_reciprocal[53][2] = {
   { 366, 334 },
 };
 
-const int nr_correspondences_result_rej_dist = 97;
-const float rej_dist_max_dist = 0.01f;
+constexpr int nr_correspondences_result_rej_dist = 97;
+constexpr float rej_dist_max_dist = 0.01f;
 const int correspondences_dist[97][2] = {
   { 1, 50 },
   { 2, 51 },
@@ -560,9 +560,9 @@ const int correspondences_dist[97][2] = {
   { 367, 334 },
 };
 
-const int nr_correspondences_result_rej_median_dist = 139;
-const float rej_median_factor = 0.5f;
-const float rej_median_distance = 0.000465391f;
+constexpr int nr_correspondences_result_rej_median_dist = 139;
+constexpr float rej_median_factor = 0.5f;
+constexpr float rej_median_distance = 0.000465391f;
 const int correspondences_median_dist[139][2] = {
   { 0, 61 },
   { 1, 50 },
@@ -705,7 +705,7 @@ const int correspondences_median_dist[139][2] = {
   { 368, 335 },
 };
 
-const int nr_correspondences_result_rej_one_to_one = 103;
+constexpr int nr_correspondences_result_rej_one_to_one = 103;
 const int correspondences_one_to_one[103][2] = {
   { 177, 27 },
   { 180, 32 },
@@ -812,9 +812,9 @@ const int correspondences_one_to_one[103][2] = {
   { 327, 360 },
 };
 
-const int nr_correspondences_result_rej_sac = 97;
-const double rej_sac_max_dist = 0.01;
-const int rej_sac_max_iter = 1000;
+constexpr int nr_correspondences_result_rej_sac = 97;
+constexpr double rej_sac_max_dist = 0.01;
+constexpr int rej_sac_max_iter = 1000;
 const int correspondences_sac[97][2] = {
   { 1, 50 },
   { 2, 51 },
@@ -915,8 +915,8 @@ const int correspondences_sac[97][2] = {
   { 390, 334 },
 };
 
-const int nr_correspondences_result_rej_trimmed = 198;
-const float rej_trimmed_overlap = 0.5;
+constexpr int nr_correspondences_result_rej_trimmed = 198;
+constexpr float rej_trimmed_overlap = 0.5;
 const int correspondences_trimmed[198][2] = {
   { 260, 286 },
   { 271, 299 },
index 5d56c571cb6ddee17bd9846847a6d9a71c2aae0f..6580283faae7b86bfec4bc84221dda11eba4b60c 100644 (file)
@@ -97,7 +97,7 @@ TYPED_TEST(SacTest, InfiniteLoop)
 {
   using namespace std::chrono_literals;
 
-  const unsigned point_count = 100;
+  constexpr unsigned point_count = 100;
   PointCloud<PointXYZ> cloud;
   cloud.resize (point_count);
   for (unsigned idx = 0; idx < point_count; ++idx)
index 40ddd4a5c6d7de6b83a5900c16f0206a4f185d5c..aa88fada96abf98102bd5f11ed6fcdf38828afca 100644 (file)
@@ -159,9 +159,9 @@ TEST (SampleConsensusModelLine, SampleValidationPointsEqual)
   // being printed a 1000 times without any chance of success.
   // The order is chosen such that with a known, fixed rng-state/-seed all
   // validation steps are actually exercised.
-  const pcl::index_t firstKnownEqualPoint = 0;
-  const pcl::index_t secondKnownEqualPoint = 1;
-  const pcl::index_t cheatPointIndex = 2;
+  constexpr pcl::index_t firstKnownEqualPoint = 0;
+  constexpr pcl::index_t secondKnownEqualPoint = 1;
+  constexpr pcl::index_t cheatPointIndex = 2;
 
   cloud[firstKnownEqualPoint].getVector3fMap () <<  0.1f,  0.0f,  0.0f;
   cloud[secondKnownEqualPoint].getVector3fMap () <<  0.1f,  0.0f,  0.0f;
@@ -258,7 +258,7 @@ TEST (SampleConsensusModelParallelLine, RANSAC)
   cloud[15].getVector3fMap () << -1.05f,  5.01f,  5.0f;
 
   // Create a shared line model pointer directly
-  const double eps = 0.1; //angle eps in radians
+  constexpr double eps = 0.1; // angle eps in radians
   const Eigen::Vector3f axis (0, 0, 1);
   SampleConsensusModelParallelLinePtr model (new SampleConsensusModelParallelLine<PointXYZ> (cloud.makeShared ()));
   model->setAxis (axis);
index 82141b3aaa34a78ab7c938c90674cf15b233f19d..4dc7ab45517291eb26b3f671dce14bc4616e28fc 100644 (file)
@@ -144,10 +144,10 @@ TEST (SampleConsensusModelPlane, SampleValidationPointsCollinear)
   // being printed a 1000 times without any chance of success.
   // The order is chosen such that with a known, fixed rng-state/-seed all
   // validation steps are actually exercised.
-  const pcl::index_t firstCollinearPointIndex = 0;
-  const pcl::index_t secondCollinearPointIndex = 1;
-  const pcl::index_t thirdCollinearPointIndex = 2;
-  const pcl::index_t cheatPointIndex = 3;
+  constexpr pcl::index_t firstCollinearPointIndex = 0;
+  constexpr pcl::index_t secondCollinearPointIndex = 1;
+  constexpr pcl::index_t thirdCollinearPointIndex = 2;
+  constexpr pcl::index_t cheatPointIndex = 3;
 
   cloud[firstCollinearPointIndex].getVector3fMap () <<  0.1f,  0.1f,  0.1f;
   cloud[secondCollinearPointIndex].getVector3fMap () <<  0.2f,  0.2f,  0.2f;
@@ -357,8 +357,8 @@ TEST (SampleConsensusModelNormalParallelPlane, RANSAC)
   SampleConsensusModelNormalParallelPlanePtr model (new SampleConsensusModelNormalParallelPlane<PointXYZ, Normal> (cloud.makeShared ()));
   model->setInputNormals (normals.makeShared ());
 
-  const float max_angle_rad = 0.01f;
-  const float angle_eps = 0.001f;
+  constexpr float max_angle_rad = 0.01f;
+  constexpr float angle_eps = 0.001f;
   model->setEpsAngle (max_angle_rad);
 
   // Test true axis
@@ -556,10 +556,14 @@ TEST (SampleConsensusModelPlane, OptimizeFarFromOrigin)
   Eigen::VectorXf coeffs(4); // Doesn't have to be initialized, the function doesn't use them
   Eigen::VectorXf optimized_coeffs(4);
   model.optimizeModelCoefficients(inliers, coeffs, optimized_coeffs);
-  EXPECT_NEAR(optimized_coeffs[0], z[0], 5e-6);
-  EXPECT_NEAR(optimized_coeffs[1], z[1], 5e-6);
-  EXPECT_NEAR(optimized_coeffs[2], z[2], 5e-6);
+  EXPECT_NEAR(optimized_coeffs[0], z[0], 6e-6);
+  EXPECT_NEAR(optimized_coeffs[1], z[1], 6e-6);
+  EXPECT_NEAR(optimized_coeffs[2], z[2], 6e-6);
+#ifndef __i386__
   EXPECT_NEAR(optimized_coeffs[3], -z.dot(center), 5e-2);
+#else
+  EXPECT_NEAR(optimized_coeffs[3], -z.dot(center), 1e-1);
+#endif
 }
 
 int
@@ -583,7 +587,7 @@ main (int argc, char** argv)
   fromPCLPointCloud2 (cloud_blob, *normals_);
 
   indices_.resize (cloud_->size ());
-  for (std::size_t i = 0; i < indices_.size (); ++i) { indices_[i] = int (i); }
+  for (std::size_t i = 0; i < indices_.size (); ++i) { indices_[i] = static_cast<int>(i); }
 
   testing::InitGoogleTest (&argc, argv);
   return (RUN_ALL_TESTS ());
diff --git a/test/search/precise_distances.h b/test/search/precise_distances.h
new file mode 100644 (file)
index 0000000..7e02e87
--- /dev/null
@@ -0,0 +1,23 @@
+namespace pcl_tests {
+// Here we want very precise distance functions, speed is less important. So we use
+// double precision, unlike euclideanDistance() in pcl/common/distances and distance()
+// in pcl/common/geometry which use float (single precision) and possibly vectorization
+
+template <typename PointT> inline double
+squared_point_distance(const PointT& p1, const PointT& p2)
+{
+  const double x_diff = (static_cast<double>(p1.x) - static_cast<double>(p2.x)),
+               y_diff = (static_cast<double>(p1.y) - static_cast<double>(p2.y)),
+               z_diff = (static_cast<double>(p1.z) - static_cast<double>(p2.z));
+  return (x_diff * x_diff + y_diff * y_diff + z_diff * z_diff);
+}
+
+template <typename PointT> inline double
+point_distance(const PointT& p1, const PointT& p2)
+{
+  const double x_diff = (static_cast<double>(p1.x) - static_cast<double>(p2.x)),
+               y_diff = (static_cast<double>(p1.y) - static_cast<double>(p2.y)),
+               z_diff = (static_cast<double>(p1.z) - static_cast<double>(p2.z));
+  return std::sqrt(x_diff * x_diff + y_diff * y_diff + z_diff * z_diff);
+}
+} // namespace pcl_tests
index 6fe198dea0f40af604b4ab707f85a5942362d585..bb8a46ef469b9918e5c0c99a053953b3ec220621 100644 (file)
@@ -61,7 +61,7 @@ init ()
   cloud.width = cloud.size ();
   cloud.height = 1;
 
-  srand (int (time (nullptr)));
+  srand (static_cast<int>(time (nullptr)));
   // Randomly create a new point cloud, use points.emplace_back
   cloud_big.width = 640;
   cloud_big.height = 480;
@@ -83,7 +83,7 @@ TEST (PCL, FlannSearch_nearestKSearch)
   for (std::size_t i = 0; i < cloud.size (); ++i)
   {
     float distance = euclideanDistance (cloud[i], test_point);
-    sorted_brute_force_result.insert (std::make_pair (distance, int (i)));
+    sorted_brute_force_result.insert (std::make_pair (distance, static_cast<int>(i)));
   }
   float max_dist = 0.0f;
   unsigned int counter = 0;
@@ -221,7 +221,7 @@ TEST (PCL, FlannSearch_knnByIndex)
   pcl::Indices query_indices;
   for (std::size_t i = 0; i<cloud_big.size (); i+=2)
   {
-    query_indices.push_back (int (i));
+    query_indices.push_back (static_cast<int>(i));
   }
   flann_search.nearestKSearch (cloud_big, query_indices,no_of_neighbors,indices,dists);
 
@@ -334,7 +334,7 @@ TEST (PCL, FlannSearch_compareToKdTreeFlann)
 
   pcl::Indices query_indices;
   for (std::size_t i = 0; i<cloud_big.size (); i+=2)
-    query_indices.push_back (int (i));
+    query_indices.push_back (static_cast<int>(i));
 
   {
     ScopeTime scopeTime ("FLANN multi nearestKSearch with indices");
index 78b7eb7328dcc6de56b348ca030293e5a1f24e24..6da19e3fd501036832ff49fd0bfbc50dea99d1c1 100644 (file)
@@ -41,6 +41,9 @@
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
 #include <pcl/search/octree.h> // for pcl::search::Octree
+#include "precise_distances.h" // for point_distance, squared_point_distance
+
+#define TOLERANCE 0.000001
 
 using namespace pcl;
 using namespace octree;
@@ -119,9 +122,7 @@ TEST (PCL, Octree_Pointcloud_Nearest_K_Neighbour_Search)
     // push all points and their distance to the search point into a priority queue - bruteforce approach.
     for (std::size_t i = 0; i < cloudIn->size (); i++)
     {
-      double pointDist = (((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x) +
-                          ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y) +
-                          ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z));
+      const auto pointDist = pcl_tests::squared_point_distance((*cloudIn)[i], searchPoint);
 
       prioPointQueueEntry pointEntry ((*cloudIn)[i], pointDist, static_cast<int> (i));
 
@@ -276,7 +277,6 @@ TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search)
 
   // instantiate point clouds
   PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
-  PointCloud<PointXYZ>::Ptr cloudOut (new PointCloud<PointXYZ> ());
 
   const unsigned int seed = time (nullptr);
   srand (seed);
@@ -301,25 +301,21 @@ TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search)
                                      static_cast<float> (5.0 *  (rand () / static_cast<double> (RAND_MAX))));
     }
 
-    pcl::search::Search<PointXYZ>* octree = new pcl::search::Octree<PointXYZ> (0.001);
+    pcl::search::Octree<PointXYZ> octree(0.001);
 
     // build octree
-    double pointDist;
     double searchRadius = 5.0 * rand () / static_cast<double> (RAND_MAX);
     
     // bruteforce radius search
-    std::vector<int> cloudSearchBruteforce;
+    std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0;
     for (std::size_t i = 0; i < cloudIn->size (); i++)
     {
-      pointDist = std::sqrt (
-                        ((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x)
-                            + ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y)
-                            + ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z));
-
-      if (pointDist <= searchRadius)
-      {
-        // add point candidates to vector list
-        cloudSearchBruteforce.push_back (static_cast<int> (i));
+      const auto pointDist = pcl_tests::point_distance((*cloudIn)[i], searchPoint);
+      if (pointDist <= (searchRadius+TOLERANCE)) {
+        ++cloudSearchBruteforce_size_upper;
+        if (pointDist <= (searchRadius-TOLERANCE)) {
+          ++cloudSearchBruteforce_size_lower;
+        }
       }
     }
 
@@ -327,25 +323,21 @@ TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search)
     std::vector<float> cloudNWRRadius;
 
     // execute octree radius search
-    octree->setInputCloud (cloudIn);
-    octree->radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius);
+    octree.setInputCloud (cloudIn);
+    octree.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius);
 
-    ASSERT_EQ ( cloudNWRRadius.size() , cloudSearchBruteforce.size());
+    ASSERT_GE ( cloudNWRRadius.size() , cloudSearchBruteforce_size_lower);
+    ASSERT_LE ( cloudNWRRadius.size() , cloudSearchBruteforce_size_upper);
 
-    // check if result from octree radius search can be also found in bruteforce search
+    // check if results from octree radius search are indeed within the search radius
     for (const auto& current : cloudNWRSearch)
     {
-      pointDist = std::sqrt (
-          ((*cloudIn)[current].x-searchPoint.x) * ((*cloudIn)[current].x-searchPoint.x) +
-          ((*cloudIn)[current].y-searchPoint.y) * ((*cloudIn)[current].y-searchPoint.y) +
-          ((*cloudIn)[current].z-searchPoint.z) * ((*cloudIn)[current].z-searchPoint.z)
-      );
-
-      ASSERT_LE (pointDist, searchRadius);
+      const auto pointDist = pcl_tests::point_distance((*cloudIn)[current], searchPoint);
+      ASSERT_LE (pointDist, (searchRadius+TOLERANCE));
     }
 
     // check if result limitation works
-    octree->radiusSearch(searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5);
+    octree.radiusSearch(searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5);
     ASSERT_LE (cloudNWRRadius.size(), 5);
   }
 }
index ca7f699d849d4159ebc56539e5f35faa44853231..5673126f78bbbb7ec2d3fd19bebf297af75b81bf 100644 (file)
@@ -44,6 +44,9 @@
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
 #include <pcl/search/organized.h> // for OrganizedNeighbor
+#include "precise_distances.h" // for point_distance, squared_point_distance
+
+#define TOLERANCE 0.000001
 
 using namespace pcl;
 
@@ -54,8 +57,8 @@ public:
   prioPointQueueEntry ()
   = default;
   prioPointQueueEntry (PointXYZ& point_arg, double pointDistance_arg, int pointIdx_arg)
+    : point_ (point_arg)
   {
-    point_ = point_arg;
     pointDistance_ = pointDistance_arg;
     pointIdx_ = pointIdx_arg;
   }
@@ -112,11 +115,11 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search)
     for (int ypos = -centerY; ypos < centerY; ypos++)
       for (int xpos = -centerX; xpos < centerX; xpos++)
       {
-        double z = 15.0 * (double (rand ()) / double (RAND_MAX+1.0))+20;
+        double z = 15.0 * (static_cast<double>(rand ()) / (RAND_MAX+1.0))+20;
         double y = ypos * oneOverFocalLength * z;
         double x = xpos * oneOverFocalLength * z;
 
-        cloudIn->points.emplace_back(float (x), float (y), float (z));
+        cloudIn->points.emplace_back(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z));
       }
 
     unsigned int searchIdx = rand()%(cloudIn->width * cloudIn->height);
@@ -127,7 +130,7 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search)
 
     // organized nearest neighbor search
     organizedNeighborSearch.setInputCloud (cloudIn);
-    organizedNeighborSearch.nearestKSearch (searchPoint, int (K), k_indices, k_sqr_distances);
+    organizedNeighborSearch.nearestKSearch (searchPoint, static_cast<int>(K), k_indices, k_sqr_distances);
 
     k_indices_bruteforce.clear();
     k_sqr_distances_bruteforce.clear();
@@ -138,11 +141,9 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search)
     // push all points and their distance to the search point into a priority queue - bruteforce approach.
     for (std::size_t i = 0; i < cloudIn->size (); i++)
     {
-      double pointDist = (((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x) +
-                          ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y) +
-                          ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z));
+      double pointDist = pcl_tests::squared_point_distance((*cloudIn)[i], searchPoint);
 
-      prioPointQueueEntry pointEntry ((*cloudIn)[i], pointDist, int (i));
+      prioPointQueueEntry pointEntry ((*cloudIn)[i], pointDist, static_cast<int>(i));
 
       pointCandidates.push (pointEntry);
     }
@@ -155,7 +156,7 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search)
     while (!pointCandidates.empty ())
     {
       k_indices_bruteforce.push_back (pointCandidates.top ().pointIdx_);
-      k_sqr_distances_bruteforce.push_back (float (pointCandidates.top ().pointDistance_));
+      k_sqr_distances_bruteforce.push_back (static_cast<float>(pointCandidates.top ().pointDistance_));
 
       pointCandidates.pop ();
     }
@@ -207,35 +208,31 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Neighbours_Within_Radius_Search)
     for (int ypos = -centerY; ypos < centerY; ypos++)
       for (int xpos = -centerX; xpos < centerX; xpos++)
       {
-        double z = 5.0 * ( (double (rand ()) / double (RAND_MAX)))+5;
+        double z = 5.0 * ( (static_cast<double>(rand ()) / static_cast<double>(RAND_MAX)))+5;
         double y = ypos*oneOverFocalLength*z;
         double x = xpos*oneOverFocalLength*z;
 
-        (*cloudIn)[idx++]= PointXYZ (float (x), float (y), float (z));
+        (*cloudIn)[idx++]= PointXYZ (static_cast<float>(x), static_cast<float>(y), static_cast<float>(z));
       }
 
     unsigned int randomIdx = rand()%(cloudIn->width * cloudIn->height);
 
     const PointXYZ& searchPoint = (*cloudIn)[randomIdx];
 
-    double pointDist;
-    double searchRadius = 1.0 * (double (rand ()) / double (RAND_MAX));
+    double searchRadius = 1.0 * (static_cast<double>(rand ()) / static_cast<double>(RAND_MAX));
 
     // bruteforce radius search
-    std::vector<int> cloudSearchBruteforce;
-    cloudSearchBruteforce.clear();
+    std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0;
 
     for (std::size_t i = 0; i < cloudIn->size (); i++)
     {
-      pointDist = std::sqrt (
-                        ((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x)
-                      + ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y)
-                      + ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z));
+      const auto pointDist = pcl_tests::point_distance((*cloudIn)[i], searchPoint);
 
-      if (pointDist <= searchRadius)
-      {
-        // add point candidates to vector list
-        cloudSearchBruteforce.push_back (int (i));
+      if (pointDist <= (searchRadius+TOLERANCE)) {
+        ++cloudSearchBruteforce_size_upper;
+        if (pointDist <= (searchRadius-TOLERANCE)) {
+          ++cloudSearchBruteforce_size_lower;
+        }
       }
     }
 
@@ -246,32 +243,16 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Neighbours_Within_Radius_Search)
     organizedNeighborSearch.setInputCloud (cloudIn);
     organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius);
 
-    // check if result from organized radius search can be also found in bruteforce search
+    // check if results from organized radius search are indeed within the search radius
     for (const auto& current : cloudNWRSearch)
     {
-      pointDist = std::sqrt (
-          ((*cloudIn)[current].x-searchPoint.x) * ((*cloudIn)[current].x-searchPoint.x) +
-          ((*cloudIn)[current].y-searchPoint.y) * ((*cloudIn)[current].y-searchPoint.y) +
-          ((*cloudIn)[current].z-searchPoint.z) * ((*cloudIn)[current].z-searchPoint.z)
-      );
-
-      ASSERT_LE (pointDist, searchRadius);
-    }
-
-
-    // check if bruteforce result from organized radius search can be also found in bruteforce search
-    for (const auto& current : cloudSearchBruteforce)
-    {
-      pointDist = std::sqrt (
-          ((*cloudIn)[current].x-searchPoint.x) * ((*cloudIn)[current].x-searchPoint.x) +
-          ((*cloudIn)[current].y-searchPoint.y) * ((*cloudIn)[current].y-searchPoint.y) +
-          ((*cloudIn)[current].z-searchPoint.z) * ((*cloudIn)[current].z-searchPoint.z)
-      );
+      const auto pointDist = pcl_tests::point_distance((*cloudIn)[current], searchPoint);
 
-      ASSERT_LE (pointDist, searchRadius);
+      ASSERT_LE (pointDist, (searchRadius+TOLERANCE));
     }
 
-    ASSERT_EQ (cloudNWRRadius.size() , cloudSearchBruteforce.size ());
+    ASSERT_GE (cloudNWRRadius.size() , cloudSearchBruteforce_size_lower);
+    ASSERT_LE (cloudNWRRadius.size() , cloudSearchBruteforce_size_upper);
 
     // check if result limitation works
     organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5);
index 1a7a7ca2e3642e8879b9be21e72831a4f36ab44d..6b63d00d2049973faf26b903e261453cb54b42b2 100644 (file)
 #include <pcl/point_types.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/search/organized.h> // for OrganizedNeighbor
+#include "precise_distances.h" // for point_distance
+
+#define TOLERANCE 0.000001
 
 using namespace pcl;
 
 std::string pcd_filename;
 
-// Here we want a very precise distance function, speed is less important. So we use
-// double precision, unlike euclideanDistance() in pcl/common/distances and distance()
-// in pcl/common/geometry which use float (single precision) and possibly vectorization
-template <typename PointT> inline double
-point_distance(const PointT& p1, const PointT& p2)
-{
-  const double x_diff = p1.x - p2.x, y_diff = p1.y - p2.y, z_diff = p1.z - p2.z;
-  return std::sqrt(x_diff * x_diff + y_diff * y_diff + z_diff * z_diff);
-}
-
 // helper class for priority queue
 class prioPointQueueEntry
 {
   public:
     prioPointQueueEntry () = default;
     prioPointQueueEntry (PointXYZ& point_arg, double pointDistance_arg, int pointIdx_arg)
+      : point_ (point_arg)
     {
-      point_ = point_arg;
       pointDistance_ = pointDistance_arg;
       pointIdx_ = pointIdx_arg;
     }
@@ -121,9 +114,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search)
     for (int ypos = -centerY; ypos < centerY; ypos++)
       for (int xpos = -centerX; xpos < centerX; xpos++)
       {
-        double z = 15.0 * ((double)rand () / (double)(RAND_MAX+1.0))+20;
-        double y = (double)ypos*oneOverFocalLength*(double)z;
-        double x = (double)xpos*oneOverFocalLength*(double)z;
+        double z = 15.0 * (static_cast<double>(rand ()) / (RAND_MAX+1.0))+20;
+        double y = static_cast<double>(ypos)*oneOverFocalLength*z;
+        double x = static_cast<double>(xpos)*oneOverFocalLength*z;
 
         cloudIn->points.emplace_back(x, y, z);
       }
@@ -145,7 +138,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search)
 
     for (auto it = cloudIn->begin(); it != cloudIn->end(); ++it)
     {
-      const auto pointDist = point_distance(*it, searchPoint);
+      const auto pointDist = pcl_tests::point_distance(*it, searchPoint);
       prioPointQueueEntry pointEntry (*it, pointDist, std::distance(cloudIn->begin(), it));
       pointCandidates.push (pointEntry);
     }
@@ -227,7 +220,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search_Kinec
 
     // organized nearest neighbor search
     organizedNeighborSearch.setInputCloud (cloudIn);
-    organizedNeighborSearch.nearestKSearch (searchPoint, (int)K, k_indices, k_sqr_distances);
+    organizedNeighborSearch.nearestKSearch (searchPoint, static_cast<int>(K), k_indices, k_sqr_distances);
 
     k_indices_bruteforce.clear();
     k_sqr_distances_bruteforce.clear();
@@ -238,7 +231,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search_Kinec
     // push all points and their distance to the search point into a priority queue - bruteforce approach.
     for (auto it = cloudIn->begin(); it != cloudIn->end(); ++it)
     {
-      const auto pointDist = point_distance(*it, searchPoint);
+      const auto pointDist = pcl_tests::point_distance(*it, searchPoint);
       prioPointQueueEntry pointEntry (*it, pointDist, std::distance(cloudIn->begin(), it));
       pointCandidates.push (pointEntry);
     }
@@ -294,7 +287,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search)
     for (int ypos = -centerY; ypos < centerY; ypos++)
       for (int xpos = -centerX; xpos < centerX; xpos++)
       {
-        double z = 5.0 * ( ((double)rand () / (double)RAND_MAX))+5;
+        double z = 5.0 * ( (static_cast<double>(rand ()) / static_cast<double>(RAND_MAX)))+5;
         double y = ypos*oneOverFocalLength*z;
         double x = xpos*oneOverFocalLength*z;
         (*cloudIn)[idx++]= PointXYZ (x, y, z);
@@ -304,21 +297,21 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search)
 
     const PointXYZ& searchPoint = (*cloudIn)[randomIdx];
 
-    const double searchRadius = 1.0 * ((double)rand () / (double)RAND_MAX);
+    const double searchRadius = 1.0 * (static_cast<double>(rand ()) / static_cast<double>(RAND_MAX));
     //   double searchRadius = 1/10;
 
     // bruteforce radius search
-    std::vector<int> cloudSearchBruteforce;
-    cloudSearchBruteforce.clear();
+    std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0;
 
-    for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it)
+    for (const auto& point : cloudIn->points)
     {
-      const auto pointDist = point_distance(*it, searchPoint);
+      const auto pointDist = pcl_tests::point_distance(point, searchPoint);
 
-      if (pointDist <= searchRadius)
-      {
-        // add point candidates to vector list
-        cloudSearchBruteforce.push_back (std::distance(cloudIn->points.cbegin(), it));
+      if (pointDist <= (searchRadius+TOLERANCE)) {
+        ++cloudSearchBruteforce_size_upper;
+        if (pointDist <= (searchRadius-TOLERANCE)) {
+          ++cloudSearchBruteforce_size_lower;
+        }
       }
     }
 
@@ -330,22 +323,15 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search)
     organizedNeighborSearch.radiusSearch ((*cloudIn)[randomIdx], searchRadius, cloudNWRSearch, cloudNWRRadius, std::numeric_limits<unsigned int>::max());
 
 
-    // check if result from organized radius search can be also found in bruteforce search
+    // check if results from organized radius search are indeed within the search radius
     for (const auto it : cloudNWRSearch)
     {
-      const auto pointDist = point_distance((*cloudIn)[it], searchPoint);
-      ASSERT_LE (pointDist, searchRadius);
+      const auto pointDist = pcl_tests::point_distance((*cloudIn)[it], searchPoint);
+      ASSERT_LE (pointDist, (searchRadius+TOLERANCE));
     }
 
-
-    // check if bruteforce result from organized radius search can be also found in bruteforce search
-    for (const auto it : cloudSearchBruteforce)
-    {
-      const auto pointDist = point_distance((*cloudIn)[it], searchPoint);
-      ASSERT_LE (pointDist, searchRadius);
-    }
-
-    ASSERT_EQ (cloudNWRRadius.size() , cloudSearchBruteforce.size ());
+    ASSERT_GE (cloudNWRRadius.size() , cloudSearchBruteforce_size_lower);
+    ASSERT_LE (cloudNWRRadius.size() , cloudSearchBruteforce_size_upper);
 
     // check if result limitation works
     organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5);
@@ -354,81 +340,6 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search)
   }
 }
 
-
-TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_Benchmark_Test)
-{
-  constexpr unsigned int test_runs = 10;
-  const unsigned int seed = time (nullptr);
-  srand (seed);
-
-  search::OrganizedNeighbor<PointXYZ> organizedNeighborSearch;
-
-  std::vector<int> k_indices;
-  std::vector<float> k_sqr_distances;
-
-  std::vector<int> k_indices_bruteforce;
-  std::vector<float> k_sqr_distances_bruteforce;
-
-  // typical focal length from kinect
-  constexpr double oneOverFocalLength = 0.0018;
-
-  for (unsigned int test_id = 0; test_id < test_runs; test_id++)
-  {
-    // generate point cloud
-
-    PointCloud<PointXYZ>::Ptr cloudIn (new PointCloud<PointXYZ> ());
-
-    cloudIn->width = 1024;
-    cloudIn->height = 768;
-    cloudIn->points.clear();
-    cloudIn->points.resize (cloudIn->width * cloudIn->height);
-
-    int centerX = cloudIn->width >> 1;
-    int centerY = cloudIn->height >> 1;
-
-    int idx = 0;
-    for (int ypos = -centerY; ypos < centerY; ypos++)
-      for (int xpos = -centerX; xpos < centerX; xpos++)
-      {
-        double z = 5.0 * ( ((double)rand () / (double)RAND_MAX))+5;
-        double y = ypos*oneOverFocalLength*z;
-        double x = xpos*oneOverFocalLength*z;
-
-        (*cloudIn)[idx++]= PointXYZ (x, y, z);
-      }
-
-    const unsigned int randomIdx = rand() % (cloudIn->width * cloudIn->height);
-
-    const PointXYZ& searchPoint = (*cloudIn)[randomIdx];
-
-    const double searchRadius = 1.0 * ((double)rand () / (double)RAND_MAX);
-
-    // bruteforce radius search
-    std::vector<int> cloudSearchBruteforce;
-    cloudSearchBruteforce.clear();
-
-    for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it)
-    {
-      const auto pointDist = point_distance(*it, searchPoint);
-
-      if (pointDist <= searchRadius)
-      {
-        // add point candidates to vector list
-        cloudSearchBruteforce.push_back (std::distance(cloudIn->points.cbegin(), it));
-      }
-    }
-
-    pcl::Indices cloudNWRSearch;
-    std::vector<float> cloudNWRRadius;
-
-    organizedNeighborSearch.setInputCloud (cloudIn);
-    organizedNeighborSearch.radiusSearch ((*cloudIn)[randomIdx], searchRadius, cloudNWRSearch, cloudNWRRadius, std::numeric_limits<unsigned int>::max());
-
-    organizedNeighborSearch.setInputCloud (cloudIn);
-    organizedNeighborSearch.radiusSearch ((*cloudIn)[randomIdx], searchRadius, cloudNWRSearch, cloudNWRRadius, std::numeric_limits<unsigned int>::max());
-  }
-}
-
 TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_Kinect_Data)
 {
 
@@ -513,36 +424,29 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_
     const PointXYZ& searchPoint = (*cloudIn)[randomIdx];
 
     // bruteforce radius search
-    std::vector<int> cloudSearchBruteforce;
-    cloudSearchBruteforce.clear();
+    std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0;
 
-    for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it)
+    for (const auto& point : cloudIn->points)
     {
-      const auto pointDist = point_distance(*it, searchPoint);
+      const auto pointDist = pcl_tests::point_distance(point, searchPoint);
 
-      if (pointDist <= searchRadius)
-      {
-        // add point candidates to vector list
-        cloudSearchBruteforce.push_back (std::distance(cloudIn->points.cbegin(), it));
+      if (pointDist <= (searchRadius+TOLERANCE)) {
+        ++cloudSearchBruteforce_size_upper;
+        if (pointDist <= (searchRadius-TOLERANCE)) {
+          ++cloudSearchBruteforce_size_lower;
+        }
       }
     }
 
-    // check if result from organized radius search can be also found in bruteforce search
+    // check if results from organized radius search are indeed within the search radius
     for (const auto it : cloudNWRSearch)
     {
-      const auto pointDist = point_distance((*cloudIn)[it], searchPoint);
-      ASSERT_LE (pointDist, searchRadius);
-    }
-
-
-    // check if bruteforce result from organized radius search can be also found in bruteforce search
-    for (const auto it : cloudSearchBruteforce)
-    {
-      const auto pointDist = point_distance((*cloudIn)[it], searchPoint);
-      ASSERT_LE (pointDist, searchRadius);
+      const auto pointDist = pcl_tests::point_distance((*cloudIn)[it], searchPoint);
+      ASSERT_LE (pointDist, (searchRadius+TOLERANCE));
     }
 
-    ASSERT_EQ (cloudNWRRadius.size() , cloudSearchBruteforce.size ());
+    ASSERT_GE (cloudNWRRadius.size() , cloudSearchBruteforce_size_lower);
+    ASSERT_LE (cloudNWRRadius.size() , cloudSearchBruteforce_size_upper);
 
     // check if result limitation works
     organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5);
index 79e4e19d62efd0467a50c11c52c28711646d93ce..94b86d76922632c5d31dfbbdf8b05bd1281de603 100644 (file)
@@ -41,6 +41,7 @@
 
 #include <pcl/search/brute_force.h>
 #include <pcl/search/kdtree.h>
+#include <pcl/search/flann_search.h>
 #include <pcl/search/organized.h>
 #include <pcl/search/octree.h>
 #include <pcl/io/pcd_io.h>
@@ -69,16 +70,16 @@ using namespace pcl;
 
 #if EXCESSIVE_TESTING
 /** \brief number of points used for creating unordered point clouds */
-const unsigned int unorganized_point_count = 100000;
+constexpr unsigned int unorganized_point_count = 100000;
 
 /** \brief number of search operations on ordered point clouds*/
-const unsigned int query_count = 5000;
+constexpr unsigned int query_count = 5000;
 #else
 /** \brief number of points used for creating unordered point clouds */
-const unsigned int unorganized_point_count = 1200;
+constexpr unsigned int unorganized_point_count = 1200;
 
 /** \brief number of search operations on ordered point clouds*/
-const unsigned int query_count = 100;
+constexpr unsigned int query_count = 100;
 #endif
 
 /** \brief organized point cloud*/
@@ -114,6 +115,9 @@ pcl::search::BruteForce<pcl::PointXYZ> brute_force;
 /** \brief instance of KDTree search method to be tested*/
 pcl::search::KdTree<pcl::PointXYZ> KDTree;
 
+/** \brief instance of FlannSearch search method to be tested*/
+pcl::search::FlannSearch<pcl::PointXYZ> FlannSearch;
+
 /** \brief instance of Octree search method to be tested*/
 pcl::search::Octree<pcl::PointXYZ> octree_search (0.1);
 
@@ -302,7 +306,7 @@ testKNNSearch (typename PointCloud<PointT>::ConstPtr point_cloud, std::vector<se
   #pragma omp parallel for \
     shared(nan_mask, point_cloud) \
     default(none)
-  for (int pIdx = 0; pIdx < int (point_cloud->size ()); ++pIdx)
+  for (int pIdx = 0; pIdx < static_cast<int>(point_cloud->size ()); ++pIdx)
   {
     if (!isFinite (point_cloud->points [pIdx]))
       nan_mask [pIdx] = false;
@@ -315,7 +319,7 @@ testKNNSearch (typename PointCloud<PointT>::ConstPtr point_cloud, std::vector<se
   #pragma omp parallel for \
     shared(input_indices, input_indices_, point_cloud, search_methods) \
     default(none)
-  for (int sIdx = 0; sIdx < int (search_methods.size ()); ++sIdx)
+  for (int sIdx = 0; sIdx < static_cast<int>(search_methods.size ()); ++sIdx)
     search_methods [sIdx]->setInputCloud (point_cloud, input_indices_);
 
   // test knn values from 1, 8, 64, 512
@@ -327,7 +331,7 @@ testKNNSearch (typename PointCloud<PointT>::ConstPtr point_cloud, std::vector<se
       #pragma omp parallel for \
         shared(indices, input_indices, indices_mask, distances, knn, nan_mask, passed, point_cloud, query_index, search_methods) \
         default(none)
-      for (int sIdx = 0; sIdx < int (search_methods.size ()); ++sIdx)
+      for (int sIdx = 0; sIdx < static_cast<int>(search_methods.size ()); ++sIdx)
       {
         search_methods [sIdx]->nearestKSearch ((*point_cloud)[query_index], knn, indices [sIdx], distances [sIdx]);
         passed [sIdx] = passed [sIdx] && testUniqueness (indices [sIdx], search_methods [sIdx]->getName ());
@@ -339,7 +343,7 @@ testKNNSearch (typename PointCloud<PointT>::ConstPtr point_cloud, std::vector<se
       #pragma omp parallel for \
         shared(distances, indices, passed, search_methods) \
         default(none)
-      for (int sIdx = 1; sIdx < int (search_methods.size ()); ++sIdx)
+      for (int sIdx = 1; sIdx < static_cast<int>(search_methods.size ()); ++sIdx)
       {
         passed [sIdx] = passed [sIdx] && compareResults (indices [0],    distances [0],    search_methods [0]->getName (),
                                                          indices [sIdx], distances [sIdx], search_methods [sIdx]->getName (), 1e-6f);
@@ -380,7 +384,7 @@ testRadiusSearch (typename PointCloud<PointT>::ConstPtr point_cloud, std::vector
   #pragma omp parallel for \
     default(none) \
     shared(nan_mask, point_cloud)
-  for (int pIdx = 0; pIdx < int (point_cloud->size ()); ++pIdx)
+  for (int pIdx = 0; pIdx < static_cast<int>(point_cloud->size ()); ++pIdx)
   {
     if (!isFinite (point_cloud->points [pIdx]))
       nan_mask [pIdx] = false;
@@ -393,7 +397,7 @@ testRadiusSearch (typename PointCloud<PointT>::ConstPtr point_cloud, std::vector
   #pragma omp parallel for \
     default(none) \
     shared(input_indices_, point_cloud, search_methods)
-  for (int sIdx = 0; sIdx < int (search_methods.size ()); ++sIdx)
+  for (int sIdx = 0; sIdx < static_cast<int>(search_methods.size ()); ++sIdx)
     search_methods [sIdx]->setInputCloud (point_cloud, input_indices_);
 
   // test radii 0.01, 0.02, 0.04, 0.08
@@ -657,10 +661,12 @@ main (int argc, char** argv)
   
   unorganized_search_methods.push_back (&brute_force);
   unorganized_search_methods.push_back (&KDTree);
+  unorganized_search_methods.push_back (&FlannSearch);
   unorganized_search_methods.push_back (&octree_search);
   
   organized_search_methods.push_back (&brute_force);
   organized_search_methods.push_back (&KDTree);
+  organized_search_methods.push_back (&FlannSearch);
   organized_search_methods.push_back (&octree_search);
   organized_search_methods.push_back (&organized);
   
index 3f22c606a501f9d356d0a4316f3c901ab3033b70..3f863d71625176dae156835f2e9fb03aa7f170a3 100644 (file)
@@ -213,8 +213,8 @@ TEST (PCL, ConcaveHull_LTable)
   {
     for (std::size_t j = 0; j <= 2; j++)
     {
-      cloud_out_ltable[npoints].x = float (i) * 0.5f;
-      cloud_out_ltable[npoints].y = -float (j) * 0.5f;
+      cloud_out_ltable[npoints].x = static_cast<float>(i) * 0.5f;
+      cloud_out_ltable[npoints].y = -static_cast<float>(j) * 0.5f;
       cloud_out_ltable[npoints].z = 0.f;
       npoints++;
     }
@@ -224,8 +224,8 @@ TEST (PCL, ConcaveHull_LTable)
   {
     for(std::size_t j = 3; j < 8; j++)
     {
-      cloud_out_ltable[npoints].x = float (i) * 0.5f;
-      cloud_out_ltable[npoints].y = -float (j) * 0.5f;
+      cloud_out_ltable[npoints].x = static_cast<float>(i) * 0.5f;
+      cloud_out_ltable[npoints].y = -static_cast<float>(j) * 0.5f;
       cloud_out_ltable[npoints].z = 0.f;
       npoints++;
     }
index 7dc05a02dc14389226496b49b46d660005fc33f9..0ad3b8e9644b99a53252bf4fbd4d9d92b4251aaa 100644 (file)
@@ -195,8 +195,8 @@ TEST (PCL, ConvexHull_LTable)
   {
     for (std::size_t j = 0; j <= 2; j++)
     {
-      cloud_out_ltable[npoints].x = float (i) * 0.5f;
-      cloud_out_ltable[npoints].y = -float (j) * 0.5f;
+      cloud_out_ltable[npoints].x = static_cast<float>(i) * 0.5f;
+      cloud_out_ltable[npoints].y = -static_cast<float>(j) * 0.5f;
       cloud_out_ltable[npoints].z = 0.f;
       npoints++;
     }
@@ -206,8 +206,8 @@ TEST (PCL, ConvexHull_LTable)
   {
     for (std::size_t j = 3; j < 8; j++)
     {
-      cloud_out_ltable[npoints].x = float (i) * 0.5f;
-      cloud_out_ltable[npoints].y = -float (j) * 0.5f;
+      cloud_out_ltable[npoints].x = static_cast<float>(i) * 0.5f;
+      cloud_out_ltable[npoints].y = -static_cast<float>(j) * 0.5f;
       cloud_out_ltable[npoints].z = 0.f;
       npoints++;
     }
index fb15467ef71a07c7924d4d5968582f213e0cd642..7095b64d3d8bcacab4aa51b4d38dc98595580f41 100644 (file)
@@ -128,8 +128,8 @@ TEST (PCL, MovingLeastSquares)
 //  EXPECT_NEAR ((*mls_normals)[10].curvature, 0.019003, 1e-3);
 //  EXPECT_EQ (mls_normals->size (), 457);
 
-  const float voxel_size = 0.005f;
-  const int num_dilations = 5;
+  constexpr float voxel_size = 0.005f;
+  constexpr int num_dilations = 5;
   mls_upsampling.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::VOXEL_GRID_DILATION);
   mls_upsampling.setDilationIterations (num_dilations);
   mls_upsampling.setDilationVoxelSize (voxel_size);
index 75491a17592a9dbf0a0837381edc3e17574a2a44..b6a0ec1bf10f80f4c844201831e0b7243fb773d9 100644 (file)
@@ -75,8 +75,8 @@ TEST (PCL, Poisson)
 
   ASSERT_EQ (mesh.polygons.size (), 4828);
   // All polygons should be triangles
-  for (std::size_t i = 0; i < mesh.polygons.size (); ++i)
-    EXPECT_EQ (mesh.polygons[i].vertices.size (), 3);
+  for (const auto & polygon : mesh.polygons)
+    EXPECT_EQ (polygon.vertices.size (), 3);
 
   EXPECT_EQ (mesh.polygons[10].vertices[0], 197);
   EXPECT_EQ (mesh.polygons[10].vertices[1], 198);
index 5a8b83e1fa9cb7718794ea36583c65380ec88272..fd21aa7e4dc3b1ca9d716903e4babf8667335ddb 100644 (file)
@@ -191,6 +191,36 @@ TEST (PCL, PCLVisualizer_getPointCloudRenderingProperties)
   EXPECT_EQ (b, 0.);
 }
 
+// This test was added to make sure the dynamic_cast in updateColorHandlerIndex works correctly
+// (see https://github.com/PointCloudLibrary/pcl/issues/5545)
+TEST(PCL, PCLVisualizer_updateColorHandlerIndex) {
+  // create
+  visualization::PCLVisualizer::Ptr viewer_ptr(
+      new visualization::PCLVisualizer);
+  // generates points
+  common::CloudGenerator<PointXYZRGB, common::UniformGenerator<float>>
+      generator;
+  PointCloud<PointXYZRGB>::Ptr rgb_cloud_ptr(new PointCloud<PointXYZRGB>());
+  generator.fill(3, 1, *rgb_cloud_ptr);
+
+  PCLPointCloud2::Ptr rgb_cloud2_ptr(new PCLPointCloud2());
+  toPCLPointCloud2(*rgb_cloud_ptr, *rgb_cloud2_ptr);
+
+  // add cloud
+  const std::string cloud_name = "RGB_cloud";
+  visualization::PointCloudColorHandlerRGBField<PCLPointCloud2>::Ptr
+      color_handler_ptr(
+          new visualization::PointCloudColorHandlerRGBField<PCLPointCloud2>(
+              rgb_cloud2_ptr));
+  viewer_ptr->addPointCloud(rgb_cloud2_ptr,
+                            color_handler_ptr,
+                            Eigen::Vector4f::Zero(),
+                            Eigen::Quaternionf(),
+                            cloud_name,
+                            0);
+  EXPECT_TRUE(viewer_ptr->updateColorHandlerIndex(cloud_name, 0));
+}
+
 /* ---[ */
 int
 main (int argc, char** argv)
index 8a72fdaa2cca0864497d251dde557d21d50837d8..a4151e9c2d4378edcdb3807b8f55c081a7d055e2 100644 (file)
@@ -1,11 +1,11 @@
 set(SUBSYS_NAME tools)
 set(SUBSYS_DESC "Useful PCL-based command line tools")
-set(SUBSYS_DEPS common io filters sample_consensus segmentation search kdtree features surface octree registration recognition geometry keypoints ml)
-set(SUBSYS_OPT_DEPS vtk visualization)
+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} ${DEFAULT} ${REASON})
 PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${SUBSYS_OPT_DEPS})
 
 if(NOT build)
@@ -15,26 +15,7 @@ endif()
 # to be filled with all targets the tools subsystem
 set(PCL_TOOLS_ALL_TARGETS)
 
-PCL_ADD_EXECUTABLE(pcl_sac_segmentation_plane COMPONENT ${SUBSYS_NAME} SOURCES sac_segmentation_plane.cpp)
-target_link_libraries(pcl_sac_segmentation_plane pcl_common pcl_io pcl_sample_consensus pcl_segmentation)
-
-PCL_ADD_EXECUTABLE(pcl_plane_projection COMPONENT ${SUBSYS_NAME} SOURCES plane_projection.cpp)
-target_link_libraries (pcl_plane_projection pcl_common pcl_io pcl_sample_consensus)
-
-PCL_ADD_EXECUTABLE(pcl_normal_estimation COMPONENT ${SUBSYS_NAME} SOURCES normal_estimation.cpp)
-target_link_libraries (pcl_normal_estimation pcl_common pcl_io pcl_features pcl_kdtree)
-
-PCL_ADD_EXECUTABLE(pcl_uniform_sampling COMPONENT ${SUBSYS_NAME} SOURCES uniform_sampling.cpp)
-target_link_libraries (pcl_uniform_sampling pcl_common pcl_io pcl_filters pcl_keypoints pcl_kdtree)
-
-PCL_ADD_EXECUTABLE(pcl_boundary_estimation COMPONENT ${SUBSYS_NAME} SOURCES boundary_estimation.cpp)
-target_link_libraries (pcl_boundary_estimation pcl_common pcl_io pcl_features pcl_kdtree)
-
-PCL_ADD_EXECUTABLE(pcl_cluster_extraction COMPONENT ${SUBSYS_NAME} SOURCES cluster_extraction.cpp)
-target_link_libraries (pcl_cluster_extraction pcl_common pcl_io pcl_segmentation pcl_filters pcl_kdtree)
-
-PCL_ADD_EXECUTABLE(pcl_fpfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES fpfh_estimation.cpp)
-target_link_libraries (pcl_fpfh_estimation pcl_common pcl_io pcl_features pcl_kdtree)
+PCL_ADD_EXECUTABLE(pcl_pcd_convert_NaN_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_convert_NaN_nan.cpp)
 
 PCL_ADD_EXECUTABLE(pcl_pcd2ply COMPONENT ${SUBSYS_NAME} SOURCES pcd2ply.cpp)
 target_link_libraries (pcl_pcd2ply pcl_common pcl_io)
@@ -51,132 +32,45 @@ target_link_libraries (pcl_pclzf2pcd pcl_common pcl_io)
 PCL_ADD_EXECUTABLE(pcl_pcd2vtk COMPONENT ${SUBSYS_NAME} SOURCES pcd2vtk.cpp)
 target_link_libraries (pcl_pcd2vtk pcl_common pcl_io)
 
-PCL_ADD_EXECUTABLE(pcl_vfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES vfh_estimation.cpp)
-target_link_libraries (pcl_vfh_estimation pcl_common pcl_io pcl_features pcl_kdtree)
-
-PCL_ADD_EXECUTABLE(pcl_spin_estimation COMPONENT ${SUBSYS_NAME} SOURCES spin_estimation.cpp)
-target_link_libraries (pcl_spin_estimation pcl_common pcl_io pcl_features pcl_kdtree)
-
-PCL_ADD_EXECUTABLE(pcl_voxel_grid COMPONENT ${SUBSYS_NAME} SOURCES voxel_grid.cpp)
-target_link_libraries (pcl_voxel_grid pcl_common pcl_io pcl_filters)
-
-PCL_ADD_EXECUTABLE(pcl_passthrough_filter COMPONENT ${SUBSYS_NAME} SOURCES passthrough_filter.cpp)
-target_link_libraries (pcl_passthrough_filter pcl_common pcl_io pcl_filters)
-
-PCL_ADD_EXECUTABLE(pcl_radius_filter COMPONENT ${SUBSYS_NAME} SOURCES radius_filter.cpp)
-target_link_libraries (pcl_radius_filter pcl_common pcl_io pcl_filters)
-
-PCL_ADD_EXECUTABLE(pcl_extract_feature COMPONENT ${SUBSYS_NAME} SOURCES extract_feature.cpp)
-target_link_libraries (pcl_extract_feature pcl_common pcl_io pcl_features pcl_kdtree)
-
-PCL_ADD_EXECUTABLE(pcl_compute_cloud_error COMPONENT ${SUBSYS_NAME} SOURCES compute_cloud_error.cpp)
-target_link_libraries (pcl_compute_cloud_error pcl_common pcl_io pcl_kdtree pcl_search)
-
-PCL_ADD_EXECUTABLE(pcl_train_unary_classifier COMPONENT ${SUBSYS_NAME} SOURCES train_unary_classifier.cpp)
-target_link_libraries (pcl_train_unary_classifier pcl_common pcl_io pcl_segmentation)
-
-PCL_ADD_EXECUTABLE(pcl_unary_classifier_segment COMPONENT ${SUBSYS_NAME} SOURCES unary_classifier_segment.cpp)
-target_link_libraries (pcl_unary_classifier_segment pcl_common pcl_io pcl_segmentation)
-
-PCL_ADD_EXECUTABLE(pcl_crf_segmentation COMPONENT ${SUBSYS_NAME} SOURCES crf_segmentation.cpp)
-target_link_libraries (pcl_crf_segmentation pcl_common pcl_io pcl_segmentation)
-
 PCL_ADD_EXECUTABLE(pcl_add_gaussian_noise COMPONENT ${SUBSYS_NAME} SOURCES add_gaussian_noise.cpp)
 target_link_libraries (pcl_add_gaussian_noise pcl_common pcl_io)
 
-PCL_ADD_EXECUTABLE(pcl_outlier_removal COMPONENT ${SUBSYS_NAME} SOURCES outlier_removal.cpp)
-target_link_libraries (pcl_outlier_removal pcl_common pcl_io 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_marching_cubes_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES marching_cubes_reconstruction.cpp)
-target_link_libraries (pcl_marching_cubes_reconstruction pcl_common pcl_io pcl_surface)
-
-PCL_ADD_EXECUTABLE(pcl_gp3_surface COMPONENT ${SUBSYS_NAME} SOURCES gp3_surface.cpp)
-target_link_libraries (pcl_gp3_surface pcl_common pcl_io pcl_surface)
-
-PCL_ADD_EXECUTABLE(pcl_icp COMPONENT ${SUBSYS_NAME} SOURCES icp.cpp)
-target_link_libraries(pcl_icp pcl_common pcl_io pcl_registration)
-
-PCL_ADD_EXECUTABLE(pcl_icp2d COMPONENT ${SUBSYS_NAME} SOURCES icp2d.cpp)
-target_link_libraries(pcl_icp2d pcl_common pcl_io pcl_registration)
-
-PCL_ADD_EXECUTABLE(pcl_elch COMPONENT ${SUBSYS_NAME} SOURCES elch.cpp)
-target_link_libraries(pcl_elch pcl_common pcl_io pcl_registration)
-
-PCL_ADD_EXECUTABLE(pcl_lum COMPONENT ${SUBSYS_NAME} SOURCES lum.cpp)
-target_link_libraries(pcl_lum pcl_common pcl_io pcl_registration)
-
-PCL_ADD_EXECUTABLE(pcl_ndt2d COMPONENT ${SUBSYS_NAME} SOURCES ndt2d.cpp)
-target_link_libraries(pcl_ndt2d pcl_common pcl_io pcl_registration)
-
-PCL_ADD_EXECUTABLE(pcl_ndt3d COMPONENT ${SUBSYS_NAME} SOURCES ndt3d.cpp)
-target_link_libraries(pcl_ndt3d pcl_common pcl_io pcl_registration)
-
 PCL_ADD_EXECUTABLE(pcl_pcd_change_viewpoint COMPONENT ${SUBSYS_NAME} SOURCES pcd_change_viewpoint.cpp)
 target_link_libraries(pcl_pcd_change_viewpoint pcl_common pcl_io)
 
 PCL_ADD_EXECUTABLE(pcl_concatenate_points_pcd COMPONENT ${SUBSYS_NAME} SOURCES concatenate_points_pcd.cpp)
 target_link_libraries(pcl_concatenate_points_pcd pcl_common pcl_io)
 
-PCL_ADD_EXECUTABLE(pcl_poisson_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES poisson_reconstruction.cpp)
-target_link_libraries(pcl_poisson_reconstruction pcl_common pcl_io pcl_surface)
-
-PCL_ADD_EXECUTABLE(pcl_train_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES train_linemod_template.cpp)
-target_link_libraries(pcl_train_linemod_template pcl_common pcl_io pcl_segmentation pcl_recognition)
-
-PCL_ADD_EXECUTABLE(pcl_match_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES match_linemod_template.cpp)
-target_link_libraries(pcl_match_linemod_template pcl_common pcl_io pcl_recognition)
-
-PCL_ADD_EXECUTABLE(pcl_linemod_detection COMPONENT ${SUBSYS_NAME} SOURCES linemod_detection.cpp)
-target_link_libraries(pcl_linemod_detection pcl_common pcl_io pcl_recognition)
-
-PCL_ADD_EXECUTABLE(pcl_fast_bilateral_filter COMPONENT ${SUBSYS_NAME} SOURCES fast_bilateral_filter.cpp)
-target_link_libraries(pcl_fast_bilateral_filter pcl_common pcl_io pcl_filters)
-
 PCL_ADD_EXECUTABLE(pcl_demean_cloud COMPONENT ${SUBSYS_NAME} SOURCES demean_cloud.cpp)
 target_link_libraries(pcl_demean_cloud pcl_common pcl_io)
 
-PCL_ADD_EXECUTABLE(pcl_compute_hausdorff COMPONENT ${SUBSYS_NAME} SOURCES compute_hausdorff.cpp)
-target_link_libraries(pcl_compute_hausdorff pcl_common pcl_io pcl_search)
-
-PCL_ADD_EXECUTABLE(pcl_morph COMPONENT ${SUBSYS_NAME} SOURCES morph.cpp)
-target_link_libraries(pcl_morph pcl_common pcl_io pcl_filters)
-
-PCL_ADD_EXECUTABLE(pcl_progressive_morphological_filter COMPONENT ${SUBSYS_NAME} SOURCES progressive_morphological_filter.cpp)
-target_link_libraries(pcl_progressive_morphological_filter pcl_common pcl_io pcl_filters pcl_segmentation)
-
 PCL_ADD_EXECUTABLE(pcl_generate COMPONENT ${SUBSYS_NAME} SOURCES generate.cpp)
 target_link_libraries(pcl_generate pcl_common pcl_io)
 
-PCL_ADD_EXECUTABLE(pcl_local_max COMPONENT ${SUBSYS_NAME} SOURCES local_max.cpp)
-target_link_libraries(pcl_local_max pcl_common pcl_io pcl_filters)
+PCL_ADD_EXECUTABLE(pcl_convert_pcd_ascii_binary COMPONENT ${SUBSYS_NAME} SOURCES convert_pcd_ascii_binary.cpp)
+target_link_libraries(pcl_convert_pcd_ascii_binary pcl_common pcl_io)
 
-PCL_ADD_EXECUTABLE(pcl_grid_min COMPONENT ${SUBSYS_NAME} SOURCES grid_min.cpp)
-target_link_libraries(pcl_grid_min pcl_common pcl_io pcl_filters)
+PCL_ADD_EXECUTABLE(pcl_pcd_introduce_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_introduce_nan.cpp)
+target_link_libraries(pcl_pcd_introduce_nan pcl_common pcl_io)
+
+PCL_ADD_EXECUTABLE(pcl_hdl_grabber COMPONENT ${SUBSYS_NAME} SOURCES hdl_grabber_example.cpp)
+target_link_libraries(pcl_hdl_grabber pcl_common pcl_io)
 
 if(WITH_OPENNI)
   PCL_ADD_EXECUTABLE(pcl_oni2pcd COMPONENT ${SUBSYS_NAME} SOURCES oni2pcd.cpp)
   target_link_libraries(pcl_oni2pcd pcl_common pcl_io)
-endif()
+  
+  PCL_ADD_EXECUTABLE(pcl_openni_grabber_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_example.cpp)
+  target_link_libraries(pcl_openni_grabber_example pcl_common pcl_io)
 
-if(QHULL_FOUND)
-  PCL_ADD_EXECUTABLE(pcl_crop_to_hull COMPONENT ${SUBSYS_NAME} SOURCES crop_to_hull.cpp)
-  target_link_libraries(pcl_crop_to_hull pcl_common pcl_io pcl_filters pcl_surface)
+  PCL_ADD_EXECUTABLE(pcl_openni_grabber_depth_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_depth_example.cpp)
+  target_link_libraries(pcl_openni_grabber_depth_example pcl_common pcl_io)
 
-  PCL_ADD_EXECUTABLE(pcl_compute_hull COMPONENT ${SUBSYS_NAME} SOURCES compute_hull.cpp)
-  target_link_libraries(pcl_compute_hull pcl_common pcl_io pcl_surface)
+  PCL_ADD_EXECUTABLE(pcl_openni_pcd_recorder COMPONENT ${SUBSYS_NAME} SOURCES openni_pcd_recorder.cpp)
+  target_link_libraries(pcl_openni_pcd_recorder pcl_common pcl_io)
 endif()
 
-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")
-
+if(VTK_FOUND)
   PCL_ADD_EXECUTABLE(pcl_png2pcd COMPONENT ${SUBSYS_NAME} SOURCES png2pcd.cpp)
   target_link_libraries(pcl_png2pcd pcl_common pcl_io)
 
@@ -219,127 +113,291 @@ else()
     target_link_libraries(pcl_vtk2pcd vtkFiltersCore)
   endif()
 
-  if(BUILD_visualization)
-    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_model_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_model_opps.cpp)
-    target_link_libraries(pcl_obj_rec_ransac_model_opps pcl_common pcl_visualization pcl_recognition)
+  PCL_ADD_EXECUTABLE(pcl_converter COMPONENT ${SUBSYS_NAME} SOURCES converter.cpp)
+  target_link_libraries(pcl_converter pcl_common pcl_io)
+endif()
 
-    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_hash_table COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_hash_table.cpp)
-    target_link_libraries(pcl_obj_rec_ransac_hash_table pcl_common pcl_visualization pcl_io pcl_recognition)
+if(TARGET pcl_io_ply)
+  PCL_ADD_EXECUTABLE(pcl_ply2obj COMPONENT ${SUBSYS_NAME} SOURCES ply2obj.cpp)
+  target_link_libraries(pcl_ply2obj pcl_io_ply)
 
-    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_scene_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_scene_opps.cpp)
-    target_link_libraries(pcl_obj_rec_ransac_scene_opps pcl_common pcl_visualization pcl_io pcl_recognition)
+  PCL_ADD_EXECUTABLE(pcl_ply2ply COMPONENT ${SUBSYS_NAME} SOURCES ply2ply.cpp)
+  target_link_libraries(pcl_ply2ply pcl_io_ply)
 
-    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_accepted_hypotheses COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_accepted_hypotheses.cpp)
-    target_link_libraries(pcl_obj_rec_ransac_accepted_hypotheses pcl_common pcl_visualization pcl_io pcl_recognition)
+  PCL_ADD_EXECUTABLE(pcl_ply2raw COMPONENT ${SUBSYS_NAME} SOURCES ply2raw.cpp)
+  target_link_libraries(pcl_ply2raw pcl_io_ply)
 
-    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree.cpp)
-    target_link_libraries(pcl_obj_rec_ransac_orr_octree pcl_common pcl_visualization pcl_io pcl_recognition)
+  PCL_ADD_EXECUTABLE(pcl_plyheader COMPONENT ${SUBSYS_NAME} SOURCES plyheader.cpp)
+  target_link_libraries(pcl_plyheader pcl_io_ply)
+endif()
 
-    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree_zprojection COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree_zprojection.cpp)
-    target_link_libraries(pcl_obj_rec_ransac_orr_octree_zprojection pcl_common pcl_visualization pcl_io pcl_recognition)
+if(TARGET pcl_sample_consensus)
+  PCL_ADD_EXECUTABLE(pcl_plane_projection COMPONENT ${SUBSYS_NAME} SOURCES plane_projection.cpp)
+  target_link_libraries (pcl_plane_projection pcl_common pcl_io pcl_sample_consensus)
+endif()
+
+if(TARGET pcl_search)
+  PCL_ADD_EXECUTABLE(pcl_compute_hausdorff COMPONENT ${SUBSYS_NAME} SOURCES compute_hausdorff.cpp)
+  target_link_libraries(pcl_compute_hausdorff pcl_common pcl_io pcl_search)
 
-    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_result COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_result.cpp)
-    target_link_libraries(pcl_obj_rec_ransac_result pcl_common pcl_visualization pcl_io pcl_segmentation pcl_recognition)
+  PCL_ADD_EXECUTABLE(pcl_compute_cloud_error COMPONENT ${SUBSYS_NAME} SOURCES compute_cloud_error.cpp)
+  target_link_libraries (pcl_compute_cloud_error pcl_common pcl_io pcl_kdtree pcl_search)
 
-    PCL_ADD_EXECUTABLE(pcl_registration_visualizer COMPONENT ${SUBSYS_NAME} SOURCES registration_visualizer.cpp)
-    target_link_libraries(pcl_registration_visualizer pcl_common pcl_io pcl_kdtree pcl_filters pcl_registration pcl_visualization)
+  if(TARGET pcl_visualization)
+    PCL_ADD_EXECUTABLE(pcl_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_viewer pcl_common pcl_io pcl_kdtree pcl_search pcl_visualization )
+  endif()
+endif()
+
+if(TARGET pcl_filters)
+  PCL_ADD_EXECUTABLE(pcl_voxel_grid COMPONENT ${SUBSYS_NAME} SOURCES voxel_grid.cpp)
+  target_link_libraries (pcl_voxel_grid pcl_common pcl_io pcl_filters)
+
+  PCL_ADD_EXECUTABLE(pcl_passthrough_filter COMPONENT ${SUBSYS_NAME} SOURCES passthrough_filter.cpp)
+  target_link_libraries (pcl_passthrough_filter pcl_common pcl_io pcl_filters)
+
+  PCL_ADD_EXECUTABLE(pcl_radius_filter COMPONENT ${SUBSYS_NAME} SOURCES radius_filter.cpp)
+  target_link_libraries (pcl_radius_filter pcl_common pcl_io pcl_filters)
+
+  PCL_ADD_EXECUTABLE(pcl_outlier_removal COMPONENT ${SUBSYS_NAME} SOURCES outlier_removal.cpp)
+  target_link_libraries (pcl_outlier_removal pcl_common pcl_io pcl_filters)
+
+  PCL_ADD_EXECUTABLE(pcl_fast_bilateral_filter COMPONENT ${SUBSYS_NAME} SOURCES fast_bilateral_filter.cpp)
+  target_link_libraries(pcl_fast_bilateral_filter pcl_common pcl_io pcl_filters)
 
+  PCL_ADD_EXECUTABLE(pcl_morph COMPONENT ${SUBSYS_NAME} SOURCES morph.cpp)
+  target_link_libraries(pcl_morph pcl_common pcl_io pcl_filters)
+
+  PCL_ADD_EXECUTABLE(pcl_local_max COMPONENT ${SUBSYS_NAME} SOURCES local_max.cpp)
+  target_link_libraries(pcl_local_max pcl_common pcl_io pcl_filters)
+
+  PCL_ADD_EXECUTABLE(pcl_grid_min COMPONENT ${SUBSYS_NAME} SOURCES grid_min.cpp)
+  target_link_libraries(pcl_grid_min pcl_common pcl_io pcl_filters)
+
+  if(TARGET pcl_segmentation)
+    PCL_ADD_EXECUTABLE(pcl_cluster_extraction COMPONENT ${SUBSYS_NAME} SOURCES cluster_extraction.cpp)
+    target_link_libraries (pcl_cluster_extraction pcl_common pcl_io pcl_kdtree pcl_filters pcl_segmentation)
+
+    PCL_ADD_EXECUTABLE(pcl_progressive_morphological_filter COMPONENT ${SUBSYS_NAME} SOURCES progressive_morphological_filter.cpp)
+    target_link_libraries(pcl_progressive_morphological_filter pcl_common pcl_io pcl_filters pcl_segmentation)
+  endif()
+
+  if(TARGET pcl_surface)
+    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)
+
+  endif()
+
+  if(TARGET pcl_keypoints)
+    PCL_ADD_EXECUTABLE(pcl_uniform_sampling COMPONENT ${SUBSYS_NAME} SOURCES uniform_sampling.cpp)
+    target_link_libraries (pcl_uniform_sampling pcl_common pcl_io pcl_kdtree pcl_filters pcl_keypoints)
+  endif()
+
+  if(TARGET pcl_registration)
+    if(TARGET pcl_visualization)
+      PCL_ADD_EXECUTABLE(pcl_registration_visualizer COMPONENT ${SUBSYS_NAME} SOURCES registration_visualizer.cpp)
+      target_link_libraries(pcl_registration_visualizer pcl_common pcl_io pcl_kdtree pcl_filters pcl_registration pcl_visualization)
+    endif()
+  endif()
+
+  if(TARGET pcl_visualization)
     PCL_ADD_EXECUTABLE(pcl_octree_viewer COMPONENT ${SUBSYS_NAME} SOURCES octree_viewer.cpp)
-    target_link_libraries(pcl_octree_viewer pcl_common pcl_io pcl_octree pcl_visualization pcl_kdtree pcl_filters)
+    target_link_libraries(pcl_octree_viewer pcl_common pcl_io pcl_octree pcl_kdtree pcl_filters pcl_visualization)
 
     PCL_ADD_EXECUTABLE(pcl_mesh2pcd COMPONENT ${SUBSYS_NAME} SOURCES mesh2pcd.cpp)
-    target_link_libraries(pcl_mesh2pcd pcl_common pcl_io pcl_visualization pcl_filters)
+    target_link_libraries(pcl_mesh2pcd pcl_common pcl_io pcl_filters pcl_visualization)
 
     PCL_ADD_EXECUTABLE(pcl_mesh_sampling COMPONENT ${SUBSYS_NAME} SOURCES mesh_sampling.cpp)
-    target_link_libraries(pcl_mesh_sampling pcl_common pcl_io pcl_visualization pcl_filters)
+    target_link_libraries(pcl_mesh_sampling pcl_common pcl_io pcl_filters pcl_visualization)
 
     PCL_ADD_EXECUTABLE(pcl_virtual_scanner COMPONENT ${SUBSYS_NAME} SOURCES virtual_scanner.cpp)
     target_link_libraries(pcl_virtual_scanner pcl_common pcl_io pcl_filters pcl_visualization)
 
     PCL_ADD_EXECUTABLE(pcl_voxel_grid_occlusion_estimation COMPONENT ${SUBSYS_NAME} SOURCES voxel_grid_occlusion_estimation.cpp)
     target_link_libraries (pcl_voxel_grid_occlusion_estimation pcl_common pcl_io pcl_filters pcl_visualization)
+  endif()
+endif()
 
-    PCL_ADD_EXECUTABLE(pcl_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_viewer.cpp BUNDLE)
-    target_link_libraries(pcl_viewer pcl_common pcl_io pcl_kdtree pcl_visualization pcl_search)
+if(TARGET pcl_segmentation)
+  PCL_ADD_EXECUTABLE(pcl_sac_segmentation_plane COMPONENT ${SUBSYS_NAME} SOURCES sac_segmentation_plane.cpp)
+  target_link_libraries(pcl_sac_segmentation_plane pcl_common pcl_io pcl_sample_consensus pcl_segmentation)
 
-    PCL_ADD_EXECUTABLE(pcl_pcd_image_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_viewer.cpp BUNDLE)
-    target_link_libraries(pcl_pcd_image_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_train_unary_classifier COMPONENT ${SUBSYS_NAME} SOURCES train_unary_classifier.cpp)
+  target_link_libraries (pcl_train_unary_classifier pcl_common pcl_io pcl_segmentation)
 
-    PCL_ADD_EXECUTABLE(pcl_timed_trigger_test COMPONENT ${SUBSYS_NAME} SOURCES timed_trigger_test.cpp)
-    target_link_libraries(pcl_timed_trigger_test pcl_io pcl_common pcl_kdtree pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_unary_classifier_segment COMPONENT ${SUBSYS_NAME} SOURCES unary_classifier_segment.cpp)
+  target_link_libraries (pcl_unary_classifier_segment pcl_common pcl_io pcl_segmentation)
 
-    PCL_ADD_EXECUTABLE(pcl_hdl_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES hdl_viewer_simple.cpp)
-    target_link_libraries(pcl_hdl_viewer_simple pcl_io pcl_common pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_crf_segmentation COMPONENT ${SUBSYS_NAME} SOURCES crf_segmentation.cpp)
+  target_link_libraries (pcl_crf_segmentation pcl_common pcl_io pcl_segmentation)
 
-    PCL_ADD_EXECUTABLE(pcl_vlp_viewer COMPONENT ${SUBSYS_NAME} SOURCES vlp_viewer.cpp)
-    target_link_libraries(pcl_vlp_viewer pcl_io pcl_common pcl_visualization)
+  if(TARGET pcl_recognition)
+    PCL_ADD_EXECUTABLE(pcl_train_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES train_linemod_template.cpp)
+    target_link_libraries(pcl_train_linemod_template pcl_common pcl_io pcl_segmentation pcl_recognition)
 
-    if(WITH_OPENNI)
-      PCL_ADD_EXECUTABLE(pcl_openni_save_image COMPONENT ${SUBSYS_NAME} SOURCES openni_save_image.cpp)
-      target_link_libraries(pcl_openni_save_image pcl_common pcl_io pcl_visualization Boost::date_time)
+    if(TARGET pcl_visualization)
+      PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_result COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_result.cpp)
+      target_link_libraries(pcl_obj_rec_ransac_result pcl_common pcl_io pcl_segmentation pcl_recognition pcl_visualization)
+    endif()
+  endif()
+endif()
 
-      PCL_ADD_EXECUTABLE(pcl_pcd_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_grabber_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_pcd_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+if(TARGET pcl_features)
+  PCL_ADD_EXECUTABLE(pcl_normal_estimation COMPONENT ${SUBSYS_NAME} SOURCES normal_estimation.cpp)
+  target_link_libraries (pcl_normal_estimation pcl_common pcl_io pcl_kdtree pcl_features)
 
-      PCL_ADD_EXECUTABLE(pcl_image_grabber_saver COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_saver.cpp BUNDLE)
-      target_link_libraries(pcl_image_grabber_saver pcl_common pcl_io pcl_kdtree pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_boundary_estimation COMPONENT ${SUBSYS_NAME} SOURCES boundary_estimation.cpp)
+  target_link_libraries (pcl_boundary_estimation pcl_common pcl_io pcl_kdtree pcl_features)
 
-      PCL_ADD_EXECUTABLE(pcl_image_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_image_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_fpfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES fpfh_estimation.cpp)
+  target_link_libraries (pcl_fpfh_estimation pcl_common pcl_io pcl_kdtree pcl_features)
 
-      #PCL_ADD_EXECUTABLE(pcl_openni_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer_simple.cpp)
-      #target_link_libraries(pcl_openni_viewer_simple pcl_common pcl_io pcl_kdtree pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_vfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES vfh_estimation.cpp)
+  target_link_libraries (pcl_vfh_estimation pcl_common pcl_io pcl_kdtree pcl_features)
 
-      PCL_ADD_EXECUTABLE(pcl_oni_viewer COMPONENT ${SUBSYS_NAME} SOURCES oni_viewer_simple.cpp BUNDLE)
-      target_link_libraries(pcl_oni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_spin_estimation COMPONENT ${SUBSYS_NAME} SOURCES spin_estimation.cpp)
+  target_link_libraries (pcl_spin_estimation pcl_common pcl_io pcl_kdtree pcl_features)
 
-      PCL_ADD_EXECUTABLE(pcl_openni_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_openni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_extract_feature COMPONENT ${SUBSYS_NAME} SOURCES extract_feature.cpp)
+  target_link_libraries (pcl_extract_feature pcl_common pcl_io pcl_kdtree pcl_features)
+endif()
 
-      PCL_ADD_EXECUTABLE(pcl_openni_image COMPONENT ${SUBSYS_NAME} SOURCES openni_image.cpp BUNDLE)
-      target_link_libraries(pcl_openni_image pcl_common pcl_io pcl_kdtree pcl_visualization Boost::date_time)
-    endif()
+if(TARGET pcl_surface)
+  PCL_ADD_EXECUTABLE(pcl_marching_cubes_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES marching_cubes_reconstruction.cpp)
+  target_link_libraries (pcl_marching_cubes_reconstruction pcl_common pcl_io pcl_surface)
 
-    if(WITH_OPENNI2)
-      PCL_ADD_EXECUTABLE(pcl_openni2_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni2_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_openni2_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
-    endif()
+  PCL_ADD_EXECUTABLE(pcl_gp3_surface COMPONENT ${SUBSYS_NAME} SOURCES gp3_surface.cpp)
+  target_link_libraries (pcl_gp3_surface pcl_common pcl_io pcl_surface)
 
-    if(WITH_ENSENSO)
-      PCL_ADD_EXECUTABLE(pcl_ensenso_viewer COMPONENT ${SUBSYS_NAME} SOURCES ensenso_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_ensenso_viewer pcl_common pcl_io pcl_visualization)
-    endif()
+  PCL_ADD_EXECUTABLE(pcl_poisson_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES poisson_reconstruction.cpp)
+  target_link_libraries(pcl_poisson_reconstruction pcl_common pcl_io pcl_surface)
 
-    if(WITH_DAVIDSDK)
-      PCL_ADD_EXECUTABLE(pcl_davidsdk_viewer COMPONENT ${SUBSYS_NAME} SOURCES davidsdk_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_davidsdk_viewer pcl_common pcl_io pcl_visualization)
-    endif()
+  if(QHULL_FOUND)
+    PCL_ADD_EXECUTABLE(pcl_crop_to_hull COMPONENT ${SUBSYS_NAME} SOURCES crop_to_hull.cpp)
+    target_link_libraries(pcl_crop_to_hull pcl_common pcl_io pcl_filters pcl_surface)
 
-    if(WITH_DSSDK)
-      PCL_ADD_EXECUTABLE(pcl_depth_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES depth_sense_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_depth_sense_viewer pcl_common pcl_io pcl_visualization)
-    endif()
+    PCL_ADD_EXECUTABLE(pcl_compute_hull COMPONENT ${SUBSYS_NAME} SOURCES compute_hull.cpp)
+    target_link_libraries(pcl_compute_hull pcl_common pcl_io pcl_surface)
+  endif()
+endif()
 
-    if(WITH_RSSDK)
-      PCL_ADD_EXECUTABLE(pcl_real_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES real_sense_viewer.cpp BUNDLE)
-      target_link_libraries(pcl_real_sense_viewer pcl_common pcl_io pcl_visualization)
-    endif()
+if(TARGET pcl_registration)
+  PCL_ADD_EXECUTABLE(pcl_icp COMPONENT ${SUBSYS_NAME} SOURCES icp.cpp)
+  target_link_libraries(pcl_icp pcl_common pcl_io pcl_registration)
+
+  PCL_ADD_EXECUTABLE(pcl_icp2d COMPONENT ${SUBSYS_NAME} SOURCES icp2d.cpp)
+  target_link_libraries(pcl_icp2d pcl_common pcl_io pcl_registration)
+
+  PCL_ADD_EXECUTABLE(pcl_elch COMPONENT ${SUBSYS_NAME} SOURCES elch.cpp)
+  target_link_libraries(pcl_elch pcl_common pcl_io pcl_registration)
+
+  PCL_ADD_EXECUTABLE(pcl_lum COMPONENT ${SUBSYS_NAME} SOURCES lum.cpp)
+  target_link_libraries(pcl_lum pcl_common pcl_io pcl_registration)
+
+  PCL_ADD_EXECUTABLE(pcl_ndt2d COMPONENT ${SUBSYS_NAME} SOURCES ndt2d.cpp)
+  target_link_libraries(pcl_ndt2d pcl_common pcl_io pcl_registration)
+
+  PCL_ADD_EXECUTABLE(pcl_ndt3d COMPONENT ${SUBSYS_NAME} SOURCES ndt3d.cpp)
+  target_link_libraries(pcl_ndt3d pcl_common pcl_io pcl_registration)
+
+  PCL_ADD_EXECUTABLE(pcl_transform_point_cloud COMPONENT ${SUBSYS_NAME} SOURCES transform_point_cloud.cpp)
+  target_link_libraries (pcl_transform_point_cloud pcl_common pcl_io pcl_registration)
+
+  PCL_ADD_EXECUTABLE(pcl_transform_from_viewpoint COMPONENT ${SUBSYS_NAME} SOURCES transform_from_viewpoint.cpp)
+  target_link_libraries (pcl_transform_from_viewpoint pcl_common pcl_io pcl_registration)
+endif()
+
+if(TARGET pcl_recognition)
+  PCL_ADD_EXECUTABLE(pcl_match_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES match_linemod_template.cpp)
+  target_link_libraries(pcl_match_linemod_template pcl_common pcl_io pcl_recognition)
+
+  PCL_ADD_EXECUTABLE(pcl_linemod_detection COMPONENT ${SUBSYS_NAME} SOURCES linemod_detection.cpp)
+  target_link_libraries(pcl_linemod_detection pcl_common pcl_io pcl_recognition)
+
+  if(TARGET pcl_visualization)
+    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_model_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_model_opps.cpp)
+    target_link_libraries(pcl_obj_rec_ransac_model_opps pcl_common pcl_recognition pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_hash_table COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_hash_table.cpp)
+    target_link_libraries(pcl_obj_rec_ransac_hash_table pcl_common pcl_io pcl_recognition pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_scene_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_scene_opps.cpp)
+    target_link_libraries(pcl_obj_rec_ransac_scene_opps pcl_common pcl_io pcl_recognition pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_accepted_hypotheses COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_accepted_hypotheses.cpp)
+    target_link_libraries(pcl_obj_rec_ransac_accepted_hypotheses pcl_common pcl_io pcl_recognition pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree.cpp)
+    target_link_libraries(pcl_obj_rec_ransac_orr_octree pcl_common pcl_io pcl_recognition pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree_zprojection COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree_zprojection.cpp)
+    target_link_libraries(pcl_obj_rec_ransac_orr_octree_zprojection pcl_common pcl_io pcl_recognition pcl_visualization)
   endif()
 endif()
 
-PCL_ADD_EXECUTABLE(pcl_transform_point_cloud COMPONENT ${SUBSYS_NAME} SOURCES transform_point_cloud.cpp)
-target_link_libraries (pcl_transform_point_cloud pcl_common pcl_io pcl_registration)
+if(TARGET pcl_visualization)
+  PCL_ADD_EXECUTABLE(pcl_pcd_image_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_viewer.cpp BUNDLE)
+  target_link_libraries(pcl_pcd_image_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+
+  PCL_ADD_EXECUTABLE(pcl_timed_trigger_test COMPONENT ${SUBSYS_NAME} SOURCES timed_trigger_test.cpp)
+  target_link_libraries(pcl_timed_trigger_test pcl_io pcl_common pcl_kdtree pcl_visualization)
+
+  PCL_ADD_EXECUTABLE(pcl_hdl_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES hdl_viewer_simple.cpp)
+  target_link_libraries(pcl_hdl_viewer_simple pcl_io pcl_common pcl_visualization)
+
+  PCL_ADD_EXECUTABLE(pcl_vlp_viewer COMPONENT ${SUBSYS_NAME} SOURCES vlp_viewer.cpp)
+  target_link_libraries(pcl_vlp_viewer pcl_io pcl_common pcl_visualization)
+
+  if(WITH_OPENNI)
+    PCL_ADD_EXECUTABLE(pcl_openni_save_image COMPONENT ${SUBSYS_NAME} SOURCES openni_save_image.cpp)
+    target_link_libraries(pcl_openni_save_image pcl_common pcl_io pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_pcd_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_grabber_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_pcd_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
 
-PCL_ADD_EXECUTABLE(pcl_transform_from_viewpoint COMPONENT ${SUBSYS_NAME} SOURCES transform_from_viewpoint.cpp)
-target_link_libraries (pcl_transform_from_viewpoint pcl_common pcl_io pcl_registration)
+    PCL_ADD_EXECUTABLE(pcl_image_grabber_saver COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_saver.cpp BUNDLE)
+    target_link_libraries(pcl_image_grabber_saver pcl_common pcl_io pcl_kdtree pcl_visualization)
 
-find_package(tide QUIET)
-if(Tide_FOUND)
-  include_directories(SYSTEM ${Tide_INCLUDE_DIRS})
-  add_definitions(${Tide_DEFINITIONS})
-  PCL_ADD_EXECUTABLE(pcl_video COMPONENT ${SUBSYS_NAME} SOURCES pcl_video.cpp)
-  target_link_libraries(pcl_video pcl_common pcl_io pcl_visualization
-    ${Tide_LIBRARIES})
+    PCL_ADD_EXECUTABLE(pcl_image_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_image_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_openni_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer_simple.cpp)
+    target_link_libraries(pcl_openni_viewer_simple pcl_common pcl_io pcl_kdtree pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_oni_viewer COMPONENT ${SUBSYS_NAME} SOURCES oni_viewer_simple.cpp BUNDLE)
+    target_link_libraries(pcl_oni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_openni_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_openni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+
+    PCL_ADD_EXECUTABLE(pcl_openni_image COMPONENT ${SUBSYS_NAME} SOURCES openni_image.cpp BUNDLE)
+    target_link_libraries(pcl_openni_image pcl_common pcl_io pcl_kdtree pcl_visualization)
+  endif()
+
+  if(WITH_OPENNI2)
+    PCL_ADD_EXECUTABLE(pcl_openni2_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni2_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_openni2_viewer pcl_common pcl_io pcl_kdtree pcl_visualization)
+  endif()
+
+  if(WITH_ENSENSO)
+    PCL_ADD_EXECUTABLE(pcl_ensenso_viewer COMPONENT ${SUBSYS_NAME} SOURCES ensenso_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_ensenso_viewer pcl_common pcl_io pcl_visualization)
+  endif()
+
+  if(WITH_DAVIDSDK)
+    PCL_ADD_EXECUTABLE(pcl_davidsdk_viewer COMPONENT ${SUBSYS_NAME} SOURCES davidsdk_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_davidsdk_viewer pcl_common pcl_io pcl_visualization)
+  endif()
+
+  if(WITH_DSSDK)
+    PCL_ADD_EXECUTABLE(pcl_depth_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES depth_sense_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_depth_sense_viewer pcl_common pcl_io pcl_visualization)
+  endif()
+
+  if(WITH_RSSDK)
+    PCL_ADD_EXECUTABLE(pcl_real_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES real_sense_viewer.cpp BUNDLE)
+    target_link_libraries(pcl_real_sense_viewer pcl_common pcl_io pcl_visualization)
+  endif()
 endif()
 
 if(CMAKE_GENERATOR_IS_IDE)
diff --git a/tools/convert_pcd_ascii_binary.cpp b/tools/convert_pcd_ascii_binary.cpp
new file mode 100644 (file)
index 0000000..d2f7918
--- /dev/null
@@ -0,0 +1,93 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Copyright (c) 2009, 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: convert_pcd_ascii_binary.cpp 33162 2010-03-10 07:41:56Z rusu $
+ *
+ */
+
+/**
+
+\author Radu Bogdan Rusu
+
+@b convert_pcd_ascii_binary converts PCD (Point Cloud Data) files from ascii to binary and vice-versa.
+
+ **/
+
+#include <iostream>
+#include <pcl/common/io.h>
+#include <pcl/io/pcd_io.h>
+#include <string>
+
+/* ---[ */
+int
+main (int argc, char** argv)
+{
+  if (argc < 4)
+  {
+    std::cerr << "Syntax is: " << argv[0] << " <file_in.pcd> <file_out.pcd> 0/1/2 (ascii/binary/binary_compressed) [precision (ASCII)]" << std::endl;
+    return (-1);
+  }
+
+  pcl::PCLPointCloud2 cloud;
+  Eigen::Vector4f origin; Eigen::Quaternionf orientation;
+
+  if (pcl::io::loadPCDFile (std::string (argv[1]), cloud, origin, orientation) < 0)
+  {
+    std::cerr << "Unable to load " << argv[1] << std::endl;
+    return (-1);
+  }
+
+  int type = atoi (argv[3]);
+
+  std::cerr << "Loaded a point cloud with " << cloud.width * cloud.height << 
+               " points (total size is " << cloud.data.size () << 
+               ") and the following channels: " << pcl::getFieldsList (cloud) << std::endl;
+
+  pcl::PCDWriter w;
+  if (type == 0)
+  {
+    std::cerr << "Saving file " << argv[2] << " as ASCII." << std::endl;
+    w.writeASCII (std::string (argv[2]), cloud, origin, orientation, (argc == 5) ? atoi (argv[4]) : 7);
+  }
+  else if (type == 1)
+  {
+    std::cerr << "Saving file " << argv[2] << " as binary." << std::endl;
+    w.writeBinary (std::string (argv[2]), cloud, origin, orientation);
+  }
+  else if (type == 2)
+  {
+    std::cerr << "Saving file " << argv[2] << " as binary_compressed." << std::endl;
+    w.writeBinaryCompressed (std::string (argv[2]), cloud, origin, orientation);
+  }
+}
+/* ]--- */
diff --git a/tools/converter.cpp b/tools/converter.cpp
new file mode 100644 (file)
index 0000000..dd155ec
--- /dev/null
@@ -0,0 +1,308 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2014-, 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.
+ */
+
+/**
+ \author Victor Lamoine
+ @b convert_point_clouds_meshes converts OBJ, PCD, PLY, STL, VTK files containing point clouds or meshes into every other format.
+ This tool allows to specify the file output type between ASCII, binary and binary compressed.
+ **/
+
+//TODO: Inform user about loss of color/alpha during conversion?
+// STL does not support color at all
+// OBJ does not support color in PCL (the format DOES support color)
+
+#include <vector>
+
+#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
+#define BINARY 1
+#define BINARY_COMPRESSED 2
+
+/**
+ * Display help for this program
+ * @param argc[in]
+ * @param argv[in]
+ */
+void
+displayHelp (int,
+             char** argv)
+{
+  PCL_INFO ("\nUsage: %s [OPTION] SOURCE DEST\n", argv[0]);
+  PCL_INFO ("Convert SOURCE point cloud or mesh to DEST.\n\n");
+
+  PCL_INFO ("Available formats types for SOURCE and DEST:\n"
+           "\tOBJ (Wavefront)\n"
+           "\tPCD (Point Cloud Library)\n"
+           "\tPLY (Polygon File Format)\n"
+           "\tSTL (STereoLithography)\n"
+           "\tVTK (The Visualization Toolkit)\n\n");
+
+  PCL_INFO ("Available options:\n"
+           "\t-f, --format Specify DEST output type, available formats are ascii, binary and binary_compressed.\n"
+           "\t             When not specified, binary is used as default.\n"
+           "\t             OBJ only supports ascii format.\n"
+           "\t             binary_compressed is only supported by the PCD file format.\n\n"
+           "\t-c --cloud   Output DEST as a point cloud, delete all faces.\n\n");
+}
+
+bool
+saveMesh (pcl::PolygonMesh& input,
+          std::string output_file,
+          int output_type);
+
+/**
+ * Saves a cloud into the specified file and output type. The file format is automatically parsed.
+ * @param input[in] The cloud to be saved
+ * @param output_file[out] The output file to be written
+ * @param output_type[in] The output file type
+ * @return True on success, false otherwise.
+ */
+bool
+savePointCloud (const pcl::PCLPointCloud2::Ptr& input,
+                std::string output_file,
+                int output_type)
+{
+  if (boost::filesystem::path (output_file).extension () == ".pcd")
+  {
+    //TODO Support precision, origin, orientation
+    pcl::PCDWriter w;
+    if (output_type == ASCII)
+    {
+      PCL_INFO ("Saving file %s as ASCII.\n", output_file.c_str ());
+      if (w.writeASCII (output_file, *input) != 0)
+        return (false);
+    }
+    else if (output_type == BINARY)
+    {
+      PCL_INFO ("Saving file %s as binary.\n", output_file.c_str ());
+      if (w.writeBinary (output_file, *input) != 0)
+        return (false);
+    }
+    else if (output_type == BINARY_COMPRESSED)
+    {
+      PCL_INFO ("Saving file %s as binary compressed.\n", output_file.c_str ());
+      if (w.writeBinaryCompressed (output_file, *input) != 0)
+        return (false);
+    }
+  }
+  else if (boost::filesystem::path (output_file).extension () == ".stl")
+  {
+    PCL_ERROR ("STL file format does not support point clouds! Aborting.\n");
+    return (false);
+  }
+  else  // OBJ, PLY and VTK
+  {
+    //TODO: Support precision
+    //FIXME: Color is lost during OBJ conversion (OBJ supports color)
+    pcl::PolygonMesh mesh;
+    mesh.cloud = *input;
+    if (!saveMesh (mesh, output_file, output_type))
+      return (false);
+  }
+
+  return (true);
+}
+
+/**
+ * Saves a mesh into the specified file and output type. The file format is automatically parsed.
+ * @param input[in] The mesh to be saved
+ * @param output_file[out] The output file to be written
+ * @param output_type[in]  The output file type
+ * @return True on success, false otherwise.
+ */
+bool
+saveMesh (pcl::PolygonMesh& input,
+          std::string output_file,
+          int output_type)
+{
+  if (boost::filesystem::path (output_file).extension () == ".obj")
+  {
+    if (output_type == BINARY || output_type == BINARY_COMPRESSED)
+      PCL_WARN ("OBJ file format only supports ASCII.\n");
+
+    //TODO: Support precision
+    //FIXME: Color is lost during conversion (OBJ supports color)
+    PCL_INFO ("Saving file %s as ASCII.\n", output_file.c_str ());
+    if (pcl::io::saveOBJFile (output_file, input) != 0)
+      return (false);
+  }
+  else if (boost::filesystem::path (output_file).extension () == ".pcd")
+  {
+    if (!input.polygons.empty ())
+      PCL_WARN ("PCD file format does not support meshes! Only points be saved.\n");
+    pcl::PCLPointCloud2::Ptr cloud = pcl::make_shared<pcl::PCLPointCloud2> (input.cloud);
+    if (!savePointCloud (cloud, output_file, output_type))
+      return (false);
+  }
+  else  // PLY, STL and VTK
+  {
+    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")
+    {
+      PCL_ERROR ("STL file format does not support point clouds! Aborting.\n");
+      return (false);
+    }
+
+    PCL_INFO ("Saving file %s as %s.\n", output_file.c_str (), (output_type == ASCII) ? "ASCII" : "binary");
+    if (!pcl::io::savePolygonFile (output_file, input, output_type != ASCII))
+      return (false);
+  }
+
+  return (true);
+}
+
+/**
+ * Parse input files and options. Calls the right conversion function.
+ * @param argc[in]
+ * @param argv[in]
+ * @return 0 on success, any other value on failure.
+ */
+int
+main (int argc,
+      char** argv)
+{
+  // Display help
+  if (pcl::console::find_switch (argc, argv, "-h") != 0 || pcl::console::find_switch (argc, argv, "--help") != 0)
+  {
+    displayHelp (argc, argv);
+    return (0);
+  }
+
+  // Parse all files and options
+  std::vector<std::string> supported_extensions;
+  supported_extensions.emplace_back("obj");
+  supported_extensions.emplace_back("pcd");
+  supported_extensions.emplace_back("ply");
+  supported_extensions.emplace_back("stl");
+  supported_extensions.emplace_back("vtk");
+  std::vector<int> file_args;
+  for (int i = 1; i < argc; ++i)
+    for (const auto &supported_extension : supported_extensions)
+      if (boost::algorithm::ends_with(argv[i], supported_extension))
+      {
+        file_args.push_back(i);
+        break;
+      }
+
+  std::string parsed_output_type;
+  pcl::console::parse_argument (argc, argv, "-f", parsed_output_type);
+  pcl::console::parse_argument (argc, argv, "--format", parsed_output_type);
+  bool cloud_output (false);
+  if (pcl::console::find_switch (argc, argv, "-c") != 0 ||
+      pcl::console::find_switch (argc, argv, "--cloud") != 0)
+    cloud_output = true;
+
+  // Make sure that we have one input and one output file only
+  if (file_args.size() != 2)
+  {
+    PCL_ERROR ("Wrong input/output file count!\n");
+    displayHelp (argc, argv);
+    return (-1);
+  }
+
+  // Convert parsed output type to output type
+  int output_type (BINARY);
+  if (!parsed_output_type.empty ())
+  {
+    if (parsed_output_type == "ascii")
+      output_type = ASCII;
+    else if (parsed_output_type == "binary")
+      output_type = BINARY;
+    else if (parsed_output_type == "binary_compressed")
+      output_type = BINARY_COMPRESSED;
+    else
+    {
+      PCL_ERROR ("Wrong output type!\n");
+      displayHelp (argc, argv);
+      return (-1);
+    }
+  }
+
+  // Try to load as mesh
+  pcl::PolygonMesh mesh;
+  if (boost::filesystem::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",
+             mesh.cloud.width * mesh.cloud.height, mesh.cloud.data.size (), pcl::getFieldsList (mesh.cloud).c_str ());
+
+    if (cloud_output)
+      mesh.polygons.clear();
+
+    if (!saveMesh (mesh, argv[file_args[1]], output_type))
+      return (-1);
+  }
+  else if (boost::filesystem::path (argv[file_args[0]]).extension () == ".stl")
+  {
+    PCL_ERROR ("Unable to load %s.\n", argv[file_args[0]]);
+    return (-1);
+  }
+  else
+  {
+    // PCD, OBJ, PLY or VTK
+    if (boost::filesystem::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
+    //Eigen::Quaternionf orientation;
+    pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
+    if (pcl::io::load (argv[file_args[0]], *cloud) < 0)
+    {
+      PCL_ERROR ("Unable to load %s.\n", argv[file_args[0]]);
+      return (-1);
+    }
+
+    PCL_INFO ("Loaded a point cloud with %d points (total size is %d) and the following channels:\n%s\n", cloud->width * cloud->height, cloud->data.size (),
+              pcl::getFieldsList (*cloud).c_str ());
+
+    if (!savePointCloud (cloud, argv[file_args[1]], output_type))
+    {
+      PCL_ERROR ("Failed to save %s.\n", argv[file_args[1]]);
+      return (-1);
+    }
+  }
+  return (0);
+}
index df7543d16db46f543799f81341f7f97761d33c13..58efaed03ab839bc9472c162a6c09e6ff9aa69c4 100644 (file)
@@ -52,7 +52,7 @@ using namespace pcl::console;
 using PointT = PointXYZ;
 using CloudT = PointCloud<PointT>;
 
-const static double default_alpha = 1e3f;
+constexpr double default_alpha = 1e3f;
 
 static void
 printHelp (int, char **argv)
index 1d170ec9b1f152020b506a14a98caaef17c99471..e8e721955eef9cf6cf3f42a4cb46a64bd85d03f9 100644 (file)
@@ -91,7 +91,7 @@ loopDetection (int end, const CloudVector &clouds, double dist, int &first, int
     }
   }
   //std::cout << "min_dist: " << min_dist << " state: " << state << " first: " << first << " end: " << end << std::endl;
-  if (min_dist > 0 && (state < 2 || end == int (clouds.size ()) - 1)) //TODO
+  if (min_dist > 0 && (state < 2 || end == static_cast<int>(clouds.size ()) - 1)) //TODO
   {
     min_dist = -1;
     return true;
@@ -136,7 +136,7 @@ main (int argc, char **argv)
   for (std::size_t i = 0; i < clouds.size (); i++)
   {
 
-    if (loopDetection (int (i), clouds, 3.0, first, last))
+    if (loopDetection (static_cast<int>(i), clouds, 3.0, first, last))
     {
       std::cout << "Loop between " << first << " (" << clouds[first].first << ") and " << last << " (" << clouds[last].first << ")" << std::endl;
       elch.setLoopStart (first);
index 4bf9835cf0f7daa7c3b7b5ef12be93c489fd8f4e..ff9d49544a30bdb38c5c6d6906f8d5568d95def5 100644 (file)
@@ -114,15 +114,16 @@ int
 batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir, float sigma_s, float sigma_r)
 {
 #pragma omp parallel for \
-  default(none) \
   shared(output_dir, pcd_files, sigma_r, sigma_s)
-  for (int i = 0; i < int (pcd_files.size ()); ++i)
+  // Disable lint since this 'for' is part of the pragma
+  // NOLINTNEXTLINE(modernize-loop-convert)
+  for (int i = 0; i < static_cast<int>(pcd_files.size ()); ++i)
   {
     // Load the first file
     Eigen::Vector4f translation;
     Eigen::Quaternionf rotation;
     pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
-    if (!loadCloud (pcd_files[i], *cloud, translation, rotation)) 
+    if (!loadCloud (pcd_files[i], *cloud, translation, rotation))
       continue;
 
     // Perform the feature estimation
@@ -209,7 +210,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
index 3a1eb742021c903596e98b15b9a8cb7899db9662..421aad041af534bf1e268765edf4c99ff30a0d2d 100644 (file)
@@ -58,7 +58,7 @@ printHelp (int, char **argv)
   print_info ("  where options are:\n");
   print_info ("                     -radius X = use a radius of Xm around each point to determine the neighborhood (default: "); 
   print_value ("%f", default_radius); print_info (")\n");
-  print_info ("                     -mu X     = set the multipler of the nearest neighbor distance to obtain the final search radius (default: "); 
+  print_info ("                     -mu X     = set the multiplier of the nearest neighbor distance to obtain the final search radius (default: "); 
   print_value ("%f", default_mu); print_info (")\n");
 }
 
index 5111500a44710d46356b1a0dcbcccd68ce8140cb..1a5c2fa913aeaa4fc084664d7670211d7e5d68f0 100644 (file)
@@ -202,7 +202,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
diff --git a/tools/hdl_grabber_example.cpp b/tools/hdl_grabber_example.cpp
new file mode 100644 (file)
index 0000000..a72574a
--- /dev/null
@@ -0,0 +1,111 @@
+/*
+ * hdl_grabber_example.cpp
+ *
+ *  Created on: Nov 29, 2012
+ *      Author: keven
+ */
+
+#include <string>
+#include <iostream>
+#include <iomanip>
+
+#include <pcl/io/hdl_grabber.h>
+#include <pcl/console/parse.h>
+#include <pcl/common/time.h>
+
+class SimpleHDLGrabber 
+{
+  public:
+    std::string calibrationFile, pcapFile;
+
+    SimpleHDLGrabber (std::string& calibFile, std::string& pcapFile) 
+      : calibrationFile (calibFile)
+      , pcapFile (pcapFile) 
+    {
+    }
+
+    void 
+    sectorScan (
+        const pcl::PointCloud<pcl::PointXYZI>::ConstPtr&,
+        float,
+        float) 
+    {
+      static unsigned count = 0;
+      static double last = pcl::getTime ();
+      if (++count == 30) 
+      {
+        double now = pcl::getTime();
+        std::cout << "got sector scan.  Avg Framerate " << static_cast<double>(count) / (now - last) << " Hz" << std::endl;
+        count = 0;
+        last = now;
+      }
+    }
+
+    void 
+    sweepScan (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& sweep)
+    {
+      static unsigned count = 0;
+      static double last = pcl::getTime();
+
+      if (sweep->header.seq == 0) {
+        std::uint64_t stamp;
+        stamp = sweep->header.stamp;
+        time_t systemTime = static_cast<time_t>(((stamp & 0xffffffff00000000l) >> 32) & 0x00000000ffffffff);
+        auto usec = static_cast<std::uint32_t>(stamp & 0x00000000ffffffff);
+        std::cout << std::hex << stamp << "  " << ctime(&systemTime) << " usec: " << usec << std::endl;
+      }
+
+      if (++count == 30) 
+      {
+        double now = pcl::getTime ();
+        std::cout << "got sweep.  Avg Framerate " << static_cast<double>(count) / (now - last) << " Hz" << std::endl;
+        count = 0;
+        last = now;
+      }
+    }
+
+    void 
+    run () 
+    {
+      pcl::HDLGrabber interface (calibrationFile, pcapFile);
+      // make callback function from member function
+      std::function<void(const pcl::PointCloud<pcl::PointXYZI>::ConstPtr&, float, float)> f =
+          [this] (const pcl::PointCloud<pcl::PointXYZI>::ConstPtr& p1, float p2, float p3) { sectorScan (p1, p2, p3); };
+
+      // connect callback function for desired signal. In this case its a sector with XYZ and intensity information
+      //boost::signals2::connection c = interface.registerCallback(f);
+
+      // Register a callback function that gets complete 360 degree sweeps.
+      std::function<void(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)> f2 =
+          [this] (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& sweep) { sweepScan (sweep); };
+      boost::signals2::connection c2 = interface.registerCallback(f2);
+
+      //interface.filterPackets(boost::asio::ip::address_v4::from_string("192.168.18.38"));
+
+      // start receiving point clouds
+      interface.start ();
+
+      std::cout << R"(<Esc>, 'q', 'Q': quit the program)" << std::endl;
+      char key;
+      do 
+      {
+        key = static_cast<char> (getchar ());
+      } while (key != 27 && key != 'q' && key != 'Q');
+
+      // stop the grabber
+      interface.stop ();
+    }
+};
+
+int 
+main (int argc, char **argv) 
+{
+       std::string hdlCalibration, pcapFile;
+
+       pcl::console::parse_argument (argc, argv, "-calibrationFile", hdlCalibration);
+       pcl::console::parse_argument (argc, argv, "-pcapFile", pcapFile);
+
+       SimpleHDLGrabber grabber (hdlCalibration, pcapFile);
+       grabber.run ();
+       return (0);
+}
index 476b2f1df38e03f42f0bdf2be2fcf22571a68d7b..41f51c2e70b013542519b0c9035d8cbf6e62fa75 100644 (file)
@@ -40,6 +40,7 @@
 #include <pcl/console/parse.h>
 #include <pcl/io/pcd_io.h>
 #include <pcl/point_types.h>
+#include <pcl/filters/filter.h> // for removeNaNFromPointCloud
 #include <pcl/registration/icp.h>
 #include <pcl/registration/icp_nl.h>
 #include <pcl/registration/incremental_registration.h>
@@ -97,6 +98,8 @@ main (int argc, char **argv)
       std::cout << "Could not read file" << std::endl;
       return -1;
     }
+    pcl::Indices dummy_indices;
+    pcl::removeNaNFromPointCloud(*data, *data, dummy_indices);
 
     if (!iicp.registerCloud (data))
     {
index 701a1dc96aa5d9c197661d01e7b29b777af7c237..b10f4e577f38dca90e2f416bcd009643fa5ae813 100644 (file)
@@ -103,7 +103,7 @@ main (int argc, char **argv)
     pcl::registration::TransformationEstimationLM<PointType, PointType>::Ptr te (new pcl::registration::TransformationEstimationLM<PointType, PointType>);
     te->setWarpFunction (warp_fcn);
 
-    // Pass the TransformationEstimation objec to the ICP algorithm
+    // Pass the TransformationEstimation object to the ICP algorithm
     icp.setTransformationEstimation (te);
 
     icp.setMaximumIterations (iter);
index 764e672d8f9ab0c1fcfd63e3c18f356b0c817b7b..1dab5d9230d81f346d9bab4e66961f6554b42048 100644 (file)
@@ -126,7 +126,7 @@ main (int argc, char** argv)
     printHelp (argc, argv);
     return (-1);
   }
-  grabber->setDepthImageUnits (float (1E-3));
+  grabber->setDepthImageUnits (static_cast<float>(1E-3));
   //grabber->setFocalLength(focal_length); // FIXME
 
   EventHelper h;
index 2669f04e970db877ae14c9e61b5fcd193e5874bd..4cf45843fe14e984c3a9f18370d48757479185f8 100644 (file)
@@ -129,7 +129,7 @@ mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie)
 int
 main (int argc, char** argv)
 {
-  srand (unsigned (time (nullptr)));
+  srand (static_cast<unsigned>(time (nullptr)));
 
   if (argc > 1)
   {
@@ -207,7 +207,7 @@ main (int argc, char** argv)
     printHelp (argc, argv);
     return (-1);
   }
-  grabber->setDepthImageUnits (float (1E-3));
+  grabber->setDepthImageUnits (static_cast<float>(1E-3));
 
   // Before manually setting
   double fx, fy, cx, cy;
index 94e048f856244d1604ee6fb5cc52d4544f021144..9a51397d1817a6bec12f433aa980b346c5827928 100644 (file)
 int
 main (int, char ** argv)
 {
-  pcl::PCDReader reader;
-  pcl::PCLPointCloud2 cloud;
-  reader.read (argv[1], cloud);
-  
   pcl::PointCloud<pcl::PointXYZ> xyz;
-  pcl::fromPCLPointCloud2 (cloud, xyz);
+  pcl::io::loadPCDFile(argv[1], xyz);
   
   pcl::visualization::ImageViewer depth_image_viewer_;
-  float* img = new float[cloud.width * cloud.height];
+  float* img = new float[xyz.width * xyz.height];
 
   for (int i = 0; i < static_cast<int> (xyz.size ()); ++i)
     img[i] = xyz[i].z;
   
   depth_image_viewer_.showFloatImage (img, 
-                                      cloud.width, cloud.height,
+                                      xyz.width, xyz.height,
                                       std::numeric_limits<float>::min (), 
                                       // Scale so that the colors look brigher on screen
                                       std::numeric_limits<float>::max () / 10, 
index e803aa31017a84d790ac9d6317e23b222282c32a..665aee3759c008b28432bd1f9a3f03017c550245 100644 (file)
@@ -203,7 +203,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
index 1ba164261d5f79c0655b9bffed240d0222e75617..5472545cd31e4f31ccead5c103c5025cb739ee37 100644 (file)
@@ -38,6 +38,7 @@
 #include <pcl/visualization/pcl_visualizer.h>
 #include <pcl/visualization/vtk/pcl_vtk_compatibility.h>
 #include <pcl/io/pcd_io.h>
+#include <pcl/io/ply_io.h>
 #include <pcl/io/vtk_lib_io.h>
 #include <vtkVersion.h>
 #include <vtkOBJReader.h>
@@ -82,7 +83,7 @@ randPSurface (vtkPolyData * polydata, std::vector<double> * cumulativeAreas, dou
   float r = static_cast<float> (uniform_deviate (rand ()) * totalArea);
 
   auto low = std::lower_bound (cumulativeAreas->begin (), cumulativeAreas->end (), r);
-  vtkIdType el = vtkIdType (low - cumulativeAreas->begin ());
+  vtkIdType el = static_cast<vtkIdType>(low - cumulativeAreas->begin ());
 
   double A[3], B[3], C[3];
   vtkIdType npts = 0;
@@ -102,9 +103,9 @@ randPSurface (vtkPolyData * polydata, std::vector<double> * cumulativeAreas, dou
   }
   float r1 = static_cast<float> (uniform_deviate (rand ()));
   float r2 = static_cast<float> (uniform_deviate (rand ()));
-  randomPointTriangle (float (A[0]), float (A[1]), float (A[2]),
-                       float (B[0]), float (B[1]), float (B[2]),
-                       float (C[0]), float (C[1]), float (C[2]), r1, r2, p);
+  randomPointTriangle (static_cast<float>(A[0]), static_cast<float>(A[1]), static_cast<float>(A[2]),
+                       static_cast<float>(B[0]), static_cast<float>(B[1]), static_cast<float>(B[2]),
+                       static_cast<float>(C[0]), static_cast<float>(C[1]), static_cast<float>(C[2]), r1, r2, p);
 
   if (calcColor)
   {
@@ -116,9 +117,9 @@ randPSurface (vtkPolyData * polydata, std::vector<double> * cumulativeAreas, dou
       colors->GetTuple (ptIds[1], cB);
       colors->GetTuple (ptIds[2], cC);
 
-      randomPointTriangle (float (cA[0]), float (cA[1]), float (cA[2]),
-                           float (cB[0]), float (cB[1]), float (cB[2]),
-                           float (cC[0]), float (cC[1]), float (cC[2]), r1, r2, c);
+      randomPointTriangle (static_cast<float>(cA[0]), static_cast<float>(cA[1]), static_cast<float>(cA[2]),
+                           static_cast<float>(cB[0]), static_cast<float>(cB[1]), static_cast<float>(cB[2]),
+                           static_cast<float>(cC[0]), static_cast<float>(cC[1]), static_cast<float>(cC[2]), r1, r2, c);
     }
     else
     {
@@ -182,8 +183,8 @@ using namespace pcl;
 using namespace pcl::io;
 using namespace pcl::console;
 
-const int default_number_samples = 100000;
-const float default_leaf_size = 0.01f;
+constexpr int default_number_samples = 100000;
+constexpr float default_leaf_size = 0.01f;
 
 void
 printHelp (int, char **argv)
@@ -244,7 +245,7 @@ main (int argc, char **argv)
   if (ply_file_indices.size () == 1)
   {
     pcl::PolygonMesh mesh;
-    pcl::io::loadPolygonFilePLY (argv[ply_file_indices[0]], mesh);
+    pcl::io::loadPLYFile (argv[ply_file_indices[0]], mesh);
     pcl::io::mesh2vtk (mesh, polydata1);
   }
   else if (obj_file_indices.size () == 1)
index 4caf14762600319b1e4ab9cfe82d8a082e86e05d..1a95bdd178ea8d8290d8ca99122c2e173dd1aac8 100644 (file)
@@ -117,7 +117,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input,
 //  mls.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::RANDOM_UNIFORM_DENSITY);
 //  mls.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::VOXEL_GRID_DILATION);
   mls.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::NONE);
-  mls.setPointDensity (60000 * int (search_radius)); // 300 points in a 5 cm radius
+  mls.setPointDensity (60000 * static_cast<int>(search_radius)); // 300 points in a 5 cm radius
   mls.setUpsamplingRadius (0.025);
   mls.setUpsamplingStepSize (0.015);
   mls.setDilationIterations (2);
index bf998ca26bc3b3b59198c85a897fa959c86c6e46..7c33cdbd2faffe7873429ec169ff47a94c5fa604 100644 (file)
@@ -226,7 +226,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
index 34401a8bcb29fda8063d3e82e93368675d4ec360..149427c3d6818a9ec47a3b3848143f105e86c623 100644 (file)
@@ -99,7 +99,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output
     IntegralImageNormalEstimation<PointXYZ, Normal> ne;
     ne.setInputCloud (xyz);
     ne.setNormalEstimationMethod (IntegralImageNormalEstimation<PointXYZ, Normal>::COVARIANCE_MATRIX);
-    ne.setNormalSmoothingSize (float (radius));
+    ne.setNormalSmoothingSize (static_cast<float>(radius));
     ne.setDepthDependentSmoothing (true);
     ne.compute (normals);
   }
@@ -133,15 +133,16 @@ int
 batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir, int k, double radius)
 {
 #pragma omp parallel for \
-  default(none) \
   shared(k, output_dir, pcd_files, radius)
-  for (int i = 0; i < int (pcd_files.size ()); ++i)
+  // Disable lint since this 'for' is part of the pragma
+  // NOLINTNEXTLINE(modernize-loop-convert)
+  for (int i = 0; i < static_cast<int>(pcd_files.size ()); ++i)
   {
     // Load the first file
     Eigen::Vector4f translation;
     Eigen::Quaternionf rotation;
     pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
-    if (!loadCloud (pcd_files[i], *cloud, translation, rotation)) 
+    if (!loadCloud (pcd_files[i], *cloud, translation, rotation))
       continue;
 
     // Perform the feature estimation
@@ -228,7 +229,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
index 4c2ec7010e4e766f45d432de38f1c307cfa5497d..f75bd66a7502efbdf923504fda25d0226d76c1b6 100644 (file)
@@ -85,9 +85,8 @@ class CallbackParameters
       viz_ (viz),
       points_ (points),
       normals_ (normals),
-      num_hypotheses_to_show_ (num_hypotheses_to_show),
-      show_models_ (true)
-    { }
+      num_hypotheses_to_show_ (num_hypotheses_to_show)
+    {}
 
     ObjRecRANSAC& objrec_;
     PCLVisualizer& viz_;
@@ -95,7 +94,7 @@ class CallbackParameters
     PointCloud<Normal>& normals_;
     int num_hypotheses_to_show_;
     std::list<vtkActor*> actors_, model_actors_;
-    bool show_models_;
+    bool show_models_{true};
 };
 
 //===============================================================================================================================
@@ -469,7 +468,7 @@ main (int argc, char** argv)
 {
   printf ("\nUsage: ./obj_rec_ransac_accepted_hypotheses <pair_width> <voxel_size> <max_coplanarity_angle> <n_hypotheses_to_show> <show_hypotheses_as_coordinate_frames>\n\n");
 
-  const int num_params = 4;
+  constexpr int num_params = 4;
   float parameters[num_params] = {40.0f/*pair width*/, 5.0f/*voxel size*/, 15.0f/*max co-planarity angle*/, 1/*n_hypotheses_to_show*/};
   std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle", "n_hypotheses_to_show"};
 
index d06c2f6bc748230738028254bb41a861fcfac7ca..d82cbfb16308e185744d5669320435df6eda8d0d 100644 (file)
@@ -76,7 +76,7 @@ main (int argc, char** argv)
 {
   printf ("\nUsage: ./pcl_obj_rec_ransac_model_opps <pair_width> <voxel_size> <max_coplanarity_angle>\n\n");
 
-  const int num_params = 3;
+  constexpr int num_params = 3;
   float parameters[num_params] = {10.0f/*pair width*/, 5.0f/*voxel size*/, 5.0f/*max co-planarity angle*/};
   std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"};
 
index 12987d7535bd8a681ee416dd67e8d9829d3e005c..884dea61bd41c942d1fcb23578b2988409cde86b 100644 (file)
@@ -106,7 +106,7 @@ main (int argc, char** argv)
 {
   printf ("\nUsage: ./pcl_obj_rec_ransac_scene_opps <pair_width> <voxel_size> <max_coplanarity_angle>\n\n");
 
-  const int num_params = 3;
+  constexpr int num_params = 3;
   float parameters[num_params] = {40.0f/*pair width*/, 5.0f/*voxel size*/, 15.0f/*max co-planarity angle*/};
   std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"};
 
index f3df089c13159f4ec91c9ecd0c56c3add76a7a93..70ddfe42a65676b3ced9811eadb9929282229958 100644 (file)
@@ -96,7 +96,7 @@ main (int argc, char** argv)
 {
   printf ("\nUsage: ./pcl_obj_rec_ransac_scene_opps <pair_width> <voxel_size> <max_coplanarity_angle>\n\n");
 
-  const int num_params = 3;
+  constexpr int num_params = 3;
   float parameters[num_params] = {40.0f/*pair width*/, 5.0f/*voxel size*/, 15.0f/*max co-planarity angle*/};
   std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"};
 
index 23d1cee4d5145d33350e76cfa92ef1221bde37b2..9962882c6827c47dd0f44f3c52aaf9e0b645d059 100644 (file)
@@ -62,12 +62,7 @@ public:
     cloud (new pcl::PointCloud<pcl::PointXYZ>()),
     displayCloud (new pcl::PointCloud<pcl::PointXYZ>()),
     cloudVoxel (new pcl::PointCloud<pcl::PointXYZ>()),
-    octree (resolution),
-    wireframe (true),
-    show_cubes_ (true),
-    show_centroids_ (false),
-    show_original_points_ (false),
-    point_size_ (1.0)
+    octree (resolution)
   {
 
     //try to load the cloud
@@ -126,9 +121,9 @@ private:
   //level
   int displayedDepth;
   //bool to decide what should be display
-  bool wireframe;
-  bool show_cubes_, show_centroids_, show_original_points_;
-  float point_size_;
+  bool wireframe{true};
+  bool show_cubes_{true}, show_centroids_{false}, show_original_points_{false};
+  float point_size_{1.0};
   //========================================================
 
   /* \brief Callback to interact with the keyboard
@@ -390,7 +385,7 @@ private:
       cloudVoxel->points.push_back (pt_voxel_center);
 
       // If the asked depth is the depth of the octree, retrieve the centroid at this LeafNode
-      if (octree.getTreeDepth () == (unsigned int) depth)
+      if (octree.getTreeDepth () == static_cast<unsigned int>(depth))
       {
         auto* container = dynamic_cast<pcl::octree::OctreePointCloudVoxelCentroid<pcl::PointXYZ>::LeafNode*> (tree_it.getCurrentOctreeNode ());
 
@@ -459,8 +454,8 @@ int main(int argc, char ** argv)
 {
   if (argc != 3)
   {
-    std::cerr << "ERROR: Syntax is octreeVisu <pcd file> <resolution>" << std::endl;
-    std::cerr << "EXAMPLE: ./octreeVisu bun0.pcd 0.001" << std::endl;
+    std::cerr << "ERROR: Syntax is " << argv[0] << " <pcd file> <resolution>" << std::endl;
+    std::cerr << "EXAMPLE: ./" << argv[0] << " bun0.pcd 0.001" << std::endl;
     return -1;
   }
 
index a1612da0c125bea53e7e60a4c5f60eaa7eb854b8..9df14649ec2f5adc89eba5a823afae5b3a200e4e 100644 (file)
@@ -114,7 +114,6 @@ public:
   OpenNI2Viewer (pcl::io::OpenNI2Grabber& grabber)
     : cloud_viewer_ (new pcl::visualization::PCLVisualizer ("PCL OpenNI2 cloud"))
     , grabber_ (grabber)
-    , rgb_data_ (nullptr), rgb_data_size_ (0)
   {
   }
 
@@ -266,19 +265,15 @@ public:
   pcl::visualization::ImageViewer::Ptr image_viewer_;
 
   pcl::io::OpenNI2Grabber& grabber_;
-  std::mutex cloud_mutex_;
-  std::mutex image_mutex_;
+  std::mutex cloud_mutex_{};
+  std::mutex image_mutex_{};
 
-  CloudConstPtr cloud_;
-  pcl::io::openni2::Image::Ptr image_;
-  unsigned char* rgb_data_;
-  unsigned rgb_data_size_;
+  CloudConstPtr cloud_{nullptr};
+  pcl::io::openni2::Image::Ptr image_{nullptr};
+  unsigned char* rgb_data_{nullptr};
+  unsigned rgb_data_size_{0};
 };
 
-// Create the PCLVisualizer object
-pcl::visualization::PCLVisualizer::Ptr cld;
-pcl::visualization::ImageViewer::Ptr img;
-
 /* ---[ */
 int
 main (int argc, char** argv)
@@ -336,10 +331,10 @@ main (int argc, char** argv)
 
   unsigned mode;
   if (pcl::console::parse (argc, argv, "-depthmode", mode) != -1)
-    depth_mode = pcl::io::OpenNI2Grabber::Mode (mode);
+    depth_mode = static_cast<pcl::io::OpenNI2Grabber::Mode> (mode);
 
   if (pcl::console::parse (argc, argv, "-imagemode", mode) != -1)
-    image_mode = pcl::io::OpenNI2Grabber::Mode (mode);
+    image_mode = static_cast<pcl::io::OpenNI2Grabber::Mode> (mode);
 
   if (pcl::console::find_argument (argc, argv, "-xyz") != -1)
     xyz = true;
diff --git a/tools/openni_grabber_depth_example.cpp b/tools/openni_grabber_depth_example.cpp
new file mode 100644 (file)
index 0000000..d224b13
--- /dev/null
@@ -0,0 +1,114 @@
+/*
+ * 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.
+ *
+ */
+
+#include <pcl/io/openni_grabber.h>
+#include <pcl/common/time.h>
+#include <pcl/console/parse.h>
+
+class SimpleOpenNIProcessor
+{
+  public:
+    bool save;
+    openni_wrapper::OpenNIDevice::DepthMode mode;
+
+    SimpleOpenNIProcessor (openni_wrapper::OpenNIDevice::DepthMode depth_mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth) : mode (depth_mode) {}
+
+    void 
+    imageDepthImageCallback (const openni_wrapper::DepthImage::Ptr& d_img)
+    {
+      static unsigned count = 0;
+      static double last = pcl::getTime ();
+      if (++count == 30)
+      {
+        double now = pcl::getTime ();
+        std::cout << "got depth-image. Average framerate: " << static_cast<double>(count)/(now - last) << " Hz" <<  std::endl;
+        std::cout << "Depth baseline: " << d_img->getBaseline () << " and focal length: " << d_img->getFocalLength () << std::endl;
+        count = 0;
+        last = now;
+      }
+    }
+
+    void 
+    run ()
+    {
+      save = false;
+
+      // create a new grabber for OpenNI devices
+      pcl::OpenNIGrabber interface;
+
+      // Set the depth output format
+      interface.getDevice ()->setDepthOutputFormat (mode);
+
+      // make callback function from member function
+      std::function<void (const openni_wrapper::DepthImage::Ptr&)> f2 = [this] (const openni_wrapper::DepthImage::Ptr& depth)
+      {
+        imageDepthImageCallback (depth);
+      };
+
+      // connect callback function for desired signal. In this case its a point cloud with color values
+      boost::signals2::connection c2 = interface.registerCallback (f2);
+
+      // start receiving point clouds
+      interface.start ();
+
+      std::cout << R"(<Esc>, 'q', 'Q': quit the program)" << std::endl;
+      std::cout << "\' \': pause" << std::endl;
+      char key;
+      do
+      {
+        key = static_cast<char> (getchar ());
+        if (key == ' ')
+        {
+          interface.toggle ();
+        }
+      } while ((key != 27) && (key != 'q') && (key != 'Q'));
+
+      // stop the grabber
+      interface.stop ();
+    }
+};
+
+int
+main (int argc, char **argv)
+{
+  int mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
+  pcl::console::parse_argument (argc, argv, "-mode", mode);
+
+  SimpleOpenNIProcessor v (static_cast<openni_wrapper::OpenNIDevice::DepthMode> (mode));
+  v.run ();
+  return (0);
+}
diff --git a/tools/openni_grabber_example.cpp b/tools/openni_grabber_example.cpp
new file mode 100644 (file)
index 0000000..105ca46
--- /dev/null
@@ -0,0 +1,156 @@
+/*
+ * 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: Suat Gedikli (gedikli@willowgarage.com)
+ */
+
+#include <pcl/point_cloud.h>
+#include <pcl/point_types.h>
+#include <pcl/io/pcd_io.h>
+#include <pcl/io/openni_grabber.h>
+#include <pcl/common/time.h>
+#include <pcl/console/parse.h>
+#include <iomanip> // for setprecision
+
+class SimpleOpenNIProcessor
+{
+  public:
+    bool save;
+    openni_wrapper::OpenNIDevice::DepthMode mode;
+
+    SimpleOpenNIProcessor (openni_wrapper::OpenNIDevice::DepthMode depth_mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth) : mode (depth_mode) {}
+
+    void 
+    cloud_cb_ (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr &cloud) const
+    {
+      static unsigned count = 0;
+      static double last = pcl::getTime ();
+      if (++count == 30)
+      {
+        double now = pcl::getTime ();
+        std::cout << "distance of center pixel :" << cloud->points [(cloud->width >> 1) * (cloud->height + 1)].z << " mm. Average framerate: " << static_cast<double>(count)/(now - last) << " Hz" <<  std::endl;
+        count = 0;
+        last = now;
+      }
+
+      if (save)
+      {
+        std::stringstream ss;
+        ss << std::setprecision (12) << pcl::getTime () * 100 << ".pcd";
+        pcl::PCDWriter w;
+        w.writeBinaryCompressed (ss.str (), *cloud);
+        std::cout << "wrote point clouds to file " << ss.str () << std::endl;
+      }
+    }
+
+    void 
+    imageDepthImageCallback (const openni_wrapper::Image::Ptr&, const openni_wrapper::DepthImage::Ptr& d_img, float constant)
+    {
+      static unsigned count = 0;
+      static double last = pcl::getTime ();
+      if (++count == 30)
+      {
+        double now = pcl::getTime ();
+        std::cout << "got synchronized image x depth-image with constant factor: " << constant << ". Average framerate: " << static_cast<double>(count)/(now - last) << " Hz" <<  std::endl;
+        std::cout << "Depth baseline: " << d_img->getBaseline () << " and focal length: " << d_img->getFocalLength () << std::endl;
+        count = 0;
+        last = now;
+      }
+    }
+
+    void 
+    run ()
+    {
+      save = false;
+
+      // create a new grabber for OpenNI devices
+      pcl::OpenNIGrabber interface;
+
+      // Set the depth output format
+      interface.getDevice ()->setDepthOutputFormat (mode);
+
+      // make callback function from member function
+      std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
+        [this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud) { cloud_cb_ (cloud); };
+
+      // connect callback function for desired signal. In this case its a point cloud with color values
+      boost::signals2::connection c = interface.registerCallback (f);
+
+      // make callback function from member function
+      std::function<void (const openni_wrapper::Image::Ptr&, const openni_wrapper::DepthImage::Ptr&, float constant)> f2 =
+        [this] (const openni_wrapper::Image::Ptr& img, const openni_wrapper::DepthImage::Ptr& depth, float constant)
+        {
+          imageDepthImageCallback (img, depth, constant);
+        };
+
+      // connect callback function for desired signal. In this case its a point cloud with color values
+      boost::signals2::connection c2 = interface.registerCallback (f2);
+
+      // start receiving point clouds
+      interface.start ();
+
+      std::cout << R"(<Esc>, 'q', 'Q': quit the program)" << std::endl;
+      std::cout << "\' \': pause" << std::endl;
+      std::cout << "\'s\': save" << std::endl;
+      char key;
+      do
+      {
+        key = static_cast<char> (getchar ());
+        switch (key)
+        {
+          case ' ':
+            if (interface.isRunning ())
+              interface.stop ();
+            else
+              interface.start ();
+            break;
+          case 's':
+            save = !save;
+        }
+      } while (key != 27 && key != 'q' && key != 'Q');
+
+      // stop the grabber
+      interface.stop ();
+    }
+};
+
+int
+main (int argc, char **argv)
+{
+  int mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
+  pcl::console::parse_argument (argc, argv, "-mode", mode);
+
+  SimpleOpenNIProcessor v (static_cast<openni_wrapper::OpenNIDevice::DepthMode> (mode));
+  v.run ();
+  return (0);
+}
index 80ffb3c21ff5f467c5b80605b7469c0f993cd270..5560ef682e22c1a4199971db39c24fe297c605c5 100644 (file)
 
 #include <pcl/point_types.h>
 #include <pcl/common/time.h> //fps calculations
-#include <pcl/io/openni_grabber.h>
 #include <pcl/io/lzf_image_io.h>
+#include <pcl/io/openni_camera/openni_driver.h>
+#include <pcl/io/openni_grabber.h>
+#include <pcl/io/timestamp.h>
 #include <pcl/visualization/common/float_image_utils.h>
 #include <pcl/visualization/image_viewer.h>
-#include <pcl/io/openni_camera/openni_driver.h>
 #include <pcl/console/parse.h>
 #include <pcl/visualization/mouse_event.h>
 
 #include <boost/circular_buffer.hpp>
-#include <boost/date_time/posix_time/posix_time.hpp> // for ptime, to_iso_string, ...
 
+#include <chrono>
 #include <csignal>
 #include <limits>
+#include <memory>
 #include <mutex>
 #include <thread>
-#include <memory>
 
 using namespace std::chrono_literals;
 using namespace pcl;
@@ -72,17 +73,17 @@ getTotalSystemMemory ()
   std::uint64_t pages = sysconf (_SC_AVPHYS_PAGES);
   std::uint64_t page_size = sysconf (_SC_PAGE_SIZE);
   print_info ("Total available memory size: %lluMB.\n", (pages * page_size) / 1048576);
-  if (pages * page_size > std::uint64_t (std::numeric_limits<std::size_t>::max ()))
+  if (pages * page_size > static_cast<std::uint64_t>(std::numeric_limits<std::size_t>::max ()))
   {
     return std::numeric_limits<std::size_t>::max ();
   }
-  return std::size_t (pages * page_size);
+  return static_cast<std::size_t>(pages * page_size);
 }
 
-const int BUFFER_SIZE = int (getTotalSystemMemory () / (640 * 480) / 2);
+const int BUFFER_SIZE = static_cast<int>(getTotalSystemMemory () / (640 * 480) / 2);
 #else
 
-const int BUFFER_SIZE = 200;
+constexpr int BUFFER_SIZE = 200;
 #endif
 
 int buff_size = BUFFER_SIZE;
@@ -145,7 +146,7 @@ struct Frame
          const openni_wrapper::DepthImage::Ptr &_depth_image,
          const io::CameraParameters &_parameters_rgb,
          const io::CameraParameters &_parameters_depth,
-         const boost::posix_time::ptime &_time)
+         const std::chrono::time_point<std::chrono::system_clock>& _time)
     : image (_image)
     , depth_image (_depth_image)
     , parameters_rgb (_parameters_rgb)
@@ -158,7 +159,7 @@ struct Frame
         
   io::CameraParameters parameters_rgb, parameters_depth;
 
-  boost::posix_time::ptime time;
+  std::chrono::time_point<std::chrono::system_clock> time;
 };
 
 //////////////////////////////////////////////////////////////////////////////////////////
@@ -223,13 +224,13 @@ class Buffer
     getSize ()
     {
       std::lock_guard<std::mutex> buff_lock (bmutex_);
-      return (int (buffer_.size ()));
+      return (static_cast<int>(buffer_.size ()));
     }
                
     inline int 
     getCapacity ()
     {
-           return (int (buffer_.capacity ()));
+           return (static_cast<int>(buffer_.capacity ()));
     }
                
     inline void 
@@ -265,8 +266,9 @@ class Writer
 
       FPS_CALC_WRITER ("data write   ", buf_);
       nr_frames_total++;
-      
-      std::string time_string = boost::posix_time::to_iso_string (frame->time);
+
+      const std::string time_string = getTimestamp(frame->time);
+
       // Save RGB data
       const std::string rgb_filename = "frame_" + time_string + "_rgb.pclzf";
       switch (frame->image->getEncoding ())
@@ -293,6 +295,7 @@ class Writer
 
       // Save depth data
       const std::string depth_filename = "frame_" + time_string + "_depth.pclzf";
+
       io::LZFDepth16ImageWriter ld;
       //io::LZFShift11ImageWriter ld;
       ld.write (reinterpret_cast<const char*> (&frame->depth_image->getDepthMetaData ().Data ()[0]), frame->depth_image->getWidth (), frame->depth_image->getHeight (), depth_filename);
@@ -371,7 +374,8 @@ class Driver
                     const openni_wrapper::DepthImage::Ptr &depth_image, 
                     float)
     {
-      boost::posix_time::ptime time = boost::posix_time::microsec_clock::local_time ();
+      const auto time = std::chrono::system_clock::now();
+
       FPS_CALC_DRIVER ("driver       ", buf_write_, buf_vis_);
 
       // Extract camera parameters
@@ -501,14 +505,14 @@ class Viewer
             {
               frame->image->fillRGB (frame->image->getWidth (), 
                                      frame->image->getHeight (), 
-                                     &rgb_data[0]);
+                                     rgb_data.data());
             }
             else
-              memcpy (&rgb_data[0],
+              memcpy (rgb_data.data(),
                       frame->image->getMetaData ().Data (),
                       rgb_data.size ());
 
-            image_viewer_->addRGBImage (reinterpret_cast<unsigned char*> (&rgb_data[0]), 
+            image_viewer_->addRGBImage (reinterpret_cast<unsigned char*> (rgb_data.data()), 
                                         frame->image->getWidth (),
                                         frame->image->getHeight (),
                                         "rgb_image");
@@ -545,7 +549,6 @@ class Viewer
     ///////////////////////////////////////////////////////////////////////////////////////
     Viewer (Buffer &buf)
       : buf_ (buf)
-      , image_cld_init_ (false), depth_image_cld_init_ (false)
     {
       image_viewer_.reset (new visualization::ImageViewer ("PCL/OpenNI RGB image viewer"));
       depth_image_viewer_.reset (new visualization::ImageViewer ("PCL/OpenNI depth image viewer"));
@@ -616,7 +619,7 @@ class Viewer
     Buffer &buf_;
     visualization::ImageViewer::Ptr image_viewer_;
     visualization::ImageViewer::Ptr depth_image_viewer_;
-    bool image_cld_init_, depth_image_cld_init_;
+    bool image_cld_init_{false}, depth_image_cld_init_{false};
 };
 
 void
diff --git a/tools/openni_pcd_recorder.cpp b/tools/openni_pcd_recorder.cpp
new file mode 100644 (file)
index 0000000..0f3bfed
--- /dev/null
@@ -0,0 +1,488 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2012, Sudarshan Srinivasan <sudarshan85@gmail.com>
+ *  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.
+ * 
+ *  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/point_cloud.h>
+#include <pcl/point_types.h>
+#include <pcl/io/openni_grabber.h>
+#include <pcl/io/timestamp.h>
+#include <boost/circular_buffer.hpp>
+#include <pcl/io/pcd_io.h>
+#include <pcl/console/print.h>
+#include <pcl/console/parse.h>
+#include <pcl/common/time.h> //fps calculations
+
+#include <chrono>
+#include <csignal>
+#include <limits>
+#include <memory>
+#include <thread>
+
+using namespace std::chrono_literals;
+using namespace pcl;
+using namespace pcl::console;
+
+bool is_done = false;
+std::mutex io_mutex;
+
+#if defined(__linux__) || defined (TARGET_OS_MAC)
+#include <unistd.h>
+// Get the available memory size on Linux/BSD systems
+
+size_t 
+getTotalSystemMemory ()
+{
+  std::uint64_t memory = std::numeric_limits<std::size_t>::max ();
+
+#ifdef _SC_AVPHYS_PAGES
+  std::uint64_t pages = sysconf (_SC_AVPHYS_PAGES);
+  std::uint64_t page_size = sysconf (_SC_PAGE_SIZE);
+  
+  memory = pages * page_size;
+  
+#elif defined(HAVE_SYSCTL) && defined(HW_PHYSMEM)
+  // This works on *bsd and darwin.
+  unsigned int physmem;
+  std::size_t len = sizeof physmem;
+  static int mib[2] = { CTL_HW, HW_PHYSMEM };
+
+  if (sysctl (mib, ARRAY_SIZE (mib), &physmem, &len, NULL, 0) == 0 && len == sizeof (physmem))
+  {
+    memory = physmem;
+  }
+#endif
+
+  if (memory > static_cast<std::uint64_t>(std::numeric_limits<std::size_t>::max ()))
+  {
+    memory = std::numeric_limits<std::size_t>::max ();
+  }
+  
+  print_info ("Total available memory size: %lluMB.\n", memory / 1048576ull);
+  return static_cast<std::size_t>(memory);
+}
+
+const std::size_t BUFFER_SIZE = static_cast<std::size_t>(getTotalSystemMemory () / (640 * 480 * sizeof (pcl::PointXYZRGBA)));
+#else
+
+constexpr std::size_t BUFFER_SIZE = 200;
+#endif
+
+//////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT>
+class PCDBuffer
+{
+  public:
+    PCDBuffer () = default;
+    PCDBuffer (const PCDBuffer&) = delete; // Disabled copy constructor
+    PCDBuffer& operator = (const PCDBuffer&) = delete; // Disabled assignment operator
+
+    bool 
+    pushBack (typename PointCloud<PointT>::ConstPtr); // thread-save wrapper for push_back() method of ciruclar_buffer
+
+    typename PointCloud<PointT>::ConstPtr 
+    getFront (); // thread-save wrapper for front() method of ciruclar_buffer
+
+    inline bool 
+    isFull ()
+    {
+      std::lock_guard<std::mutex> buff_lock (bmutex_);
+      return (buffer_.full ());
+    }
+
+    inline bool
+    isEmpty ()
+    {
+      std::lock_guard<std::mutex> buff_lock (bmutex_);
+      return (buffer_.empty ());
+    }
+
+    inline int 
+    getSize ()
+    {
+      std::lock_guard<std::mutex> buff_lock (bmutex_);
+      return (static_cast<int>(buffer_.size ()));
+    }
+
+    inline int 
+    getCapacity ()
+    {
+      return (int (buffer_.capacity ()));
+    }
+
+    inline void 
+    setCapacity (int buff_size)
+    {
+      std::lock_guard<std::mutex> buff_lock (bmutex_);
+      buffer_.set_capacity (buff_size);
+    }
+
+  private:
+    std::mutex bmutex_;
+    std::condition_variable buff_empty_;
+    boost::circular_buffer<typename PointCloud<PointT>::ConstPtr> buffer_;
+};
+
+//////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT> bool 
+PCDBuffer<PointT>::pushBack (typename PointCloud<PointT>::ConstPtr cloud)
+{
+  bool retVal = false;
+  {
+    std::lock_guard<std::mutex> buff_lock (bmutex_);
+    if (!buffer_.full ())
+      retVal = true;
+    buffer_.push_back (cloud);
+  }
+  buff_empty_.notify_one ();
+  return (retVal);
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////
+template <typename PointT> typename PointCloud<PointT>::ConstPtr 
+PCDBuffer<PointT>::getFront ()
+{
+  typename PointCloud<PointT>::ConstPtr cloud;
+  {
+    std::unique_lock<std::mutex> buff_lock (bmutex_);
+    while (buffer_.empty ())
+    {
+      if (is_done)
+        break;
+      {
+        std::lock_guard<std::mutex> io_lock (io_mutex);
+        //std::cerr << "No data in buffer_ yet or buffer is empty." << std::endl;
+      }
+      buff_empty_.wait (buff_lock);
+    }
+    cloud = buffer_.front ();
+    buffer_.pop_front ();
+  }
+  return (cloud);
+}
+
+#define FPS_CALC(_WHAT_, buff) \
+do \
+{ \
+    static unsigned count = 0;\
+    static double last = getTime ();\
+    double now = getTime (); \
+    ++count; \
+    if (now - last >= 1.0) \
+    { \
+      std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << "\n"; \
+      count = 0; \
+      last = now; \
+    } \
+}while(false)
+
+//////////////////////////////////////////////////////////////////////////////////////////
+// Producer thread class
+template <typename PointT>
+class Producer
+{
+  private:
+    ///////////////////////////////////////////////////////////////////////////////////////
+    void 
+    grabberCallBack (const typename PointCloud<PointT>::ConstPtr& cloud)
+    {
+      if (!buf_.pushBack (cloud))
+      {
+        {
+          std::lock_guard<std::mutex> io_lock (io_mutex);
+          print_warn ("Warning! Buffer was full, overwriting data!\n");
+        }
+      }
+      FPS_CALC ("cloud callback.", buf_);
+    }
+
+    ///////////////////////////////////////////////////////////////////////////////////////
+    void 
+    grabAndSend ()
+    {
+      auto* grabber = new OpenNIGrabber ();
+      grabber->getDevice ()->setDepthOutputFormat (depth_mode_);
+
+      Grabber* interface = grabber;
+      std::function<void (const typename PointCloud<PointT>::ConstPtr&)> f = [this] (const typename PointCloud<PointT>::ConstPtr& cloud)
+      {
+        grabberCallBack (cloud);
+      };
+      interface->registerCallback (f);
+      interface->start ();
+
+      while (true)
+      {
+        if (is_done)
+          break;
+        std::this_thread::sleep_for(1s);
+      }
+      interface->stop ();
+    }
+
+  public:
+    Producer (PCDBuffer<PointT> &buf, openni_wrapper::OpenNIDevice::DepthMode depth_mode)
+      : buf_ (buf),
+        depth_mode_ (depth_mode)
+    {
+      thread_.reset (new std::thread (&Producer::grabAndSend, this));
+    }
+
+    ///////////////////////////////////////////////////////////////////////////////////////
+    void
+    stop ()
+    {
+      thread_->join ();
+      std::lock_guard<std::mutex> io_lock (io_mutex);
+      print_highlight ("Producer done.\n");
+    }
+
+  private:
+    PCDBuffer<PointT> &buf_;
+    openni_wrapper::OpenNIDevice::DepthMode depth_mode_;
+    std::shared_ptr<std::thread> thread_;
+};
+
+//////////////////////////////////////////////////////////////////////////////////////////
+// Consumer thread class
+template <typename PointT>
+class Consumer
+{
+  private:
+    ///////////////////////////////////////////////////////////////////////////////////////
+    void 
+    writeToDisk (const typename PointCloud<PointT>::ConstPtr& cloud)
+    {
+      const std::string file_name = "frame-" + pcl::getTimestamp() + ".pcd";
+      writer_.writeBinaryCompressed(file_name, *cloud);
+      FPS_CALC ("cloud write.", buf_);
+    }
+
+    ///////////////////////////////////////////////////////////////////////////////////////
+    // Consumer thread function
+    void 
+    receiveAndProcess ()
+    {
+      while (true)
+      {
+        if (is_done)
+          break;
+        writeToDisk (buf_.getFront ());
+      }
+
+      {
+        std::lock_guard<std::mutex> io_lock (io_mutex);
+        print_info ("Writing remaining %ld clouds in the buffer to disk...\n", buf_.getSize ());
+      }
+      while (!buf_.isEmpty ())
+        writeToDisk (buf_.getFront ());
+    }
+
+  public:
+    Consumer (PCDBuffer<PointT> &buf)
+      : buf_ (buf)
+    {
+      thread_.reset (new std::thread (&Consumer::receiveAndProcess, this));
+    }
+
+    ///////////////////////////////////////////////////////////////////////////////////////
+    void
+    stop ()
+    {
+      thread_->join ();
+      std::lock_guard<std::mutex> io_lock (io_mutex);
+      print_highlight ("Consumer done.\n");
+    }
+
+  private:
+    PCDBuffer<PointT> &buf_;
+    std::shared_ptr<std::thread> thread_;
+    PCDWriter writer_;
+};
+
+//////////////////////////////////////////////////////////////////////////////////////////
+void 
+ctrlC (int)
+{
+  std::lock_guard<std::mutex> io_lock (io_mutex);
+  print_info ("\nCtrl-C detected, exit condition set to true.\n");
+  is_done = true;
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////
+void
+printHelp (int default_buff_size, int, char **argv)
+{
+  using pcl::console::print_error;
+  using pcl::console::print_info;
+
+  print_error ("Syntax is: %s ((<device_id> | <path-to-oni-file>) [-xyz] [-shift] [-buf X]  | -l [<device_id>] | -h | --help)]\n", argv [0]);
+  print_info ("%s -h | --help : shows this help\n", argv [0]);
+  print_info ("%s -xyz : save only XYZ data, even if the device is RGB capable\n", argv [0]);
+  print_info ("%s -shift : use OpenNI shift values rather than 12-bit depth\n", argv [0]);
+  print_info ("%s -buf X ; use a buffer size of X frames (default: ", argv [0]);
+  print_value ("%d", default_buff_size); print_info (")\n");
+  print_info ("%s -l : list all available devices\n", argv [0]);
+  print_info ("%s -l <device-id> :list all available modes for specified device\n", argv [0]);
+  print_info ("\t\t<device_id> may be \"#1\", \"#2\", ... for the first, second etc device in the list\n");
+#ifndef _WIN32
+  print_info ("\t\t                   bus@address for the device connected to a specific usb-bus / address combination\n");
+  print_info ("\t\t                   <serial-number>\n");
+#endif
+  print_info ("\n\nexamples:\n");
+  print_info ("%s \"#1\"\n", argv [0]);
+  print_info ("\t\t uses the first device.\n");
+  print_info ("%s  \"./temp/test.oni\"\n", argv [0]);
+  print_info ("\t\t uses the oni-player device to play back oni file given by path.\n");
+  print_info ("%s -l\n", argv [0]);
+  print_info ("\t\t list all available devices.\n");
+  print_info ("%s -l \"#2\"\n", argv [0]);
+  print_info ("\t\t list all available modes for the second device.\n");
+  #ifndef _WIN32
+  print_info ("%s A00361800903049A\n", argv [0]);
+  print_info ("\t\t uses the device with the serial number \'A00361800903049A\'.\n");
+  print_info ("%s 1@16\n", argv [0]);
+  print_info ("\t\t uses the device on address 16 at USB bus 1.\n");
+  #endif
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////
+int
+main (int argc, char** argv)
+{
+  print_highlight ("PCL OpenNI Recorder for saving buffered PCD (binary compressed to disk). See %s -h for options.\n", argv[0]);
+
+  std::string device_id;
+  int buff_size = BUFFER_SIZE;
+
+  if (argc >= 2)
+  {
+    device_id = argv[1];
+    if (device_id == "--help" || device_id == "-h")
+    {
+      printHelp (buff_size, argc, argv);
+      return 0;
+    }
+    if (device_id == "-l")
+    {
+      if (argc >= 3)
+      {
+        pcl::OpenNIGrabber grabber (argv[2]);
+        openni_wrapper::OpenNIDevice::Ptr device = grabber.getDevice ();
+        std::cout << "Supported depth modes for device: " << device->getVendorName () << " , " << device->getProductName () << std::endl;
+        std::vector<std::pair<int, XnMapOutputMode > > modes = grabber.getAvailableDepthModes ();
+        for (const auto& mode : modes)
+        {
+          std::cout << mode.first << " = " << mode.second.nXRes << " x " << mode.second.nYRes << " @ " << mode.second.nFPS << std::endl;
+        }
+
+        if (device->hasImageStream ())
+        {
+          std::cout << std::endl << "Supported image modes for device: " << device->getVendorName () << " , " << device->getProductName () << std::endl;
+          modes = grabber.getAvailableImageModes ();
+          for (const auto& mode : modes)
+          {
+            std::cout << mode.first << " = " << mode.second.nXRes << " x " << mode.second.nYRes << " @ " << mode.second.nFPS << std::endl;
+          }
+        }
+      }
+      else
+      {
+        openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
+        if (driver.getNumberDevices() > 0)
+        {
+          for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
+          {
+            std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
+              << ", connected: " << driver.getBus(deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
+          }
+
+        }
+        else
+          std::cout << "No devices connected." << std::endl;
+
+        std::cout <<"Virtual Devices available: ONI player" << std::endl;
+      }
+      return 0;
+    }
+  }
+  else
+  {
+    openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
+    if (driver.getNumberDevices () > 0)
+      std::cout << "Device Id not set, using first device." << std::endl;
+  }
+
+  bool just_xyz = find_switch (argc, argv, "-xyz");
+  openni_wrapper::OpenNIDevice::DepthMode depth_mode = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
+  if (find_switch (argc, argv, "-shift"))
+    depth_mode = openni_wrapper::OpenNIDevice::OpenNI_shift_values;
+
+  if (parse_argument (argc, argv, "-buf", buff_size) != -1)
+    print_highlight ("Setting buffer size to %d frames.\n", buff_size);
+  else
+    print_highlight ("Using default buffer size of %d frames.\n", buff_size);
+
+  print_highlight ("Starting the producer and consumer threads... Press Ctrl+C to end\n");
+  OpenNIGrabber grabber (device_id);
+  if (grabber.providesCallback<OpenNIGrabber::sig_cb_openni_point_cloud_rgba> () && 
+      !just_xyz)
+  {
+    print_highlight ("PointXYZRGBA enabled.\n");
+    PCDBuffer<PointXYZRGBA> buf;
+    buf.setCapacity (buff_size);
+    Producer<PointXYZRGBA> producer (buf, depth_mode);
+    std::this_thread::sleep_for(2s);
+    Consumer<PointXYZRGBA> consumer (buf);
+
+    signal (SIGINT, ctrlC);
+    producer.stop ();
+    consumer.stop ();
+  }
+  else
+  {
+    print_highlight ("PointXYZ enabled.\n");
+    PCDBuffer<PointXYZ> buf;
+    buf.setCapacity (buff_size);
+    Producer<PointXYZ> producer (buf, depth_mode);
+    std::this_thread::sleep_for(2s);
+    Consumer<PointXYZ> consumer (buf);
+
+    signal (SIGINT, ctrlC);
+    producer.stop ();
+    consumer.stop ();
+  }
+  return (0);
+}
+
index b7cf2e6cacd810777585e922782d7daefa92cf8d..1787c977d3c6dbb70a1c535d6e0858f70e7f29d6 100644 (file)
@@ -36,6 +36,7 @@
  */
 
 #include <pcl/common/time.h> //fps calculations
+#include <pcl/io/timestamp.h>
 #include <pcl/io/openni_grabber.h>
 #include <pcl/io/openni_camera/openni_driver.h>
 #include <pcl/console/parse.h>
 #include <vtkTIFFWriter.h>
 #include <vtkImageFlip.h>
 
+#include <chrono>
 #include <mutex>
 #include <string>
 #include <vector>
-#include <boost/date_time/posix_time/posix_time.hpp> // for to_iso_string, local_time
 
 
 #define SHOW_FPS 1
@@ -125,7 +126,8 @@ class SimpleOpenNIViewer
       {
         std::lock_guard<std::mutex> lock (image_mutex_);
 
-        std::string time = boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ());
+        const auto timestamp = pcl::getTimestamp();
+
         if (image_)
         {
           FPS_CALC ("writer callback");
@@ -151,7 +153,7 @@ class SimpleOpenNIViewer
             data = reinterpret_cast<const void*> (rgb_data);
           }
 
-          const std::string filename = "frame_" + time + "_rgb.tiff";
+          const std::string filename = "frame_" + timestamp + "_rgb.tiff";
           importer_->SetImportVoidPointer (const_cast<void*>(data), 1);
           importer_->Update ();
           flipper_->SetInputConnection (importer_->GetOutputPort ());
@@ -166,7 +168,7 @@ class SimpleOpenNIViewer
           openni_wrapper::DepthImage::Ptr depth_image;
           depth_image.swap (depth_image_);
 
-          const std::string filename = "frame_" + time + "_depth.tiff";
+          const std::string filename = "frame_" + timestamp + "_depth.tiff";
 
           depth_importer_->SetWholeExtent (0, depth_image->getWidth () - 1, 0, depth_image->getHeight () - 1, 0, 0);
           depth_importer_->SetDataExtentToWholeExtent ();
@@ -290,10 +292,10 @@ main(int argc, char ** argv)
   
   unsigned imagemode;
   if (pcl::console::parse (argc, argv, "-imagemode", imagemode) != -1)
-    image_mode = pcl::OpenNIGrabber::Mode (imagemode);
+    image_mode = static_cast<pcl::OpenNIGrabber::Mode>(imagemode);
   unsigned depthmode;
   if (pcl::console::parse (argc, argv, "-depthmode", depthmode) != -1)
-    depth_mode = pcl::OpenNIGrabber::Mode (depthmode);
+    depth_mode = static_cast<pcl::OpenNIGrabber::Mode>(depthmode);
   
 
   pcl::OpenNIGrabber grabber (device_id, depth_mode, image_mode);
index b2e70ce5106398bd372f5e5d21b73d4d765febcb..3b131c8a820de5161fd6830ebf7fe1b97cc7391c 100644 (file)
@@ -109,12 +109,10 @@ class OpenNIViewer
     using Cloud = pcl::PointCloud<PointType>;
     using CloudConstPtr = typename Cloud::ConstPtr;
 
-    OpenNIViewer (pcl::Grabber& grabber)
-      : cloud_viewer_ (new pcl::visualization::PCLVisualizer ("PCL OpenNI cloud"))
-      , grabber_ (grabber)
-      , rgb_data_ (nullptr), rgb_data_size_ (0)
-    {
-    }
+    OpenNIViewer(pcl::Grabber& grabber)
+    : cloud_viewer_(new pcl::visualization::PCLVisualizer("PCL OpenNI cloud"))
+    , grabber_(grabber)
+    {}
 
     void
     cloud_callback (const CloudConstPtr& cloud)
@@ -263,8 +261,8 @@ class OpenNIViewer
     
     CloudConstPtr cloud_;
     openni_wrapper::Image::Ptr image_;
-    unsigned char* rgb_data_;
-    unsigned rgb_data_size_;
+    unsigned char* rgb_data_{nullptr};
+    unsigned rgb_data_size_{0};
 };
 
 // Create the PCLVisualizer object
@@ -340,10 +338,10 @@ main (int argc, char** argv)
   
   unsigned mode;
   if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1)
-    depth_mode = pcl::OpenNIGrabber::Mode (mode);
+    depth_mode = static_cast<pcl::OpenNIGrabber::Mode>(mode);
 
   if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1)
-    image_mode = pcl::OpenNIGrabber::Mode (mode);
+    image_mode = static_cast<pcl::OpenNIGrabber::Mode>(mode);
   
   if (pcl::console::find_argument (argc, argv, "-xyz") != -1)
     xyz = true;
index db5dea2e3dc8e607178e77be683ad353d62ea2bc..90190279d297e234aed318e3e69397718493fc86 100644 (file)
@@ -121,10 +121,10 @@ class SimpleOpenNIViewer
     void 
     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie)
     {
-      string* message = (string*)cookie;
+      auto message = static_cast<std::string*>(cookie);
       std::cout << (*message) << " :: ";
       if (event.getKeyCode())
-        std::cout << "the key \'" << event.getKeyCode() << "\' (" << (int)event.getKeyCode() << ") was";
+        std::cout << "the key \'" << event.getKeyCode() << "\' (" << static_cast<int>(event.getKeyCode()) << ") was";
       else
         std::cout << "the special key \'" << event.getKeySym() << "\' was";
       if (event.keyDown())
@@ -135,7 +135,7 @@ class SimpleOpenNIViewer
     
     void mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie)
     {
-      string* message = (string*) cookie;
+      auto message = static_cast<std::string*>(cookie);
       if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
       {
         std::cout << (*message) << " :: " << mouse_event.getX () << " , " << mouse_event.getY () << std::endl;
@@ -167,8 +167,10 @@ class SimpleOpenNIViewer
 
       std::string mouseMsg3D("Mouse coordinates in PCL Visualizer");
       std::string keyMsg3D("Key event for PCL Visualizer");
-      cloud_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg3D));    
-      cloud_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg3D));
+      cloud_viewer_.registerMouseCallback(
+          &SimpleOpenNIViewer::mouse_callback, *this, static_cast<void*>(&mouseMsg3D));
+      cloud_viewer_.registerKeyboardCallback(
+          &SimpleOpenNIViewer::keyboard_callback, *this, static_cast<void*>(&keyMsg3D));
       std::function<void (const CloudConstPtr&)> cloud_cb = [this] (const CloudConstPtr& cloud) { cloud_callback (cloud); };
       boost::signals2::connection cloud_connection = grabber_.registerCallback (cloud_cb);
       
@@ -177,12 +179,16 @@ class SimpleOpenNIViewer
       {
           std::string mouseMsg2D("Mouse coordinates in image viewer");
           std::string keyMsg2D("Key event for image viewer");
-          image_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg2D));
-          image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg2D));
+          image_viewer_.registerMouseCallback(&SimpleOpenNIViewer::mouse_callback,
+                                              *this,
+                                              static_cast<void*>(&mouseMsg2D));
+          image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback,
+                                                 *this,
+                                                 static_cast<void*>(&keyMsg2D));
           std::function<void (const openni_wrapper::Image::Ptr&)> image_cb = [this] (const openni_wrapper::Image::Ptr& img) { image_callback (img); };
           image_connection = grabber_.registerCallback (image_cb);
       }
-      unsigned char* rgb_data = 0;
+      unsigned char* rgb_data = nullptr;
       unsigned rgb_data_size = 0;
       
       grabber_.start ();
@@ -271,7 +277,7 @@ usage(char ** argv)
 int
 main(int argc, char ** argv)
 {
-  std::string device_id("");
+  std::string device_id;
   pcl::OpenNIGrabber::Mode depth_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
   bool xyz = false;
@@ -315,7 +321,7 @@ main(int argc, char ** argv)
           for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx)
           {
             std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName(deviceIdx) << ", product: " << driver.getProductName(deviceIdx)
-              << ", connected: " << (int) driver.getBus(deviceIdx) << " @ " << (int) driver.getAddress(deviceIdx) << ", serial number: \'" << driver.getSerialNumber(deviceIdx) << "\'" << std::endl;
+              << ", connected: " << static_cast<int>(driver.getBus(deviceIdx)) << " @ " << static_cast<int>(driver.getAddress(deviceIdx)) << ", serial number: \'" << driver.getSerialNumber(deviceIdx) << "\'" << std::endl;
           }
 
         }
@@ -336,10 +342,10 @@ main(int argc, char ** argv)
   
   unsigned mode;
   if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1)
-    depth_mode = (pcl::OpenNIGrabber::Mode) mode;
+    depth_mode = static_cast<pcl::OpenNIGrabber::Mode>(mode);
 
   if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1)
-    image_mode = (pcl::OpenNIGrabber::Mode) mode;
+    image_mode = static_cast<pcl::OpenNIGrabber::Mode>(mode);
   
   if (pcl::console::find_argument(argc, argv, "-xyz") != -1)
     xyz = true;
index 0681095e026f625666ed51fe4e28f3420c8c2307..6b2f883358bd1712f8fd2661ca1ffa9a1e74f51f 100644 (file)
@@ -111,7 +111,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output
   if (keep_organized)
   {
     xyz_cloud = xyz_cloud_pre;
-    for (int i = 0; i < int (xyz_cloud->size ()); ++i)
+    for (int i = 0; i < static_cast<int>(xyz_cloud->size ()); ++i)
       valid_indices.push_back (i);
   }
   else
index c8f153131e6ca9bff663949f9bd0f6b09b3697a3..f79a87f0d63bb6c21f7ad29043b175809c666478 100644 (file)
@@ -218,7 +218,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
diff --git a/tools/pcd_convert_NaN_nan.cpp b/tools/pcd_convert_NaN_nan.cpp
new file mode 100644 (file)
index 0000000..541a27c
--- /dev/null
@@ -0,0 +1,80 @@
+/*
+ * 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.
+ */
+
+#include <cstring>
+#include <fstream>
+#include <iostream>
+#include <limits>
+#include <sstream>
+#include <string>
+
+int
+main (int argc, char **argv)
+{
+  if (argc != 3)
+  {
+    std::cout << "call with " << argv[0] << " input.pcd output.pcd" << std::endl;
+    return 0;
+  }
+
+  if (!strcmp (argv[1], argv[2]))
+  {
+    std::cout << "called with same name for input and output! (done nothing)" << std::endl;
+    return 1;
+  }
+
+  std::ostringstream ss;
+  ss << std::numeric_limits<float>::quiet_NaN ();
+  std::string nanStr (ss.str ());
+
+  std::cout << R"(converting ")" << nanStr << R"(" to "nan")" << std::endl;
+
+  std::ifstream input (argv[1]);
+  std::ofstream output (argv[2]);
+  std::string str;
+
+  while (input >> str)
+  {
+    if (str == nanStr)
+      output << "nan";
+    else
+      output << str;
+    char next = static_cast<char> (input.peek ());
+    if (next == '\n' || next == '\r')
+      output << "\n";
+    else
+      output << " ";
+  }
+  return 0;
+}
index dd46219c774b232f18edbc4e473a4c7662419afb..b8216c3a82afde3821861ae1619746a3e4c3489e 100644 (file)
@@ -114,7 +114,7 @@ mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie)
 int
 main (int argc, char** argv)
 {
-  srand (unsigned (time (nullptr)));
+  srand (static_cast<unsigned>(time (nullptr)));
 
   if (argc > 1)
   {
@@ -193,7 +193,7 @@ main (int argc, char** argv)
       boost::filesystem::directory_iterator end_itr;
       for (boost::filesystem::directory_iterator itr (path); itr != end_itr; ++itr)
       {
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           std::cout << "added: " << itr->path ().string () << std::endl;
diff --git a/tools/pcd_introduce_nan.cpp b/tools/pcd_introduce_nan.cpp
new file mode 100644 (file)
index 0000000..c7c517b
--- /dev/null
@@ -0,0 +1,85 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2014-, 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/io/pcd_io.h>
+#include <boost/lexical_cast.hpp> // for lexical_cast
+
+/** @brief PCL point object */
+using PointT = pcl::PointXYZRGBA;
+
+/** @brief PCL Point cloud object */
+using PointCloudT = pcl::PointCloud<PointT>;
+
+int
+main (int argc,
+      char** argv)
+{
+  if (argc != 3 && argc != 4)
+  {
+    PCL_ERROR ("Usage: %s cloud_in.pcd cloud_out_ascii.pcd percentage_of_NaN \n", argv[0]);
+    return (-1);
+  }
+
+  int percentage_of_NaN = 20;
+  if (argc == 4)
+    percentage_of_NaN = boost::lexical_cast<int>(argv[3]);
+
+  PCL_INFO ("Replacing approximately %d%% of the cloud with NaN values (already existing NaN values are conserved)\n", percentage_of_NaN);
+  PointCloudT::Ptr cloud (new PointCloudT);
+  if (pcl::io::loadPCDFile (argv[1], *cloud) != 0)
+    return (-1);
+
+  for (auto &point : *cloud)
+  {
+    int random = 1 + (rand () % (100));
+    int random_xyz = 1 + (rand () % (3 - 1 + 1));
+
+    if (random < percentage_of_NaN)
+    {
+      if (random_xyz == 1)
+        point.x = std::numeric_limits<double>::quiet_NaN ();
+      else if (random_xyz == 2)
+        point.y = std::numeric_limits<double>::quiet_NaN ();
+      else
+        point.z = std::numeric_limits<double>::quiet_NaN ();
+    }
+  }
+
+  pcl::io::savePCDFile (argv[2], *cloud);
+  return (0);
+}
+
index 8ed0062a2b1c84fe5cd8d84618fa98f394f0e2d5..7d045fc9cb71cac3e82aff6980a3c2a35c7f542f 100644 (file)
@@ -129,10 +129,10 @@ printHelp (int, char **argv)
   print_info ("\n");
   print_info ("                     -immediate_rendering 0/1 = use immediate mode rendering to draw the data (default: "); print_value ("disabled"); print_info (")\n");
   print_info ("                                                Note: the use of immediate rendering will enable the visualization of larger datasets at the expense of extra RAM.\n");
-  print_info ("                                                See http://en.wikipedia.org/wiki/Immediate_mode for more information.\n");
+  print_info ("                                                See https://en.wikipedia.org/wiki/Immediate_mode for more information.\n");
   print_info ("                     -vbo_rendering 0/1       = use OpenGL 1.4+ Vertex Buffer Objects for rendering (default: "); print_value ("disabled"); print_info (")\n");
   print_info ("                                                Note: the use of VBOs will enable the visualization of larger datasets at the expense of extra RAM.\n");
-  print_info ("                                                See http://en.wikipedia.org/wiki/Vertex_Buffer_Object for more information.\n");
+  print_info ("                                                See https://en.wikipedia.org/wiki/Vertex_Buffer_Object for more information.\n");
   print_info ("\n");
   print_info ("                     -use_point_picking       = enable the usage of picking points on screen (default "); print_value ("disabled"); print_info (")\n");
   print_info ("\n");
@@ -323,7 +323,7 @@ main (int argc, char** argv)
     print_highlight ("Multi-viewport rendering enabled.\n");
 
     int y_s = static_cast<int>(std::floor (std::sqrt (static_cast<float>(p_file_indices.size () + vtk_file_indices.size ()))));
-    x_s = y_s + static_cast<int>(std::ceil (double (p_file_indices.size () + vtk_file_indices.size ()) / double (y_s) - y_s));
+    x_s = y_s + static_cast<int>(std::ceil (static_cast<double>(p_file_indices.size () + vtk_file_indices.size ()) / static_cast<double>(y_s) - y_s));
 
     if (!p_file_indices.empty ())
     {
diff --git a/tools/pcl_video.cpp b/tools/pcl_video.cpp
deleted file mode 100644 (file)
index d79d7db..0000000
+++ /dev/null
@@ -1,437 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2011, Geoffrey Biggs
- *  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.
- *
- *  \author Geoffrey Biggs
- */
-
-#include <iostream>
-#include <string>
-#include <thread>
-#include <tide/ebml_element.h>
-#include <tide/file_cluster.h>
-#include <tide/segment.h>
-#include <tide/simple_block.h>
-#include <tide/tide_impl.h>
-#include <tide/tracks.h>
-#include <tide/track_entry.h>
-#include <pcl/point_cloud.h>
-#include <pcl/point_types.h>
-#include <pcl/io/openni_grabber.h>
-#include <pcl/PCLPointCloud2.h>
-#include <pcl/conversions.h>
-#include <pcl/visualization/cloud_viewer.h>
-#include <pcl/console/parse.h>
-#include <pcl/common/time.h>
-#include <boost/date_time/gregorian/gregorian_types.hpp> // for date
-#include <boost/date_time/posix_time/posix_time.hpp> // for local_time
-#include <boost/date_time/posix_time/posix_time_types.hpp> // for time_duration
-
-using namespace std::chrono_literals;
-namespace bpt = boost::posix_time;
-
-
-class Recorder
-{
-    public:
-        Recorder(std::string const& filename, std::string const& title)
-            : filename_(filename), title_(title),
-            stream_(filename, std::ios::in|std::ios::out|std::ios::trunc),
-            count_(0)
-        {
-        }
-
-        void Callback(pcl::PointCloud<pcl::PointXYZ>::ConstPtr const& cloud)
-        {
-            // When creating a block, the track number must be specified. Currently,
-            // all blocks belong to track 1 (because this program only records one
-            // track). A timecode must also be given.  It is an offset from the
-            // cluster's timecode measured in the segment's timecode scale.
-            bpt::ptime blk_start(bpt::microsec_clock::local_time());
-            bpt::time_duration blk_offset = blk_start - cltr_start_;
-            tide::BlockElement::Ptr block(new tide::SimpleBlock(1,
-                        blk_offset.total_microseconds() / 10000));
-            // Here the frame data itself is added to the block
-            pcl::PCLPointCloud2 blob;
-            pcl::toPCLPointCloud2(*cloud, blob);
-            tide::Block::FramePtr frame_ptr(new tide::Block::Frame(blob.data.begin(),
-                        blob.data.end()));
-            block->push_back(frame_ptr);
-            cluster_->push_back(block);
-            // Benchmarking
-            if (++count_ == 30)
-            {
-                double now = pcl::getTime();
-                std::cerr << "Average framerate: " <<
-                    static_cast<double>(count_) / (now - last_) << "Hz\n";
-                count_ = 0;
-                last_ = now;
-            }
-            // Check if the cluster has enough data in it.
-            // What "enough" is depends on your own needs. Generally, a cluster
-            // shouldn't be allowed to get too big in data size or too long in time, or
-            // it has an adverse affect on seeking through the file. We will aim for 1
-            // second of data per cluster.
-            bpt::time_duration cluster_len(
-                    bpt::microsec_clock::local_time() - cltr_start_);
-            if (cluster_len.total_seconds() >= 1)
-            {
-                // Finalise the cluster
-                cluster_->finalise(stream_);
-                // Create a new cluster
-                cltr_start_ = bpt::microsec_clock::local_time();
-                bpt::time_duration cltr_offset = cltr_start_ - seg_start_;
-                cluster_.reset(new tide::FileCluster(
-                            cltr_offset.total_microseconds() / 10000));
-                cluster_->write(stream_);
-            }
-        }
-
-        int Run()
-        {
-            // Write the EBML PCLHeader. This specifies that the file is an EBML
-            // file, and is a Tide document.
-            tide::EBMLElement ebml_el;
-            ebml_el.write(stream_);
-
-            // Open a new segment in the file. This will write some initial meta-data
-            // and place some padding at the start of the file for final meta-data to
-            // be written after tracks, clusters, etc. have been written.
-            tide::Segment segment;
-            segment.write(stream_);
-            // Set up the segment information so it can be used while writing tracks
-            // and clusters.
-            // A UID is not required, but is highly recommended.
-            boost::uuids::random_generator gen;
-            boost::uuids::uuid uuid = gen();
-            std::vector<char> uuid_data(uuid.size());
-            std::copy(uuid.cbegin(), uuid.cend(), uuid_data.begin());
-            segment.info.uid(uuid_data);
-            // The filename can be nice to know.
-            segment.info.filename(filename_);
-            // The segment's timecode scale is possibly the most important value in the
-            // segment meta-data data. Without it, timely playback of frames is not
-            // possible. It has a sensible default (defined in the Tide specification),
-            // but here we set it to ten milliseconds for demonstrative purposes.
-            segment.info.timecode_scale(10000000);
-            // The segment's date should be set. It is the somewhat-awkward value of
-            // the number of seconds since the start of the millennium. Boost::Date_Time
-            // to the rescue!
-            bpt::ptime basis(boost::gregorian::date(2001, 1, 1));
-            seg_start_ = boost::posix_time::microsec_clock::local_time();
-            bpt::time_duration td = seg_start_ - basis;
-            segment.info.date(td.total_microseconds() * 1000);
-            // Let's give the segment an inspirational title.
-            segment.info.title(title_);
-            // It sometimes helps to know what created a Tide file.
-            segment.info.muxing_app("libtide-0.1");
-            segment.info.writing_app("pcl_video");
-
-            // Set up the tracks meta-data and write it to the file.
-            tide::Tracks tracks;
-            // Each track is represented in the Tracks information by a TrackEntry.
-            // This specifies such things as the track number, the track's UID and the
-            // codec used.
-            tide::TrackEntry::Ptr track(new tide::TrackEntry(1, 1, "pointcloud2"));
-            track->name("3D video");
-            track->codec_name("pcl::PCLPointCloud2");
-            // Adding each level 1 element (only the first occurrence, in the case of
-            // clusters) to the index makes opening the file later much faster.
-            segment.index.insert(std::make_pair(tracks.id(),
-                        segment.to_segment_offset(stream_.tellp())));
-            // Now we can write the Tracks element.
-            tracks.insert(track);
-            tracks.write(stream_);
-            // The file is now ready for writing the data. The data itself is stored in
-            // clusters. Each cluster contains a number of blocks, with each block
-            // containing a single frame of data. Different cluster implementations are
-            // (will be) available using different optimisations. Here, we use the
-            // implementation that stores all its blocks in memory before writing them
-            // all to the file at once. As with the segment, clusters must be opened
-            // for writing before blocks are added. Once the cluster is complete, it is
-            // finalised. How many blocks each cluster contains is relatively flexible:
-            // the only limitation is on the range of block timecodes that can be
-            // stored. Each timecode is a signed 16-bit integer, and usually blocks
-            // have timecodes that are positive, limiting the range to 32767. The unit
-            // of this value is the segment's timecode scale. The default timecode
-            // scale therefore gives approximately 65 seconds of total range, with 32
-            // seconds being usable.
-            // The first cluster will appear at this point in the file, so it is
-            // recorded in the segment's index for faster file reading.
-            segment.index.insert(std::make_pair(tide::ids::Cluster,
-                        segment.to_segment_offset(stream_.tellp())));
-
-            // Set up a callback to get clouds from a grabber and write them to the
-            // file.
-            pcl::Grabber* interface(new pcl::OpenNIGrabber());
-            std::function<void (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)> f (
-                [this] (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&) { Callback (cloud); }
-            );
-            interface->registerCallback(f);
-            // Start the first cluster
-            cltr_start_ = bpt::microsec_clock::local_time();
-            bpt::time_duration cltr_offset = cltr_start_ - seg_start_;
-            cluster_.reset(new tide::FileCluster(
-                        cltr_offset.total_microseconds() / 10000));
-            cluster_->write(stream_);
-            last_ = pcl::getTime();
-            interface->start();
-
-            std::cout << "Recording frames. Press any key to stop.\n";
-            getchar();
-
-            interface->stop();
-            // Close the last open cluster
-            if (cluster_)
-            {
-                cluster_->finalise(stream_);
-            }
-
-            // Now that the data has been written, the last thing to do is to finalise
-            // the segment.
-            segment.finalise(stream_);
-            // And finally, close the file.
-            stream_.close();
-
-            return 0;
-        }
-
-    private:
-        std::string filename_;
-        std::string title_;
-        std::fstream stream_;
-        tide::FileCluster::Ptr cluster_;
-        bpt::ptime seg_start_;
-        bpt::ptime cltr_start_;
-        unsigned int count_;
-        double last_;
-};
-
-
-class Player
-{
-    public:
-        Player(std::string const& filename)
-            : filename_(filename), viewer_("PCL Video Player: " + filename)
-        {
-            //viewer_.setBackgroundColor(0, 0, 0);
-            //viewer_.initCameraParameters();
-        }
-
-        int Run()
-        {
-            // Open the file and check for the EBML header. This confirms that the file
-            // is an EBML file, and is a Tide document.
-            std::ifstream stream(filename_, std::ios::in);
-            tide::ids::ReadResult id = tide::ids::read(stream);
-            if (id.first != tide::ids::EBML)
-            {
-                std::cerr << "File does not begin with an EBML header.\n";
-                return 1;
-            }
-            tide::EBMLElement ebml_el;
-            ebml_el.read(stream);
-            if (ebml_el.doc_type() != tide::TideDocType)
-            {
-                std::cerr << "Specified EBML file is not a Tide document.\n";
-                return 1;
-            }
-            if (ebml_el.read_version() > tide::TideEBMLVersion)
-            {
-                std::cerr << "This Tide document requires read version " <<
-                    ebml_el.read_version() << ".\n";
-                return 1;
-            }
-            if (ebml_el.doc_read_version() > tide::TideVersionMajor)
-            {
-                std::cerr << "This Tide document requires doc read version " <<
-                    ebml_el.read_version() << ".\n";
-                return 1;
-            }
-            std::cerr << "Found EBML header\n";
-
-            // Open the file's segment. This will read some meta-data about the segment
-            // and read (or build, if necessary) an index of the level 1 elements. With
-            // this index, we will be able to quickly jump to important elements such
-            // as the Tracks and the first Cluster.
-            id = tide::ids::read(stream);
-            if (id.first != tide::ids::Segment)
-            {
-                std::cerr << "Segment element not found\n";
-                return 1;
-            }
-            tide::Segment segment;
-            segment.read(stream);
-            // The segment's date is stored as the number of nanoseconds since the
-            // start of the millennium. Boost::Date_Time is invaluable here.
-            bpt::ptime basis(boost::gregorian::date(2001, 1, 1));
-            bpt::time_duration sd(bpt::microseconds(segment.info.date() / 1000));
-            bpt::ptime seg_start(basis + sd);
-
-            // The segment is now open and we can start reading its child elements. To
-            // begin with, we get the tracks element (their may be more than one, if
-            // the document was created by merging other documents) but generally only
-            // one will exist).
-            // We can guarantee that there is at least one in the index because
-            // otherwise the call to segment.read() would have thrown an error.
-            std::streampos tracks_pos(segment.index.find(tide::ids::Tracks)->second);
-            stream.seekg(segment.to_stream_offset(tracks_pos));
-            // To be sure, we can check it really is a Tracks element, but this is
-            // usually not necessary.
-            id = tide::ids::read(stream);
-            if (id.first != tide::ids::Tracks)
-            {
-                std::cerr << "Tracks element not at indicated position.\n";
-                return 1;
-            }
-            // Read the tracks
-            tide::Tracks tracks;
-            tracks.read(stream);
-            // Now we can introspect the tracks available in the file.
-            if (tracks.empty())
-            {
-                std::cerr << "No tracks found.\n";
-                return 1;
-            }
-            // Let's check that the file contains the codec we expect for the first
-            // track.
-            if (tracks[1]->codec_id() != "pointcloud2")
-            {
-                std::cerr << "Track #1 has wrong codec type " <<
-                    tracks[1]->codec_id() << '\n';
-                return 1;
-            }
-
-            bpt::ptime pb_start(bpt::microsec_clock::local_time());
-
-            // Now we can start reading the clusters. Get an iterator to the clusters
-            // in the segment.
-            // In this case, we are using a file-based cluster implementation, which
-            // reads blocks from the file on demand. This is usually a better
-            // option tham the memory-based cluster when the size of the stored
-            // data is large.
-            for (tide::Segment::FileBlockIterator block(segment.blocks_begin_file(stream));
-                    block != segment.blocks_end_file(stream); ++block)
-            {
-                bpt::time_duration blk_offset(bpt::microseconds((
-                        (block.cluster()->timecode() + block->timecode()) *
-                        segment.info.timecode_scale() / 1000)));
-                bpt::time_duration played_time(bpt::microsec_clock::local_time() -
-                        pb_start);
-                // If the current playback time is ahead of this block, skip it
-                if (played_time > blk_offset)
-                {
-                    std::cerr << "Skipping block at " << blk_offset <<
-                        " because current playback time is " << played_time << '\n';
-                    continue;
-                }
-                // Some blocks may actually contain multiple frames in a lace.
-                // In this case, we are reading blocks that do not use lacing,
-                // so there is only one frame per block. This is the general
-                // case; lacing is typically only used when the frame size is
-                // very small to reduce overhead.
-                tide::BlockElement::FramePtr frame_data(*block->begin());
-                // Copy the frame data into a serialised cloud structure
-                pcl::PCLPointCloud2 blob;
-                blob.height = 480;
-                blob.width = 640;
-                pcl::PCLPointField ptype;
-                ptype.name = "x";
-                ptype.offset = 0;
-                ptype.datatype = 7;
-                ptype.count = 1;
-                blob.fields.push_back(ptype);
-                ptype.name = "y";
-                ptype.offset = 4;
-                ptype.datatype = 7;
-                ptype.count = 1;
-                blob.fields.push_back(ptype);
-                ptype.name = "z";
-                ptype.offset = 8;
-                ptype.datatype = 7;
-                ptype.count = 1;
-                blob.fields.push_back(ptype);
-                blob.is_bigendian = false;
-                blob.point_step = 16;
-                blob.row_step = 10240;
-                blob.is_dense = false;
-                blob.data.assign(frame_data->begin(), frame_data->end());
-                pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
-                pcl::fromPCLPointCloud2(blob, *cloud);
-                // Sleep until the block's display time. The played_time is
-                // updated to account for the time spent preparing the data.
-                played_time = bpt::microsec_clock::local_time() - pb_start;
-                bpt::time_duration sleep_time(blk_offset - played_time);
-                std::cerr << "Will sleep " << sleep_time << " until displaying block\n";
-                std::this_thread::sleep_for(sleep_time);
-                viewer_.showCloud(cloud);
-                //viewer_.removePointCloud("1");
-                //viewer_.addPointCloud(cloud, "1");
-                //viewer_.spinOnce();
-                //if (viewer_.wasStopped())
-                //{
-                    //break;
-                //}
-            }
-
-            return 0;
-        }
-
-    private:
-        std::string filename_;
-        //pcl::visualization::PCLVisualizer viewer_;
-        pcl::visualization::CloudViewer viewer_;
-};
-
-
-int main(int argc, char** argv)
-{
-    std::string filename;
-    if (pcl::console::parse_argument(argc, argv, "-f", filename) < 0)
-    {
-        std::cerr << "Usage: " << argv[0] << " -f filename [-p] [-t title]\n";
-        return 1;
-    }
-    std::string title("PCL 3D video");
-    pcl::console::parse_argument(argc, argv, "-t", title);
-    if (pcl::console::find_switch(argc, argv, "-p"))
-    {
-        Player player(filename);
-        return player.Run();
-    }
-    else
-    {
-        Recorder recorder(filename, title);
-        return recorder.Run();
-    }
-}
-
diff --git a/tools/ply2obj.cpp b/tools/ply2obj.cpp
new file mode 100644 (file)
index 0000000..df1e409
--- /dev/null
@@ -0,0 +1,454 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2007-2012, Ares Lagae
+ *  Copyright (c) 2012, 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$
+ *
+ */
+
+#include <pcl/io/ply/ply_parser.h>
+
+#include <cstdlib>
+#include <cstring>
+#include <fstream>
+#include <iostream>
+#include <tuple>
+
+/** \class ply_to_obj_converter
+  * Convert a PLY file, optionally meshed to an OBJ file.
+  * The following PLY elements and properties are supported.
+  *  element vertex
+  *    property float32 x
+  *    property float32 y
+  *    property float32 z
+  *  element face
+  *    property list uint8 int32 vertex_indices.
+  *
+  * \author Ares Lagae
+  * \ingroup io
+  */ 
+class ply_to_obj_converter
+{
+  public:
+    using flags_type = int;
+    enum { triangulate = 1 << 0 };
+
+    ply_to_obj_converter (flags_type flags = 0);
+
+    bool 
+    convert (std::istream& istream, const std::string& istream_filename, std::ostream& ostream, const std::string& ostream_filename);
+
+  private:
+
+    void
+    info_callback (const std::string& filename, std::size_t line_number, const std::string& message);
+
+    void
+    warning_callback (const std::string& filename, std::size_t line_number, const std::string& message);
+
+    void
+    error_callback (const std::string& filename, std::size_t line_number, const std::string& message);
+
+    std::tuple<std::function<void ()>, std::function<void ()> > 
+    element_definition_callback (const std::string& element_name, std::size_t count);
+
+    template <typename ScalarType> std::function<void (ScalarType)> 
+    scalar_property_definition_callback (const std::string& element_name, const std::string& property_name);
+
+    template <typename SizeType, typename ScalarType> std::tuple<std::function<void (SizeType)>, 
+                                                                      std::function<void (ScalarType)>, 
+                                                                      std::function<void ()> > 
+    list_property_definition_callback (const std::string& element_name, const std::string& property_name);
+
+    void
+    vertex_begin ();
+
+    void
+    vertex_x (pcl::io::ply::float32 x);
+
+    void
+    vertex_y (pcl::io::ply::float32 y);
+
+    void
+    vertex_z (pcl::io::ply::float32 z);
+
+    void
+    vertex_end ();
+
+    void
+    face_begin ();
+
+    void
+    face_vertex_indices_begin (pcl::io::ply::uint8 size);
+
+    void
+    face_vertex_indices_element (pcl::io::ply::int32 vertex_index);
+
+    void
+    face_vertex_indices_end ();
+
+    void
+    face_end ();
+
+    flags_type flags_{0};
+    std::ostream* ostream_{};
+    double vertex_x_{0.0}, vertex_y_{0.0}, vertex_z_{0.0};
+    std::size_t face_vertex_indices_element_index_{0}, face_vertex_indices_first_element_{0}, face_vertex_indices_previous_element_{0};
+};
+
+ply_to_obj_converter::ply_to_obj_converter (flags_type flags)
+  : flags_ (flags)
+{
+}
+
+void 
+ply_to_obj_converter::info_callback (const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ":" << line_number << ": " << "info: " << message << std::endl;
+}
+
+void 
+ply_to_obj_converter::warning_callback (const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ":" << line_number << ": " << "warning: " << message << std::endl;
+}
+
+void 
+ply_to_obj_converter::error_callback (const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ":" << line_number << ": " << "error: " << message << std::endl;
+}
+
+std::tuple<std::function<void ()>, std::function<void ()> > 
+ply_to_obj_converter::element_definition_callback (const std::string& element_name, std::size_t)
+{
+  if (element_name == "vertex") 
+  {
+    return {[this] { vertex_begin(); }, [this] { vertex_end(); }};
+  }
+  if (element_name == "face") 
+  {
+    return {[this] { face_begin(); }, [this] { face_end(); }};
+  }
+  return {};
+}
+
+template <> std::function<void (pcl::io::ply::float32)> 
+ply_to_obj_converter::scalar_property_definition_callback (const std::string& element_name, const std::string& property_name)
+{
+  if (element_name == "vertex") {
+    if (property_name == "x") {
+      return [this] (pcl::io::ply::float32 x) { vertex_x (x); };
+    }
+    if (property_name == "y") {
+      return [this] (pcl::io::ply::float32 y) { vertex_y (y); };
+    }
+    if (property_name == "z") {
+      return [this] (pcl::io::ply::float32 z) { vertex_z (z); };
+    }
+  }
+  return {};
+}
+
+template <> std::tuple<std::function<void (pcl::io::ply::uint8)>, std::function<void (pcl::io::ply::int32)>, std::function<void ()> > 
+ply_to_obj_converter::list_property_definition_callback (const std::string& element_name, const std::string& property_name)
+{
+  if ((element_name == "face") && (property_name == "vertex_indices")) {
+    return {[this](pcl::io::ply::uint8 p) { face_vertex_indices_begin(p); },
+            [this](pcl::io::ply::int32 vertex_index) {
+              face_vertex_indices_element(vertex_index);
+            },
+            [this] { face_vertex_indices_end(); }};
+  }
+  return {};
+}
+
+void 
+ply_to_obj_converter::vertex_begin ()
+{
+}
+
+void 
+ply_to_obj_converter::vertex_x (pcl::io::ply::float32 x)
+{
+  vertex_x_ = x;
+}
+
+void 
+ply_to_obj_converter::vertex_y (pcl::io::ply::float32 y)
+{
+  vertex_y_ = y;
+}
+
+void 
+ply_to_obj_converter::vertex_z (pcl::io::ply::float32 z)
+{
+  vertex_z_ = z;
+}
+
+void 
+ply_to_obj_converter::vertex_end ()
+{
+  (*ostream_) << "v " << vertex_x_ << " " << vertex_y_ << " " << vertex_z_ << "\n";
+}
+
+void 
+ply_to_obj_converter::face_begin ()
+{
+  if (!(flags_ & triangulate)) {
+    (*ostream_) << "f";
+  }
+}
+
+void 
+ply_to_obj_converter::face_vertex_indices_begin (pcl::io::ply::uint8)
+{
+  face_vertex_indices_element_index_ = 0;
+}
+
+void 
+ply_to_obj_converter::face_vertex_indices_element (pcl::io::ply::int32 vertex_index)
+{
+  if (flags_ & triangulate) {
+    if (face_vertex_indices_element_index_ == 0) {
+      face_vertex_indices_first_element_ = vertex_index;
+    }
+    else if (face_vertex_indices_element_index_ == 1) {
+      face_vertex_indices_previous_element_ = vertex_index;
+    }
+    else {
+      (*ostream_) << "f " << (face_vertex_indices_first_element_ + 1) << " " << (face_vertex_indices_previous_element_ + 1) << " " << (vertex_index + 1) << "\n";
+      face_vertex_indices_previous_element_ = vertex_index;
+    }
+    ++face_vertex_indices_element_index_;
+  }
+  else {
+    (*ostream_) << " " << (vertex_index + 1);
+  }
+}
+
+void 
+ply_to_obj_converter::face_vertex_indices_end ()
+{
+  if (!(flags_ & triangulate)) {
+    (*ostream_) << "\n";
+  }
+}
+
+void 
+ply_to_obj_converter::face_end ()
+{
+}
+
+bool 
+ply_to_obj_converter::convert (std::istream&, const std::string& istream_filename, std::ostream& ostream, const std::string&)
+{
+  pcl::io::ply::ply_parser ply_parser;
+
+  ply_parser.info_callback ([&, this] (std::size_t line_number, const std::string& message) { info_callback (istream_filename, line_number, message); });
+  ply_parser.warning_callback ([&, this] (std::size_t line_number, const std::string& message) { warning_callback (istream_filename, line_number, message); });
+  ply_parser.error_callback ([&, this] (std::size_t line_number, const std::string& message) { error_callback (istream_filename, line_number, message); });
+
+  ply_parser.element_definition_callback ([this] (const std::string& element_name, std::size_t count) { return element_definition_callback (element_name, count); });
+
+  pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
+  pcl::io::ply::ply_parser::at<pcl::io::ply::float32> (scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
+  {
+    return scalar_property_definition_callback<pcl::io::ply::float32> (element_name, property_name);
+  };
+  ply_parser.scalar_property_definition_callbacks (scalar_property_definition_callbacks);
+
+  pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int32> (list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
+  {
+    return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32> (element_name, property_name);
+  };
+  ply_parser.list_property_definition_callbacks (list_property_definition_callbacks);
+
+  ostream_ = &ostream;
+
+  return ply_parser.parse (istream_filename);
+}
+
+int main (int argc, char* argv[])
+{
+  ply_to_obj_converter::flags_type ply_to_obj_converter_flags = 0;
+
+  int argi;
+  for (argi = 1; argi < argc; ++argi) {
+
+    if (argv[argi][0] != '-') {
+      break;
+    }
+    if (argv[argi][1] == 0) {
+      ++argi;
+      break;
+    }
+    char short_opt, *long_opt, *opt_arg;
+    if (argv[argi][1] != '-') {
+      short_opt = argv[argi][1];
+      opt_arg = &argv[argi][2];
+      long_opt = &argv[argi][2];
+      while (*long_opt != '\0') {
+        ++long_opt;
+      }
+    }
+    else {
+      short_opt = 0;
+      long_opt = &argv[argi][2];
+      opt_arg = long_opt;
+      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
+        ++opt_arg;
+      }
+      if (*opt_arg == '=') {
+        *opt_arg++ = '\0';
+      }
+    }
+
+    if ((short_opt == 'h') || (std::strcmp (long_opt, "help") == 0)) {
+      std::cout << "Usage: ply2obj [OPTION] [[INFILE] OUTFILE]\n";
+      std::cout << "Convert a PLY file to an OBJ file.\n";
+      std::cout << "\n";
+      std::cout << "  -h, --help       display this help and exit\n";
+      std::cout << "  -v, --version    output version information and exit\n";
+      std::cout << "  -f, --flag=FLAG  set flag\n";
+      std::cout << "\n";
+      std::cout << "FLAG may be one of the following: triangulate.\n";
+      std::cout << "\n";
+      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
+      std::cout << "\n";
+      std::cout << "The following PLY elements and properties are supported.\n";
+      std::cout << "  element vertex\n";
+      std::cout << "    property float32 x\n";
+      std::cout << "    property float32 y\n";
+      std::cout << "    property float32 z\n";
+      std::cout << "  element face\n";
+      std::cout << "    property list uint8 int32 vertex_indices.\n";
+      std::cout << "\n";
+      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
+      return EXIT_SUCCESS;
+    }
+
+    if ((short_opt == 'v') || (std::strcmp (long_opt, "version") == 0)) {
+      std::cout << "ply2obj \n";
+      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
+      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
+      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
+      std::cout << " All rights reserved.\n";
+      std::cout << " Redistribution and use in source and binary forms, with or without\n";
+      std::cout << " modification, are permitted provided that the following conditions\n";
+      std::cout << " are met:\n";
+      std::cout << "  * Redistributions of source code must retain the above copyright\n";
+      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
+      std::cout << "  * Redistributions in binary form must reproduce the above\n";
+      std::cout << "    copyright notice, this list of conditions and the following\n";
+      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
+      std::cout << "    with the distribution.\n";
+      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
+      std::cout << "    contributors may be used to endorse or promote products derived\n";
+      std::cout << "    from this software without specific prior written permission.\n";
+      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
+      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
+      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
+      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
+      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
+      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
+      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
+      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
+      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
+      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
+      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
+      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
+      return EXIT_SUCCESS;
+    }
+
+    if ((short_opt == 'f') || (std::strcmp (long_opt, "flag") == 0)) {
+      if (strcmp (opt_arg, "triangulate") == 0) {
+        ply_to_obj_converter_flags |= ply_to_obj_converter::triangulate;
+      }
+      else {
+        std::cerr << "ply2obj : " << "invalid option `" << argv[argi] << "'" << "\n";
+        std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+        return EXIT_FAILURE;
+      }
+    }
+
+    else {
+      std::cerr << "ply2obj: " << "invalid option `" << argv[argi] << "'" << "\n";
+      std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+      return EXIT_FAILURE;
+    }
+  }
+
+  int parc = argc - argi;
+  char** parv = argv + argi;
+  if (parc > 2) {
+    std::cerr << "ply2obj: " << "too many parameters" << "\n";
+    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+    return EXIT_FAILURE;
+  }
+
+  std::ifstream ifstream;
+  const char* istream_filename = "";
+  if (parc > 0) {
+    istream_filename = parv[0];
+    if (std::strcmp (istream_filename, "-") != 0) {
+      ifstream.open (istream_filename);
+      if (!ifstream.is_open ()) {
+        std::cerr << "ply2obj: " << istream_filename << ": " << "no such file or directory" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::ofstream ofstream;
+  const char* ostream_filename = "";
+  if (parc > 1) {
+    ostream_filename = parv[1];
+    if (std::strcmp (ostream_filename, "-") != 0) {
+      ofstream.open (ostream_filename);
+      if (!ofstream.is_open ()) {
+        std::cerr << "ply2obj: " << ostream_filename << ": " << "could not open file" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::istream& istream = ifstream.is_open () ? ifstream : std::cin;
+  std::ostream& ostream = ofstream.is_open () ? ofstream : std::cout;
+
+  class ply_to_obj_converter ply_to_obj_converter (ply_to_obj_converter_flags);
+  return ply_to_obj_converter.convert (istream, istream_filename, ostream, ostream_filename);
+}
diff --git a/tools/ply2ply.cpp b/tools/ply2ply.cpp
new file mode 100644 (file)
index 0000000..e749f4b
--- /dev/null
@@ -0,0 +1,552 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2007-2012, Ares Lagae
+ *  Copyright (c) 2012, 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$
+ *
+ */
+
+#include <pcl/io/ply/ply_parser.h>
+
+#include <cstdlib>
+#include <cstring>
+#include <fstream>
+#include <iostream>
+#include <tuple>
+
+/** \class ply_to_ply_converter
+  * Converts a PLY file with format FORMAT_IN to PLY file with format FORMAT_OUT.
+  * Format may be one of the following: ascii, binary, binary_big_endian, binary_little_endian.
+  * If no format is given, the format of input is kept.
+  *
+  * \author Ares Lagae
+  * \ingroup io
+  */
+class ply_to_ply_converter
+{
+  public:
+    using format_type = int;
+    enum format
+    {
+      same_format,
+      ascii_format,
+      binary_format,
+      binary_big_endian_format,
+      binary_little_endian_format
+    };
+
+    ply_to_ply_converter(format_type format) : format_(format) {}
+
+    bool 
+    convert (const std::string &filename, std::istream& istream, std::ostream& ostream);
+
+  private:
+    void
+    info_callback(const std::string& filename, std::size_t line_number, const std::string& message);
+    
+    void
+    warning_callback(const std::string& filename, std::size_t line_number, const std::string& message);
+    
+    void
+    error_callback(const std::string& filename, std::size_t line_number, const std::string& message);
+    
+    void
+    magic_callback();
+    
+    void
+    format_callback(pcl::io::ply::format_type format, const std::string& version);
+    
+    void
+    element_begin_callback();
+    
+    void
+    element_end_callback();
+
+    std::tuple<std::function<void()>, std::function<void()> > 
+    element_definition_callback(const std::string& element_name, std::size_t count);
+
+    template <typename ScalarType> void
+    scalar_property_callback(ScalarType scalar);
+
+    template <typename ScalarType> std::function<void (ScalarType)> 
+    scalar_property_definition_callback(const std::string& element_name, const std::string& property_name);
+
+    template <typename SizeType, typename ScalarType> void
+    list_property_begin_callback(SizeType size);
+
+    template <typename SizeType, typename ScalarType> void
+    list_property_element_callback(ScalarType scalar);
+
+    template <typename SizeType, typename ScalarType> void
+    list_property_end_callback();
+
+    template <typename SizeType, typename ScalarType> std::tuple<std::function<void (SizeType)>, 
+                                                                      std::function<void (ScalarType)>, 
+                                                                      std::function<void ()> > 
+    list_property_definition_callback(const std::string& element_name, const std::string& property_name);
+    
+    void
+    comment_callback(const std::string& comment);
+    
+    void
+    obj_info_callback(const std::string& obj_info);
+
+    bool 
+    end_header_callback();
+
+    format_type format_;
+    pcl::io::ply::format_type input_format_{}, output_format_{};
+    bool bol_{false};
+    std::ostream* ostream_{};
+};
+
+void
+ply_to_ply_converter::info_callback(const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ": " << line_number << ": " << "info: " << message << std::endl;
+}
+
+void
+ply_to_ply_converter::warning_callback(const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ": " << line_number << ": " << "warning: " << message << std::endl;
+}
+
+void
+ply_to_ply_converter::error_callback(const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ": " << line_number << ": " << "error: " << message << std::endl;
+}
+
+void
+ply_to_ply_converter::magic_callback()
+{
+  (*ostream_) << "ply" << "\n";
+}
+
+void
+ply_to_ply_converter::format_callback(pcl::io::ply::format_type format, const std::string& version)
+{
+  input_format_ = format;
+
+  switch (format_) {
+    case same_format:
+      output_format_ = input_format_;
+      break;
+    case ascii_format:
+      output_format_ = pcl::io::ply::ascii_format;
+      break;
+    case binary_format:
+      output_format_ = pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order ? pcl::io::ply::binary_little_endian_format : pcl::io::ply::binary_big_endian_format;
+      break;
+    case binary_big_endian_format:
+      output_format_ = pcl::io::ply::binary_big_endian_format;
+      break;
+    case binary_little_endian_format:
+      output_format_ = pcl::io::ply::binary_little_endian_format;
+      break;
+  };
+
+  (*ostream_) << "format ";
+  switch (output_format_) {
+    case pcl::io::ply::ascii_format:
+      (*ostream_) << "ascii";
+      break;
+    case pcl::io::ply::binary_little_endian_format:
+      (*ostream_) << "binary_little_endian";
+      break;
+    case pcl::io::ply::binary_big_endian_format:
+      (*ostream_) << "binary_big_endian";
+      break;
+  }
+  (*ostream_) << " " << version << "\n";
+}
+
+void
+ply_to_ply_converter::element_begin_callback()
+{
+  if (output_format_ == pcl::io::ply::ascii_format) {
+    bol_ = true;
+  }
+}
+
+void
+ply_to_ply_converter::element_end_callback()
+{
+  if (output_format_ == pcl::io::ply::ascii_format) {
+    (*ostream_) << "\n";
+  }
+}
+
+std::tuple<std::function<void()>, std::function<void()> > ply_to_ply_converter::element_definition_callback(const std::string& element_name, std::size_t count)
+{
+  (*ostream_) << "element " << element_name << " " << count << "\n";
+  return {[this] { element_begin_callback(); }, [this] { element_end_callback(); }};
+}
+
+template <typename ScalarType>
+void
+ply_to_ply_converter::scalar_property_callback(ScalarType scalar)
+{
+  if (output_format_ == pcl::io::ply::ascii_format) {
+    using namespace pcl::io::ply::io_operators;
+    if (bol_) {
+      bol_ = false;
+      (*ostream_) << scalar;
+    }
+    else {
+      (*ostream_) << " " << scalar;
+    }
+  }
+  else {
+    if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format))
+      || ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format))) {
+      pcl::io::ply::swap_byte_order(scalar);
+    }
+    ostream_->write(reinterpret_cast<char*>(&scalar), sizeof(scalar));
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename ScalarType> std::function<void (ScalarType)> 
+ply_to_ply_converter::scalar_property_definition_callback (const std::string&, const std::string& property_name)
+{
+  (*ostream_) << "property " << pcl::io::ply::type_traits<ScalarType>::old_name() << " " << property_name << "\n";
+  return [this] (ScalarType scalar) { scalar_property_callback<ScalarType> (scalar); };
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename SizeType, typename ScalarType> void
+ply_to_ply_converter::list_property_begin_callback (SizeType size)
+{
+  if (output_format_ == pcl::io::ply::ascii_format) 
+  {
+    using namespace pcl::io::ply::io_operators;
+    if (bol_) 
+    {
+      bol_ = false;
+      (*ostream_) << size;
+    }
+    else 
+      (*ostream_) << " " << size;
+  }
+  else 
+  {
+    if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format))
+      || ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format))) {
+      pcl::io::ply::swap_byte_order(size);
+    }
+    ostream_->write(reinterpret_cast<char*>(&size), sizeof(size));
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename SizeType, typename ScalarType> void
+ply_to_ply_converter::list_property_element_callback (ScalarType scalar)
+{
+  if (output_format_ == pcl::io::ply::ascii_format) 
+  {
+    using namespace pcl::io::ply::io_operators;
+    (*ostream_) << " " << scalar;
+  }
+  else 
+  {
+    if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format)) || 
+        ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format)))
+      pcl::io::ply::swap_byte_order(scalar);
+
+    ostream_->write(reinterpret_cast<char*>(&scalar), sizeof(scalar));
+  }
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename SizeType, typename ScalarType> void
+ply_to_ply_converter::list_property_end_callback() {}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+template <typename SizeType, typename ScalarType> std::tuple<std::function<void (SizeType)>, 
+                                                                  std::function<void (ScalarType)>, 
+                                                                  std::function<void ()> > 
+ply_to_ply_converter::list_property_definition_callback (const std::string&, const std::string& property_name)
+{
+  (*ostream_) << "property list " << pcl::io::ply::type_traits<SizeType>::old_name() << " " << pcl::io::ply::type_traits<ScalarType>::old_name() << " " << property_name << "\n";
+  return std::tuple<std::function<void (SizeType)>, std::function<void (ScalarType)>, std::function<void ()> >(
+    [this] (SizeType size) { list_property_begin_callback<SizeType, ScalarType> (size); },
+    [this] (ScalarType scalar) { list_property_element_callback<SizeType, ScalarType> (scalar); },
+    [this] { list_property_end_callback<SizeType, ScalarType> (); }
+  );
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+void
+ply_to_ply_converter::comment_callback(const std::string& comment)
+{
+  (*ostream_) << comment << "\n";
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+void
+ply_to_ply_converter::obj_info_callback(const std::string& obj_info)
+{
+  (*ostream_) << obj_info << "\n";
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+bool 
+ply_to_ply_converter::end_header_callback()
+{
+  (*ostream_) << "end_header" << "\n";
+  return true;
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+bool 
+ply_to_ply_converter::convert (const std::string &ifilename, std::istream&, std::ostream& ostream)
+{
+  pcl::io::ply::ply_parser ply_parser;
+
+  ply_parser.info_callback ([&, this] (std::size_t line_number, const std::string& message) { info_callback (ifilename, line_number, message); });
+  ply_parser.warning_callback ([&, this] (std::size_t line_number, const std::string& message) { warning_callback (ifilename, line_number, message); });
+  ply_parser.error_callback ([&, this] (std::size_t line_number, const std::string& message) { error_callback (ifilename, line_number, message); });
+
+  ply_parser.magic_callback ([this] { magic_callback (); });
+  ply_parser.format_callback ([this] (pcl::io::ply::format_type format, const std::string& version) { format_callback (format, version); });
+  ply_parser.element_definition_callback ([this] (const std::string& element_name, std::size_t count) { return element_definition_callback (element_name, count); });
+
+  pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
+
+  pcl::io::ply::ply_parser::at<pcl::io::ply::int8>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::int8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::int16>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::int16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::int32>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::int32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::uint8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::uint16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::uint32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::float32>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::float32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::float64>(scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return scalar_property_definition_callback<pcl::io::ply::float64> (element_name, property_name); };
+
+  ply_parser.scalar_property_definition_callbacks(scalar_property_definition_callbacks);
+
+  pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
+
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::uint8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::uint16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::uint32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::float32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::float32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::float64>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::float64> (element_name, property_name); };
+
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::int8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::int16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::int32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::uint8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::uint16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::uint32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::float32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::float32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint16, pcl::io::ply::float64>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::float64> (element_name, property_name); };
+
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::int8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::int16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::int32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::uint8>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint8> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::uint16>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint16> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::uint32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::float32>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::float32> (element_name, property_name); };
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint32, pcl::io::ply::float64>(list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name) { return list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::float64> (element_name, property_name); };
+
+  ply_parser.list_property_definition_callbacks(list_property_definition_callbacks);
+
+  ply_parser.comment_callback([this] (const std::string& comment) { comment_callback (comment); });
+  ply_parser.obj_info_callback([this] (const std::string& obj_info) { obj_info_callback (obj_info); });
+  ply_parser.end_header_callback( [this] { return end_header_callback (); });
+
+  ostream_ = &ostream;
+  return ply_parser.parse(ifilename);
+}
+
+//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+int 
+main(int argc, char* argv[])
+{
+  ply_to_ply_converter::format_type ply_to_ply_converter_format = ply_to_ply_converter::same_format;
+
+  int argi;
+  for (argi = 1; argi < argc; ++argi) {
+
+    if (argv[argi][0] != '-') {
+      break;
+    }
+    if (argv[argi][1] == 0) {
+      ++argi;
+      break;
+    }
+    char short_opt, *long_opt, *opt_arg;
+    if (argv[argi][1] != '-') {
+      short_opt = argv[argi][1];
+      opt_arg = &argv[argi][2];
+      long_opt = &argv[argi][2];
+      while (*long_opt != '\0') {
+        ++long_opt;
+      }
+    }
+    else {
+      short_opt = 0;
+      long_opt = &argv[argi][2];
+      opt_arg = long_opt;
+      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
+        ++opt_arg;
+      }
+      if (*opt_arg == '=') {
+        *opt_arg++ = '\0';
+      }
+    }
+
+    if ((short_opt == 'h') || (std::strcmp(long_opt, "help") == 0)) {
+      std::cout << "Usage: ply2ply [OPTION] [[INFILE] OUTFILE]\n";
+      std::cout << "Parse an PLY file.\n";
+      std::cout << "\n";
+      std::cout << "  -h, --help           display this help and exit\n";
+      std::cout << "  -v, --version        output version information and exit\n";
+      std::cout << "  -f, --format=FORMAT  set format\n";
+      std::cout << "\n";
+      std::cout << "FORMAT may be one of the following: ascii, binary, binary_big_endian,\n";
+      std::cout << "binary_little_endian.\n";
+      std::cout << "If no format is given, the format of INFILE is kept.\n";
+      std::cout << "\n";
+      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
+      std::cout << "\n";
+      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
+      return EXIT_SUCCESS;
+    }
+
+    if ((short_opt == 'v') || (std::strcmp(long_opt, "version") == 0)) {
+      std::cout << "ply2ply\n";
+      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
+      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
+      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
+      std::cout << " All rights reserved.\n";
+      std::cout << " Redistribution and use in source and binary forms, with or without\n";
+      std::cout << " modification, are permitted provided that the following conditions\n";
+      std::cout << " are met:\n";
+      std::cout << "  * Redistributions of source code must retain the above copyright\n";
+      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
+      std::cout << "  * Redistributions in binary form must reproduce the above\n";
+      std::cout << "    copyright notice, this list of conditions and the following\n";
+      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
+      std::cout << "    with the distribution.\n";
+      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
+      std::cout << "    contributors may be used to endorse or promote products derived\n";
+      std::cout << "    from this software without specific prior written permission.\n";
+      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
+      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
+      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
+      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
+      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
+      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
+      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
+      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
+      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
+      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
+      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
+      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
+      return EXIT_SUCCESS;
+    }
+
+    if ((short_opt == 'f') || (std::strcmp(long_opt, "format") == 0)) {
+      if (strcmp(opt_arg, "ascii") == 0) {
+        ply_to_ply_converter_format = ply_to_ply_converter::ascii_format;
+      }
+      else if (strcmp(opt_arg, "binary") == 0) {
+        ply_to_ply_converter_format = ply_to_ply_converter::binary_format;
+      }
+      else if (strcmp(opt_arg, "binary_little_endian") == 0) {
+        ply_to_ply_converter_format = ply_to_ply_converter::binary_little_endian_format;
+      }
+      else if (strcmp(opt_arg, "binary_big_endian") == 0) {
+        ply_to_ply_converter_format = ply_to_ply_converter::binary_big_endian_format;
+      }
+      else {
+        std::cerr << "ply2ply: " << "invalid option `" << argv[argi] << "'" << "\n";
+        std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+        return EXIT_FAILURE;
+      }
+    }
+
+    else {
+      std::cerr << "ply2ply: " << "invalid option `" << argv[argi] << "'" << "\n";
+      std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+      return EXIT_FAILURE;
+    }
+  }
+
+  int parc = argc - argi;
+  char** parv = argv + argi;
+  if (parc > 2) {
+    std::cerr << "ply2ply: " << "too many parameters" << "\n";
+    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+    return EXIT_FAILURE;
+  }
+
+  std::ifstream ifstream;
+  const char* ifilename = "";
+  if (parc > 0) {
+    ifilename = parv[0];
+    if (std::strcmp(ifilename, "-") != 0) {
+      ifstream.open(ifilename);
+      if (!ifstream.is_open()) {
+        std::cerr << "ply2ply: " << ifilename << ": " << "no such file or directory" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::ofstream ofstream;
+  if (parc > 1) {
+    const char* ofilename = parv[1];
+    if (std::strcmp(ofilename, "-") != 0) {
+      ofstream.open(ofilename);
+      if (!ofstream.is_open()) {
+        std::cerr << "ply2ply: " << ofilename << ": " << "could not open file" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::istream& istream = ifstream.is_open() ? ifstream : std::cin;
+  std::ostream& ostream = ofstream.is_open() ? ofstream : std::cout;
+
+  class ply_to_ply_converter ply_to_ply_converter(ply_to_ply_converter_format);
+  return ply_to_ply_converter.convert (ifilename, istream, ostream);
+}
diff --git a/tools/ply2raw.cpp b/tools/ply2raw.cpp
new file mode 100644 (file)
index 0000000..1fd1f83
--- /dev/null
@@ -0,0 +1,433 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2007-2012, Ares Lagae
+ *  Copyright (c) 2012, 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$
+ *
+ */
+
+#include <pcl/io/ply/ply_parser.h>
+
+#include <cstdlib>
+#include <cstring>
+#include <fstream>
+#include <iostream>
+#include <tuple>
+
+/** Class ply_to_raw_converter converts a PLY file to a povray (www.povray.org) RAW file
+  * The following PLY elements and properties are supported.
+  *   element vertex
+  *     property float32 x
+  *     property float32 y
+  *     property float32 z
+  *   element face
+  *     property list uint8 int32 vertex_indices.
+  * 
+  * \author Ares Lagae
+  * \ingroup io
+  */
+
+class ply_to_raw_converter
+{
+  public:
+  ply_to_raw_converter() = default;
+
+  ply_to_raw_converter (const ply_to_raw_converter &f)
+    {
+      *this = f;
+    }
+
+    ply_to_raw_converter&
+    operator = (const ply_to_raw_converter &f)
+    {
+      ostream_ = f.ostream_;
+      vertex_x_ = f.vertex_x_;
+      vertex_y_ = f.vertex_y_;
+      vertex_z_ = f.vertex_z_;
+      face_vertex_indices_element_index_ = f.face_vertex_indices_element_index_;
+      face_vertex_indices_first_element_ = f.face_vertex_indices_first_element_;
+      face_vertex_indices_previous_element_ = f.face_vertex_indices_previous_element_;
+      return (*this);
+    }
+
+    bool 
+    convert (std::istream& istream, const std::string& istream_filename, std::ostream& ostream, const std::string& ostream_filename);
+
+  private:
+    void
+    info_callback (const std::string& filename, std::size_t line_number, const std::string& message);
+
+    void
+    warning_callback (const std::string& filename, std::size_t line_number, const std::string& message);
+
+    void
+    error_callback (const std::string& filename, std::size_t line_number, const std::string& message);
+
+    std::tuple<std::function<void ()>, std::function<void ()> > 
+    element_definition_callback (const std::string& element_name, std::size_t count);
+
+    template <typename ScalarType> std::function<void (ScalarType)> 
+    scalar_property_definition_callback (const std::string& element_name, const std::string& property_name);
+
+    template <typename SizeType, typename ScalarType>  std::tuple<std::function<void (SizeType)>, 
+                                                                       std::function<void (ScalarType)>, 
+                                                                       std::function<void ()> > 
+    list_property_definition_callback (const std::string& element_name, const std::string& property_name);
+
+    void
+    vertex_begin ();
+
+    void
+    vertex_x (pcl::io::ply::float32 x);
+
+    void
+    vertex_y (pcl::io::ply::float32 y);
+
+    void
+    vertex_z (pcl::io::ply::float32 z);
+
+    void
+    vertex_end ();
+
+    void
+    face_begin ();
+
+    void
+    face_vertex_indices_begin (pcl::io::ply::uint8 size);
+
+    void
+    face_vertex_indices_element (pcl::io::ply::int32 vertex_index);
+
+    void
+    face_vertex_indices_end ();
+
+    void
+    face_end ();
+
+    std::ostream* ostream_{};
+    pcl::io::ply::float32 vertex_x_{0.0f}, vertex_y_{0.0f}, vertex_z_{0.0f};
+    pcl::io::ply::int32 face_vertex_indices_element_index_{0}, face_vertex_indices_first_element_{0}, face_vertex_indices_previous_element_{0};
+    std::vector<std::tuple<pcl::io::ply::float32, pcl::io::ply::float32, pcl::io::ply::float32> > vertices_{};
+};
+
+void
+ply_to_raw_converter::info_callback (const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ":" << line_number << ": " << "info: " << message << std::endl;
+}
+
+void
+ply_to_raw_converter::warning_callback (const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ":" << line_number << ": " << "warning: " << message << std::endl;
+}
+
+void
+ply_to_raw_converter::error_callback (const std::string& filename, std::size_t line_number, const std::string& message)
+{
+  std::cerr << filename << ":" << line_number << ": " << "error: " << message << std::endl;
+}
+
+std::tuple<std::function<void ()>, std::function<void ()> > 
+ply_to_raw_converter::element_definition_callback (const std::string& element_name, std::size_t)
+{
+  if (element_name == "vertex") {
+    return {[this] { vertex_begin(); }, [this] { vertex_end(); }};
+  }
+  if (element_name == "face") {
+    return {[this] { face_begin(); }, [this] { face_end(); }};
+  }
+  return {};
+}
+
+template <> std::function<void (pcl::io::ply::float32)> 
+ply_to_raw_converter::scalar_property_definition_callback (const std::string& element_name, const std::string& property_name)
+{
+  if (element_name == "vertex") {
+    if (property_name == "x") {
+      return [this] (pcl::io::ply::float32 x) { vertex_x (x); };
+    }
+    if (property_name == "y") {
+      return [this] (pcl::io::ply::float32 y) { vertex_y (y); };
+    }
+    if (property_name == "z") {
+      return [this] (pcl::io::ply::float32 z) { vertex_z (z); };
+    }
+  }
+  return {};
+}
+
+template <> std::tuple<std::function<void (pcl::io::ply::uint8)>, 
+                            std::function<void (pcl::io::ply::int32)>, 
+                            std::function<void ()> > 
+ply_to_raw_converter::list_property_definition_callback (const std::string& element_name, const std::string& property_name)
+{
+  if ((element_name == "face") && (property_name == "vertex_indices")) 
+  {
+    return {[this](pcl::io::ply::uint8 p) { face_vertex_indices_begin(p); },
+            [this](pcl::io::ply::int32 vertex_index) {
+              face_vertex_indices_element(vertex_index);
+            },
+            [this] { face_vertex_indices_end(); }};
+  }
+  return {};
+}
+
+void
+ply_to_raw_converter::vertex_begin () {}
+
+void
+ply_to_raw_converter::vertex_x (pcl::io::ply::float32 x)
+{
+  vertex_x_ = x;
+}
+
+void
+ply_to_raw_converter::vertex_y (pcl::io::ply::float32 y)
+{
+  vertex_y_ = y;
+}
+
+void
+ply_to_raw_converter::vertex_z (pcl::io::ply::float32 z)
+{
+  vertex_z_ = z;
+}
+
+void
+ply_to_raw_converter::vertex_end ()
+{
+  vertices_.emplace_back(vertex_x_, vertex_y_, vertex_z_);
+}
+
+void
+ply_to_raw_converter::face_begin () {}
+
+void
+ply_to_raw_converter::face_vertex_indices_begin (pcl::io::ply::uint8)
+{
+  face_vertex_indices_element_index_ = 0;
+}
+
+void
+ply_to_raw_converter::face_vertex_indices_element (pcl::io::ply::int32 vertex_index)
+{
+  if (face_vertex_indices_element_index_ == 0) {
+    face_vertex_indices_first_element_ = vertex_index;
+  }
+  else if (face_vertex_indices_element_index_ == 1) {
+    face_vertex_indices_previous_element_ = vertex_index;
+  }
+  else {
+    (*ostream_) << std::get<0> (vertices_[   face_vertex_indices_first_element_])
+         << " " << std::get<1> (vertices_[   face_vertex_indices_first_element_])
+         << " " << std::get<2> (vertices_[   face_vertex_indices_first_element_])
+         << " " << std::get<0> (vertices_[face_vertex_indices_previous_element_])
+         << " " << std::get<1> (vertices_[face_vertex_indices_previous_element_])
+         << " " << std::get<2> (vertices_[face_vertex_indices_previous_element_])
+         << " " << std::get<0> (vertices_[                         vertex_index])
+         << " " << std::get<1> (vertices_[                         vertex_index])
+         << " " << std::get<2> (vertices_[                         vertex_index]) << "\n";
+    face_vertex_indices_previous_element_ = vertex_index;
+  }
+  ++face_vertex_indices_element_index_;
+}
+
+void
+ply_to_raw_converter::face_vertex_indices_end () {}
+
+void
+ply_to_raw_converter::face_end () {}
+
+bool 
+ply_to_raw_converter::convert (std::istream&, const std::string& istream_filename, std::ostream& ostream, const std::string&)
+{
+  pcl::io::ply::ply_parser ply_parser;
+
+  ply_parser.info_callback ([&, this] (std::size_t line_number, const std::string& message) { info_callback (istream_filename, line_number, message); });
+  ply_parser.warning_callback ([&, this] (std::size_t line_number, const std::string& message) { warning_callback (istream_filename, line_number, message); });
+  ply_parser.error_callback ([&, this] (std::size_t line_number, const std::string& message) { error_callback (istream_filename, line_number, message); });
+
+  ply_parser.element_definition_callback ([this] (const std::string& element_name, std::size_t count) { return element_definition_callback (element_name, count); });
+
+  pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
+  pcl::io::ply::ply_parser::at<pcl::io::ply::float32> (scalar_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
+  {
+    return scalar_property_definition_callback<pcl::io::ply::float32> (element_name, property_name);
+  };
+  ply_parser.scalar_property_definition_callbacks (scalar_property_definition_callbacks);
+
+  pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
+  pcl::io::ply::ply_parser::at<pcl::io::ply::uint8, pcl::io::ply::int32> (list_property_definition_callbacks) = [this] (const std::string& element_name, const std::string& property_name)
+  {
+    return list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32> (element_name, property_name);
+  };
+  ply_parser.list_property_definition_callbacks (list_property_definition_callbacks);
+
+  ostream_ = &ostream;
+
+  return ply_parser.parse (istream_filename);
+}
+
+int main (int argc, char* argv[])
+{
+  int argi;
+  for (argi = 1; argi < argc; ++argi) {
+
+    if (argv[argi][0] != '-') {
+      break;
+    }
+    if (argv[argi][1] == 0) {
+      ++argi;
+      break;
+    }
+    char short_opt, *long_opt;
+    if (argv[argi][1] != '-') {
+      short_opt = argv[argi][1];
+      long_opt = &argv[argi][2];
+      while (*long_opt != '\0') {
+        ++long_opt;
+      }
+    }
+    else {
+      short_opt = 0;
+      long_opt = &argv[argi][2];
+      char *opt_arg = long_opt;
+      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
+        ++opt_arg;
+      }
+      if (*opt_arg == '=') {
+        *opt_arg++ = '\0';
+      }
+    }
+
+    if ((short_opt == 'h') || (std::strcmp (long_opt, "help") == 0)) {
+      std::cout << "Usage: ply2raw [OPTION] [[INFILE] OUTFILE]\n";
+      std::cout << "Convert from PLY to POV-Ray RAW triangle format.\n";
+      std::cout << "\n";
+      std::cout << "  -h, --help       display this help and exit\n";
+      std::cout << "  -v, --version    output version information and exit\n";
+      std::cout << "\n";
+      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
+      std::cout << "\n";
+      std::cout << "The following PLY elements and properties are supported.\n";
+      std::cout << "  element vertex\n";
+      std::cout << "    property float32 x\n";
+      std::cout << "    property float32 y\n";
+      std::cout << "    property float32 z\n";
+      std::cout << "  element face\n";
+      std::cout << "    property list uint8 int32 vertex_indices.\n";
+      std::cout << "\n";
+      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
+      return EXIT_SUCCESS;
+    }
+
+    if ((short_opt == 'v') || (std::strcmp (long_opt, "version") == 0)) {
+      std::cout << "ply2raw \n";
+      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
+      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
+      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
+      std::cout << " All rights reserved.\n";
+      std::cout << " Redistribution and use in source and binary forms, with or without\n";
+      std::cout << " modification, are permitted provided that the following conditions\n";
+      std::cout << " are met:\n";
+      std::cout << "  * Redistributions of source code must retain the above copyright\n";
+      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
+      std::cout << "  * Redistributions in binary form must reproduce the above\n";
+      std::cout << "    copyright notice, this list of conditions and the following\n";
+      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
+      std::cout << "    with the distribution.\n";
+      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
+      std::cout << "    contributors may be used to endorse or promote products derived\n";
+      std::cout << "    from this software without specific prior written permission.\n";
+      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
+      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
+      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
+      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
+      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
+      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
+      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
+      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
+      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
+      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
+      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
+      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
+      return EXIT_SUCCESS;
+    }
+
+    std::cerr << "ply2raw: " << "invalid option `" << argv[argi] << "'" << "\n";
+    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+    return EXIT_FAILURE;
+  }
+
+  int parc = argc - argi;
+  char** parv = argv + argi;
+  if (parc > 2) {
+    std::cerr << "ply2raw: " << "too many parameters" << "\n";
+    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+    return EXIT_FAILURE;
+  }
+
+  std::ifstream ifstream;
+  const char* istream_filename = "";
+  if (parc > 0) {
+    istream_filename = parv[0];
+    if (std::strcmp (istream_filename, "-") != 0) {
+      ifstream.open (istream_filename);
+      if (!ifstream.is_open ()) {
+        std::cerr << "ply2raw: " << istream_filename << ": " << "no such file or directory" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::ofstream ofstream;
+  const char* ostream_filename = "";
+  if (parc > 1) {
+    ostream_filename = parv[1];
+    if (std::strcmp (ostream_filename, "-") != 0) {
+      ofstream.open (ostream_filename);
+      if (!ofstream.is_open ()) {
+        std::cerr << "ply2raw: " << ostream_filename << ": " << "could not open file" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::istream& istream = ifstream.is_open () ? ifstream : std::cin;
+  std::ostream& ostream = ofstream.is_open () ? ofstream : std::cout;
+
+  class ply_to_raw_converter ply_to_raw_converter;
+  return ply_to_raw_converter.convert (istream, istream_filename, ostream, ostream_filename);
+}
diff --git a/tools/plyheader.cpp b/tools/plyheader.cpp
new file mode 100644 (file)
index 0000000..d9907f9
--- /dev/null
@@ -0,0 +1,184 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ *  Point Cloud Library (PCL) - www.pointclouds.org
+ *  Copyright (c) 2007-2012, Ares Lagae
+ *  Copyright (c) 2012, 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$
+ *
+ */
+
+#include <fstream>
+#include <iostream>
+#include <cstring>
+#include <string>
+#include <cstdlib>
+
+/** \file plheader extracts and prints out the header of a PLY file
+  * 
+  * \author Ares Lagae
+  * \ingroup io
+  */
+int main (int argc, char* argv[])
+{
+  int argi;
+  for (argi = 1; argi < argc; ++argi) {
+
+    if (argv[argi][0] != '-') {
+      break;
+    }
+    if (argv[argi][1] == 0) {
+      ++argi;
+      break;
+    }
+    char short_opt, *long_opt;
+    if (argv[argi][1] != '-') {
+      short_opt = argv[argi][1];
+      long_opt = &argv[argi][2];
+      while (*long_opt != '\0') {
+        ++long_opt;
+      }
+    }
+    else {
+      short_opt = 0;
+      long_opt = &argv[argi][2];
+      char *opt_arg = long_opt;
+      while ((*opt_arg != '=') && (*opt_arg != '\0')) {
+        ++opt_arg;
+      }
+      if (*opt_arg == '=') {
+        *opt_arg++ = '\0';
+      }
+    }
+
+    if ((short_opt == 'h') || (strcmp (long_opt, "help") == 0)) {
+      std::cout << "Usage: plyheader [OPTION] [[INFILE] OUTFILE]\n";
+      std::cout << "Extract the header from a PLY file.\n";
+      std::cout << "\n";
+      std::cout << "  -h, --help       display this help and exit\n";
+      std::cout << "  -v, --version    output version information and exit\n";
+      std::cout << "\n";
+      std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
+      std::cout << "\n";
+      std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
+      return EXIT_SUCCESS;
+    }
+
+    if ((short_opt == 'v') || (strcmp (long_opt, "version") == 0)) {
+      std::cout << "plyheader \n";
+      std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
+      std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
+      std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
+      std::cout << " All rights reserved.\n";
+      std::cout << " Redistribution and use in source and binary forms, with or without\n";
+      std::cout << " modification, are permitted provided that the following conditions\n";
+      std::cout << " are met:\n";
+      std::cout << "  * Redistributions of source code must retain the above copyright\n";
+      std::cout << "    notice, this list of conditions and the following disclaimer.\n";
+      std::cout << "  * Redistributions in binary form must reproduce the above\n";
+      std::cout << "    copyright notice, this list of conditions and the following\n";
+      std::cout << "    disclaimer in the documentation and/or other materials provided\n";
+      std::cout << "    with the distribution.\n";
+      std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
+      std::cout << "    contributors may be used to endorse or promote products derived\n";
+      std::cout << "    from this software without specific prior written permission.\n";
+      std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
+      std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
+      std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
+      std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
+      std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
+      std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
+      std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
+      std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
+      std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
+      std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
+      std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
+      std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
+      return EXIT_SUCCESS;
+    }
+
+    std::cerr << "plyheader: " << "invalid option `" << argv[argi] << "'" << "\n";
+    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+    return EXIT_FAILURE;
+  }
+
+  int parc = argc - argi;
+  char** parv = argv + argi;
+  if (parc > 2) {
+    std::cerr << "plyheader: " << "too many parameters" << "\n";
+    std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
+    return EXIT_FAILURE;
+  }
+
+  std::ifstream ifstream;
+  if (parc > 0) {
+    const char* ifilename = parv[0];
+    if (strcmp (ifilename, "-") != 0) {
+      ifstream.open (ifilename);
+      if (!ifstream.is_open ()) {
+        std::cerr << "plyheader: " << ifilename << ": " << "no such file or directory" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::ofstream ofstream;
+  if (parc > 1) {
+    const char* ofilename = parv[1];
+    if (strcmp (ofilename, "-") != 0) {
+      ofstream.open (ofilename);
+      if (!ofstream.is_open ()) {
+        std::cerr << "plyheader: " << ofilename << ": " << "could not open file" << "\n";
+        return EXIT_FAILURE;
+      }
+    }
+  }
+
+  std::istream& istream = ifstream.is_open () ? ifstream : std::cin;
+  std::ostream& ostream = ofstream.is_open () ? ofstream : std::cout;
+
+  char magic[3];
+  istream.read (magic, 3);
+  if (!istream || (magic[0] != 'p') || (magic[1] != 'l') || (magic[2] != 'y')){
+    return EXIT_FAILURE;
+  }
+  istream.ignore (1);
+  ostream << magic[0] << magic[1] << magic[2] << "\n";
+  std::string line;
+  while (std::getline (istream, line)) {
+    ostream << line << "\n";
+    if (line == "end_header") {
+      break;
+    }
+  }
+  return istream ? EXIT_SUCCESS : EXIT_FAILURE;
+}
index 8a0bab0526a47c2d6484c210a1ceef9a20037861..943d5657c9da5b3a40c83c13be3b9a34b2de7a45 100644 (file)
@@ -304,7 +304,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
index 36f336a1d2fad8f3be61608d8a9f88cada6708fe..be5c50dbd8bf6e41fde49d81ec7509e0eefdf5e3 100644 (file)
@@ -57,8 +57,8 @@ printHelp (int, char **argv)
 {
   pcl::console::print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
   pcl::console::print_info ("  where options are:\n");
-  pcl::console::print_info ("                     -radius X = Radius of the spere to filter (default: ");
-  pcl::console::print_value ("%s", default_radius); pcl::console::print_info (")\n");
+  pcl::console::print_info ("                     -radius X = Radius of the sphere to filter (default: ");
+  pcl::console::print_value ("%f", default_radius); pcl::console::print_info (")\n");
   pcl::console::print_info ("                     -inside X = keep the points inside the [min, max] interval or not (default: ");
   pcl::console::print_value ("%d", default_inside); pcl::console::print_info (")\n");
   pcl::console::print_info ("                     -keep 0/1 = keep the points organized (1) or not (default: ");
@@ -132,7 +132,7 @@ batchProcess (const std::vector<std::string> &pcd_files, std::string &output_dir
 
     // Prepare output file name
     std::string filename = boost::filesystem::path(pcd_file).filename().string();
-    
+
     // Save into the second file
     const std::string filepath = output_dir + '/' + filename;
     saveCloud (filepath, output);
@@ -208,7 +208,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
index 38e2091549d595691d284d5d2f25ccd86db3647a..455546840554ee512ef53bb8ecaa9a60869b887c 100644 (file)
@@ -283,7 +283,7 @@ main (int argc, char** argv)
       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
       {
         // Only add PCD files
-        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
+        if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" )
         {
           pcd_files.push_back (itr->path ().string ());
           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
index 4c186acc0b86e31e91deeb5f655b7a9de3d85b93..0bee446cfdf5194bc6d6b23ea9af3065d83b93ea 100644 (file)
@@ -118,8 +118,8 @@ maskForegroundPoints (const PointCloudXYZRGBA::ConstPtr & input,
   }
 
   // Find the dominant plane between the specified near/far thresholds
-  const float distance_threshold = 0.02f;
-  const int max_iterations = 500;
+  constexpr float distance_threshold = 0.02f;
+  constexpr int max_iterations = 500;
   pcl::SACSegmentation<pcl::PointXYZRGBA> seg;
   seg.setOptimizeCoefficients (true);
   seg.setModelType (pcl::SACMODEL_PLANE);
index af3769a7b01ff20922c753235aed45f0d0e9d237..e7dcfd6b7aec759118c008d27ae79a85746d80c1 100644 (file)
@@ -60,8 +60,8 @@ printHelp (int, char **argv)
   print_info ("           -quat x,y,z,w             = rotation as quaternion\n");
   print_info ("           -axisangle ax,ay,az,theta = rotation in axis-angle form\n"); 
   print_info ("           -scale x,y,z              = scale each dimension with these values\n"); 
-  print_info ("           -matrix v1,v2,...,v8,v9   = a 3x3 affine transform\n");
-  print_info ("           -matrix v1,v2,...,v15,v16 = a 4x4 transformation matrix\n");
+  print_info ("           -matrix v1,v2,...,v8,v9   = a 3x3 affine transform in column-major order\n");
+  print_info ("           -matrix v1,v2,...,v15,v16 = a 4x4 transformation matrix in column-major order\n");
   print_info ("   Note: If a rotation is not specified, it will default to no rotation.\n");
   print_info ("         If redundant or conflicting transforms are specified, then:\n");
   print_info ("           -axisangle will override -quat\n");
index 1a9c6e06fb53e390d19d4a363dd871f97401686a..cdec686d155b04ae2ffb639045381c2e3dfb8a44 100644 (file)
@@ -84,7 +84,7 @@ loadTrainedFeatures (std::vector<FeatureT::Ptr> &out,
   for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it)
   {    
     if (!boost::filesystem::is_directory (it->status ()) &&
-        boost::filesystem::extension (it->path ()) == ".pcd")
+        it->path ().extension ().string () == ".pcd")
     {   
       const std::string path = it->path ().string ();
 
index 2d92fd41f240dd76b197b6b3e7e08b42578758bb..269552b16aa70e9271fe985d1705188cc64778fe 100644 (file)
@@ -129,7 +129,7 @@ saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
 
   PCDWriter w_pcd;
   PLYWriter w_ply;
-  std::string output_ext = boost::filesystem::extension (filename);
+  std::string output_ext = boost::filesystem::path (filename).extension ().string ();
   std::transform (output_ext.begin (), output_ext.end (), output_ext.begin (), ::tolower);
 
   if (output_ext == ".pcd")
index 775ccde3026993e756b7785e6b6bc8f55453f198..d339a88413d1a2c4a5812fa4f0073454747edacf 100644 (file)
@@ -64,7 +64,7 @@
 #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::extension, boost::filesystem::path
+#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::extension (file_name);
+  std::string extension = boost::filesystem::path (file_name).extension ().string ();
   if (extension == ".ply")
   {
     vtkPLYReader* reader = vtkPLYReader::New ();
@@ -255,7 +255,6 @@ main (int argc, char** argv)
   if (single_view)
     number_of_points = 1;
 
-  int sid = -1;
   for (int i = 0; i < number_of_points; i++)
   {
     // Clear cloud for next view scan
@@ -334,18 +333,13 @@ main (int argc, char** argv)
     // Sweep vertically
     for (double vert = vert_start; vert <= vert_end; vert += sp.vert_res)
     {
-      sid++;
-
       tr1->Identity ();
       tr1->RotateWXYZ (vert, right);
       tr1->InternalTransformPoint (viewray, temp_beam);
 
       // Sweep horizontally
-      int pid = -1;
       for (double hor = hor_start; hor <= hor_end; hor += sp.hor_res)
       {
-        pid ++;
-
         // Create a beam vector with (lat,long) angles (vert, hor) with the viewray
         tr2->Identity ();
         tr2->RotateWXYZ (hor, up);
index 48ee5de786eee159cd4fe8aef2f54017989b3dba..b2409585b95109c3ed5645dd39dde8b53989f67e 100644 (file)
@@ -43,6 +43,7 @@
 #include <pcl/console/print.h>
 #include <pcl/console/parse.h>
 #include <pcl/console/time.h>
+#include <pcl/visualization/vtk/vtkRenderWindowInteractorFix.h>
 #include <pcl/visualization/pcl_visualizer.h>
 #include <pcl/filters/voxel_grid_occlusion_estimation.h>
 #include <vtkCubeSource.h>
@@ -68,7 +69,7 @@ createDataSetFromVTKPoints (vtkPoints *points)
   // Iterate through the points                                                          
                              
   for (vtkIdType i = 0; i < points->GetNumberOfPoints (); i++)
-    verts->InsertNextCell ((vtkIdType)1, &i);
+    verts->InsertNextCell (static_cast<vtkIdType>(1), &i);
   data->SetPoints (points);
   data->SetVerts (verts);
   return data;
@@ -79,6 +80,7 @@ getCuboid (double minX, double maxX, double minY, double maxY, double minZ, doub
 {
   vtkSmartPointer < vtkCubeSource > cube = vtkSmartPointer<vtkCubeSource>::New ();
   cube->SetBounds (minX, maxX, minY, maxY, minZ, maxZ);
+  cube->Update ();
   return cube->GetOutput ();
 }
 
@@ -99,6 +101,7 @@ getVoxelActors (pcl::PointCloud<pcl::PointXYZ>& voxelCenters,
     
     treeWireframe->AddInputData (getCuboid (x - s, x + s, y - s, y + s, z - s, z + s));
   }
+  treeWireframe->Update ();
 
   vtkSmartPointer < vtkLODActor > treeActor = vtkSmartPointer<vtkLODActor>::New ();
   
@@ -119,6 +122,7 @@ displayBoundingBox (Eigen::Vector3f& min_b, Eigen::Vector3f& max_b,
 {
   vtkSmartPointer < vtkAppendPolyData > treeWireframe = vtkSmartPointer<vtkAppendPolyData>::New ();
   treeWireframe->AddInputData (getCuboid (min_b[0], max_b[0], min_b[1], max_b[1], min_b[2], max_b[2]));
+  treeWireframe->Update();
 
   vtkSmartPointer < vtkActor > treeActor = vtkSmartPointer<vtkActor>::New ();
 
@@ -201,7 +205,7 @@ int main (int argc, char** argv)
   std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> > occluded_voxels;
   vg.occlusionEstimationAll (occluded_voxels);
 
-  print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", (int)occluded_voxels.size ()); print_info (" occluded voxels]\n");
+  print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", static_cast<int>(occluded_voxels.size ())); print_info (" occluded voxels]\n");
   
   CloudT::Ptr occ_centroids (new CloudT);
   occ_centroids->width = occluded_voxels.size ();
@@ -218,17 +222,19 @@ int main (int argc, char** argv)
     (*occ_centroids)[i] = point;
   }
 
+  // we use the filtered cloud because it contains exactly one point per occupied voxel (avoids drawing the same voxel box multiple times)
+  CloudT filtered_cloud = vg.getFilteredPointCloud();
   CloudT::Ptr cloud_centroids (new CloudT);
-  cloud_centroids->width = input_cloud->size ();
+  cloud_centroids->width = filtered_cloud.size ();
   cloud_centroids->height = 1;
   cloud_centroids->is_dense = false;
-  cloud_centroids->points.resize (input_cloud->size ());
+  cloud_centroids->points.resize (filtered_cloud.size ());
 
-  for (std::size_t i = 0; i < input_cloud->size (); ++i)
+  for (std::size_t i = 0; i < filtered_cloud.size (); ++i)
   {
-    float x = (*input_cloud)[i].x;
-    float y = (*input_cloud)[i].y;
-    float z = (*input_cloud)[i].z;
+    float x = filtered_cloud[i].x;
+    float y = filtered_cloud[i].y;
+    float z = filtered_cloud[i].z;
     Eigen::Vector3i c = vg.getGridCoordinates (x, y, z);
     Eigen::Vector4f xyz = vg.getCentroidCoordinate (c);
     PointT point;
@@ -254,7 +260,7 @@ int main (int argc, char** argv)
     vtkSmartPointer<vtkRenderWindow>::New();
   renderWindow->AddRenderer (renderer);  
   vtkSmartPointer<vtkRenderWindowInteractor> renderWindowInteractor = 
-    vtkSmartPointer<vtkRenderWindowInteractor>::New();
+    vtkSmartPointer<vtkRenderWindowInteractor>::Take (vtkRenderWindowInteractorFixNew ());
   renderWindowInteractor->SetRenderWindow (renderWindow);
 
   // Add the actors to the renderer, set the background and size
index 408480383912f29217d2edecebc28b489c21fafa..2a2cd74e7cd6e841218f325d598c9e22c93f9839 100644 (file)
@@ -79,7 +79,7 @@ loadCloud (const std::string &filename, PointCloud<PointXYZ> &cloud)
     if (st.size () != 3)
       continue;
 
-    cloud.push_back (PointXYZ (float (atof (st[0].c_str ())), float (atof (st[1].c_str ())), float (atof (st[2].c_str ()))));
+    cloud.push_back (PointXYZ (static_cast<float>(atof (st[0].c_str ())), static_cast<float>(atof (st[1].c_str ())), static_cast<float>(atof (st[2].c_str ()))));
   }
   fs.close ();
 
index c0af27953169f2656c54fb3833dda1a312dfec97..985e4ce64dc0e323dee03799386cdf6a0bc21fab 100644 (file)
@@ -4,7 +4,7 @@ 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})
+PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP)
 
 PCL_ADD_DOC("${SUBSYS_NAME}")
 
index a8a47729b5f318f929988e3526c0980b7676c608..69c4211bec83fc1b8e41970a00e36843cde5ea56 100644 (file)
@@ -21,7 +21,7 @@ public:
   /** \brief empty constructor */
   PointCoherence() = default;
 
-  /** \brief empty distructor */
+  /** \brief empty destructor */
   virtual ~PointCoherence() = default;
 
   /** \brief compute coherence from the source point to the target point.
index e2f15f4f69205e9ca945e85c02625673d800e9b8..e56e72bfba07dd562b56c6e1ca32d0a4109b3bd7 100644 (file)
@@ -17,7 +17,7 @@ public:
   using ConstPtr = shared_ptr<const DistanceCoherence<PointInT>>;
 
   /** \brief initialize the weight to 1.0. */
-  DistanceCoherence() : PointCoherence<PointInT>(), weight_(1.0) {}
+  DistanceCoherence() : PointCoherence<PointInT>() {}
 
   /** \brief set the weight of coherence.
    * \param weight the value of the wehgit.
@@ -44,7 +44,7 @@ protected:
   computeCoherence(PointInT& source, PointInT& target) override;
 
   /** \brief the weight of coherence.*/
-  double weight_;
+  double weight_{1.0};
 };
 } // namespace tracking
 } // namespace pcl
index 946a4c5d0cb2df1f0e160a549198f6208eb164b2..5f0085f80baa7444ad33233d81637eae8663c715 100644 (file)
@@ -69,7 +69,7 @@ KLDAdaptiveParticleFilterTracker<PointInT, StateT>::resample()
     x_t.sample(zero_mean, step_noise_covariance_);
 
     // motion
-    if (rand() / double(RAND_MAX) < motion_ratio_)
+    if (rand() / static_cast<double>(RAND_MAX) < motion_ratio_)
       x_t = x_t + motion_;
 
     S->points.push_back(x_t);
index e0d75058b0a49942f72b506d6653b99ddb66c417..3fbd503b99b042157331f1b8130e8399115a597f 100644 (file)
@@ -164,9 +164,9 @@ ParticleFilterTracker<PointInT, StateT>::cropInputPointCloud(
 {
   double x_min, y_min, z_min, x_max, y_max, z_max;
   calcBoundingBox(x_min, x_max, y_min, y_max, z_min, z_max);
-  pass_x_.setFilterLimits(float(x_min), float(x_max));
-  pass_y_.setFilterLimits(float(y_min), float(y_max));
-  pass_z_.setFilterLimits(float(z_min), float(z_max));
+  pass_x_.setFilterLimits(static_cast<float>(x_min), static_cast<float>(x_max));
+  pass_y_.setFilterLimits(static_cast<float>(y_min), static_cast<float>(y_max));
+  pass_z_.setFilterLimits(static_cast<float>(z_min), static_cast<float>(z_max));
 
   // x
   PointCloudInPtr xcloud(new PointCloudIn);
@@ -365,13 +365,11 @@ template <typename PointInT, typename StateT>
 void
 ParticleFilterTracker<PointInT, StateT>::update()
 {
-
   StateT orig_representative = representative_state_;
   representative_state_.zero();
   representative_state_.weight = 0.0;
-  for (const auto& p : *particles_) {
-    representative_state_ = representative_state_ + p * p.weight;
-  }
+  representative_state_ =
+      StateT::weightedAverage(particles_->begin(), particles_->end());
   representative_state_.weight = 1.0f / static_cast<float>(particles_->size());
   motion_ = representative_state_ - orig_representative;
 }
index 4ee37e28d39c348b53d734edc3d9641576ce1c70..29d0fc9b6f829dade44963d96a276c5d396980e6 100644 (file)
@@ -225,6 +225,8 @@ PyramidalKLTTracker<PointInT, IntensityT>::derivatives(const FloatImage& src,
       grad_y_row[x] = (trow1[x + 1] + trow1[x - 1]) * 3 + trow1[x] * 10;
     }
   }
+  delete[] row0;
+  delete[] row1;
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////////
index 2fe9bbfd28250c7b0d590ac33915cd653b77877c..91c29e8c47351182144c2d73e6396593bf2b7b46 100644 (file)
@@ -9,7 +9,7 @@
 namespace pcl {
 namespace tracking {
 struct _ParticleXYZRPY {
-  PCL_ADD_POINT4D;
+  PCL_ADD_POINT4D
   union {
     struct {
       float roll;
@@ -86,7 +86,7 @@ struct EIGEN_ALIGN16 ParticleXYZRPY : public _ParticleXYZRPY {
 
     // Scales 1.0 radians of variance in RPY sampling into equivalent units for
     // quaternion sampling.
-    const float scale_factor = 0.2862;
+    constexpr float scale_factor = 0.2862;
 
     float a = sampleNormal(0, scale_factor * cov[3]);
     float b = sampleNormal(0, scale_factor * cov[4]);
@@ -129,6 +129,30 @@ struct EIGEN_ALIGN16 ParticleXYZRPY : public _ParticleXYZRPY {
     return {trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw};
   }
 
+  template <class InputIterator>
+  static ParticleXYZRPY
+  weightedAverage(InputIterator first, InputIterator last)
+  {
+    ParticleXYZRPY wa;
+    float wa_roll_sin = 0.0, wa_roll_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0,
+          wa_yaw_sin = 0.0, wa_yaw_cos = 0.0;
+    for (auto point = first; point != last; ++point) {
+      wa.x += point->x * point->weight;
+      wa.y += point->y * point->weight;
+      wa.z += point->z * point->weight;
+      wa_pitch_cos = std::cos(point->pitch);
+      wa_roll_sin += wa_pitch_cos * std::sin(point->roll) * point->weight;
+      wa_roll_cos += wa_pitch_cos * std::cos(point->roll) * point->weight;
+      wa_pitch_sin += std::sin(point->pitch) * point->weight;
+      wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight;
+      wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight;
+    }
+    wa.roll = std::atan2(wa_roll_sin, wa_roll_cos);
+    wa.pitch = std::asin(wa_pitch_sin);
+    wa.yaw = std::atan2(wa_yaw_sin, wa_yaw_cos);
+    return wa;
+  }
+
   // a[i]
   inline float
   operator[](unsigned int i)
@@ -212,7 +236,7 @@ operator-(const ParticleXYZRPY& a, const ParticleXYZRPY& b)
 namespace pcl {
 namespace tracking {
 struct _ParticleXYZR {
-  PCL_ADD_POINT4D;
+  PCL_ADD_POINT4D
   union {
     struct {
       float roll;
@@ -292,7 +316,25 @@ struct EIGEN_ALIGN16 ParticleXYZR : public _ParticleXYZR {
     float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
     getTranslationAndEulerAngles(
         trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
-    return (pcl::tracking::ParticleXYZR(trans_x, trans_y, trans_z, 0, trans_pitch, 0));
+    return {trans_x, trans_y, trans_z, 0, trans_pitch, 0};
+  }
+
+  template <class InputIterator>
+  static ParticleXYZR
+  weightedAverage(InputIterator first, InputIterator last)
+  {
+    ParticleXYZR wa;
+    float wa_pitch_sin = 0.0;
+    for (auto point = first; point != last; ++point) {
+      wa.x += point->x * point->weight;
+      wa.y += point->y * point->weight;
+      wa.z += point->z * point->weight;
+      wa_pitch_sin += std::sin(point->pitch) * point->weight;
+    }
+    wa.roll = 0.0;
+    wa.pitch = std::asin(wa_pitch_sin);
+    wa.yaw = 0.0;
+    return wa;
   }
 
   // a[i]
@@ -378,7 +420,7 @@ operator-(const ParticleXYZR& a, const ParticleXYZR& b)
 namespace pcl {
 namespace tracking {
 struct _ParticleXYRPY {
-  PCL_ADD_POINT4D;
+  PCL_ADD_POINT4D
   union {
     struct {
       float roll;
@@ -458,8 +500,31 @@ struct EIGEN_ALIGN16 ParticleXYRPY : public _ParticleXYRPY {
     float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
     getTranslationAndEulerAngles(
         trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
-    return (pcl::tracking::ParticleXYRPY(
-        trans_x, 0, trans_z, trans_roll, trans_pitch, trans_yaw));
+    return {trans_x, 0, trans_z, trans_roll, trans_pitch, trans_yaw};
+  }
+
+  template <class InputIterator>
+  static ParticleXYRPY
+  weightedAverage(InputIterator first, InputIterator last)
+  {
+    ParticleXYRPY wa;
+    float wa_roll_sin = 0.0, wa_roll_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0,
+          wa_yaw_sin = 0.0, wa_yaw_cos = 0.0;
+    for (auto point = first; point != last; ++point) {
+      wa.x += point->x * point->weight;
+      wa.z += point->z * point->weight;
+      wa_pitch_cos = std::cos(point->pitch);
+      wa_roll_sin += wa_pitch_cos * std::sin(point->roll) * point->weight;
+      wa_roll_cos += wa_pitch_cos * std::cos(point->roll) * point->weight;
+      wa_pitch_sin += std::sin(point->pitch) * point->weight;
+      wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight;
+      wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight;
+    }
+    wa.y = 0;
+    wa.roll = std::atan2(wa_roll_sin, wa_roll_cos);
+    wa.pitch = std::asin(wa_pitch_sin);
+    wa.yaw = std::atan2(wa_yaw_sin, wa_yaw_cos);
+    return wa;
   }
 
   // a[i]
@@ -545,7 +610,7 @@ operator-(const ParticleXYRPY& a, const ParticleXYRPY& b)
 namespace pcl {
 namespace tracking {
 struct _ParticleXYRP {
-  PCL_ADD_POINT4D;
+  PCL_ADD_POINT4D
   union {
     struct {
       float roll;
@@ -625,8 +690,28 @@ struct EIGEN_ALIGN16 ParticleXYRP : public _ParticleXYRP {
     float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
     getTranslationAndEulerAngles(
         trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
-    return (
-        pcl::tracking::ParticleXYRP(trans_x, 0, trans_z, 0, trans_pitch, trans_yaw));
+    return {trans_x, 0, trans_z, 0, trans_pitch, trans_yaw};
+  }
+
+  template <class InputIterator>
+  static ParticleXYRP
+  weightedAverage(InputIterator first, InputIterator last)
+  {
+    ParticleXYRP wa;
+    float wa_yaw_sin = 0.0, wa_yaw_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0;
+    for (auto point = first; point != last; ++point) {
+      wa.x += point->x * point->weight;
+      wa.z += point->z * point->weight;
+      wa_pitch_cos = std::cos(point->pitch);
+      wa_pitch_sin += std::sin(point->pitch) * point->weight;
+      wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight;
+      wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight;
+    }
+    wa.y = 0.0;
+    wa.roll = 0.0;
+    wa.pitch = std::asin(wa_pitch_sin);
+    wa.yaw = std::atan2(wa_yaw_sin, wa_yaw_cos);
+    return wa;
   }
 
   // a[i]
@@ -712,7 +797,7 @@ operator-(const ParticleXYRP& a, const ParticleXYRP& b)
 namespace pcl {
 namespace tracking {
 struct _ParticleXYR {
-  PCL_ADD_POINT4D;
+  PCL_ADD_POINT4D
   union {
     struct {
       float roll;
@@ -792,7 +877,25 @@ struct EIGEN_ALIGN16 ParticleXYR : public _ParticleXYR {
     float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
     getTranslationAndEulerAngles(
         trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
-    return (pcl::tracking::ParticleXYR(trans_x, 0, trans_z, 0, trans_pitch, 0));
+    return {trans_x, 0, trans_z, 0, trans_pitch, 0};
+  }
+
+  template <class InputIterator>
+  static ParticleXYR
+  weightedAverage(InputIterator first, InputIterator last)
+  {
+    ParticleXYR wa;
+    float wa_pitch_sin = 0.0;
+    for (auto point = first; point != last; ++point) {
+      wa.x += point->x * point->weight;
+      wa.z += point->z * point->weight;
+      wa_pitch_sin += std::sin(point->pitch) * point->weight;
+    }
+    wa.y = 0.0;
+    wa.roll = 0.0;
+    wa.pitch = std::asin(wa_pitch_sin);
+    wa.yaw = 0.0;
+    return wa;
   }
 
   // a[i]
index a28fbf806c8aa9de438485d125fc2a23f52a4fff..b1291f2ab62bcfa2f5f34ec73c33ac23e491ebc9 100644 (file)
@@ -63,11 +63,7 @@ public:
 
   /** \brief Empty constructor. */
   KLDAdaptiveParticleFilterTracker()
-  : ParticleFilterTracker<PointInT, StateT>()
-  , maximum_particle_number_()
-  , epsilon_(0)
-  , delta_(0.99)
-  , bin_size_()
+  : ParticleFilterTracker<PointInT, StateT>(), bin_size_()
   {
     tracker_name_ = "KLDAdaptiveParticleFilterTracker";
   }
@@ -243,14 +239,14 @@ protected:
   resample() override;
 
   /** \brief the maximum number of the particles. */
-  unsigned int maximum_particle_number_;
+  unsigned int maximum_particle_number_{0};
 
   /** \brief error between K-L distance and MLE*/
-  double epsilon_;
+  double epsilon_{0.0};
 
   /** \brief probability of distance between K-L distance and MLE is less than
    * epsilon_*/
-  double delta_;
+  double delta_{0.99};
 
   /** \brief the size of a bin.*/
   StateT bin_size_;
index 8e54f38e8f8149a34f3ff749a4c12e56138dc49e..f7d6eda2a2b5784236c70ba2e550f6355db7f415 100644 (file)
@@ -29,7 +29,6 @@ public:
 
   /** \brief empty constructor */
   NearestPairPointCloudCoherence()
-  : new_target_(false), search_(), maximum_distance_(std::numeric_limits<double>::max())
   {
     coherence_name_ = "NearestPairPointCloudCoherence";
   }
@@ -82,13 +81,13 @@ protected:
   initCompute() override;
 
   /** \brief A flag which is true if target_input_ is updated */
-  bool new_target_;
+  bool new_target_{false};
 
   /** \brief A pointer to the spatial search object. */
-  SearchPtr search_;
+  SearchPtr search_{nullptr};
 
   /** \brief max of distance for points to be taken into account*/
-  double maximum_distance_;
+  double maximum_distance_{std::numeric_limits<double>::max()};
 
   /** \brief compute the nearest pairs and compute coherence using
    * point_coherences_ */
index 604e28d61f19c6f5007800833f7a8d4d7e9bcad0..d251ca0a3e5d098e4e80a88161b9de405ebdca08 100644 (file)
@@ -13,7 +13,7 @@ template <typename PointInT>
 class NormalCoherence : public PointCoherence<PointInT> {
 public:
   /** \brief initialize the weight to 1.0. */
-  NormalCoherence() : PointCoherence<PointInT>(), weight_(1.0) {}
+  NormalCoherence() : PointCoherence<PointInT>() {}
 
   /** \brief set the weight of coherence
    * \param weight the weight of coherence
@@ -40,7 +40,7 @@ protected:
   computeCoherence(PointInT& source, PointInT& target) override;
 
   /** \brief the weight of coherence */
-  double weight_;
+  double weight_{1.0};
 };
 } // namespace tracking
 } // namespace pcl
index f4cf99e6113bedc01fce0d41a181bf3259f52f98..122d4b5417cfbf61e7ed814313ad1521f33c3da9 100644 (file)
@@ -50,30 +50,7 @@ public:
 
   /** \brief Empty constructor. */
   ParticleFilterTracker()
-  : iteration_num_(1)
-  , particle_num_()
-  , min_indices_(1)
-  , ref_()
-  , particles_()
-  , coherence_()
-  , resample_likelihood_thr_(0.0)
-  , occlusion_angle_thr_(M_PI / 2.0)
-  , alpha_(15.0)
-  , representative_state_()
-  , use_normal_(false)
-  , motion_()
-  , motion_ratio_(0.25)
-  , pass_x_()
-  , pass_y_()
-  , pass_z_()
-  , transed_reference_vector_()
-  , change_detector_()
-  , changed_(false)
-  , change_counter_(0)
-  , change_detector_filter_(10)
-  , change_detector_interval_(10)
-  , change_detector_resolution_(0.01)
-  , use_change_detector_(false)
+  : representative_state_(), motion_(), pass_x_(), pass_y_(), pass_z_()
   {
     tracker_name_ = "ParticleFilterTracker";
     pass_x_.setFilterFieldName("x");
@@ -484,7 +461,7 @@ protected:
   computeTransformedPointCloudWithoutNormal(const StateT& hypothesis,
                                             PointCloudIn& cloud);
 
-  /** \brief This method should get called before starting the actua computation. */
+  /** \brief This method should get called before starting the actual computation. */
   bool
   initCompute() override;
 
@@ -558,48 +535,48 @@ protected:
   testChangeDetection(const PointCloudInConstPtr& input);
 
   /** \brief The number of iteration of particlefilter. */
-  int iteration_num_;
+  int iteration_num_{1};
 
   /** \brief The number of the particles. */
-  int particle_num_;
+  int particle_num_{0};
 
   /** \brief The minimum number of points which the hypothesis should have. */
-  int min_indices_;
+  int min_indices_{1};
 
   /** \brief Adjustment of the particle filter. */
-  double fit_ratio_;
+  double fit_ratio_{0.0};
 
   /** \brief A pointer to reference point cloud. */
-  PointCloudInConstPtr ref_;
+  PointCloudInConstPtr ref_{nullptr};
 
   /** \brief A pointer to the particles  */
-  PointCloudStatePtr particles_;
+  PointCloudStatePtr particles_{nullptr};
 
   /** \brief A pointer to PointCloudCoherence. */
-  CloudCoherencePtr coherence_;
+  CloudCoherencePtr coherence_{nullptr};
 
   /** \brief The diagonal elements of covariance matrix of the step noise. the
    * covariance matrix is used at every resample method.
    */
-  std::vector<double> step_noise_covariance_;
+  std::vector<double> step_noise_covariance_{};
 
   /** \brief The diagonal elements of covariance matrix of the initial noise.
    * the covariance matrix is used when initialize the particles.
    */
-  std::vector<double> initial_noise_covariance_;
+  std::vector<double> initial_noise_covariance_{};
 
   /** \brief The mean values of initial noise. */
-  std::vector<double> initial_noise_mean_;
+  std::vector<double> initial_noise_mean_{};
 
   /** \brief The threshold for the particles to be re-initialized. */
-  double resample_likelihood_thr_;
+  double resample_likelihood_thr_{0.0};
 
   /** \brief The threshold for the points to be considered as occluded. */
-  double occlusion_angle_thr_;
+  double occlusion_angle_thr_{M_PI / 2.0};
 
   /** \brief The weight to be used in normalization of the weights of the
    * particles. */
-  double alpha_;
+  double alpha_{15.0};
 
   /** \brief The result of tracking. */
   StateT representative_state_;
@@ -609,13 +586,13 @@ protected:
   Eigen::Affine3f trans_;
 
   /** \brief A flag to use normal or not. defaults to false. */
-  bool use_normal_;
+  bool use_normal_{false};
 
   /** \brief Difference between the result in t and t-1. */
   StateT motion_;
 
   /** \brief Ratio of hypothesis to use motion model. */
-  double motion_ratio_;
+  double motion_ratio_{0.25};
 
   /** \brief Pass through filter to crop the pointclouds within the hypothesis
    * bounding box. */
@@ -628,30 +605,31 @@ protected:
   pcl::PassThrough<PointInT> pass_z_;
 
   /** \brief A list of the pointers to pointclouds. */
-  std::vector<PointCloudInPtr> transed_reference_vector_;
+  std::vector<PointCloudInPtr> transed_reference_vector_{};
 
   /** \brief Change detector used as a trigger to track. */
-  typename pcl::octree::OctreePointCloudChangeDetector<PointInT>::Ptr change_detector_;
+  typename pcl::octree::OctreePointCloudChangeDetector<PointInT>::Ptr change_detector_{
+      nullptr};
 
   /** \brief A flag to be true when change of pointclouds is detected. */
-  bool changed_;
+  bool changed_{false};
 
   /** \brief A counter to skip change detection. */
-  unsigned int change_counter_;
+  unsigned int change_counter_{0};
 
   /** \brief Minimum points in a leaf when calling change detector. defaults
    * to 10. */
-  unsigned int change_detector_filter_;
+  unsigned int change_detector_filter_{10};
 
   /** \brief The number of interval frame to run change detection. defaults
    * to 10. */
-  unsigned int change_detector_interval_;
+  unsigned int change_detector_interval_{10};
 
   /** \brief Resolution of change detector. defaults to 0.01. */
-  double change_detector_resolution_;
+  double change_detector_resolution_{0.01};
 
   /** \brief The flag which will be true if using change detection. */
-  bool use_change_detector_;
+  bool use_change_detector_{false};
 };
 } // namespace tracking
 } // namespace pcl
index d971ccc7d7fa658e29ee327f37fb64baeb1b0578..fa4101142733252364d8d36a922c8a04a82e6a25 100644 (file)
@@ -349,7 +349,7 @@ protected:
   convolveRows(const FloatImageConstPtr& input, FloatImage& output) const;
 
   /** \brief extract the patch from the previous image, previous image gradients
-   * surrounding pixel alocation while interpolating image and gradients data
+   * surrounding pixel allocation while interpolating image and gradients data
    * and compute covariation matrix of derivatives.
    * \param[in] img original image
    * \param[in] grad_x original image gradient along X direction
index 4ae65ab4a37491ca3b869543405595bd7e65eea3..15514de9c05073d59a3108c7b904a835685a5934 100644 (file)
@@ -45,7 +45,10 @@ namespace pcl {
 namespace tracking {
 /* state definition */
 struct ParticleXYZRPY;
+struct ParticleXYRPY;
+struct ParticleXYRP;
 struct ParticleXYR;
+struct ParticleXYZR;
 
 /* \brief return the value of normal distribution */
 PCL_EXPORTS double
index 7753b96d8d24b16966c7276e5d42c8b083e686f6..26cb217612f019ad2ee2dddbea5063be992f3259 100644 (file)
@@ -95,7 +95,7 @@ namespace pcl
         {
           const auto cloud = cloud_indices_.find (name);
           if(cloud == cloud_indices_.cend ())
-            return Indices ();
+            return {};
 
           return cloud->second;
         }
index 8efff445ec33fefb6b50deee64cf1e55d87c60ed..a1978ca68ee28c25c41a7ac2350fa3c8698a7930 100644 (file)
@@ -51,5 +51,4 @@ PCL_DEPRECATED_HEADER(1, 16, "Please include the needed boost headers directly."
 #include <boost/algorithm/string/split.hpp>
 #include <boost/algorithm/string/classification.hpp>
 #include <boost/foreach.hpp>
-#include <boost/date_time/posix_time/posix_time.hpp>
 #include <boost/filesystem.hpp>
index 57525d21029fcf4b4d8c933cfadb27b55ffeb731..8e23c6b40d3a86371f025568573df2e5a929ee10 100644 (file)
@@ -67,7 +67,7 @@ namespace pcl
       using ColorHandlerConstPtr = ColorHandler::ConstPtr;
 
       public:
-        CloudActor () : color_handler_index_ (0), geometry_handler_index_ (0) {}
+        CloudActor () = default;
 
         virtual ~CloudActor () = default;
 
@@ -81,10 +81,10 @@ namespace pcl
         std::vector<ColorHandlerConstPtr> color_handlers;
 
         /** \brief The active color handler. */
-        int color_handler_index_;
+        int color_handler_index_{0};
 
         /** \brief The active geometry handler. */
-        int geometry_handler_index_;
+        int geometry_handler_index_{0};
 
         /** \brief The viewpoint transformation matrix. */
         vtkSmartPointer<vtkMatrix4x4> viewpoint_transformation_;
index bc5de74e8c70f88751de7dce3ccd888f810e7a6c..0168815359e11f174e6de60cca437e40760a25d7 100644 (file)
@@ -43,7 +43,7 @@ namespace pcl
 {
   namespace visualization
   {
-    /** @b Provide some gerneral functionalities regarding 2d float arrays, e.g., for visualization purposes
+    /** @b Provide some general functionalities regarding 2d float arrays, e.g., for visualization purposes
       * \author Bastian Steder
       * \ingroup visualization
       */
index 6da04f7f103775558f34427838fdf856c1a1f499..901846341a876cf38498eec6137c7c013d864fc3 100644 (file)
@@ -229,7 +229,7 @@ namespace pcl
         
         struct ExitCallback : public vtkCommand
         {
-          ExitCallback () : his () {}
+          ExitCallback () = default;
 
           static ExitCallback* New ()
           {
@@ -239,14 +239,14 @@ namespace pcl
           void 
           Execute (vtkObject*, unsigned long event_id, void*) override;
 
-          PCLHistogramVisualizer *his;
+          PCLHistogramVisualizer *his{nullptr};
         };
 
         /** \brief Callback object enabling us to leave the main loop, when a timer fires. */
         vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
         vtkSmartPointer<ExitCallback> exit_callback_;
         /** \brief Set to true when the histogram visualizer is ready to be terminated. */
-        bool stopped_;
+        bool stopped_{false};
     };
   }
 }
index 1c2d147332b33d87f77c4a1305ef09286cb16e6e..de682f6d91c444aa34a2af1b9f584bd3d55f07e9 100644 (file)
@@ -560,7 +560,7 @@ namespace pcl
         bool
         wasStopped () const { return (stopped_); }
 
-        /** \brief Stop the interaction and close the visualizaton window. */
+        /** \brief Stop the interaction and close the visualization window. */
         void
         close ()
         {
@@ -920,7 +920,7 @@ namespace pcl
       protected: // types
         struct ExitMainLoopTimerCallback : public vtkCommand
         {
-          ExitMainLoopTimerCallback () : right_timer_id (), window () {}
+          ExitMainLoopTimerCallback () = default;
 
           static ExitMainLoopTimerCallback* New ()
           {
@@ -936,12 +936,12 @@ namespace pcl
               return;
             window->interactor_->TerminateApp ();
           }
-          int right_timer_id;
-          ImageViewer* window;
+          int right_timer_id{0};
+          ImageViewer* window{nullptr};
         };
         struct ExitCallback : public vtkCommand
         {
-          ExitCallback () : window () {}
+          ExitCallback () = default;
 
           static ExitCallback* New ()
           {
@@ -955,7 +955,7 @@ namespace pcl
             window->stopped_ = true;
             window->interactor_->TerminateApp ();
           }
-          ImageViewer* window;
+          ImageViewer* window{nullptr};
         };
 
     private:
@@ -1009,13 +1009,13 @@ namespace pcl
         boost::shared_array<unsigned char> data_;
   
         /** \brief The data array (representing the image) size. Used internally. */
-        std::size_t data_size_;
+        std::size_t data_size_{0};
 
         /** \brief Set to false if the interaction loop is running. */
-        bool stopped_;
+        bool stopped_{false};
 
         /** \brief Global timer ID. Used in destructor only. */
-        int timer_id_;
+        int timer_id_{0};
 
         // /** \brief Internal blender used to overlay 2D geometry over the image. */
         // vtkSmartPointer<vtkImageBlend> blend_;
@@ -1029,7 +1029,7 @@ namespace pcl
         /** \brief Internal data array. Used everytime add***Image is called. 
           * Cleared, everytime the render loop is executed. 
           */
-        std::vector<unsigned char*> image_data_;
+        std::vector<unsigned char*> image_data_{};
 
         struct LayerComparator
         {
index 06883af3831db8ec19887bebd2cb841045e2895f..0f746cabb8397a8f6aece506401c226fff876d2e 100644 (file)
@@ -618,7 +618,7 @@ pcl::visualization::PCLVisualizer::addSphere (const PointT &center, double radiu
 
   vtkSmartPointer<vtkSphereSource> data = vtkSmartPointer<vtkSphereSource>::New ();
   data->SetRadius (radius);
-  data->SetCenter (double (center.x), double (center.y), double (center.z));
+  data->SetCenter (static_cast<double>(center.x), static_cast<double>(center.y), static_cast<double>(center.z));
   data->SetPhiResolution (10);
   data->SetThetaResolution (10);
   data->LatLongTessellationOff ();
@@ -896,7 +896,7 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
   // If the cloud is organized, then distribute the normal step in both directions
   if (cloud->isOrganized () && normals->isOrganized ())
   {
-    auto point_step = static_cast<vtkIdType> (sqrt (double (level)));
+    auto point_step = static_cast<vtkIdType> (sqrt (static_cast<double>(level)));
     nr_normals = (static_cast<vtkIdType> ((cloud->width - 1)/ point_step) + 1) *
                  (static_cast<vtkIdType> ((cloud->height - 1) / point_step) + 1);
     pts = new float[2 * nr_normals * 3];
@@ -906,6 +906,8 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
       for (vtkIdType x = 0; x < normals->width; x += point_step)
       {
         PointT p = (*cloud)(x, y);
+        if (!pcl::isFinite(p) || !pcl::isNormalFinite((*normals)(x, y)))
+          continue;
         p.x += (*normals)(x, y).normal[0] * scale;
         p.y += (*normals)(x, y).normal[1] * scale;
         p.z += (*normals)(x, y).normal[2] * scale;
@@ -928,8 +930,10 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
     nr_normals = (cloud->size () - 1) / level + 1 ;
     pts = new float[2 * nr_normals * 3];
 
-    for (vtkIdType i = 0, j = 0; j < nr_normals; j++, i = j * level)
+    for (vtkIdType i = 0, j = 0; (j < nr_normals) && (i < static_cast<vtkIdType>(cloud->size())); i += level)
     {
+      if (!pcl::isFinite((*cloud)[i]) || !pcl::isNormalFinite((*normals)[i]))
+        continue;
       PointT p = (*cloud)[i];
       p.x += (*normals)[i].normal[0] * scale;
       p.y += (*normals)[i].normal[1] * scale;
@@ -945,6 +949,7 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
       lines->InsertNextCell (2);
       lines->InsertCellPoint (2 * j);
       lines->InsertCellPoint (2 * j + 1);
+      ++j;
     }
   }
 
@@ -1216,7 +1221,7 @@ pcl::visualization::PCLVisualizer::addCorrespondences (
     overwrite = false; // Correspondences doesn't exist, add them instead of updating them
   }
 
-  int n_corr = int (correspondences.size () / nth);
+  int n_corr = static_cast<int>(correspondences.size () / nth);
   vtkSmartPointer<vtkPolyData> line_data = vtkSmartPointer<vtkPolyData>::New ();
 
   // Prepare colors
index c605ab1e89871bb539cedc1ba9968da0f17c2dd5..4202b1952b7c29614a50018833b9d3e4a9ed6f2a 100644 (file)
@@ -112,12 +112,7 @@ namespace pcl
         static PCLVisualizerInteractorStyle *New ();
 
         /** \brief Empty constructor. */
-        PCLVisualizerInteractorStyle () : 
-          init_ (), win_height_ (), win_width_ (), win_pos_x_ (), win_pos_y_ (),
-          max_win_height_ (), max_win_width_ (), use_vbos_ (false), grid_enabled_ (), lut_enabled_ (),
-          stereo_anaglyph_mask_default_ (),
-          modifier_ (), camera_saved_ (), lut_actor_id_ ("")
-        {}
+        PCLVisualizerInteractorStyle () = default;
       
         /** \brief Empty destructor */
         ~PCLVisualizerInteractorStyle () override = default;
@@ -260,36 +255,36 @@ namespace pcl
 
        protected:
         /** \brief Set to true after initialization is complete. */
-        bool init_;
+        bool init_{false};
 
         /** \brief Collection of vtkRenderers stored internally. */
         vtkSmartPointer<vtkRendererCollection> rens_;
 
         /** \brief Cloud actor map stored internally. */
-        CloudActorMapPtr cloud_actors_;
+        CloudActorMapPtr cloud_actors_{nullptr};
 
         /** \brief Shape map stored internally. */
-        ShapeActorMapPtr shape_actors_;
+        ShapeActorMapPtr shape_actors_{nullptr};
 
         /** \brief The current window width/height. */
-        int win_height_, win_width_;
+        int win_height_{0}, win_width_{0};
 
         /** \brief The current window position x/y. */
-        int win_pos_x_, win_pos_y_;
+        int win_pos_x_{0}, win_pos_y_{0};
 
         /** \brief The maximum resizeable window width/height. */
-        int max_win_height_, max_win_width_;
+        int max_win_height_{0}, max_win_width_{0};
 
         /** \brief Boolean that holds whether or not to use the vtkVertexBufferObjectMapper*/
-        bool use_vbos_;
+        bool use_vbos_{false};
 
         /** \brief Set to true if the grid actor is enabled. */
-        bool grid_enabled_;
+        bool grid_enabled_{false};
         /** \brief Actor for 2D grid on screen. */
         vtkSmartPointer<vtkLegendScaleActor> grid_actor_;
 
         /** \brief Set to true if the LUT actor is enabled. */
-        bool lut_enabled_;
+        bool lut_enabled_{false};
         /** \brief Actor for 2D lookup table on screen. */
         vtkSmartPointer<vtkScalarBarActor> lut_actor_;
 
@@ -364,20 +359,20 @@ namespace pcl
         }
 
         /** \brief True if we're using red-blue colors for anaglyphic stereo, false if magenta-green. */
-        bool stereo_anaglyph_mask_default_;
+        bool stereo_anaglyph_mask_default_{false};
 
         /** \brief A VTK Mouse Callback object, used for point picking. */
         vtkSmartPointer<PointPickingCallback> mouse_callback_;
 
         /** \brief The keyboard modifier to use. Default: Alt. */
-        InteractorKeyboardModifier modifier_;
+        InteractorKeyboardModifier modifier_{};
 
         /** \brief Camera file for camera parameter saving/restoring. */
         std::string camera_file_;
         /** \brief A \ref pcl::visualization::Camera for camera parameter saving/restoring. */
         Camera camera_;
         /** \brief A \ref pcl::visualization::Camera is saved or not. */
-        bool camera_saved_;
+        bool camera_saved_{false};
         /** \brief The render window.
           * Only used when interactor maybe not available
           */
@@ -408,7 +403,7 @@ namespace pcl
         static PCLHistogramVisualizerInteractorStyle *New ();
 
         /** \brief Empty constructor. */
-        PCLHistogramVisualizerInteractorStyle () : init_ (false) {}
+        PCLHistogramVisualizerInteractorStyle () = default;
 
         /** \brief Initialization routine. Must be called before anything else. */
         void 
@@ -425,7 +420,7 @@ namespace pcl
         RenWinInteractMap wins_;
 
         /** \brief Set to true after initialization is complete. */
-        bool init_;
+        bool init_{false};
 
         /** \brief Interactor style internal method. Gets called whenever a key is pressed. */
         void OnKeyDown () override;
index 042381893bda4e6405c19f50ebc1f884926a184b..2fb9baa3f42b002396c0108cf8b3a3d6d0a7e8ca 100644 (file)
@@ -48,11 +48,11 @@ namespace pcl
     class KeyboardEvent
     {
       public:
-        /** \brief bit patter for the ALT key*/
+        /** \brief bit pattern for the ALT key*/
         static const unsigned int Alt   = 1;
-        /** \brief bit patter for the Control key*/
+        /** \brief bit pattern for the Control key*/
         static const unsigned int Ctrl  = 2;
-        /** \brief bit patter for the Shift key*/
+        /** \brief bit pattern for the Shift key*/
         static const unsigned int Shift = 4;
 
         /** \brief Constructor
@@ -111,7 +111,7 @@ namespace pcl
       protected:
 
         bool action_;
-        unsigned int modifiers_;
+        unsigned int modifiers_{0};
         unsigned char key_code_;
         std::string key_sym_;
     };
@@ -119,8 +119,8 @@ namespace pcl
     KeyboardEvent::KeyboardEvent (bool action, const std::string& key_sym, unsigned char key, 
                                   bool alt, bool ctrl, bool shift)
       : action_ (action)
-      , modifiers_ (0)
-      , key_code_(key)
+      , 
+       key_code_(key)
       , key_sym_ (key_sym)
     {
       if (alt)
index 96413d3cc775b57b12fc2f1d33e7668639996a8f..6bc4ee71b16f05ba6e76ee1a81f2615b61b7f762 100644 (file)
@@ -132,7 +132,7 @@ namespace pcl
         MouseButton button_;
         unsigned int pointer_x_;
         unsigned int pointer_y_;
-        unsigned int key_state_;
+        unsigned int key_state_{0};
         bool selection_mode_;
     };
 
@@ -144,8 +144,8 @@ namespace pcl
     , button_ (button)
     , pointer_x_ (x)
     , pointer_y_ (y)
-    , key_state_ (0)
-    , selection_mode_ (selection_mode)
+    , 
+     selection_mode_ (selection_mode)
     {
       if (alt)
         key_state_ = KeyboardEvent::Alt;
index 12b29321b53f5e6419ff6fda4ec065e6f277c1e0..cfed860035cb05c0aee2b24ae5b5e9c35ff70a7d 100644 (file)
@@ -123,7 +123,7 @@ namespace pcl
       void draw (vtkContext2D * painter) override
       {
         applyInternals(painter);  
-        painter->DrawPoly (&info_[0], static_cast<unsigned int> (info_.size ()) / 2);
+        painter->DrawPoly (info_.data(), static_cast<unsigned int> (info_.size ()) / 2);
       }
     };
 
@@ -137,7 +137,7 @@ namespace pcl
       void draw (vtkContext2D * painter) override
       {
         applyInternals(painter);  
-        painter->DrawPoints (&info_[0], static_cast<unsigned int> (info_.size ()) / 2);
+        painter->DrawPoints (info_.data(), static_cast<unsigned int> (info_.size ()) / 2);
       }
     };
 
@@ -151,7 +151,7 @@ namespace pcl
       void draw (vtkContext2D * painter) override
       {
         applyInternals(painter);  
-        painter->DrawQuad (&info_[0]);
+        painter->DrawQuad (info_.data());
       }
     };
     
@@ -165,7 +165,7 @@ namespace pcl
       void draw (vtkContext2D * painter) override
       {
         applyInternals(painter);  
-        painter->DrawPolygon (&info_[0], static_cast<unsigned int> (info_.size ()) / 2);
+        painter->DrawPolygon (info_.data(), static_cast<unsigned int> (info_.size ()) / 2);
       }
     };
     
index 93f78695d17422be08b6309c8464a7be17d08315..1df71fd8734b8d4a869949a2cfee20f2caeced42 100644 (file)
@@ -393,7 +393,7 @@ namespace pcl
         bool
         wasStopped () const;
         
-        /** \brief Stop the interaction and close the visualizaton window. */
+        /** \brief Stop the interaction and close the visualization window. */
         void
         close ();
       
index 4d1d9290e4ab4b891e1aa48b4fc63fc54a8a6d33..8e5d42fa5651fd964e9efbfbd46862b814572dbf 100644 (file)
@@ -288,6 +288,8 @@ namespace pcl
           *  \param[in] time - How long (in ms) should the visualization loop be allowed to run.
           *  \param[in] force_redraw - if false it might return without doing anything if the
           *  interactor's framerate does not require a redraw yet.
+          *  \note This function may not return immediately after the specified time has elapsed, for example if
+          *  the user continues to interact with the visualizer, meaning that there are still events to process.
           */
         void
         spinOnce (int time = 1, bool force_redraw = false);
@@ -1252,7 +1254,7 @@ namespace pcl
         void
         resetStoppedFlag ();
 
-        /** \brief Stop the interaction and close the visualizaton window. */
+        /** \brief Stop the interaction and close the visualization window. */
         void
         close ();
 
@@ -2068,27 +2070,27 @@ namespace pcl
         {
           static FPSCallback *New () { return (new FPSCallback); }
 
-          FPSCallback () : actor (), pcl_visualizer (), decimated (), last_fps(0.0f) {}
+          FPSCallback () = default;
           FPSCallback (const FPSCallback& src)  = default;
           FPSCallback& operator = (const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; last_fps = src.last_fps; return (*this); }
 
           void
           Execute (vtkObject*, unsigned long event_id, void*) override;
 
-          vtkTextActor *actor;
-          PCLVisualizer* pcl_visualizer;
-          bool decimated;
-          float last_fps;
+          vtkTextActor *actor{nullptr};
+          PCLVisualizer* pcl_visualizer{nullptr};
+          bool decimated{false};
+          float last_fps{0.0f};
         };
 
         /** \brief The FPSCallback object for the current visualizer. */
         vtkSmartPointer<FPSCallback> update_fps_;
 
         /** \brief Set to false if the interaction loop is running. */
-        bool stopped_;
+        bool stopped_{false};
 
         /** \brief Global timer ID. Used in destructor only. */
-        int timer_id_;
+        int timer_id_{0};
 
         /** \brief Callback object enabling us to leave the main loop, when a timer fires. */
         vtkSmartPointer<ExitMainLoopTimerCallback> exit_main_loop_timer_callback_;
index ea2be9563a63842eb93f7940fc85b63c15420e9a..df18ad3158b39d9122f11cd481403286e2598c56 100644 (file)
@@ -89,7 +89,7 @@ namespace pcl
         virtual std::string
         getFieldName () const  = 0;
 
-        /** \brief Checl if this handler is capable of handling the input data or not. */
+        /** \brief Check if this handler is capable of handling the input data or not. */
         inline bool
         isCapable () const { return (capable_); }
 
index bfcdd7f954653b6edea0c6cd9cc8660f19f30546..bbddda91d60be4a3a60d0ea2baf0c6a517a3fdd3 100644 (file)
@@ -83,7 +83,7 @@ namespace pcl
 
 
       private:
-        float x_{0}, y_{0}, z_{0};
+        float x_{0.0f}, y_{0.0f}, z_{0.0f};
         pcl::index_t idx_{pcl::UNAVAILABLE};
         bool pick_first_{false};
         const vtkActor* actor_{nullptr};
index 74996fc3d757be59fb3d080be6e239f94a9be305..4a9b1d7a4e33d76a552d89911e34fd6febe71fbb 100644 (file)
@@ -61,11 +61,9 @@ namespace pcl
       /** \brief Empty constructor. */
       RegistrationVisualizer () : 
         update_visualizer_ (),
-        first_update_flag_ (false),
         cloud_source_ (),
         cloud_target_ (),
-        cloud_intermediate_ (),
-        maximum_displayed_correspondences_ (0)
+        cloud_intermediate_ ()
       {}
 
       ~RegistrationVisualizer ()
@@ -180,7 +178,7 @@ namespace pcl
           PointTarget> &cloud_tgt, const pcl::Indices &indices_tgt)> update_visualizer_;
 
       /** \brief Updates source and target point clouds only for the first update call. */
-      bool first_update_flag_;
+      bool first_update_flag_{false};
 
       /** \brief The local buffer for source point cloud. */
       pcl::PointCloud<PointSource> cloud_source_;
@@ -201,7 +199,7 @@ namespace pcl
       pcl::Indices cloud_target_indices_;
 
       /** \brief The maximum number of displayed correspondences. */
-      std::size_t maximum_displayed_correspondences_;
+      std::size_t maximum_displayed_correspondences_{0};
 
     };
 }
index 10ffdf9d9c400cdcf57185e68e582cef7868fc90..54bac8e739610d16997bab52cd833850835af41a 100644 (file)
@@ -148,7 +148,7 @@ protected:
   void StartEventLoop() override;
 
   /**
-   * Deallocate X ressource that may have been allocated
+   * Deallocate X resource that may have been allocated
    * Also calls finalize on the render window if available
    */
   void Finalize();
index d34448f362c3037db0a96317e4dada2610365c7b..7db1e4331ed2915fb5d9d8e9d5a11ad80b2ffaee 100644 (file)
@@ -184,8 +184,8 @@ namespace pcl
           void 
           Execute (vtkObject*, unsigned long event_id, void* call_data) override;
 
-          int right_timer_id;
-          Window* window;
+          int right_timer_id{-1};
+          Window* window{nullptr};
         };
 
         struct ExitCallback : public vtkCommand
@@ -200,11 +200,11 @@ namespace pcl
           void 
           Execute (vtkObject*, unsigned long event_id, void*) override;
 
-          Window* window;
+          Window* window{nullptr};
         };
 
-        bool stopped_;
-        int timer_id_;
+        bool stopped_{false};
+        int timer_id_{0};
 
     protected: // member fields
         boost::signals2::signal<void (const pcl::visualization::MouseEvent&)> mouse_signal_;
index afe884ac235b4fe3aa671111911b529ebf6c5774..fae72d1ad4b1aff3e343a9b83e37d41ea5ab874d 100644 (file)
@@ -61,7 +61,7 @@ namespace pcl
 
     cloud_show (const std::string &cloud_name, typename CloudT::ConstPtr cloud,
       pcl::visualization::PCLVisualizer::Ptr viewer) :
-      cloud_name (cloud_name), cloud (cloud), viewer (viewer),popped_ (false)
+      cloud_name (cloud_name), cloud (cloud), viewer (viewer)
     {}
 
     template <typename Handler> void
@@ -96,7 +96,7 @@ namespace pcl
     std::string cloud_name;
     typename CloudT::ConstPtr cloud;
     pcl::visualization::PCLVisualizer::Ptr viewer;
-    bool popped_;
+    bool popped_{false};
   };
   
   using cca = pcl::PointCloud<pcl::PointXYZRGBA>;
@@ -137,7 +137,7 @@ struct pcl::visualization::CloudViewer::CloudViewer_impl
 {
   ////////////////////////////////////////////////////////////////////////////////////////////
   CloudViewer_impl (const std::string& window_name) :
-    window_name_ (window_name), has_cloud_ (false), quit_ (false)
+    window_name_ (window_name)
   {
     viewer_thread_ = std::thread (&CloudViewer_impl::operator(), this);
     while (!viewer_)
@@ -251,8 +251,8 @@ struct pcl::visualization::CloudViewer::CloudViewer_impl
   pcl::visualization::PCLVisualizer::Ptr viewer_;
   std::mutex mtx_, spin_mtx_, c_mtx, once_mtx;
   std::thread viewer_thread_;
-  bool has_cloud_;
-  bool quit_;
+  bool has_cloud_{false};
+  bool quit_{false};
   std::list<cloud_show_base::Ptr> cloud_shows_;
   using CallableMap = std::map<std::string, VizCallable>;
   CallableMap callables;
index 9dd3777eae549ba15c651bafccb3eb72c596b3bd..92932334e44b6fa35788a2175d177fa523edda67 100644 (file)
@@ -77,9 +77,9 @@ pcl::visualization::getRandomColors (pcl::RGB &rgb, double min, double max)
     sum = r + g + b;
   }
   while (sum <= min || sum >= max);
-  rgb.r = std::uint8_t (r * 255.0);
-  rgb.g = std::uint8_t (g * 255.0);
-  rgb.b = std::uint8_t (b * 255.0);
+  rgb.r = static_cast<std::uint8_t>(r * 255.0);
+  rgb.g = static_cast<std::uint8_t>(g * 255.0);
+  rgb.b = static_cast<std::uint8_t>(b * 255.0);
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////////
@@ -109,13 +109,13 @@ pcl::visualization::worldToView (const Eigen::Vector4d &world_pt, const Eigen::M
   world /= world.w ();
 
   // X/Y screen space coordinate
-  int screen_x = int (std::floor (double (((world.x () + 1) / 2.0) * width) + 0.5));
-  int screen_y = int (std::floor (double (((world.y () + 1) / 2.0) * height) + 0.5));
+  int screen_x = static_cast<int>(std::floor ((((world.x () + 1) / 2.0) * width) + 0.5));
+  int screen_y = static_cast<int>(std::floor ((((world.y () + 1) / 2.0) * height) + 0.5));
 
   // Calculate -world_pt.y () because the screen Y axis is oriented top->down, ie 0 is top-left
   //int winY = (int) std::floor ( (double) (((1 - world_pt.y ()) / 2.0) * height) + 0.5); // top left
 
-  return (Eigen::Vector2i (screen_x, screen_y));
+  return {screen_x, screen_y};
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////////
@@ -288,7 +288,7 @@ pcl::visualization::viewScreenArea (
   int num = hull_vertex_table[pos][6];
   if (num == 0)
   {
-    return (float (width * height));
+    return (static_cast<float>(width * height));
   }
     //return 0.0;
 
@@ -359,7 +359,7 @@ pcl::visualization::viewScreenArea (
     sum += (dst[i].x () - dst[(i+1) % num].x ()) * (dst[i].y () + dst[(i+1) % num].y ());
   }
 
-  return (std::abs (float (sum * 0.5f)));
+  return (std::abs (static_cast<float>(sum * 0.5f)));
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////////
index 50cfa387bd185312af1b4c5d6464fd5a31bc59f7..e901860a03cefa050a70f7113d7fcbd0c03a1eef 100644 (file)
@@ -225,7 +225,7 @@ pcl::visualization::FloatImageUtils::getVisualImage (const unsigned short* short
   auto* data = new unsigned char[arraySize];
   unsigned char* dataPtr = data;
   
-  float factor = 1.0f / float (max_value - min_value), offset = float (-min_value);
+  float factor = 1.0f / static_cast<float>(max_value - min_value), offset = static_cast<float>(-min_value);
   
   for (int i=0; i<size; ++i) 
   {
index 9eae0418feba90f42986e03c3914710d280d3bb7..7fbeab14dd3876dd7647d16c1ea720f0b344dd29 100644 (file)
@@ -56,8 +56,7 @@ using namespace std::chrono_literals;
 //////////////////////////////////////////////////////////////////////////////////////////////
 pcl::visualization::PCLHistogramVisualizer::PCLHistogramVisualizer () : 
   exit_main_loop_timer_callback_ (vtkSmartPointer<ExitMainLoopTimerCallback>::New ()), 
-  exit_callback_ (vtkSmartPointer<ExitCallback>::New ()), 
-  stopped_ ()
+  exit_callback_ (vtkSmartPointer<ExitCallback>::New ())
 {
 }
 
index 588eb6ca85b08d63b1e6c80c395eb1cbe31d1de9..ca1f4579aec941117fbd47016fa0c1ab6a446794 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////
 pcl::visualization::ImageViewer::ImageViewer (const std::string& window_title)
-  : mouse_command_ (vtkSmartPointer<vtkCallbackCommand>::New ())
+  : interactor_ (vtkSmartPointer <vtkRenderWindowInteractor>::Take (vtkRenderWindowInteractorFixNew ()))
+  , mouse_command_ (vtkSmartPointer<vtkCallbackCommand>::New ())
   , keyboard_command_ (vtkSmartPointer<vtkCallbackCommand>::New ())
   , win_ (vtkSmartPointer<vtkRenderWindow>::New ())
   , ren_ (vtkSmartPointer<vtkRenderer>::New ())
   , slice_ (vtkSmartPointer<vtkImageSlice>::New ())
   , interactor_style_ (vtkSmartPointer<ImageViewerInteractorStyle>::New ())
-  , data_size_ (0)
-  , stopped_ ()
-  , timer_id_ ()
-  , algo_ (vtkSmartPointer<vtkImageFlip>::New ())
+  , 
+   algo_ (vtkSmartPointer<vtkImageFlip>::New ())
 {
-  interactor_ = vtkSmartPointer <vtkRenderWindowInteractor>::Take (vtkRenderWindowInteractorFixNew ());
-
   // Prepare for image flip
   algo_->SetInterpolationModeToCubic ();
   algo_->PreserveImageExtentOn ();
@@ -130,8 +127,8 @@ pcl::visualization::ImageViewer::addRGBImage (
     const std::string &layer_id, double opacity, bool autoresize)
 {
   if (autoresize &&
-      (unsigned (getSize ()[0]) != width ||
-      unsigned (getSize ()[1]) != height))
+      (static_cast<unsigned>(getSize ()[0]) != width ||
+      static_cast<unsigned>(getSize ()[1]) != height))
     setSize (width, height);
 
   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
@@ -171,8 +168,8 @@ pcl::visualization::ImageViewer::addMonoImage (
     const unsigned char* rgb_data, unsigned width, unsigned height,
     const std::string &layer_id, double opacity)
 {
-  if (unsigned (getSize ()[0]) != width ||
-      unsigned (getSize ()[1]) != height)
+  if (static_cast<unsigned>(getSize ()[0]) != width ||
+      static_cast<unsigned>(getSize ()[1]) != height)
     setSize (width, height);
 
   // Check to see if this ID entry already exists (has it been already added to the visualizer?)
@@ -505,7 +502,7 @@ pcl::visualization::ImageViewer::emitMouseEvent (unsigned long event_id)
 void
 pcl::visualization::ImageViewer::emitKeyboardEvent (unsigned long event_id)
 {
-  KeyboardEvent event (bool(event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (),  interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
+  KeyboardEvent event ((event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (),  interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
   keyboard_signal_ (event);
 }
 
index f257dc93283baf6c26e5c83c3856dd5e3f4568c9..8e9106a62014b684485bedee02948628ba870c36 100644 (file)
@@ -54,7 +54,7 @@ pcl::visualization::PCLPainter2D::PCLPainter2D(char const * name)
   
   exit_loop_timer_->interactor = view_->GetInteractor ();
   
-  //defaulat state
+  //default state
   win_width_ = 640;
   win_height_ = 480;
   bkg_color_[0] = 1; bkg_color_[1] = 1; bkg_color_[2] = 1;
index 15acf7eceb639df735c7b01afc39ff82712af07b..707f79240bad283ce1cb7927904d8a59fc4eb86c 100644 (file)
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
 pcl::visualization::PCLPlotter::PCLPlotter (char const *name)
+  : view_ (vtkSmartPointer<vtkContextView>::New ())
+  , chart_(vtkSmartPointer<vtkChartXY>::New())
+  , color_series_(vtkSmartPointer<vtkColorSeries>::New ())
+  , exit_loop_timer_(vtkSmartPointer<ExitMainLoopTimerCallback>::New ())
+  , exit_callback_(vtkSmartPointer<ExitCallback>::New ())
 {
-  //constructing
-  view_ = vtkSmartPointer<vtkContextView>::New ();
-  chart_=vtkSmartPointer<vtkChartXY>::New();
-  color_series_ = vtkSmartPointer<vtkColorSeries>::New ();
-  exit_loop_timer_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
-  exit_callback_ = vtkSmartPointer<ExitCallback>::New ();
-  
   //connecting and mandatory bookkeeping
   view_->GetScene ()->AddItem (chart_);
   view_->GetRenderWindow ()->SetWindowName (name);
@@ -147,7 +145,7 @@ pcl::visualization::PCLPlotter::addPlotData (
     int type /* = vtkChart::LINE */, 
     std::vector<char> const &color)
 {
-  this->addPlotData (&array_X[0], &array_Y[0], static_cast<unsigned long> (array_X.size ()), name, type, (color.empty ()) ? nullptr : &color[0]);
+  this->addPlotData (array_X.data(), array_Y.data(), static_cast<unsigned long> (array_X.size ()), name, type, (color.empty ()) ? nullptr : color.data());
 }
 
 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -166,7 +164,7 @@ pcl::visualization::PCLPlotter::addPlotData (
     array_x[i] = plot_data[i].first;
     array_y[i] = plot_data[i].second;
   }
-  this->addPlotData (array_x, array_y, static_cast<unsigned long> (plot_data.size ()), name, type, (color.empty ()) ? nullptr : &color[0]);
+  this->addPlotData (array_x, array_y, static_cast<unsigned long> (plot_data.size ()), name, type, (color.empty ()) ? nullptr : color.data());
   delete[] array_x;
   delete[] array_y;
 }
@@ -264,7 +262,7 @@ pcl::visualization::PCLPlotter::addPlotData (
   while (ss >> temp)
     pnames.push_back(temp);
     
-  int nop = int (pnames.size ());// number of plots (y coordinate vectors)  
+  int nop = static_cast<int>(pnames.size ());// number of plots (y coordinate vectors)  
   
   std::vector<double> xarray;      //array of X coordinates
   std::vector< std::vector<double> > yarrays (nop); //a set of array of Y coordinates
@@ -614,8 +612,8 @@ pcl::visualization::PCLPlotter::computeHistogram (
   {
     if (std::isfinite (value))
     {
-      auto index = (unsigned int) (std::floor ((value - min) / size));
-      if (index == (unsigned int) nbins) index = nbins - 1; //including right boundary
+      auto index = static_cast<unsigned int>(std::floor ((value - min) / size));
+      if (index == static_cast<unsigned int>(nbins)) index = nbins - 1; //including right boundary
       histogram[index].second++;
     }
   }
index 70657c3d6bbc1131546ba7b503f33f70cf29ddab..85c4061fb45726f2d9bb0868363379adc963bdac 100644 (file)
 #include <vtkEDLShading.h>
 #endif
 
+#include <pcl/common/time.h>
 #include <pcl/visualization/common/shapes.h>
 #include <pcl/visualization/pcl_visualizer.h>
-#include <pcl/visualization/common/common.h>
-#include <pcl/common/time.h>
+
 #include <boost/version.hpp> // for BOOST_VERSION
 #if (BOOST_VERSION >= 106600)
 #include <boost/uuid/detail/sha1.hpp>
@@ -182,8 +182,6 @@ pcl::visualization::details::fillCells(std::vector<int>& lookup, const std::vect
 /////////////////////////////////////////////////////////////////////////////////////////////
 pcl::visualization::PCLVisualizer::PCLVisualizer (const std::string &name, const bool create_interactor)
   : update_fps_ (vtkSmartPointer<FPSCallback>::New ())
-  , stopped_ ()
-  , timer_id_ ()
   , rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
   , win_ (vtkSmartPointer<vtkRenderWindow>::New ())
   , style_ (vtkSmartPointer<pcl::visualization::PCLVisualizerInteractorStyle>::New ())
@@ -207,8 +205,6 @@ pcl::visualization::PCLVisualizer::PCLVisualizer (const std::string &name, const
 /////////////////////////////////////////////////////////////////////////////////////////////
 pcl::visualization::PCLVisualizer::PCLVisualizer (int &argc, char **argv, const std::string &name, PCLVisualizerInteractorStyle* style, const bool create_interactor)
   : update_fps_ (vtkSmartPointer<FPSCallback>::New ())
-  , stopped_ ()
-  , timer_id_ ()
   , rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
   , win_ (vtkSmartPointer<vtkRenderWindow>::New ())
   , style_ (style)
@@ -239,8 +235,6 @@ pcl::visualization::PCLVisualizer::PCLVisualizer (int &argc, char **argv, const
 pcl::visualization::PCLVisualizer::PCLVisualizer (vtkSmartPointer<vtkRenderer> ren, vtkSmartPointer<vtkRenderWindow> wind,
                                                   const std::string &name, const bool create_interactor)
   : update_fps_ (vtkSmartPointer<FPSCallback>::New ())
-  , stopped_ ()
-  , timer_id_ ()
   , rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
   , win_ (wind)
   , style_ (vtkSmartPointer<pcl::visualization::PCLVisualizerInteractorStyle>::New ())
@@ -264,8 +258,6 @@ pcl::visualization::PCLVisualizer::PCLVisualizer (vtkSmartPointer<vtkRenderer> r
 pcl::visualization::PCLVisualizer::PCLVisualizer (int &argc, char **argv, vtkSmartPointer<vtkRenderer> ren, vtkSmartPointer<vtkRenderWindow> wind,
                                                   const std::string &name, PCLVisualizerInteractorStyle* style, const bool create_interactor)
   : update_fps_ (vtkSmartPointer<FPSCallback>::New ())
-  , stopped_ ()
-  , timer_id_ ()
   , rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
   , win_ (wind)
   , style_ (style)
@@ -593,11 +585,24 @@ pcl::visualization::PCLVisualizer::spinOnce (int time, bool force_redraw)
 
 #if VTK_MAJOR_VERSION >= 9 && (VTK_MINOR_VERSION != 0 || VTK_BUILD_VERSION != 0) && (VTK_MINOR_VERSION != 0 || VTK_BUILD_VERSION != 1)
 // All VTK 9 versions, except 9.0.0 and 9.0.1
-  if(interactor_->IsA("vtkXRenderWindowInteractor")) {
-    DO_EVERY (1.0 / interactor_->GetDesiredUpdateRate (),
-      interactor_->ProcessEvents ();
-      std::this_thread::sleep_for (std::chrono::milliseconds (time));
-    );
+  if (interactor_->IsA("vtkXRenderWindowInteractor") || interactor_->IsA("vtkWin32RenderWindowInteractor")) {
+    const auto start_time = std::chrono::steady_clock::now();
+    const auto stop_time = start_time + std::chrono::milliseconds(time);
+
+    // Older versions of VTK 9 block for up to 1s or more on X11 when there are no events.
+    // So add a one-shot timer to guarantee an event will happen roughly by the time the user expects this function to return
+    // https://gitlab.kitware.com/vtk/vtk/-/issues/18951#note_1351387
+    interactor_->CreateOneShotTimer(time);
+
+    // Process any pending events at least once, this could take a while due to a long running render event
+    interactor_->ProcessEvents();
+
+    // Wait for the requested amount of time to have elapsed or exit immediately via GetDone being true when terminateApp is called
+    while(std::chrono::steady_clock::now() < stop_time && !interactor_->GetDone() )
+    {
+      interactor_->ProcessEvents();
+      std::this_thread::sleep_for(std::chrono::milliseconds(1));
+    }
   }
   else
 #endif
@@ -1197,7 +1202,7 @@ pcl::visualization::PCLVisualizer::createActorFromVTKDataSet (const vtkSmartPoin
     }
   }
 
-  actor->SetNumberOfCloudPoints (int (std::max<vtkIdType> (1, data->GetNumberOfPoints () / 10)));
+  actor->SetNumberOfCloudPoints (static_cast<int>(std::max<vtkIdType> (1, data->GetNumberOfPoints () / 10)));
   actor->GetProperty ()->SetInterpolationToFlat ();
 
   /// FIXME disabling backface culling due to known VTK bug: vtkTextActors are not
@@ -1527,7 +1532,7 @@ pcl::visualization::PCLVisualizer::setPointCloudRenderingProperties (
   {
     case PCL_VISUALIZER_POINT_SIZE:
     {
-      actor->GetProperty ()->SetPointSize (float (value));
+      actor->GetProperty ()->SetPointSize (static_cast<float>(value));
       actor->Modified ();
       break;
     }
@@ -1549,7 +1554,7 @@ pcl::visualization::PCLVisualizer::setPointCloudRenderingProperties (
     }
     case PCL_VISUALIZER_LINE_WIDTH:
     {
-      actor->GetProperty ()->SetLineWidth (float (value));
+      actor->GetProperty ()->SetLineWidth (static_cast<float>(value));
       actor->Modified ();
       break;
     }
@@ -1587,7 +1592,7 @@ pcl::visualization::PCLVisualizer::setPointCloudRenderingProperties (
       if (actor->GetMapper ()->GetInput ()->GetPointData ()->GetScalars ()->IsA ("vtkUnsignedCharArray"))
         break;
 
-      switch (int(value))
+      switch (static_cast<int>(value))
       {
         case PCL_VISUALIZER_LUT_RANGE_AUTO:
           double range[2];
@@ -1617,7 +1622,7 @@ pcl::visualization::PCLVisualizer::setPointCloudSelected (const bool selected, c
 
   if (am_it == cloud_actor_map_->end ())
   {
-    pcl::console::print_error ("[setPointCloudRenderingProperties] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ());
+    pcl::console::print_error ("[setPointCloudSelected] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ());
     return (false);
   }
   // Get the actor pointer
@@ -1761,7 +1766,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties (
   {
     case PCL_VISUALIZER_POINT_SIZE:
     {
-      actor->GetProperty ()->SetPointSize (float (value));
+      actor->GetProperty ()->SetPointSize (static_cast<float>(value));
       actor->Modified ();
       break;
     }
@@ -1773,7 +1778,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties (
     }
     case PCL_VISUALIZER_LINE_WIDTH:
     {
-      actor->GetProperty ()->SetLineWidth (float (value));
+      actor->GetProperty ()->SetLineWidth (static_cast<float>(value));
       actor->Modified ();
       break;
     }
@@ -1783,13 +1788,13 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties (
       if (!text_actor)
         return (false);
       vtkSmartPointer<vtkTextProperty> tprop = text_actor->GetTextProperty ();
-      tprop->SetFontSize (int (value));
+      tprop->SetFontSize (static_cast<int>(value));
       text_actor->Modified ();
       break;
     }
     case PCL_VISUALIZER_REPRESENTATION:
     {
-      switch (int (value))
+      switch (static_cast<int>(value))
       {
         case PCL_VISUALIZER_REPRESENTATION_POINTS:
         {
@@ -1812,7 +1817,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties (
     }
     case PCL_VISUALIZER_SHADING:
     {
-      switch (int (value))
+      switch (static_cast<int>(value))
       {
         case PCL_VISUALIZER_SHADING_FLAT:
         {
@@ -1881,7 +1886,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties (
       if (actor->GetMapper ()->GetInput ()->GetPointData ()->GetScalars ()->IsA ("vtkUnsignedCharArray"))
         break;
 
-      switch (int(value))
+      switch (static_cast<int>(value))
       {
         case PCL_VISUALIZER_LUT_RANGE_AUTO:
           double range[2];
@@ -2948,9 +2953,9 @@ pcl::visualization::PCLVisualizer::updateColorHandlerIndex (const std::string &i
   }
 
   std::size_t color_handler_size = am_it->second.color_handlers.size ();
-  if (!(std::size_t (index) < color_handler_size))
+  if (!(static_cast<std::size_t>(index) < color_handler_size))
   {
-    pcl::console::print_warn (stderr, "[updateColorHandlerIndex] Invalid index <%d> given! Index must be less than %d.\n", index, int (color_handler_size));
+    pcl::console::print_warn (stderr, "[updateColorHandlerIndex] Invalid index <%d> given! Index must be less than %d.\n", index, static_cast<int>(color_handler_size));
     return (false);
   }
   // Get the handler
@@ -3373,7 +3378,7 @@ pcl::visualization::PCLVisualizer::addTextureMesh (const pcl::TextureMesh &mesh,
     return (false);
   // hardware always supports multitexturing of some degree
   int texture_units = tex_manager->GetNumberOfTextureUnits ();
-  if ((std::size_t) texture_units < mesh.tex_materials.size ())
+  if (static_cast<std::size_t>(texture_units) < mesh.tex_materials.size ())
     PCL_WARN ("[PCLVisualizer::addTextureMesh] GPU texture units %d < mesh textures %d!\n",
               texture_units, mesh.tex_materials.size ());
   // Load textures
@@ -3650,7 +3655,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere (
       sphere->GetPoint (ptIds_com[1], p2_com);
       sphere->GetPoint (ptIds_com[2], p3_com);
       vtkTriangle::TriangleCenter (p1_com, p2_com, p3_com, center);
-      cam_positions[i] = Eigen::Vector3f (float (center[0]), float (center[1]), float (center[2]));
+      cam_positions[i] = Eigen::Vector3f (static_cast<float>(center[0]), static_cast<float>(center[1]), static_cast<float>(center[2]));
       cam_positions[i].normalize ();
       i++;
     }
@@ -3663,7 +3668,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere (
     {
       double cam_pos[3];
       sphere->GetPoint (i, cam_pos);
-      cam_positions[i] = Eigen::Vector3f (float (cam_pos[0]), float (cam_pos[1]), float (cam_pos[2]));
+      cam_positions[i] = Eigen::Vector3f (static_cast<float>(cam_pos[0]), static_cast<float>(cam_pos[1]), static_cast<float>(cam_pos[2]));
       cam_positions[i].normalize ();
     }
   }
@@ -3958,8 +3963,8 @@ pcl::visualization::PCLVisualizer::renderView (int xres, int yres, pcl::PointClo
   win_->SetSize (xres, yres);
   win_->Render ();
 
-  float dwidth = 2.0f / float (xres),
-        dheight = 2.0f / float (yres);
+  float dwidth = 2.0f / static_cast<float>(xres),
+        dheight = 2.0f / static_cast<float>(yres);
 
   cloud->points.resize (xres * yres);
   cloud->width = xres;
@@ -3997,8 +4002,8 @@ pcl::visualization::PCLVisualizer::renderView (int xres, int yres, pcl::PointClo
         continue;
       }
 
-      Eigen::Vector4f world_coords (dwidth  * float (x) - 1.0f,
-                                    dheight * float (y) - 1.0f,
+      Eigen::Vector4f world_coords (dwidth  * static_cast<float>(x) - 1.0f,
+                                    dheight * static_cast<float>(y) - 1.0f,
                                     depth[ptr],
                                     1.0f);
       world_coords = mat2 * mat1 * world_coords;
index ee9f06cf4ed949f14ca1af499aad273fd50338c6..4b70dd9ec17a954e2da898d5348526006d0b2ca4 100644 (file)
@@ -181,9 +181,10 @@ pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>::getColo
   }
   if (j != 0)
     scalars->SetArray (colors, j, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE);
-  else
+  else {
     scalars->SetNumberOfTuples (0);
-  //delete [] colors;
+    delete [] colors;
+  }
   return scalars;
 }
 
@@ -418,10 +419,7 @@ pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2>::Poi
   field_name_ (field_name)
 {
   field_idx_  = pcl::getFieldIndex (*cloud, field_name);
-  if (field_idx_ != -1)
-    capable_ = true;
-  else
-    capable_ = false;
+  capable_ = field_idx_ != -1;
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////
@@ -493,10 +491,7 @@ pcl::visualization::PointCloudColorHandlerRGBAField<pcl::PCLPointCloud2>::PointC
 {
   // Handle the 24-bit packed RGBA values
   field_idx_ = pcl::getFieldIndex (*cloud, "rgba");
-  if (field_idx_ != -1)
-    capable_ = true;
-  else
-    capable_ = false;
+  capable_ = field_idx_ != -1;
 }
 
 ///////////////////////////////////////////////////////////////////////////////////////////
@@ -565,9 +560,10 @@ pcl::visualization::PointCloudColorHandlerRGBAField<pcl::PCLPointCloud2>::getCol
   }
   if (j != 0)
     scalars->SetArray (colors, j, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE);
-  else
+  else {
     scalars->SetNumberOfTuples (0);
-  //delete [] colors;
+    delete [] colors;
+  }
   return scalars;
 }
 
@@ -577,10 +573,7 @@ pcl::visualization::PointCloudColorHandlerLabelField<pcl::PCLPointCloud2>::Point
 : pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudColorHandler (cloud)
 {
   field_idx_ = pcl::getFieldIndex (*cloud, "label");
-  if (field_idx_ != -1)
-    capable_ = true;
-  else
-    capable_ = false;
+  capable_ = field_idx_ != -1;
   static_mapping_ = static_mapping;
 }
 
@@ -670,9 +663,10 @@ pcl::visualization::PointCloudColorHandlerLabelField<pcl::PCLPointCloud2>::getCo
   }
   if (j != 0)
     scalars->SetArray (colors, j, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE);
-  else
+  else {
     scalars->SetNumberOfTuples (0);
-  //delete [] colors;
+    delete [] colors;
+  }
   return scalars;
 }
 
index cb13eea1a3c3f03c3da883875503249d10f2b4a0..aae888cb5d3d03ec3a0a2ebc986ee97a293aa257 100644 (file)
@@ -161,7 +161,7 @@ pcl::visualization::PointPickingCallback::performSinglePick (
   {
     double p[3];
     point_picker->GetDataSet ()->GetPoint (idx, p);
-    x = float (p[0]); y = float (p[1]); z = float (p[2]);
+    x = static_cast<float>(p[0]); y = static_cast<float>(p[1]); z = static_cast<float>(p[2]);
     actor_ = point_picker->GetActor();
   }
 
index 48d1cf3c6a86784da47a31c7d66643adc2196850..19a436dc534b2c8700fa22863cdd3f8a17d27d26 100644 (file)
@@ -197,7 +197,7 @@ pcl::visualization::context_items::Polygon::Paint (vtkContext2D *painter)
 {
   painter->GetBrush ()->SetColor (colors[0], colors[1], colors[2], static_cast<unsigned char> ((255.0 * GetOpacity ())));
   painter->GetPen ()->SetColor (colors[0], colors[1], colors[2], static_cast<unsigned char> ((255.0 * GetOpacity ())));
-  painter->DrawPolygon (&params[0], static_cast<int> (params.size () / 2));
+  painter->DrawPolygon (params.data(), static_cast<int> (params.size () / 2));
   return (true);
 }
 
@@ -215,7 +215,7 @@ bool
 pcl::visualization::context_items::Points::Paint (vtkContext2D *painter)
 {
   painter->GetPen ()->SetColor (colors[0], colors[1], colors[2], static_cast<unsigned char> ((255.0 * GetOpacity ())));
-  painter->DrawPoints (&params[0], static_cast<int> (params.size () / 2));
+  painter->DrawPoints (params.data(), static_cast<int> (params.size () / 2));
   return (true);
 }
 
@@ -259,10 +259,10 @@ pcl::visualization::context_items::Markers::Paint (vtkContext2D *painter)
 
   painter->GetPen ()->SetWidth (size);
   painter->GetPen ()->SetColor (colors[0], colors[1], colors[2], static_cast<unsigned char> ((255.0 * GetOpacity ())));
-  painter->DrawPointSprites (nullptr, &params[0], nb_points);
+  painter->DrawPointSprites (nullptr, params.data(), nb_points);
   painter->GetPen ()->SetWidth (1);
   painter->GetPen ()->SetColor (point_colors[0], point_colors[1], point_colors[2], static_cast<unsigned char> ((255.0 * GetOpacity ())));
-  painter->DrawPointSprites (nullptr, &params[0], nb_points);
+  painter->DrawPointSprites (nullptr, params.data(), nb_points);
   return (true);
 }
 
index 07a0d08318788cb80e035fb1ec625c8d1cba87cc..60faa683e5a811a51a62f3529dc73b8dedd168b3 100644 (file)
@@ -794,7 +794,7 @@ void vtkXRenderWindowInteractor::DispatchEvent(XEvent* event)
       this->InvokeEvent(vtkCommand::DropFilesEvent, filePaths);
       XFree(data);
 
-      // Inform the source the the drag and drop operation was sucessfull
+      // Inform the source the the drag and drop operation was successful
       XEvent reply;
       memset(&reply, 0, sizeof(reply));
 
index 53b04809920df0a252e06807fbdcf155bc958e3d..652d6efabe9a2db5c02c4266762746cd44f54fdc 100644 (file)
@@ -50,9 +50,8 @@
 
 /////////////////////////////////////////////////////////////////////////////////////////////
 pcl::visualization::Window::Window (const std::string& window_name)
-  : stopped_ ()
-  , timer_id_ ()
-  , mouse_command_ (vtkCallbackCommand::New ())
+  : 
+   mouse_command_ (vtkCallbackCommand::New ())
   , keyboard_command_ (vtkCallbackCommand::New ())
   , style_ (vtkSmartPointer<pcl::visualization::PCLVisualizerInteractorStyle>::New ())
   , rens_ (vtkSmartPointer<vtkRendererCollection>::New ())
@@ -301,7 +300,7 @@ pcl::visualization::Window::emitMouseEvent (unsigned long event_id)
 void 
 pcl::visualization::Window::emitKeyboardEvent (unsigned long event_id)
 {
-  KeyboardEvent event (bool(event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
+  KeyboardEvent event ((event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ());
   keyboard_signal_ (event);
 }
 
@@ -322,10 +321,7 @@ pcl::visualization::Window::KeyboardCallback (vtkObject*, unsigned long eid, voi
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////////
-pcl::visualization::Window::ExitMainLoopTimerCallback::ExitMainLoopTimerCallback () 
-  : right_timer_id (-1), window (nullptr) 
-{
-}
+pcl::visualization::Window::ExitMainLoopTimerCallback::ExitMainLoopTimerCallback () = default;
 
 /////////////////////////////////////////////////////////////////////////////////////////////
 void
@@ -342,10 +338,7 @@ pcl::visualization::Window::ExitMainLoopTimerCallback::Execute (
 }
 
 /////////////////////////////////////////////////////////////////////////////////////////////
-pcl::visualization::Window::ExitCallback::ExitCallback () 
-  : window (nullptr)
-{
-}
+pcl::visualization::Window::ExitCallback::ExitCallback () = default;
 
 /////////////////////////////////////////////////////////////////////////////////////////////
 void