From 9f7a246f962aa26740b8ded6f45e8a8ae944d588 Mon Sep 17 00:00:00 2001 From: Heiko Thiel Date: Tue, 13 Nov 2018 17:48:21 +0100 Subject: [PATCH] Replace include guards in all *.h-files by #pragma once Fixes #429 --- 2d/include/pcl/2d/convolution.h | 4 +--- 2d/include/pcl/2d/edge.h | 6 +----- 2d/include/pcl/2d/kernel.h | 7 +++---- 2d/include/pcl/2d/keypoint.h | 5 +---- 2d/include/pcl/2d/morphology.h | 5 +---- .../include/pcl/apps/in_hand_scanner/boost.h | 5 +---- .../include/pcl/apps/in_hand_scanner/common_types.h | 5 +---- .../include/pcl/apps/in_hand_scanner/eigen.h | 5 +---- .../include/pcl/apps/in_hand_scanner/help_window.h | 6 +----- .../include/pcl/apps/in_hand_scanner/icp.h | 5 +---- .../pcl/apps/in_hand_scanner/in_hand_scanner.h | 5 +---- .../pcl/apps/in_hand_scanner/input_data_processing.h | 5 +---- .../include/pcl/apps/in_hand_scanner/integration.h | 5 +---- .../include/pcl/apps/in_hand_scanner/main_window.h | 5 +---- .../pcl/apps/in_hand_scanner/mesh_processing.h | 5 +---- .../pcl/apps/in_hand_scanner/offline_integration.h | 5 +---- .../include/pcl/apps/in_hand_scanner/opengl_viewer.h | 5 +---- .../include/pcl/apps/in_hand_scanner/utils.h | 5 +---- .../pcl/apps/in_hand_scanner/visibility_confidence.h | 5 +---- apps/include/pcl/apps/openni_passthrough.h | 5 +---- apps/include/pcl/apps/openni_passthrough_qt.h | 5 +---- apps/include/pcl/apps/organized_segmentation_demo.h | 5 +---- .../include/pcl/apps/organized_segmentation_demo_qt.h | 5 +---- apps/include/pcl/apps/timer.h | 5 +---- apps/modeler/include/pcl/apps/modeler/abstract_item.h | 5 +---- .../include/pcl/apps/modeler/abstract_worker.h | 5 +---- .../include/pcl/apps/modeler/channel_actor_item.h | 6 ++---- apps/modeler/include/pcl/apps/modeler/cloud_mesh.h | 6 ++---- .../include/pcl/apps/modeler/cloud_mesh_item.h | 6 ++---- .../pcl/apps/modeler/cloud_mesh_item_updater.h | 6 ++---- apps/modeler/include/pcl/apps/modeler/dock_widget.h | 5 +---- .../pcl/apps/modeler/icp_registration_worker.h | 5 +---- apps/modeler/include/pcl/apps/modeler/main_window.h | 5 +---- .../pcl/apps/modeler/normal_estimation_worker.h | 4 +--- .../include/pcl/apps/modeler/normals_actor_item.h | 6 ++---- apps/modeler/include/pcl/apps/modeler/parameter.h | 6 ++---- .../include/pcl/apps/modeler/parameter_dialog.h | 6 ++---- .../include/pcl/apps/modeler/points_actor_item.h | 6 ++---- .../modeler/include/pcl/apps/modeler/poisson_worker.h | 5 +---- apps/modeler/include/pcl/apps/modeler/qt.h | 5 +---- apps/modeler/include/pcl/apps/modeler/render_window.h | 5 +---- .../include/pcl/apps/modeler/render_window_item.h | 5 +---- apps/modeler/include/pcl/apps/modeler/scene_tree.h | 5 +---- .../apps/modeler/statistical_outlier_removal_worker.h | 5 +---- .../include/pcl/apps/modeler/surface_actor_item.h | 6 ++---- .../include/pcl/apps/modeler/thread_controller.h | 5 +---- .../pcl/apps/modeler/voxel_grid_downsample_worker.h | 5 +---- .../include/pcl/apps/optronic_viewer/cloud_filter.h | 5 +---- .../include/pcl/apps/optronic_viewer/filter_window.h | 5 +---- .../include/pcl/apps/optronic_viewer/main_window.h | 5 +---- .../include/pcl/apps/optronic_viewer/openni_grabber.h | 5 +---- .../include/pcl/apps/optronic_viewer/qt.h | 5 +---- common/include/pcl/ModelCoefficients.h | 7 ++----- common/include/pcl/PCLHeader.h | 6 +----- common/include/pcl/PCLImage.h | 7 ++----- common/include/pcl/PCLPointCloud2.h | 6 +----- common/include/pcl/PCLPointField.h | 6 +----- common/include/pcl/PointIndices.h | 7 ++----- common/include/pcl/PolygonMesh.h | 7 ++----- common/include/pcl/TextureMesh.h | 6 +----- common/include/pcl/Vertices.h | 7 ++----- common/include/pcl/cloud_iterator.h | 5 +---- common/include/pcl/common/angles.h | 5 +---- common/include/pcl/common/boost.h | 5 +---- common/include/pcl/common/centroid.h | 5 +---- common/include/pcl/common/colors.h | 6 +----- common/include/pcl/common/common.h | 5 +---- common/include/pcl/common/common_headers.h | 5 +---- common/include/pcl/common/concatenate.h | 7 ++----- common/include/pcl/common/copy_point.h | 6 +----- common/include/pcl/common/distances.h | 7 ++----- common/include/pcl/common/eigen.h | 6 ++---- common/include/pcl/common/feature_histogram.h | 4 +--- common/include/pcl/common/file_io.h | 5 +---- common/include/pcl/common/gaussian.h | 5 +---- common/include/pcl/common/generate.h | 5 +---- common/include/pcl/common/geometry.h | 6 +----- common/include/pcl/common/intensity.h | 5 +---- common/include/pcl/common/intersections.h | 5 +---- common/include/pcl/common/io.h | 6 +----- common/include/pcl/common/norms.h | 5 +---- common/include/pcl/common/pca.h | 6 +----- common/include/pcl/common/piecewise_linear_function.h | 5 +---- common/include/pcl/common/point_operators.h | 5 +---- common/include/pcl/common/point_tests.h | 6 +----- common/include/pcl/common/polynomial_calculations.h | 5 +---- common/include/pcl/common/poses_from_matches.h | 5 +---- common/include/pcl/common/random.h | 5 +---- common/include/pcl/common/spring.h | 5 +---- common/include/pcl/common/time.h | 5 +---- common/include/pcl/common/time_trigger.h | 5 +---- .../pcl/common/transformation_from_correspondences.h | 6 +----- common/include/pcl/common/transforms.h | 6 ++---- common/include/pcl/common/utils.h | 5 +---- common/include/pcl/common/vector_average.h | 6 +----- common/include/pcl/console/parse.h | 7 ++----- common/include/pcl/conversions.h | 5 +---- common/include/pcl/correspondence.h | 6 ++---- common/include/pcl/exceptions.h | 8 ++------ common/include/pcl/for_each_type.h | 5 +---- common/include/pcl/pcl_base.h | 6 ++---- common/include/pcl/pcl_exports.h | 5 +---- common/include/pcl/pcl_macros.h | 5 +---- common/include/pcl/pcl_tests.h | 6 +----- common/include/pcl/point_cloud.h | 5 +---- common/include/pcl/point_representation.h | 6 ++---- common/include/pcl/point_traits.h | 5 +---- common/include/pcl/point_types.h | 6 ++---- common/include/pcl/point_types_conversion.h | 6 +----- common/include/pcl/range_image/bearing_angle_image.h | 5 +---- common/include/pcl/range_image/range_image.h | 5 +---- common/include/pcl/range_image/range_image_planar.h | 5 +---- .../include/pcl/range_image/range_image_spherical.h | 5 +---- common/include/pcl/register_point_struct.h | 5 +---- common/include/pcl/sse.h | 5 ++--- cuda/common/include/pcl/cuda/common/eigen.h | 5 +---- cuda/common/include/pcl/cuda/common/point_type_rgb.h | 5 +---- cuda/common/include/pcl/cuda/pcl_cuda_base.h | 6 ++---- cuda/common/include/pcl/cuda/point_cloud.h | 5 +---- cuda/common/include/pcl/cuda/point_types.h | 6 +----- cuda/common/include/pcl/cuda/thrust.h | 6 +----- cuda/common/include/pcl/cuda/time_cpu.h | 5 +---- cuda/common/include/pcl/cuda/time_gpu.h | 5 +---- cuda/features/include/pcl/cuda/features/normal_3d.h | 7 +------ .../include/pcl/cuda/features/normal_3d_kernels.h | 7 +------ cuda/filters/include/pcl/cuda/filters/filter.h | 5 +---- cuda/filters/include/pcl/cuda/filters/passthrough.h | 5 +---- cuda/filters/include/pcl/cuda/filters/voxel_grid.h | 5 +---- cuda/io/include/pcl/cuda/io/cloud_to_pcl.h | 5 +---- cuda/io/include/pcl/cuda/io/debayering.h | 5 +---- cuda/io/include/pcl/cuda/io/disparity_to_cloud.h | 5 +---- cuda/io/include/pcl/cuda/io/extract_indices.h | 6 +----- cuda/io/include/pcl/cuda/io/host_device.h | 5 +---- cuda/io/include/pcl/cuda/io/kinect_smoothing.h | 6 +----- cuda/io/include/pcl/cuda/io/predicate.h | 7 +------ .../include/pcl/cuda/sample_consensus/msac.h | 6 +----- .../include/pcl/cuda/sample_consensus/multi_ransac.h | 6 +----- .../include/pcl/cuda/sample_consensus/ransac.h | 6 +----- .../include/pcl/cuda/sample_consensus/sac.h | 5 +---- .../include/pcl/cuda/sample_consensus/sac_model.h | 5 +---- .../cuda/sample_consensus/sac_model_1point_plane.h | 5 +---- .../pcl/cuda/sample_consensus/sac_model_plane.h | 5 +---- features/include/pcl/features/3dsc.h | 5 +---- features/include/pcl/features/board.h | 5 +---- features/include/pcl/features/boost.h | 5 +---- features/include/pcl/features/boundary.h | 5 +---- features/include/pcl/features/brisk_2d.h | 5 +---- features/include/pcl/features/cppf.h | 5 +---- features/include/pcl/features/crh.h | 5 +---- features/include/pcl/features/cvfh.h | 5 +---- features/include/pcl/features/don.h | 6 ++---- features/include/pcl/features/eigen.h | 5 +---- features/include/pcl/features/esf.h | 6 ++---- features/include/pcl/features/feature.h | 5 +---- features/include/pcl/features/flare.h | 5 +---- features/include/pcl/features/fpfh.h | 5 +---- features/include/pcl/features/fpfh_omp.h | 5 +---- features/include/pcl/features/from_meshes.h | 8 +------- features/include/pcl/features/gasd.h | 5 +---- features/include/pcl/features/gfpfh.h | 5 +---- features/include/pcl/features/grsd.h | 5 +---- features/include/pcl/features/integral_image2D.h | 6 +----- features/include/pcl/features/integral_image_normal.h | 6 +----- features/include/pcl/features/intensity_gradient.h | 6 ++---- features/include/pcl/features/intensity_spin.h | 8 +++++--- .../pcl/features/linear_least_squares_normal.h | 6 +----- features/include/pcl/features/moment_invariants.h | 5 +---- .../pcl/features/moment_of_inertia_estimation.h | 5 +---- .../pcl/features/multiscale_feature_persistence.h | 5 +---- features/include/pcl/features/narf.h | 5 +---- features/include/pcl/features/narf_descriptor.h | 5 +---- features/include/pcl/features/normal_3d.h | 6 +----- features/include/pcl/features/normal_3d_omp.h | 5 +---- .../include/pcl/features/normal_based_signature.h | 5 +---- .../include/pcl/features/organized_edge_detection.h | 5 +---- features/include/pcl/features/our_cvfh.h | 5 +---- features/include/pcl/features/pfh.h | 6 +----- features/include/pcl/features/pfh_tools.h | 6 +----- features/include/pcl/features/pfhrgb.h | 5 +---- features/include/pcl/features/ppf.h | 5 +---- features/include/pcl/features/ppfrgb.h | 5 +---- features/include/pcl/features/principal_curvatures.h | 5 +---- .../pcl/features/range_image_border_extractor.h | 5 +---- features/include/pcl/features/rift.h | 5 +---- features/include/pcl/features/rops_estimation.h | 5 +---- features/include/pcl/features/rsd.h | 5 +---- features/include/pcl/features/shot.h | 5 +---- features/include/pcl/features/shot_lrf.h | 6 +----- features/include/pcl/features/shot_lrf_omp.h | 6 +----- features/include/pcl/features/shot_omp.h | 5 +---- features/include/pcl/features/spin_image.h | 6 +----- features/include/pcl/features/usc.h | 5 +---- features/include/pcl/features/vfh.h | 5 +---- filters/include/pcl/filters/approximate_voxel_grid.h | 5 +---- filters/include/pcl/filters/bilateral.h | 5 +---- filters/include/pcl/filters/boost.h | 5 +---- filters/include/pcl/filters/box_clipper3D.h | 6 ++---- filters/include/pcl/filters/clipper3D.h | 6 ++---- filters/include/pcl/filters/conditional_removal.h | 6 ++---- filters/include/pcl/filters/convolution.h | 5 +---- filters/include/pcl/filters/convolution_3d.h | 5 +---- filters/include/pcl/filters/covariance_sampling.h | 7 +------ filters/include/pcl/filters/crop_box.h | 5 +---- filters/include/pcl/filters/crop_hull.h | 5 +---- filters/include/pcl/filters/extract_indices.h | 6 +----- filters/include/pcl/filters/fast_bilateral.h | 7 +------ filters/include/pcl/filters/fast_bilateral_omp.h | 8 +------- filters/include/pcl/filters/filter.h | 5 +---- filters/include/pcl/filters/filter_indices.h | 6 +----- filters/include/pcl/filters/frustum_culling.h | 6 +----- filters/include/pcl/filters/grid_minimum.h | 6 +----- filters/include/pcl/filters/local_maximum.h | 6 +----- filters/include/pcl/filters/median_filter.h | 5 +---- filters/include/pcl/filters/model_outlier_removal.h | 5 +---- filters/include/pcl/filters/morphological_filter.h | 6 +----- filters/include/pcl/filters/normal_refinement.h | 5 +---- filters/include/pcl/filters/normal_space.h | 5 +---- filters/include/pcl/filters/passthrough.h | 6 +----- filters/include/pcl/filters/plane_clipper3D.h | 6 ++---- filters/include/pcl/filters/project_inliers.h | 5 +---- filters/include/pcl/filters/pyramid.h | 5 +---- filters/include/pcl/filters/radius_outlier_removal.h | 6 +----- filters/include/pcl/filters/random_sample.h | 5 +---- filters/include/pcl/filters/sampling_surface_normal.h | 5 +---- filters/include/pcl/filters/shadowpoints.h | 5 +---- .../include/pcl/filters/statistical_outlier_removal.h | 6 +----- filters/include/pcl/filters/uniform_sampling.h | 6 +----- filters/include/pcl/filters/voxel_grid.h | 5 +---- filters/include/pcl/filters/voxel_grid_covariance.h | 5 +---- filters/include/pcl/filters/voxel_grid_label.h | 5 +---- .../pcl/filters/voxel_grid_occlusion_estimation.h | 5 +---- geometry/include/pcl/geometry/boost.h | 5 +---- geometry/include/pcl/geometry/eigen.h | 5 +---- geometry/include/pcl/geometry/get_boundary.h | 5 +---- geometry/include/pcl/geometry/mesh_base.h | 5 +---- geometry/include/pcl/geometry/mesh_circulators.h | 5 +---- geometry/include/pcl/geometry/mesh_conversion.h | 5 +---- geometry/include/pcl/geometry/mesh_elements.h | 5 +---- geometry/include/pcl/geometry/mesh_indices.h | 5 +---- geometry/include/pcl/geometry/mesh_io.h | 5 +---- geometry/include/pcl/geometry/mesh_traits.h | 5 +---- geometry/include/pcl/geometry/planar_polygon.h | 7 +------ geometry/include/pcl/geometry/polygon_mesh.h | 5 +---- geometry/include/pcl/geometry/polygon_operations.h | 4 +--- geometry/include/pcl/geometry/quad_mesh.h | 5 +---- geometry/include/pcl/geometry/triangle_mesh.h | 5 +---- .../include/pcl/gpu/containers/device_array.h | 5 +---- .../include/pcl/gpu/containers/device_memory.h | 5 +---- .../include/pcl/gpu/containers/initialization.h | 5 +---- .../include/pcl/gpu/containers/kernel_containers.h | 8 +------- gpu/kinfu/include/pcl/gpu/kinfu/color_volume.h | 5 +---- gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h | 5 +---- gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h | 5 +---- gpu/kinfu/include/pcl/gpu/kinfu/pixel_rgb.h | 5 +---- gpu/kinfu/include/pcl/gpu/kinfu/raycaster.h | 7 +------ gpu/kinfu/include/pcl/gpu/kinfu/tsdf_volume.h | 5 +---- gpu/kinfu/src/internal.h | 5 +---- .../include/pcl/gpu/kinfu_large_scale/color_volume.h | 5 +---- .../pcl/gpu/kinfu_large_scale/cyclical_buffer.h | 6 +----- .../include/pcl/gpu/kinfu_large_scale/device.h | 5 +---- .../include/pcl/gpu/kinfu_large_scale/kinfu.h | 5 +---- .../pcl/gpu/kinfu_large_scale/marching_cubes.h | 5 +---- .../include/pcl/gpu/kinfu_large_scale/pixel_rgb.h | 6 ++---- .../pcl/gpu/kinfu_large_scale/point_intensity.h | 8 ++------ .../include/pcl/gpu/kinfu_large_scale/raycaster.h | 7 +------ .../pcl/gpu/kinfu_large_scale/screenshot_manager.h | 5 +---- .../gpu/kinfu_large_scale/standalone_marching_cubes.h | 6 +----- .../include/pcl/gpu/kinfu_large_scale/tsdf_buffer.h | 5 +---- .../include/pcl/gpu/kinfu_large_scale/tsdf_volume.h | 5 +---- .../include/pcl/gpu/kinfu_large_scale/world_model.h | 5 +---- gpu/kinfu_large_scale/src/estimate_combined.h | 5 +---- gpu/kinfu_large_scale/src/internal.h | 5 +---- .../include/pcl/gpu/people/bodyparts_detector.h | 6 +----- gpu/people/include/pcl/gpu/people/colormap.h | 4 +--- gpu/people/include/pcl/gpu/people/face_detector.h | 6 +----- gpu/people/include/pcl/gpu/people/label_blob2.h | 5 +---- gpu/people/include/pcl/gpu/people/label_common.h | 5 +---- gpu/people/include/pcl/gpu/people/label_segment.h | 5 +---- gpu/people/include/pcl/gpu/people/label_tree.h | 4 +--- .../include/pcl/gpu/people/organized_plane_detector.h | 5 +---- gpu/people/include/pcl/gpu/people/people_detector.h | 4 +--- .../include/pcl/gpu/people/probability_processor.h | 5 +---- gpu/people/include/pcl/gpu/people/tree.h | 4 +--- gpu/people/include/pcl/gpu/people/tree_train.h | 4 +--- gpu/people/src/cuda/device.h | 5 +---- gpu/people/src/cuda_async_copy.h | 7 +------ gpu/people/src/internal.h | 5 +---- .../pcl/gpu/segmentation/gpu_extract_clusters.h | 9 +-------- .../gpu/segmentation/gpu_extract_labeled_clusters.h | 6 +----- .../gpu/segmentation/gpu_seeded_hue_segmentation.h | 11 +---------- gpu/surface/include/pcl/gpu/surface/convex_hull.h | 6 +----- gpu/surface/src/cuda/device.h | 5 +---- gpu/surface/src/internal.h | 5 +---- .../include/pcl/gpu/tracking/particle_filter.h | 5 +---- gpu/tracking/src/internal.h | 6 +----- .../compression/organized_pointcloud_compression.h | 5 +---- .../pcl/compression/organized_pointcloud_conversion.h | 6 +----- io/include/pcl/io/ascii_io.h | 8 +------- io/include/pcl/io/auto_io.h | 5 +---- io/include/pcl/io/buffers.h | 6 +----- io/include/pcl/io/debayer.h | 6 +----- .../pcl/io/depth_sense/depth_sense_device_manager.h | 6 +----- .../pcl/io/depth_sense/depth_sense_grabber_impl.h | 6 +----- io/include/pcl/io/depth_sense_grabber.h | 6 +----- io/include/pcl/io/dinast_grabber.h | 5 +---- io/include/pcl/io/file_grabber.h | 4 ---- io/include/pcl/io/file_io.h | 5 +---- io/include/pcl/io/hdl_grabber.h | 7 ++----- io/include/pcl/io/ifs_io.h | 5 +---- io/include/pcl/io/image.h | 7 +++---- io/include/pcl/io/image_depth.h | 7 ++----- io/include/pcl/io/image_ir.h | 6 ++---- io/include/pcl/io/image_metadata_wrapper.h | 4 ---- io/include/pcl/io/image_rgb24.h | 8 +++----- io/include/pcl/io/image_yuv422.h | 8 +++----- io/include/pcl/io/io.h | 6 +----- io/include/pcl/io/io_exception.h | 6 ++---- io/include/pcl/io/lzf.h | 6 +----- io/include/pcl/io/lzf_image_io.h | 5 +---- io/include/pcl/io/openni2/openni.h | 10 +++++----- io/include/pcl/io/openni2/openni2_convert.h | 5 +---- io/include/pcl/io/openni2/openni2_device.h | 5 +---- io/include/pcl/io/openni2/openni2_device_info.h | 5 +---- io/include/pcl/io/openni2/openni2_device_manager.h | 5 +---- io/include/pcl/io/openni2/openni2_frame_listener.h | 5 +---- io/include/pcl/io/openni2/openni2_metadata_wrapper.h | 8 ++------ io/include/pcl/io/openni2/openni2_timer_filter.h | 5 +---- io/include/pcl/io/openni2/openni2_video_mode.h | 5 +---- io/include/pcl/io/openni2_grabber.h | 8 +++----- io/include/pcl/io/pcd_grabber.h | 6 ++---- io/include/pcl/io/pcd_io.h | 5 +---- io/include/pcl/io/ply/byte_order.h | 5 +---- io/include/pcl/io/ply/io_operators.h | 5 +---- io/include/pcl/io/ply/ply_parser.h | 5 +---- io/include/pcl/io/ply_io.h | 5 +---- io/include/pcl/io/png_io.h | 5 +---- io/include/pcl/io/point_cloud_image_extractors.h | 6 ++---- .../pcl/io/real_sense/real_sense_device_manager.h | 6 +----- io/include/pcl/io/real_sense_grabber.h | 6 +----- io/include/pcl/io/robot_eye_grabber.h | 7 ++----- io/include/pcl/io/tar.h | 5 +---- io/include/pcl/io/vlp_grabber.h | 7 ++----- io/include/pcl/io/vtk_io.h | 5 +---- io/include/pcl/io/vtk_lib_io.h | 5 +---- kdtree/include/pcl/kdtree/flann.h | 7 +------ kdtree/include/pcl/kdtree/io.h | 6 +----- kdtree/include/pcl/kdtree/kdtree.h | 5 +---- kdtree/include/pcl/kdtree/kdtree_flann.h | 5 +---- keypoints/include/pcl/keypoints/agast_2d.h | 6 +----- keypoints/include/pcl/keypoints/brisk_2d.h | 5 +---- keypoints/include/pcl/keypoints/harris_2d.h | 5 +---- keypoints/include/pcl/keypoints/harris_3d.h | 6 +----- keypoints/include/pcl/keypoints/harris_6d.h | 6 +----- keypoints/include/pcl/keypoints/iss_3d.h | 5 +---- keypoints/include/pcl/keypoints/keypoint.h | 5 +---- keypoints/include/pcl/keypoints/narf_keypoint.h | 5 +---- keypoints/include/pcl/keypoints/sift_keypoint.h | 5 +---- .../pcl/keypoints/smoothed_surfaces_keypoint.h | 5 +---- keypoints/include/pcl/keypoints/susan.h | 5 +---- keypoints/include/pcl/keypoints/trajkovic_2d.h | 5 +---- keypoints/include/pcl/keypoints/trajkovic_3d.h | 5 +---- keypoints/include/pcl/keypoints/uniform_sampling.h | 6 +----- ml/include/pcl/ml/branch_estimator.h | 5 +---- ml/include/pcl/ml/densecrf.h | 9 +-------- ml/include/pcl/ml/dt/decision_forest.h | 5 +---- ml/include/pcl/ml/dt/decision_forest_evaluator.h | 5 +---- ml/include/pcl/ml/dt/decision_forest_trainer.h | 5 +---- ml/include/pcl/ml/dt/decision_tree.h | 5 +---- ml/include/pcl/ml/dt/decision_tree_evaluator.h | 5 +---- ml/include/pcl/ml/dt/decision_tree_trainer.h | 5 +---- ml/include/pcl/ml/feature_handler.h | 5 +---- ml/include/pcl/ml/ferns/fern.h | 5 +---- ml/include/pcl/ml/ferns/fern_evaluator.h | 5 +---- ml/include/pcl/ml/ferns/fern_trainer.h | 5 +---- ml/include/pcl/ml/kmeans.h | 5 +---- .../pcl/ml/multi_channel_2d_comparison_feature.h | 5 +---- .../ml/multi_channel_2d_comparison_feature_handler.h | 5 +---- ml/include/pcl/ml/multi_channel_2d_data_set.h | 5 +---- ml/include/pcl/ml/multiple_data_2d_example_index.h | 5 +---- ml/include/pcl/ml/pairwise_potential.h | 5 +---- ml/include/pcl/ml/permutohedral.h | 5 +---- ml/include/pcl/ml/point_xy_32f.h | 5 +---- ml/include/pcl/ml/point_xy_32i.h | 5 +---- .../pcl/ml/regression_variance_stats_estimator.h | 5 +---- ml/include/pcl/ml/stats_estimator.h | 5 +---- ml/include/pcl/ml/svm_wrapper.h | 5 +---- octree/include/pcl/octree/boost.h | 4 +--- octree/include/pcl/octree/octree.h | 6 +----- octree/include/pcl/octree/octree2buf_base.h | 6 +----- octree/include/pcl/octree/octree_base.h | 6 +----- octree/include/pcl/octree/octree_container.h | 5 +---- octree/include/pcl/octree/octree_impl.h | 5 +---- octree/include/pcl/octree/octree_iterator.h | 6 +----- octree/include/pcl/octree/octree_key.h | 5 +---- octree/include/pcl/octree/octree_node_pool.h | 5 +---- octree/include/pcl/octree/octree_nodes.h | 5 +---- octree/include/pcl/octree/octree_pointcloud.h | 6 +----- .../include/pcl/octree/octree_pointcloud_adjacency.h | 6 +----- .../octree/octree_pointcloud_adjacency_container.h | 5 +---- .../pcl/octree/octree_pointcloud_changedetector.h | 6 +----- octree/include/pcl/octree/octree_pointcloud_density.h | 6 +----- .../include/pcl/octree/octree_pointcloud_occupancy.h | 6 +----- .../pcl/octree/octree_pointcloud_pointvector.h | 5 +---- .../pcl/octree/octree_pointcloud_singlepoint.h | 5 +---- .../pcl/octree/octree_pointcloud_voxelcentroid.h | 6 +----- octree/include/pcl/octree/octree_search.h | 5 +---- outofcore/include/pcl/outofcore/boost.h | 5 +---- outofcore/include/pcl/outofcore/metadata.h | 6 +----- .../pcl/outofcore/octree_abstract_node_container.h | 5 +---- outofcore/include/pcl/outofcore/octree_base.h | 6 +----- outofcore/include/pcl/outofcore/octree_base_node.h | 5 +---- .../include/pcl/outofcore/octree_disk_container.h | 5 +---- .../include/pcl/outofcore/octree_ram_container.h | 5 +---- outofcore/include/pcl/outofcore/outofcore_base_data.h | 5 +---- .../pcl/outofcore/outofcore_breadth_first_iterator.h | 5 +---- .../pcl/outofcore/outofcore_depth_first_iterator.h | 5 +---- .../include/pcl/outofcore/outofcore_iterator_base.h | 5 +---- outofcore/include/pcl/outofcore/outofcore_node_data.h | 5 +---- outofcore/include/pcl/outofcore/visualization/axes.h | 6 +----- .../include/pcl/outofcore/visualization/camera.h | 5 +---- .../include/pcl/outofcore/visualization/common.h | 5 +---- .../include/pcl/outofcore/visualization/geometry.h | 5 +---- outofcore/include/pcl/outofcore/visualization/grid.h | 5 +---- .../include/pcl/outofcore/visualization/object.h | 5 +---- .../pcl/outofcore/visualization/outofcore_cloud.h | 5 +---- outofcore/include/pcl/outofcore/visualization/scene.h | 5 +---- .../include/pcl/outofcore/visualization/viewport.h | 5 +---- .../pcl/people/ground_based_people_detection_app.h | 4 +--- people/include/pcl/people/head_based_subcluster.h | 4 +--- people/include/pcl/people/height_map_2d.h | 4 +--- people/include/pcl/people/hog.h | 4 +--- people/include/pcl/people/person_classifier.h | 4 +--- people/include/pcl/people/person_cluster.h | 4 +--- recognition/include/pcl/recognition/boost.h | 5 +---- .../pcl/recognition/cg/correspondence_grouping.h | 5 +---- .../pcl/recognition/cg/geometric_consistency.h | 5 +---- recognition/include/pcl/recognition/cg/hough_3d.h | 5 +---- .../pcl/recognition/color_gradient_dot_modality.h | 5 +---- .../include/pcl/recognition/color_gradient_modality.h | 5 +---- recognition/include/pcl/recognition/color_modality.h | 6 +----- .../recognition/dense_quantized_multi_mod_template.h | 5 +---- recognition/include/pcl/recognition/distance_map.h | 6 +----- recognition/include/pcl/recognition/dot_modality.h | 5 +---- recognition/include/pcl/recognition/dotmod.h | 5 +---- .../face_detection/rf_face_detector_trainer.h | 5 +---- .../pcl/recognition/face_detection/rf_face_utils.h | 5 +---- .../include/pcl/recognition/hv/greedy_verification.h | 5 +---- recognition/include/pcl/recognition/hv/hv_papazov.h | 5 +---- .../pcl/recognition/hv/hypotheses_verification.h | 5 +---- .../include/pcl/recognition/hv/occlusion_reasoning.h | 5 +---- .../include/pcl/recognition/implicit_shape_model.h | 5 +---- recognition/include/pcl/recognition/linemod.h | 5 +---- .../include/pcl/recognition/linemod/line_rgbd.h | 5 +---- recognition/include/pcl/recognition/mask_map.h | 5 +---- recognition/include/pcl/recognition/point_types.h | 5 +---- .../include/pcl/recognition/quantizable_modality.h | 5 +---- recognition/include/pcl/recognition/quantized_map.h | 5 +---- .../include/pcl/recognition/ransac_based/auxiliary.h | 5 +---- .../include/pcl/recognition/ransac_based/bvh.h | 5 +---- .../include/pcl/recognition/ransac_based/hypothesis.h | 5 +---- .../pcl/recognition/ransac_based/model_library.h | 5 +---- .../pcl/recognition/ransac_based/obj_rec_ransac.h | 5 +---- .../include/pcl/recognition/ransac_based/orr_graph.h | 5 +---- .../include/pcl/recognition/ransac_based/orr_octree.h | 5 +---- .../recognition/ransac_based/rigid_transform_space.h | 5 +---- .../pcl/recognition/ransac_based/voxel_structure.h | 5 +---- recognition/include/pcl/recognition/region_xy.h | 5 +---- .../recognition/sparse_quantized_multi_mod_template.h | 5 +---- .../include/pcl/recognition/surface_normal_modality.h | 6 +----- registration/include/pcl/registration/bfgs.h | 5 +---- registration/include/pcl/registration/boost.h | 5 +---- registration/include/pcl/registration/boost_graph.h | 5 +---- .../include/pcl/registration/convergence_criteria.h | 6 +----- .../pcl/registration/correspondence_estimation.h | 5 +---- .../correspondence_estimation_backprojection.h | 5 +---- .../correspondence_estimation_normal_shooting.h | 5 +---- .../correspondence_estimation_organized_projection.h | 6 +----- .../pcl/registration/correspondence_rejection.h | 6 +----- .../registration/correspondence_rejection_distance.h | 6 ++---- .../registration/correspondence_rejection_features.h | 6 ++---- .../correspondence_rejection_median_distance.h | 6 ++---- .../correspondence_rejection_one_to_one.h | 6 ++---- .../correspondence_rejection_organized_boundary.h | 6 +----- .../pcl/registration/correspondence_rejection_poly.h | 6 ++---- .../correspondence_rejection_sample_consensus.h | 6 ++---- .../correspondence_rejection_sample_consensus_2d.h | 6 +----- .../correspondence_rejection_surface_normal.h | 6 ++---- .../registration/correspondence_rejection_trimmed.h | 6 ++---- .../correspondence_rejection_var_trimmed.h | 6 ++---- .../include/pcl/registration/correspondence_sorting.h | 6 ++---- .../include/pcl/registration/correspondence_types.h | 6 ++---- .../pcl/registration/default_convergence_criteria.h | 6 +----- registration/include/pcl/registration/distances.h | 6 ++---- .../include/pcl/registration/edge_measurements.h | 5 +---- registration/include/pcl/registration/eigen.h | 5 +---- registration/include/pcl/registration/elch.h | 5 +---- registration/include/pcl/registration/exceptions.h | 5 ++--- registration/include/pcl/registration/gicp.h | 5 +---- registration/include/pcl/registration/gicp6d.h | 5 +---- registration/include/pcl/registration/graph_handler.h | 5 +---- .../include/pcl/registration/graph_optimizer.h | 5 +---- .../include/pcl/registration/graph_registration.h | 5 +---- registration/include/pcl/registration/ia_fpcs.h | 5 +---- registration/include/pcl/registration/ia_kfpcs.h | 5 +---- registration/include/pcl/registration/icp.h | 5 +---- registration/include/pcl/registration/icp_nl.h | 5 +---- .../pcl/registration/incremental_registration.h | 5 +---- registration/include/pcl/registration/joint_icp.h | 7 +------ registration/include/pcl/registration/lum.h | 6 +----- .../include/pcl/registration/matching_candidate.h | 6 +----- .../include/pcl/registration/meta_registration.h | 5 +---- registration/include/pcl/registration/ndt.h | 5 +---- registration/include/pcl/registration/ndt_2d.h | 6 +----- .../pcl/registration/pairwise_graph_registration.h | 5 +---- .../include/pcl/registration/ppf_registration.h | 6 +----- .../pcl/registration/pyramid_feature_matching.h | 5 +---- registration/include/pcl/registration/registration.h | 5 +---- .../pcl/registration/sample_consensus_prerejective.h | 5 +---- .../pcl/registration/transformation_estimation.h | 6 ++---- .../pcl/registration/transformation_estimation_2D.h | 6 ++---- .../registration/transformation_estimation_3point.h | 6 ++---- .../pcl/registration/transformation_estimation_dq.h | 6 ++---- .../transformation_estimation_dual_quaternion.h | 6 ++---- .../pcl/registration/transformation_estimation_lm.h | 7 ++----- .../transformation_estimation_point_to_plane.h | 7 ++----- .../transformation_estimation_point_to_plane_lls.h | 6 ++---- ...formation_estimation_point_to_plane_lls_weighted.h | 6 ++---- ...ransformation_estimation_point_to_plane_weighted.h | 7 +------ .../pcl/registration/transformation_estimation_svd.h | 6 ++---- .../transformation_estimation_svd_scale.h | 6 ++---- .../pcl/registration/transformation_validation.h | 6 ++---- .../transformation_validation_euclidean.h | 7 ++----- registration/include/pcl/registration/transforms.h | 6 ++---- .../include/pcl/registration/vertex_estimates.h | 5 +---- .../include/pcl/registration/warp_point_rigid.h | 5 +---- .../include/pcl/registration/warp_point_rigid_3d.h | 7 +------ .../include/pcl/registration/warp_point_rigid_6d.h | 7 +------ sample_consensus/include/pcl/sample_consensus/boost.h | 5 +---- sample_consensus/include/pcl/sample_consensus/eigen.h | 5 +---- sample_consensus/include/pcl/sample_consensus/lmeds.h | 6 +----- .../include/pcl/sample_consensus/method_types.h | 5 +---- .../include/pcl/sample_consensus/mlesac.h | 5 +---- .../include/pcl/sample_consensus/model_types.h | 5 +---- sample_consensus/include/pcl/sample_consensus/msac.h | 5 +---- .../include/pcl/sample_consensus/prosac.h | 5 +---- .../include/pcl/sample_consensus/ransac.h | 6 +----- sample_consensus/include/pcl/sample_consensus/rmsac.h | 5 +---- .../include/pcl/sample_consensus/rransac.h | 6 +----- sample_consensus/include/pcl/sample_consensus/sac.h | 5 +---- .../include/pcl/sample_consensus/sac_model.h | 5 +---- .../include/pcl/sample_consensus/sac_model_circle.h | 5 +---- .../include/pcl/sample_consensus/sac_model_circle3d.h | 5 +---- .../include/pcl/sample_consensus/sac_model_cone.h | 5 +---- .../include/pcl/sample_consensus/sac_model_cylinder.h | 5 +---- .../include/pcl/sample_consensus/sac_model_line.h | 5 +---- .../sac_model_normal_parallel_plane.h | 5 +---- .../pcl/sample_consensus/sac_model_normal_plane.h | 5 +---- .../pcl/sample_consensus/sac_model_normal_sphere.h | 5 +---- .../pcl/sample_consensus/sac_model_parallel_line.h | 5 +---- .../pcl/sample_consensus/sac_model_parallel_plane.h | 5 +---- .../sample_consensus/sac_model_perpendicular_plane.h | 5 +---- .../include/pcl/sample_consensus/sac_model_plane.h | 5 +---- .../pcl/sample_consensus/sac_model_registration.h | 5 +---- .../pcl/sample_consensus/sac_model_registration_2d.h | 6 +----- .../include/pcl/sample_consensus/sac_model_sphere.h | 5 +---- .../include/pcl/sample_consensus/sac_model_stick.h | 5 +---- search/include/pcl/search/brute_force.h | 5 +---- search/include/pcl/search/flann_search.h | 6 +----- search/include/pcl/search/kdtree.h | 6 +----- search/include/pcl/search/octree.h | 5 +---- search/include/pcl/search/organized.h | 6 +----- search/include/pcl/search/pcl_search.h | 6 +----- search/include/pcl/search/search.h | 5 +---- .../approximate_progressive_morphological_filter.h | 6 +----- segmentation/include/pcl/segmentation/boost.h | 5 +---- segmentation/include/pcl/segmentation/comparator.h | 5 +---- .../segmentation/conditional_euclidean_clustering.h | 6 +----- .../include/pcl/segmentation/cpc_segmentation.h | 5 +---- .../pcl/segmentation/crf_normal_segmentation.h | 5 +---- .../include/pcl/segmentation/crf_segmentation.h | 5 +---- .../pcl/segmentation/edge_aware_plane_comparator.h | 5 +---- .../pcl/segmentation/euclidean_cluster_comparator.h | 5 +---- .../euclidean_plane_coefficient_comparator.h | 5 +---- .../include/pcl/segmentation/extract_clusters.h | 5 +---- .../pcl/segmentation/extract_labeled_clusters.h | 5 +---- .../pcl/segmentation/extract_polygonal_prism_data.h | 5 +---- .../include/pcl/segmentation/grabcut_segmentation.h | 5 +---- .../pcl/segmentation/ground_plane_comparator.h | 5 +---- .../include/pcl/segmentation/lccp_segmentation.h | 5 +---- .../include/pcl/segmentation/min_cut_segmentation.h | 4 +--- .../organized_connected_component_segmentation.h | 5 +---- .../segmentation/organized_multi_plane_segmentation.h | 5 +---- .../include/pcl/segmentation/planar_polygon_fusion.h | 5 +---- segmentation/include/pcl/segmentation/planar_region.h | 5 +---- .../pcl/segmentation/plane_coefficient_comparator.h | 5 +---- .../pcl/segmentation/plane_refinement_comparator.h | 5 +---- .../segmentation/progressive_morphological_filter.h | 6 +----- segmentation/include/pcl/segmentation/random_walker.h | 6 +----- segmentation/include/pcl/segmentation/region_3d.h | 5 +---- .../include/pcl/segmentation/region_growing.h | 5 +---- .../include/pcl/segmentation/region_growing_rgb.h | 5 +---- .../segmentation/rgb_plane_coefficient_comparator.h | 5 +---- .../include/pcl/segmentation/sac_segmentation.h | 5 +---- .../pcl/segmentation/seeded_hue_segmentation.h | 5 +---- .../include/pcl/segmentation/segment_differences.h | 5 +---- .../include/pcl/segmentation/supervoxel_clustering.h | 5 +---- .../include/pcl/segmentation/unary_classifier.h | 5 +---- simulation/include/pcl/simulation/camera.h | 5 +---- simulation/include/pcl/simulation/glsl_shader.h | 5 +---- simulation/include/pcl/simulation/model.h | 5 +---- simulation/include/pcl/simulation/range_likelihood.h | 5 +---- simulation/include/pcl/simulation/scene.h | 5 +---- simulation/include/pcl/simulation/sum_reduce.h | 5 +---- stereo/include/pcl/stereo/digital_elevation_map.h | 6 ++---- stereo/include/pcl/stereo/disparity_map_converter.h | 6 ++---- stereo/include/pcl/stereo/stereo_grabber.h | 4 +--- stereo/include/pcl/stereo/stereo_matching.h | 6 ++---- surface/include/pcl/surface/bilateral_upsampling.h | 6 +----- surface/include/pcl/surface/boost.h | 5 +---- surface/include/pcl/surface/concave_hull.h | 8 +++----- surface/include/pcl/surface/convex_hull.h | 8 +++----- surface/include/pcl/surface/ear_clipping.h | 5 +---- surface/include/pcl/surface/eigen.h | 5 +---- surface/include/pcl/surface/gp3.h | 6 +----- surface/include/pcl/surface/grid_projection.h | 6 +----- surface/include/pcl/surface/marching_cubes.h | 6 +----- surface/include/pcl/surface/marching_cubes_hoppe.h | 6 +----- surface/include/pcl/surface/marching_cubes_rbf.h | 6 +----- surface/include/pcl/surface/mls.h | 5 +---- surface/include/pcl/surface/organized_fast_mesh.h | 5 +---- surface/include/pcl/surface/poisson.h | 5 +---- surface/include/pcl/surface/processing.h | 6 +----- surface/include/pcl/surface/qhull.h | 8 +++----- surface/include/pcl/surface/reconstruction.h | 6 +----- .../surface/simplification_remove_unused_vertices.h | 5 +---- surface/include/pcl/surface/surfel_smoothing.h | 5 +---- surface/include/pcl/surface/texture_mapping.h | 6 +----- surface/include/pcl/surface/vtk_smoothing/vtk.h | 7 ++----- test/common/boost.h | 5 +---- test/geometry/test_mesh_common_functions.h | 5 +---- tools/boost.h | 5 +---- .../approx_nearest_pair_point_cloud_coherence.h | 6 +----- tracking/include/pcl/tracking/boost.h | 5 +---- tracking/include/pcl/tracking/coherence.h | 7 +------ tracking/include/pcl/tracking/distance_coherence.h | 7 +------ tracking/include/pcl/tracking/hsv_color_coherence.h | 7 +------ .../pcl/tracking/kld_adaptive_particle_filter.h | 5 +---- .../pcl/tracking/kld_adaptive_particle_filter_omp.h | 5 +---- .../pcl/tracking/nearest_pair_point_cloud_coherence.h | 5 +---- tracking/include/pcl/tracking/normal_coherence.h | 5 +---- tracking/include/pcl/tracking/particle_filter.h | 5 +---- tracking/include/pcl/tracking/particle_filter_omp.h | 5 +---- tracking/include/pcl/tracking/pyramidal_klt.h | 4 +--- tracking/include/pcl/tracking/tracker.h | 5 +---- tracking/include/pcl/tracking/tracking.h | 5 +---- .../include/pcl/visualization/area_picking_event.h | 5 +---- visualization/include/pcl/visualization/boost.h | 5 +---- .../include/pcl/visualization/cloud_viewer.h | 6 ++---- .../include/pcl/visualization/common/actor_map.h | 6 ++---- .../include/pcl/visualization/common/common.h | 6 ++---- .../pcl/visualization/common/float_image_utils.h | 9 ++------- visualization/include/pcl/visualization/common/io.h | 6 ++---- .../pcl/visualization/common/ren_win_interact_map.h | 5 +---- .../include/pcl/visualization/common/shapes.h | 6 ++---- visualization/include/pcl/visualization/eigen.h | 5 +---- .../include/pcl/visualization/histogram_visualizer.h | 6 ++---- .../include/pcl/visualization/image_viewer.h | 6 +----- visualization/include/pcl/visualization/interactor.h | 6 ++---- .../include/pcl/visualization/interactor_style.h | 6 ++---- .../include/pcl/visualization/keyboard_event.h | 6 +----- visualization/include/pcl/visualization/mouse_event.h | 6 +----- .../include/pcl/visualization/pcl_painter2D.h | 6 +----- visualization/include/pcl/visualization/pcl_plotter.h | 7 ++----- .../include/pcl/visualization/pcl_visualizer.h | 7 ++----- .../pcl/visualization/point_cloud_color_handlers.h | 7 ++----- .../pcl/visualization/point_cloud_geometry_handlers.h | 7 ++----- .../include/pcl/visualization/point_cloud_handlers.h | 6 ++---- .../include/pcl/visualization/point_picking_event.h | 6 +----- .../pcl/visualization/range_image_visualizer.h | 8 ++------ .../pcl/visualization/registration_visualizer.h | 5 +---- .../pcl/visualization/simple_buffer_visualizer.h | 5 +---- visualization/include/pcl/visualization/vtk.h | 7 ++----- .../include/pcl/visualization/vtk/pcl_context_item.h | 5 +---- .../visualization/vtk/pcl_image_canvas_source_2d.h | 6 ++---- .../visualization/vtk/vtkRenderWindowInteractorFix.h | 7 ++----- visualization/include/pcl/visualization/window.h | 6 +----- 686 files changed, 801 insertions(+), 2940 deletions(-) diff --git a/2d/include/pcl/2d/convolution.h b/2d/include/pcl/2d/convolution.h index 7938e2b098d..33c2442d50a 100644 --- a/2d/include/pcl/2d/convolution.h +++ b/2d/include/pcl/2d/convolution.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_2D_CONVOLUTION_H -#define PCL_2D_CONVOLUTION_H +#pragma once #include #include @@ -156,4 +155,3 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZIEdge, (float, magnitude_x, magnitude_x) (float, magnitude_y, magnitude_y) ) -#endif // PCL_2D_CONVOLUTION_2D_H diff --git a/2d/include/pcl/2d/edge.h b/2d/include/pcl/2d/edge.h index a0e059ed33b..a4cfb0bca6e 100644 --- a/2d/include/pcl/2d/edge.h +++ b/2d/include/pcl/2d/edge.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_2D_EDGE_H -#define PCL_2D_EDGE_H +#pragma once #include #include @@ -303,6 +302,3 @@ namespace pcl }; } #include - -#endif // PCL_2D_EDGE_H - diff --git a/2d/include/pcl/2d/kernel.h b/2d/include/pcl/2d/kernel.h index e440933b335..4b74be3aa1b 100644 --- a/2d/include/pcl/2d/kernel.h +++ b/2d/include/pcl/2d/kernel.h @@ -35,10 +35,11 @@ * */ -#ifndef PCL_2D_KERNEL_H_ -#define PCL_2D_KERNEL_H_ +#pragma once + #include #include + namespace pcl { template @@ -240,5 +241,3 @@ namespace pcl } #include - -#endif // PCL_2D_KERNEL_H_ diff --git a/2d/include/pcl/2d/keypoint.h b/2d/include/pcl/2d/keypoint.h index 677e52e6bff..2f9b1e4980c 100644 --- a/2d/include/pcl/2d/keypoint.h +++ b/2d/include/pcl/2d/keypoint.h @@ -39,8 +39,7 @@ * Author: somani */ -#ifndef PCL_2D_KEYPOINT_H_ -#define PCL_2D_KEYPOINT_H_ +#pragma once #include @@ -71,5 +70,3 @@ namespace pcl } #include - -#endif // PCL_2D_KEYPOINT_H_ diff --git a/2d/include/pcl/2d/morphology.h b/2d/include/pcl/2d/morphology.h index a3847b45bb6..8f7cc61387c 100644 --- a/2d/include/pcl/2d/morphology.h +++ b/2d/include/pcl/2d/morphology.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_2D_MORPHOLOGY_H_ -#define PCL_2D_MORPHOLOGY_H_ +#pragma once #include @@ -196,5 +195,3 @@ namespace pcl } #include - -#endif // PCL_2D_MORPHOLOGY_H_ diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h index 8314cd0a8d2..bf45fae25e9 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_BOOST_H -#define PCL_APPS_IN_HAND_SCANNER_BOOST_H +#pragma once #ifdef __GNUC__ # pragma GCC system_header @@ -55,5 +54,3 @@ #include #include #include - -#endif // PCL_APPS_IN_HAND_SCANNER_BOOST_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h index 1dbb52087de..300fd210fa8 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_COMMON_TYPES_H -#define PCL_APPS_IN_HAND_SCANNER_COMMON_TYPES_H +#pragma once #include @@ -93,5 +92,3 @@ namespace pcl typedef Mesh::ConstPtr MeshConstPtr; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_COMMON_TYPES_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h index 9b42bedeca0..7c1208e399b 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_EIGEN_H -#define PCL_APPS_IN_HAND_SCANNER_EIGEN_H +#pragma once #ifdef __GNUC__ # pragma GCC system_header @@ -48,5 +47,3 @@ #include #include #include - -#endif // PCL_APPS_IN_HAND_SCANNER_EIGEN_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/help_window.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/help_window.h index 952542639c6..99ede4d0c02 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/help_window.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/help_window.h @@ -38,9 +38,7 @@ * */ - -#ifndef PCL_APPS_IN_HAND_SCANNER_HELP_WINDOW_H -#define PCL_APPS_IN_HAND_SCANNER_HELP_WINDOW_H +#pragma once #include @@ -66,5 +64,3 @@ namespace pcl }; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_HELP_WINDOW_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h index e5db6c12b02..af8abdb5b71 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_ICP_H -#define PCL_APPS_IN_HAND_SCANNER_ICP_H +#pragma once #include #include @@ -221,5 +220,3 @@ namespace pcl }; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_ICP_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h index ef09cad41d2..3fd882bb7d7 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H -#define PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H +#pragma once #include #include @@ -307,5 +306,3 @@ namespace pcl // http://doc.qt.digia.com/qt/qmetatype.html#Q_DECLARE_METATYPE Q_DECLARE_METATYPE (pcl::ihs::InHandScanner::RunningMode) - -#endif // PCL_APPS_IN_HAND_SCANNER_IN_HAND_SCANNER_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h index 3da5d329c50..ba0df87b308 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H -#define PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H +#pragma once #include #include @@ -239,5 +238,3 @@ namespace pcl }; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_INPUT_DATA_PROCESSING_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/integration.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/integration.h index f6ff2e24ac8..da04a616bad 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/integration.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/integration.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H -#define PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H +#pragma once #include @@ -230,5 +229,3 @@ namespace pcl }; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_INTEGRATION_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/main_window.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/main_window.h index 61ec1757cd1..66624438fbc 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/main_window.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/main_window.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_MAIN_WINDOW_H -#define PCL_APPS_IN_HAND_SCANNER_MAIN_WINDOW_H +#pragma once #include @@ -136,5 +135,3 @@ namespace pcl }; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_MAIN_WINDOW_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/mesh_processing.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/mesh_processing.h index 544a07b33de..546da7523b0 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/mesh_processing.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/mesh_processing.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_MESH_PROCESSING_H -#define PCL_APPS_IN_HAND_SCANNER_MESH_PROCESSING_H +#pragma once #include @@ -74,5 +73,3 @@ namespace pcl }; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_MESH_PROCESSING_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h index ce888322cd6..e6291bfeadf 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_OFFLINE_INTEGRATION_H -#define PCL_APPS_IN_HAND_SCANNER_OFFLINE_INTEGRATION_H +#pragma once #include #include @@ -223,5 +222,3 @@ namespace pcl }; } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_OFFLINE_INTEGRATION_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h index 114050c1380..15e5d32ebe0 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H -#define PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H +#pragma once #include @@ -452,5 +451,3 @@ namespace pcl // http://doc.qt.digia.com/qt/qmetatype.html#Q_DECLARE_METATYPE Q_DECLARE_METATYPE (pcl::ihs::OpenGLViewer::MeshRepresentation) Q_DECLARE_METATYPE (pcl::ihs::OpenGLViewer::Coloring) - -#endif // PCL_APPS_IN_HAND_SCANNER_OPENGL_VIEWER_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/utils.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/utils.h index 2fe5b1e4897..937734a6223 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/utils.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/utils.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_UTILS_H -#define PCL_APPS_IN_HAND_SCANNER_UTILS_H +#pragma once namespace pcl { @@ -53,5 +52,3 @@ namespace pcl } } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_UTILS_H diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h index 11fa7a63fe8..95b1c061646 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_APPS_IN_HAND_SCANNER_VISIBILITY_CONFIDENCE_H -#define PCL_APPS_IN_HAND_SCANNER_VISIBILITY_CONFIDENCE_H +#pragma once #include @@ -86,5 +85,3 @@ namespace pcl } // End namespace ihs } // End namespace pcl - -#endif // PCL_APPS_IN_HAND_SCANNER_VISIBILITY_CONFIDENCE_H diff --git a/apps/include/pcl/apps/openni_passthrough.h b/apps/include/pcl/apps/openni_passthrough.h index b70aecaa23b..a939b4e2c4d 100644 --- a/apps/include/pcl/apps/openni_passthrough.h +++ b/apps/include/pcl/apps/openni_passthrough.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_APPS_OPENNI_PASSTHROUGH_3D_ -#define PCL_APPS_OPENNI_PASSTHROUGH_3D_ +#pragma once // PCL #include @@ -116,5 +115,3 @@ class OpenNIPassthrough : public QMainWindow void valueChanged (int new_value); }; - -#endif // PCL_APPS_OPENNI_PASSTHROUGH_3D_ diff --git a/apps/include/pcl/apps/openni_passthrough_qt.h b/apps/include/pcl/apps/openni_passthrough_qt.h index 86805ad882e..cdb8f010bb1 100644 --- a/apps/include/pcl/apps/openni_passthrough_qt.h +++ b/apps/include/pcl/apps/openni_passthrough_qt.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_APPS_OPENNI_PASSTHROUGH_QT_ -#define PCL_APPS_OPENNI_PASSTHROUGH_QT_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -48,5 +47,3 @@ #include #include #include - -#endif // PCL_APPS_OPENNI_PASSTHROUGH_QT_ diff --git a/apps/include/pcl/apps/organized_segmentation_demo.h b/apps/include/pcl/apps/organized_segmentation_demo.h index 2d873a347ab..e82e3f9bbd1 100644 --- a/apps/include/pcl/apps/organized_segmentation_demo.h +++ b/apps/include/pcl/apps/organized_segmentation_demo.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_ORGANIZED_SEGMENTATION_DEMO_H_ -#define PCL_ORGANIZED_SEGMENTATION_DEMO_H_ +#pragma once #include @@ -182,5 +181,3 @@ class OrganizedSegmentationDemo : public QMainWindow timeoutSlot(); }; - -#endif // PCL_ORGANIZED_SEGMENTATION_DEMO_H_ diff --git a/apps/include/pcl/apps/organized_segmentation_demo_qt.h b/apps/include/pcl/apps/organized_segmentation_demo_qt.h index 9dbc8446ac7..218ad679c0d 100644 --- a/apps/include/pcl/apps/organized_segmentation_demo_qt.h +++ b/apps/include/pcl/apps/organized_segmentation_demo_qt.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_ORGANIZED_SEGMENTATION_DEMO_QT_H_ -#define PCL_ORGANIZED_SEGMENTATION_DEMO_QT_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -46,5 +45,3 @@ #include #include #include - -#endif // PCL_ORGANIZED_SEGMENTATION_DEMO_QT_H_ diff --git a/apps/include/pcl/apps/timer.h b/apps/include/pcl/apps/timer.h index 00f6bf15287..630a22e98c3 100644 --- a/apps/include/pcl/apps/timer.h +++ b/apps/include/pcl/apps/timer.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_APPS_TIMER_H_ -#define PCL_APPS_TIMER_H_ +#pragma once #define MEASURE_FUNCTION_TIME #include //fps calculations @@ -64,5 +63,3 @@ do \ { \ }while(false) #endif - -#endif // PCL_APPS_TIMER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/abstract_item.h b/apps/modeler/include/pcl/apps/modeler/abstract_item.h index 6d98737bff1..ad69a5d06ba 100755 --- a/apps/modeler/include/pcl/apps/modeler/abstract_item.h +++ b/apps/modeler/include/pcl/apps/modeler/abstract_item.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_ABSTRACT_ITEM_H_ -#define PCL_MODELER_ABSTRACT_ITEM_H_ +#pragma once #include @@ -82,5 +81,3 @@ namespace pcl } } - -#endif // PCL_MODELER_ABSTRACT_ITEM_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/abstract_worker.h b/apps/modeler/include/pcl/apps/modeler/abstract_worker.h index 6c5ba319655..c7a2264480c 100755 --- a/apps/modeler/include/pcl/apps/modeler/abstract_worker.h +++ b/apps/modeler/include/pcl/apps/modeler/abstract_worker.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_ABSTRACT_WORKER_H_ -#define PCL_MODELER_ABSTRACT_WORKER_H_ +#pragma once #include @@ -91,5 +90,3 @@ namespace pcl } } - -#endif // PCL_MODELER_ABSTRACT_WORKER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/channel_actor_item.h b/apps/modeler/include/pcl/apps/modeler/channel_actor_item.h index e7f6c39d256..67e4d2a4b1a 100755 --- a/apps/modeler/include/pcl/apps/modeler/channel_actor_item.h +++ b/apps/modeler/include/pcl/apps/modeler/channel_actor_item.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_CHANNEL_ACTOR_ITEM_H_ -#define PCL_MODELER_CHANNEL_ACTOR_ITEM_H_ + +#pragma once #include #include @@ -100,5 +100,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_CHANNEL_ACTOR_ITEM_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h b/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h index c5929e677f6..2cfab04be8c 100755 --- a/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h +++ b/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_CLOUD_MESH_H_ -#define PCL_MODELER_CLOUD_MESH_H_ + +#pragma once #include #include @@ -117,5 +117,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_CLOUD_MESH_H_ \ No newline at end of file diff --git a/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item.h b/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item.h index 5f6ea96805d..cac4b3b9628 100755 --- a/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item.h +++ b/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_CLOUD_MESH_ITEM_H_ -#define PCL_MODELER_CLOUD_MESH_ITEM_H_ + +#pragma once #include #include @@ -108,5 +108,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_CLOUD_MESH_ITEM_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item_updater.h b/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item_updater.h index 2f297855a2f..9b35b265d9a 100755 --- a/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item_updater.h +++ b/apps/modeler/include/pcl/apps/modeler/cloud_mesh_item_updater.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_CLOUD_MESH_ITEM_UPDATER_H_ -#define PCL_MODELER_CLOUD_MESH_ITEM_UPDATER_H_ + +#pragma once #include @@ -61,5 +61,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_CLOUD_MESH_ITEM_UPDATER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/dock_widget.h b/apps/modeler/include/pcl/apps/modeler/dock_widget.h index 280da304f50..ce2cd97dd63 100755 --- a/apps/modeler/include/pcl/apps/modeler/dock_widget.h +++ b/apps/modeler/include/pcl/apps/modeler/dock_widget.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_DOCK_WIDGET_H_ -#define PCL_MODELER_DOCK_WIDGET_H_ +#pragma once #include @@ -60,5 +59,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_DOCK_WIDGET_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/icp_registration_worker.h b/apps/modeler/include/pcl/apps/modeler/icp_registration_worker.h index 67330342b7d..2f00a29a5db 100755 --- a/apps/modeler/include/pcl/apps/modeler/icp_registration_worker.h +++ b/apps/modeler/include/pcl/apps/modeler/icp_registration_worker.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_ICP_REGISTRATION_WORKER_H_ -#define PCL_MODELER_ICP_REGISTRATION_WORKER_H_ +#pragma once #include #include @@ -81,5 +80,3 @@ namespace pcl } } - -#endif // PCL_MODELER_ICP_REGISTRATION_WORKER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/main_window.h b/apps/modeler/include/pcl/apps/modeler/main_window.h index 4f061834da0..ac5ac592516 100755 --- a/apps/modeler/include/pcl/apps/modeler/main_window.h +++ b/apps/modeler/include/pcl/apps/modeler/main_window.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_MAIN_WINDOW_H_ -#define PCL_MODELER_MAIN_WINDOW_H_ +#pragma once #include #include @@ -145,5 +144,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_MAIN_WINDOW_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/normal_estimation_worker.h b/apps/modeler/include/pcl/apps/modeler/normal_estimation_worker.h index e594da2fb8f..1c1507d9505 100755 --- a/apps/modeler/include/pcl/apps/modeler/normal_estimation_worker.h +++ b/apps/modeler/include/pcl/apps/modeler/normal_estimation_worker.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_NORMAL_ESTIMATION_WORKER_H_ -#define PCL_MODELER_NORMAL_ESTIMATION_WORKER_H_ +#pragma once #include @@ -75,4 +74,3 @@ namespace pcl } } -#endif // PCL_MODELER_NORMAL_ESTIMATION_WORKER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/normals_actor_item.h b/apps/modeler/include/pcl/apps/modeler/normals_actor_item.h index da0fe1db3ae..d0077740753 100755 --- a/apps/modeler/include/pcl/apps/modeler/normals_actor_item.h +++ b/apps/modeler/include/pcl/apps/modeler/normals_actor_item.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_NORMALS_ACTOR_ITEM_H_ -#define PCL_MODELER_NORMALS_ACTOR_ITEM_H_ + +#pragma once #include #include @@ -81,5 +81,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_NORMALS_ACTOR_ITEM_H_ \ No newline at end of file diff --git a/apps/modeler/include/pcl/apps/modeler/parameter.h b/apps/modeler/include/pcl/apps/modeler/parameter.h index d45f1c1f1dc..9f279ce4e47 100755 --- a/apps/modeler/include/pcl/apps/modeler/parameter.h +++ b/apps/modeler/include/pcl/apps/modeler/parameter.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_PARAMETER_H_ -#define PCL_MODELER_PARAMETER_H_ + +#pragma once #include #include @@ -273,5 +273,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_PARAMETER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/parameter_dialog.h b/apps/modeler/include/pcl/apps/modeler/parameter_dialog.h index 4e1247e4950..4e64c6138d5 100755 --- a/apps/modeler/include/pcl/apps/modeler/parameter_dialog.h +++ b/apps/modeler/include/pcl/apps/modeler/parameter_dialog.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_PARAMETER_DIALOG_H_ -#define PCL_MODELER_PARAMETER_DIALOG_H_ + +#pragma once #include @@ -111,5 +111,3 @@ namespace pcl } } - -#endif // PCL_MODELER_PARAMETER_DIALOG_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/points_actor_item.h b/apps/modeler/include/pcl/apps/modeler/points_actor_item.h index f6ed4a2e591..10014f492f5 100755 --- a/apps/modeler/include/pcl/apps/modeler/points_actor_item.h +++ b/apps/modeler/include/pcl/apps/modeler/points_actor_item.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_POINTS_ACTOR_ITEM_H_ -#define PCL_MODELER_POINTS_ACTOR_ITEM_H_ + +#pragma once #include #include @@ -77,5 +77,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_POINTS_ACTOR_ITEM_H_ \ No newline at end of file diff --git a/apps/modeler/include/pcl/apps/modeler/poisson_worker.h b/apps/modeler/include/pcl/apps/modeler/poisson_worker.h index be399091072..69c2fed113a 100755 --- a/apps/modeler/include/pcl/apps/modeler/poisson_worker.h +++ b/apps/modeler/include/pcl/apps/modeler/poisson_worker.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_POISSON_WORKER_H_ -#define PCL_MODELER_POISSON_WORKER_H_ +#pragma once #include @@ -76,5 +75,3 @@ namespace pcl } } - -#endif // PCL_MODELER_POISSON_WORKER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/qt.h b/apps/modeler/include/pcl/apps/modeler/qt.h index 6ba50022c43..e0ff3832f70 100644 --- a/apps/modeler/include/pcl/apps/modeler/qt.h +++ b/apps/modeler/include/pcl/apps/modeler/qt.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_MODELER_QT_H_ -#define PCL_MODELER_QT_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -87,5 +86,3 @@ #include #include #include - -#endif // PCL_MODELER_QT_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/render_window.h b/apps/modeler/include/pcl/apps/modeler/render_window.h index 8b3058138f4..c6b54e19ef9 100755 --- a/apps/modeler/include/pcl/apps/modeler/render_window.h +++ b/apps/modeler/include/pcl/apps/modeler/render_window.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_RENDER_WINDOW_H_ -#define PCL_MODELER_RENDER_WINDOW_H_ +#pragma once #include #include @@ -94,5 +93,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_RENDER_WINDOW_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/render_window_item.h b/apps/modeler/include/pcl/apps/modeler/render_window_item.h index a94374b63c9..354658c50e9 100755 --- a/apps/modeler/include/pcl/apps/modeler/render_window_item.h +++ b/apps/modeler/include/pcl/apps/modeler/render_window_item.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_RENDER_WINDOW_ITEM_H_ -#define PCL_MODELER_RENDER_WINDOW_ITEM_H_ +#pragma once #include #include @@ -94,5 +93,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_RENDER_WINDOW_ITEM_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/scene_tree.h b/apps/modeler/include/pcl/apps/modeler/scene_tree.h index 45ab04685b2..78475071f4a 100755 --- a/apps/modeler/include/pcl/apps/modeler/scene_tree.h +++ b/apps/modeler/include/pcl/apps/modeler/scene_tree.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_SCENE_TREE_H_ -#define PCL_MODELER_SCENE_TREE_H_ +#pragma once #include @@ -140,5 +139,3 @@ namespace pcl } #include - -#endif // PCL_MODELER_SCENE_TREE_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/statistical_outlier_removal_worker.h b/apps/modeler/include/pcl/apps/modeler/statistical_outlier_removal_worker.h index 7992a89697a..3d59496d306 100755 --- a/apps/modeler/include/pcl/apps/modeler/statistical_outlier_removal_worker.h +++ b/apps/modeler/include/pcl/apps/modeler/statistical_outlier_removal_worker.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_STATISTICAL_OUTLIER_REMOVAL_WORKER_H_ -#define PCL_MODELER_STATISTICAL_OUTLIER_REMOVAL_WORKER_H_ +#pragma once #include @@ -73,5 +72,3 @@ namespace pcl } } - -#endif // PCL_MODELER_STATISTICAL_OUTLIER_REMOVAL_WORKER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/surface_actor_item.h b/apps/modeler/include/pcl/apps/modeler/surface_actor_item.h index 43a1a4460ea..57716dc237b 100755 --- a/apps/modeler/include/pcl/apps/modeler/surface_actor_item.h +++ b/apps/modeler/include/pcl/apps/modeler/surface_actor_item.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_MODELER_SURFACE_ACTOR_ITEM_H_ -#define PCL_MODELER_SURFACE_ACTOR_ITEM_H_ + +#pragma once #include #include @@ -84,5 +84,3 @@ namespace pcl }; } } - -#endif // PCL_MODELER_SURFACE_ACTOR_ITEM_H_ \ No newline at end of file diff --git a/apps/modeler/include/pcl/apps/modeler/thread_controller.h b/apps/modeler/include/pcl/apps/modeler/thread_controller.h index f6a56be1e3f..20a31ed669f 100755 --- a/apps/modeler/include/pcl/apps/modeler/thread_controller.h +++ b/apps/modeler/include/pcl/apps/modeler/thread_controller.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_THREAD_CONTROLLER_H_ -#define PCL_MODELER_THREAD_CONTROLLER_H_ +#pragma once #include @@ -68,5 +67,3 @@ namespace pcl } } - -#endif // PCL_MODELER_THREAD_CONTROLLER_H_ diff --git a/apps/modeler/include/pcl/apps/modeler/voxel_grid_downsample_worker.h b/apps/modeler/include/pcl/apps/modeler/voxel_grid_downsample_worker.h index c68133d750d..28784b902dd 100755 --- a/apps/modeler/include/pcl/apps/modeler/voxel_grid_downsample_worker.h +++ b/apps/modeler/include/pcl/apps/modeler/voxel_grid_downsample_worker.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_MODELER_DOWNSAMPLE_WORKER_H_ -#define PCL_MODELER_DOWNSAMPLE_WORKER_H_ +#pragma once #include @@ -77,5 +76,3 @@ namespace pcl } } - -#endif // PCL_MODELER_DOWNSAMPLE_WORKER_H_ diff --git a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/cloud_filter.h b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/cloud_filter.h index 8c28f7a7f9a..35f61da8839 100644 --- a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/cloud_filter.h +++ b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/cloud_filter.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_APPS_OPTRONIC_VIEWER_CLOUD_FILTER_H_ -#define PCL_APPS_OPTRONIC_VIEWER_CLOUD_FILTER_H_ +#pragma once #include #include @@ -445,5 +444,3 @@ namespace pcl } } } - -#endif // PCL_APPS_OPTRONIC_VIEWER_CLOUD_FILTER_H_ diff --git a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h index d92618c017a..fa5fd1047f8 100644 --- a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h +++ b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_APPS_OPTRONIC_VIEWER_FILTER_WINDOW_H_ -#define PCL_APPS_OPTRONIC_VIEWER_FILTER_WINDOW_H_ +#pragma once #include @@ -116,5 +115,3 @@ namespace pcl } } } - -#endif // PCL_APPS_OPTRONIC_VIEWER_FILTER_WINDOW_H_ diff --git a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/main_window.h b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/main_window.h index 3da12a63464..c60ab71cfc2 100644 --- a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/main_window.h +++ b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/main_window.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_APPS_OPTRONIC_VIEWER_MAIN_WINDOW_H_ -#define PCL_APPS_OPTRONIC_VIEWER_MAIN_WINDOW_H_ +#pragma once #include @@ -170,5 +169,3 @@ namespace pcl } } } - -#endif // PCL_APPS_OPTRONIC_VIEWER_MAIN_WINDOW_H_ diff --git a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/openni_grabber.h b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/openni_grabber.h index 9963a7a77c0..0f6a8d509cc 100644 --- a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/openni_grabber.h +++ b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/openni_grabber.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_APPS_OPTRONIC_VIEWER_OPENNI_GRABBER_H_ -#define PCL_APPS_OPTRONIC_VIEWER_OPENNI_GRABBER_H_ +#pragma once #include #include @@ -84,5 +83,3 @@ namespace pcl } } } - -#endif // PCL_APPS_OPTRONIC_VIEWER_OPENNI_GRABBER_H_ diff --git a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/qt.h b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/qt.h index 140ff70ae3d..467f9ca566e 100644 --- a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/qt.h +++ b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/qt.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_APPS_OPTRONIC_VIEWER_QT_H_ -#define PCL_APPS_OPTRONIC_VIEWER_QT_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -97,5 +96,3 @@ #include #include - -#endif // PCL_APPS_OPTRONIC_VIEWER_QT_H_ diff --git a/common/include/pcl/ModelCoefficients.h b/common/include/pcl/ModelCoefficients.h index e47a568c99c..dfbab2a786e 100644 --- a/common/include/pcl/ModelCoefficients.h +++ b/common/include/pcl/ModelCoefficients.h @@ -1,5 +1,5 @@ -#ifndef PCL_MESSAGE_MODELCOEFFICIENTS_H -#define PCL_MESSAGE_MODELCOEFFICIENTS_H +#pragma once + #include #include #include @@ -41,6 +41,3 @@ namespace pcl } } // namespace pcl - -#endif // PCL_MESSAGE_MODELCOEFFICIENTS_H - diff --git a/common/include/pcl/PCLHeader.h b/common/include/pcl/PCLHeader.h index 854b869ad4b..affc7ffdbe5 100644 --- a/common/include/pcl/PCLHeader.h +++ b/common/include/pcl/PCLHeader.h @@ -1,5 +1,4 @@ -#ifndef PCL_ROSLIB_MESSAGE_HEADER_H -#define PCL_ROSLIB_MESSAGE_HEADER_H +#pragma once #ifdef USE_ROS #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated @@ -50,6 +49,3 @@ namespace pcl } } // namespace pcl - -#endif // PCL_ROSLIB_MESSAGE_HEADER_H - diff --git a/common/include/pcl/PCLImage.h b/common/include/pcl/PCLImage.h index 8d55b5d1003..3e291529ef5 100644 --- a/common/include/pcl/PCLImage.h +++ b/common/include/pcl/PCLImage.h @@ -1,5 +1,5 @@ -#ifndef PCL_MESSAGE_IMAGE_H -#define PCL_MESSAGE_IMAGE_H +#pragma once + #include #include #include @@ -60,6 +60,3 @@ namespace pcl return (s); } } // namespace pcl - -#endif // PCL_MESSAGE_IMAGE_H - diff --git a/common/include/pcl/PCLPointCloud2.h b/common/include/pcl/PCLPointCloud2.h index 6a00c1f2ed1..2f75d5da3d3 100644 --- a/common/include/pcl/PCLPointCloud2.h +++ b/common/include/pcl/PCLPointCloud2.h @@ -1,5 +1,4 @@ -#ifndef PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H -#define PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H +#pragma once #ifdef USE_ROS #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated @@ -89,6 +88,3 @@ namespace pcl } } // namespace pcl - -#endif // PCL_SENSOR_MSGS_MESSAGE_POINTCLOUD2_H - diff --git a/common/include/pcl/PCLPointField.h b/common/include/pcl/PCLPointField.h index 835e353e31e..0aa52fd8572 100644 --- a/common/include/pcl/PCLPointField.h +++ b/common/include/pcl/PCLPointField.h @@ -1,5 +1,4 @@ -#ifndef PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H -#define PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H +#pragma once #ifdef USE_ROS #error USE_ROS setup requires PCL to compile against ROS message headers, which is now deprecated @@ -54,6 +53,3 @@ namespace pcl return (s); } } // namespace pcl - -#endif // PCL_SENSOR_MSGS_MESSAGE_POINTFIELD_H - diff --git a/common/include/pcl/PointIndices.h b/common/include/pcl/PointIndices.h index f2de80654fe..d1320362fc6 100644 --- a/common/include/pcl/PointIndices.h +++ b/common/include/pcl/PointIndices.h @@ -1,5 +1,5 @@ -#ifndef PCL_MESSAGE_POINTINDICES_H -#define PCL_MESSAGE_POINTINDICES_H +#pragma once + #include #include #include @@ -39,6 +39,3 @@ namespace pcl return (s); } } // namespace pcl - -#endif // PCL_MESSAGE_POINTINDICES_H - diff --git a/common/include/pcl/PolygonMesh.h b/common/include/pcl/PolygonMesh.h index 06aa69ef366..b4719c7f36e 100644 --- a/common/include/pcl/PolygonMesh.h +++ b/common/include/pcl/PolygonMesh.h @@ -1,6 +1,6 @@ /* Auto-generated by genmsg_cpp for file /work/ros/pkgs-trunk/point_cloud_perception/pcl/msg/PolygonMesh.msg */ -#ifndef PCL_MESSAGE_POLYGONMESH_H -#define PCL_MESSAGE_POLYGONMESH_H +#pragma once + #include #include #include @@ -48,6 +48,3 @@ namespace pcl } } // namespace pcl - -#endif // PCL_MESSAGE_POLYGONMESH_H - diff --git a/common/include/pcl/TextureMesh.h b/common/include/pcl/TextureMesh.h index 2fd1233d64a..3a58c2656dc 100644 --- a/common/include/pcl/TextureMesh.h +++ b/common/include/pcl/TextureMesh.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_TEXTUREMESH_H_ -#define PCL_TEXTUREMESH_H_ +#pragma once #include #include @@ -109,6 +108,3 @@ namespace pcl typedef boost::shared_ptr TextureMeshPtr; typedef boost::shared_ptr TextureMeshConstPtr; } // namespace pcl - -#endif /* PCL_TEXTUREMESH_H_ */ - diff --git a/common/include/pcl/Vertices.h b/common/include/pcl/Vertices.h index 81ba8a95c50..f222c57527b 100644 --- a/common/include/pcl/Vertices.h +++ b/common/include/pcl/Vertices.h @@ -1,5 +1,5 @@ -#ifndef PCL_MESSAGE_VERTICES_H -#define PCL_MESSAGE_VERTICES_H +#pragma once + #include #include #include @@ -38,6 +38,3 @@ namespace pcl return (s); } } // namespace pcl - -#endif // PCL_MESSAGE_VERTICES_H - diff --git a/common/include/pcl/cloud_iterator.h b/common/include/pcl/cloud_iterator.h index b7a0011267a..b435baa2601 100644 --- a/common/include/pcl/cloud_iterator.h +++ b/common/include/pcl/cloud_iterator.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_POINT_CLOUD_ITERATOR_H_ -#define PCL_POINT_CLOUD_ITERATOR_H_ +#pragma once #include #include @@ -189,5 +188,3 @@ namespace pcl } // namespace pcl #include - -#endif // PCL_POINT_CLOUD_ITERATOR_H_ diff --git a/common/include/pcl/common/angles.h b/common/include/pcl/common/angles.h index 619fe7c2e2e..da7acd789ab 100644 --- a/common/include/pcl/common/angles.h +++ b/common/include/pcl/common/angles.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_COMMON_ANGLES_H_ -#define PCL_COMMON_ANGLES_H_ +#pragma once /** * \file pcl/common/angles.h @@ -85,5 +84,3 @@ namespace pcl } /*@}*/ #include - -#endif // PCL_COMMON_ANGLES_H_ diff --git a/common/include/pcl/common/boost.h b/common/include/pcl/common/boost.h index acc70af5b63..a0d83a1c049 100644 --- a/common/include/pcl/common/boost.h +++ b/common/include/pcl/common/boost.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_COMMON_BOOST_H_ -#define PCL_COMMON_BOOST_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -58,5 +57,3 @@ #include #include #endif - -#endif // PCL_COMMON_BOOST_H_ diff --git a/common/include/pcl/common/centroid.h b/common/include/pcl/common/centroid.h index 7d8e1173e18..8b40e51d290 100644 --- a/common/include/pcl/common/centroid.h +++ b/common/include/pcl/common/centroid.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_COMMON_CENTROID_H_ -#define PCL_COMMON_CENTROID_H_ +#pragma once #include #include @@ -1130,5 +1129,3 @@ namespace pcl } /*@}*/ #include - -#endif //#ifndef PCL_COMMON_CENTROID_H_ diff --git a/common/include/pcl/common/colors.h b/common/include/pcl/common/colors.h index 419bd97805b..584fba454e4 100644 --- a/common/include/pcl/common/colors.h +++ b/common/include/pcl/common/colors.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_COMMON_COLORS_H -#define PCL_COMMON_COLORS_H +#pragma once #include #include @@ -85,6 +84,3 @@ namespace pcl typedef ColorLUT ViridisLUT; } - -#endif /* PCL_COMMON_COLORS_H */ - diff --git a/common/include/pcl/common/common.h b/common/include/pcl/common/common.h index d9fc4faf81c..49b2210b25a 100644 --- a/common/include/pcl/common/common.h +++ b/common/include/pcl/common/common.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_COMMON_H_ -#define PCL_COMMON_H_ +#pragma once #include #include @@ -204,5 +203,3 @@ namespace pcl } /*@}*/ #include - -#endif //#ifndef PCL_COMMON_H_ diff --git a/common/include/pcl/common/common_headers.h b/common/include/pcl/common/common_headers.h index 626f3b78701..bf68765d8d8 100644 --- a/common/include/pcl/common/common_headers.h +++ b/common/include/pcl/common/common_headers.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_COMMON_HEADERS_ -#define PCL_COMMON_HEADERS_ +#pragma once #include #include @@ -42,5 +41,3 @@ #include #include #include - -#endif //#ifndef PCL_COMMON_HEADERS_ diff --git a/common/include/pcl/common/concatenate.h b/common/include/pcl/common/concatenate.h index f1aa87e1223..3c391b3a4b1 100644 --- a/common/include/pcl/common/concatenate.h +++ b/common/include/pcl/common/concatenate.h @@ -35,8 +35,8 @@ * * */ -#ifndef PCL_COMMON_CONCATENATE_H_ -#define PCL_COMMON_CONCATENATE_H_ + +#pragma once #include @@ -102,6 +102,3 @@ namespace pcl # pragma warning(pop) # endif #endif - -#endif // PCL_COMMON_CONCATENATE_H_ - diff --git a/common/include/pcl/common/copy_point.h b/common/include/pcl/common/copy_point.h index 0e80cfe733a..2f490ad64be 100644 --- a/common/include/pcl/common/copy_point.h +++ b/common/include/pcl/common/copy_point.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_COMMON_COPY_POINT_H_ -#define PCL_COMMON_COPY_POINT_H_ +#pragma once namespace pcl { @@ -57,6 +56,3 @@ namespace pcl } #include - -#endif // PCL_COMMON_COPY_POINT_H_ - diff --git a/common/include/pcl/common/distances.h b/common/include/pcl/common/distances.h index 144074813c7..44dc99967d7 100644 --- a/common/include/pcl/common/distances.h +++ b/common/include/pcl/common/distances.h @@ -34,8 +34,8 @@ * $Id$ * */ -#ifndef PCL_DISTANCES_H_ -#define PCL_DISTANCES_H_ + +#pragma once #include @@ -198,6 +198,3 @@ namespace pcl return (std::sqrt (squaredEuclideanDistance (p1, p2))); } } -/*@*/ -#endif //#ifndef PCL_DISTANCES_H_ - diff --git a/common/include/pcl/common/eigen.h b/common/include/pcl/common/eigen.h index 3869c92fe3d..f5219b39ae8 100644 --- a/common/include/pcl/common/eigen.h +++ b/common/include/pcl/common/eigen.h @@ -39,8 +39,8 @@ * $Id$ * */ -#ifndef PCL_COMMON_EIGEN_H_ -#define PCL_COMMON_EIGEN_H_ + +#pragma once #ifndef NOMINMAX #define NOMINMAX @@ -718,5 +718,3 @@ namespace pcl #if defined __SUNPRO_CC # pragma enable_warn #endif - -#endif //PCL_COMMON_EIGEN_H_ diff --git a/common/include/pcl/common/feature_histogram.h b/common/include/pcl/common/feature_histogram.h index 99ba8a6ddc9..46d7d611442 100644 --- a/common/include/pcl/common/feature_histogram.h +++ b/common/include/pcl/common/feature_histogram.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_FEATURE_HISTOGRAM_H_ -#define PCL_FEATURE_HISTOGRAM_H_ +#pragma once #include @@ -122,4 +121,3 @@ namespace pcl size_t number_of_bins_; }; } -#endif // PCL_FEATURE_HISTOGRAM_H_ \ No newline at end of file diff --git a/common/include/pcl/common/file_io.h b/common/include/pcl/common/file_io.h index fb1ee18a62c..f4fa71c9886 100644 --- a/common/include/pcl/common/file_io.h +++ b/common/include/pcl/common/file_io.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_COMMON_FILE_IO_H_ -#define PCL_COMMON_FILE_IO_H_ +#pragma once #include #ifndef _WIN32 @@ -87,5 +86,3 @@ namespace pcl } // namespace end /*@}*/ #include - -#endif //#ifndef PCL_FILE_IO_H_ diff --git a/common/include/pcl/common/gaussian.h b/common/include/pcl/common/gaussian.h index 2c38937d632..16c6d225eda 100644 --- a/common/include/pcl/common/gaussian.h +++ b/common/include/pcl/common/gaussian.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_GAUSSIAN_KERNEL -#define PCL_GAUSSIAN_KERNEL +#pragma once #include #include @@ -262,5 +261,3 @@ namespace pcl } #include - -#endif // PCL_GAUSSIAN_KERNEL diff --git a/common/include/pcl/common/generate.h b/common/include/pcl/common/generate.h index 1cfd214c069..6305c713628 100644 --- a/common/include/pcl/common/generate.h +++ b/common/include/pcl/common/generate.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_COMMON_GENERATE_H_ -#define PCL_COMMON_GENERATE_H_ +#pragma once #include #include @@ -185,5 +184,3 @@ namespace pcl } #include - -#endif diff --git a/common/include/pcl/common/geometry.h b/common/include/pcl/common/geometry.h index dd19237f0e1..c7b613e17cb 100644 --- a/common/include/pcl/common/geometry.h +++ b/common/include/pcl/common/geometry.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_GEOMETRY_H_ -#define PCL_GEOMETRY_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -160,6 +159,3 @@ namespace pcl } } - -/*@}*/ -#endif //#ifndef PCL_GEOMETRY_H_ diff --git a/common/include/pcl/common/intensity.h b/common/include/pcl/common/intensity.h index 18ede88eb0a..cd38fc402d7 100644 --- a/common/include/pcl/common/intensity.h +++ b/common/include/pcl/common/intensity.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_COMMON_INTENSITY_FIELD_SELECTOR_H -#define PCL_COMMON_INTENSITY_FIELD_SELECTOR_H +#pragma once namespace pcl { @@ -100,5 +99,3 @@ namespace pcl } #include - -#endif diff --git a/common/include/pcl/common/intersections.h b/common/include/pcl/common/intersections.h index d0b6733b369..28a3f80e828 100644 --- a/common/include/pcl/common/intersections.h +++ b/common/include/pcl/common/intersections.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_INTERSECTIONS_H_ -#define PCL_INTERSECTIONS_H_ +#pragma once #include #include @@ -156,5 +155,3 @@ namespace pcl /*@}*/ #include - -#endif //#ifndef PCL_INTERSECTIONS_H_ diff --git a/common/include/pcl/common/io.h b/common/include/pcl/common/io.h index 6779d800c17..11316f1c645 100644 --- a/common/include/pcl/common/io.h +++ b/common/include/pcl/common/io.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_COMMON_IO_H_ -#define PCL_COMMON_IO_H_ +#pragma once #include #include @@ -532,6 +531,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_COMMON_IO_H_ - diff --git a/common/include/pcl/common/norms.h b/common/include/pcl/common/norms.h index d4fb82ccba9..c97a162f055 100644 --- a/common/include/pcl/common/norms.h +++ b/common/include/pcl/common/norms.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_COMMON_NORMS_H_ -#define PCL_COMMON_NORMS_H_ +#pragma once /** * \file norms.h @@ -197,5 +196,3 @@ namespace pcl } /*@}*/ #include - -#endif //#ifndef PCL_NORMS_H_ diff --git a/common/include/pcl/common/pca.h b/common/include/pcl/common/pca.h index de71fd0cb05..1857abe3749 100644 --- a/common/include/pcl/common/pca.h +++ b/common/include/pcl/common/pca.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_PCA_H -#define PCL_PCA_H +#pragma once #include #include @@ -284,6 +283,3 @@ namespace pcl } // namespace pcl #include - -#endif // PCL_PCA_H - diff --git a/common/include/pcl/common/piecewise_linear_function.h b/common/include/pcl/common/piecewise_linear_function.h index 1be4eb0b95c..837f9cea165 100644 --- a/common/include/pcl/common/piecewise_linear_function.h +++ b/common/include/pcl/common/piecewise_linear_function.h @@ -35,8 +35,7 @@ /* \author Bastian Steder */ -#ifndef PCL_PIECEWISE_LINEAR_FUNCTION_H_ -#define PCL_PIECEWISE_LINEAR_FUNCTION_H_ +#pragma once #include @@ -77,5 +76,3 @@ namespace pcl } // end namespace pcl #include - -#endif //#ifndef PCL_PIECEWISE_LINEAR_FUNCTION_H_ diff --git a/common/include/pcl/common/point_operators.h b/common/include/pcl/common/point_operators.h index a28397f991a..b32c86e6ae8 100644 --- a/common/include/pcl/common/point_operators.h +++ b/common/include/pcl/common/point_operators.h @@ -38,7 +38,4 @@ * */ -#ifndef PCL_COMMON_POINT_OPERATORS_H -#define PCL_COMMON_POINT_OPERATORS_H - -#endif +#pragma once diff --git a/common/include/pcl/common/point_tests.h b/common/include/pcl/common/point_tests.h index a110f76325b..730911b100a 100644 --- a/common/include/pcl/common/point_tests.h +++ b/common/include/pcl/common/point_tests.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_COMMON_POINT_TESTS_H_ -#define PCL_COMMON_POINT_TESTS_H_ +#pragma once #ifdef _MSC_VER #include @@ -109,6 +108,3 @@ namespace pcl return (pcl_isfinite (n.normal_x) && pcl_isfinite (n.normal_y) && pcl_isfinite (n.normal_z)); } } - -#endif // PCL_COMMON_POINT_TESTS_H_ - diff --git a/common/include/pcl/common/polynomial_calculations.h b/common/include/pcl/common/polynomial_calculations.h index 111d41fe30b..b537debb8b5 100644 --- a/common/include/pcl/common/polynomial_calculations.h +++ b/common/include/pcl/common/polynomial_calculations.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_POLYNOMIAL_CALCULATIONS_H_ -#define PCL_POLYNOMIAL_CALCULATIONS_H_ +#pragma once #include #include @@ -131,5 +130,3 @@ namespace pcl } // end namespace #include - -#endif diff --git a/common/include/pcl/common/poses_from_matches.h b/common/include/pcl/common/poses_from_matches.h index 45a10d9c9d8..332e078665a 100644 --- a/common/include/pcl/common/poses_from_matches.h +++ b/common/include/pcl/common/poses_from_matches.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_POSES_FROM_MATCHES_H_ -#define PCL_POSES_FROM_MATCHES_H_ +#pragma once #include #include @@ -128,5 +127,3 @@ namespace pcl }; } // end namespace pcl - -#endif //#ifndef PCL_POSES_FROM_MATCHES_H_ diff --git a/common/include/pcl/common/random.h b/common/include/pcl/common/random.h index da446086ba0..65c9b582cb7 100644 --- a/common/include/pcl/common/random.h +++ b/common/include/pcl/common/random.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_COMMON_RANDOM_H_ -#define PCL_COMMON_RANDOM_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -229,5 +228,3 @@ namespace pcl } #include - -#endif diff --git a/common/include/pcl/common/spring.h b/common/include/pcl/common/spring.h index 4d980829df4..2cb02f0dea7 100644 --- a/common/include/pcl/common/spring.h +++ b/common/include/pcl/common/spring.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_POINT_CLOUD_SPRING_H_ -#define PCL_POINT_CLOUD_SPRING_H_ +#pragma once #include @@ -128,5 +127,3 @@ namespace pcl } #include - -#endif diff --git a/common/include/pcl/common/time.h b/common/include/pcl/common/time.h index 093c262eca2..1f88e2c2170 100644 --- a/common/include/pcl/common/time.h +++ b/common/include/pcl/common/time.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_TIME_H_ -#define PCL_TIME_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -233,5 +232,3 @@ if (1) {\ } // end namespace /*@}*/ - -#endif //#ifndef PCL_NORMS_H_ diff --git a/common/include/pcl/common/time_trigger.h b/common/include/pcl/common/time_trigger.h index c4af9b5e910..cb8f50adfec 100644 --- a/common/include/pcl/common/time_trigger.h +++ b/common/include/pcl/common/time_trigger.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_COMMON_TIME_TRIGGER_H_ -#define PCL_COMMON_TIME_TRIGGER_H_ +#pragma once #include #ifndef Q_MOC_RUN @@ -104,5 +103,3 @@ namespace pcl boost::mutex condition_mutex_; }; } - -#endif diff --git a/common/include/pcl/common/transformation_from_correspondences.h b/common/include/pcl/common/transformation_from_correspondences.h index 8d4ca51c46e..e83c11025c9 100644 --- a/common/include/pcl/common/transformation_from_correspondences.h +++ b/common/include/pcl/common/transformation_from_correspondences.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_TRANSFORMATION_FROM_CORRESPONDENCES_H -#define PCL_TRANSFORMATION_FROM_CORRESPONDENCES_H +#pragma once #include @@ -96,6 +95,3 @@ namespace pcl } // END namespace #include - -#endif // #ifndef PCL_TRANSFORMATION_FROM_CORRESPONDENCES_H - diff --git a/common/include/pcl/common/transforms.h b/common/include/pcl/common/transforms.h index b7b6bdfc20e..7d6a9dfc6b1 100644 --- a/common/include/pcl/common/transforms.h +++ b/common/include/pcl/common/transforms.h @@ -36,8 +36,8 @@ * * */ -#ifndef PCL_TRANSFORMS_H_ -#define PCL_TRANSFORMS_H_ + +#pragma once #include #include @@ -496,5 +496,3 @@ namespace pcl } #include - -#endif // PCL_TRANSFORMS_H_ diff --git a/common/include/pcl/common/utils.h b/common/include/pcl/common/utils.h index 8a7ef86471a..ffc83f4fd21 100644 --- a/common/include/pcl/common/utils.h +++ b/common/include/pcl/common/utils.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_UTILS -#define PCL_UTILS +#pragma once #include @@ -58,5 +57,3 @@ namespace pcl } } } - -#endif diff --git a/common/include/pcl/common/vector_average.h b/common/include/pcl/common/vector_average.h index 3651c96c924..b7523aeb4b1 100644 --- a/common/include/pcl/common/vector_average.h +++ b/common/include/pcl/common/vector_average.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_COMMON_VECTOR_AVERAGE_H -#define PCL_COMMON_VECTOR_AVERAGE_H +#pragma once #include @@ -117,6 +116,3 @@ namespace pcl } // END namespace #include - -#endif // #ifndef PCL_VECTOR_AVERAGE_H - diff --git a/common/include/pcl/console/parse.h b/common/include/pcl/console/parse.h index b9afc062dbf..79e14f456c1 100644 --- a/common/include/pcl/console/parse.h +++ b/common/include/pcl/console/parse.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_CONSOLE_PARSE_H_ -#define PCL_CONSOLE_PARSE_H_ + +#pragma once #include #include @@ -368,6 +368,3 @@ namespace pcl parse_file_extension_argument (int argc, const char * const * argv, const std::string &ext); } } - -#endif // PCL_CONSOLE_PARSE_H_ - diff --git a/common/include/pcl/conversions.h b/common/include/pcl/conversions.h index f365d5ded7b..6e41f823c87 100644 --- a/common/include/pcl/conversions.h +++ b/common/include/pcl/conversions.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_CONVERSIONS_H_ -#define PCL_CONVERSIONS_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -351,5 +350,3 @@ namespace pcl } } } - -#endif //#ifndef PCL_CONVERSIONS_H_ diff --git a/common/include/pcl/correspondence.h b/common/include/pcl/correspondence.h index ed01627d7d7..ba9312eb5a1 100644 --- a/common/include/pcl/correspondence.h +++ b/common/include/pcl/correspondence.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_COMMON_CORRESPONDENCE_H_ -#define PCL_COMMON_CORRESPONDENCE_H_ + +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -159,5 +159,3 @@ namespace pcl return (pc1.distance > pc2.distance); } } - -#endif /* PCL_COMMON_CORRESPONDENCE_H_ */ diff --git a/common/include/pcl/exceptions.h b/common/include/pcl/exceptions.h index 485e1e67a8a..f5d98b7e3e0 100644 --- a/common/include/pcl/exceptions.h +++ b/common/include/pcl/exceptions.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_EXCEPTIONS_H_ -#define PCL_EXCEPTIONS_H_ + +#pragma once #include #include @@ -263,7 +263,3 @@ namespace pcl : pcl::PCLException (error_description, file_name, function_name, line_number) { } }; } - - - -#endif diff --git a/common/include/pcl/for_each_type.h b/common/include/pcl/for_each_type.h index d6973d4ad12..762d0c37b11 100644 --- a/common/include/pcl/for_each_type.h +++ b/common/include/pcl/for_each_type.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FOR_EACH_TYPE_H_ -#define PCL_FOR_EACH_TYPE_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -105,5 +104,3 @@ namespace pcl typedef typename boost::mpl::remove_if > >::type type; }; } - -#endif //#ifndef PCL_FOR_EACH_TYPE_H_ diff --git a/common/include/pcl/pcl_base.h b/common/include/pcl/pcl_base.h index 92f94720e27..3c5f2d0e81f 100644 --- a/common/include/pcl/pcl_base.h +++ b/common/include/pcl/pcl_base.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_PCL_BASE_H_ -#define PCL_PCL_BASE_H_ + +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -259,5 +259,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_PCL_BASE_H_ diff --git a/common/include/pcl/pcl_exports.h b/common/include/pcl/pcl_exports.h index 708216a68a7..b92818a465b 100644 --- a/common/include/pcl/pcl_exports.h +++ b/common/include/pcl/pcl_exports.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_EXPORTS_H_ -#define PCL_EXPORTS_H_ +#pragma once // This header is created to include to NVCC compiled sources. // Header 'pcl_macros' is not suitable since it includes , @@ -48,5 +47,3 @@ #else #define PCL_EXPORTS #endif - -#endif //#ifndef PCL_EXPORTS_H_ diff --git a/common/include/pcl/pcl_macros.h b/common/include/pcl/pcl_macros.h index 7a5f78dd12e..cd755043917 100644 --- a/common/include/pcl/pcl_macros.h +++ b/common/include/pcl/pcl_macros.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_MACROS_H_ -#define PCL_MACROS_H_ +#pragma once #include #include @@ -438,5 +437,3 @@ aligned_free (void* ptr) #error aligned_free not supported on your platform #endif } - -#endif //#ifndef PCL_MACROS_H_ diff --git a/common/include/pcl/pcl_tests.h b/common/include/pcl/pcl_tests.h index 5b378542303..5b242218dd4 100644 --- a/common/include/pcl/pcl_tests.h +++ b/common/include/pcl/pcl_tests.h @@ -36,9 +36,7 @@ * $Id$ */ - -#ifndef PCL_TEST_MACROS -#define PCL_TEST_MACROS +#pragma once #include @@ -314,5 +312,3 @@ namespace pcl #define EXPECT_METADATA_EQ(expected, actual) \ EXPECT_PRED_FORMAT2(::pcl::test::internal::MetaDataEQ, \ expected, actual) - -#endif diff --git a/common/include/pcl/point_cloud.h b/common/include/pcl/point_cloud.h index aa1e8f4555f..bf4d4e71b03 100644 --- a/common/include/pcl/point_cloud.h +++ b/common/include/pcl/point_cloud.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_POINT_CLOUD_H_ -#define PCL_POINT_CLOUD_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -629,5 +628,3 @@ namespace pcl } #define PCL_INSTANTIATE_PointCloud(T) template class PCL_EXPORTS pcl::PointCloud; - -#endif //#ifndef PCL_POINT_CLOUD_H_ diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h index 4b8843d7ea7..287dca9ed26 100644 --- a/common/include/pcl/point_representation.h +++ b/common/include/pcl/point_representation.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_POINT_REPRESENTATION_H_ -#define PCL_POINT_REPRESENTATION_H_ + +#pragma once #include #include @@ -579,5 +579,3 @@ namespace pcl int start_dim_; }; } - -#endif // #ifndef PCL_POINT_REPRESENTATION_H_ diff --git a/common/include/pcl/point_traits.h b/common/include/pcl/point_traits.h index e69004316d4..d595498d649 100644 --- a/common/include/pcl/point_traits.h +++ b/common/include/pcl/point_traits.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_POINT_TRAITS_H_ -#define PCL_POINT_TRAITS_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -353,5 +352,3 @@ namespace pcl value = *reinterpret_cast(data_ptr); } } - -#endif //#ifndef PCL_POINT_TRAITS_H_ diff --git a/common/include/pcl/point_types.h b/common/include/pcl/point_types.h index b0c6ddfdad7..386f9bb2419 100644 --- a/common/include/pcl/point_types.h +++ b/common/include/pcl/point_types.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_DATA_TYPES_H_ -#define PCL_DATA_TYPES_H_ + +#pragma once #include #include @@ -834,5 +834,3 @@ namespace pcl #pragma warning(default: 4201) #endif //#pragma warning(pop) - -#endif //#ifndef PCL_DATA_TYPES_H_ diff --git a/common/include/pcl/point_types_conversion.h b/common/include/pcl/point_types_conversion.h index cc561f9cf67..15d0a29865c 100644 --- a/common/include/pcl/point_types_conversion.h +++ b/common/include/pcl/point_types_conversion.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_TYPE_CONVERSIONS_H -#define PCL_TYPE_CONVERSIONS_H +#pragma once #include @@ -394,6 +393,3 @@ namespace pcl out.height = height_; } } - -#endif //#ifndef PCL_TYPE_CONVERSIONS_H - diff --git a/common/include/pcl/range_image/bearing_angle_image.h b/common/include/pcl/range_image/bearing_angle_image.h index b022be520af..4f0c5813c12 100644 --- a/common/include/pcl/range_image/bearing_angle_image.h +++ b/common/include/pcl/range_image/bearing_angle_image.h @@ -39,8 +39,7 @@ * \Created on: July 07, 2012 */ -#ifndef PCL_BEARING_ANGLE_IMAGE_H_ -#define PCL_BEARING_ANGLE_IMAGE_H_ +#pragma once #include #include @@ -85,5 +84,3 @@ namespace pcl PointXYZRGBA unobserved_point_; }; } - -#endif // PCL_BEARING_ANGLE_IMAGE_H_ diff --git a/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index e2d1d2a6836..88f2a2e70b0 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RANGE_IMAGE_H_ -#define PCL_RANGE_IMAGE_H_ +#pragma once #include #include @@ -840,5 +839,3 @@ namespace pcl #include // Definitions of templated and inline functions - -#endif //#ifndef PCL_RANGE_IMAGE_H_ diff --git a/common/include/pcl/range_image/range_image_planar.h b/common/include/pcl/range_image/range_image_planar.h index 3d2db0c6d9f..88c1ea75213 100644 --- a/common/include/pcl/range_image/range_image_planar.h +++ b/common/include/pcl/range_image/range_image_planar.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RANGE_IMAGE_PLANAR_H_ -#define PCL_RANGE_IMAGE_PLANAR_H_ +#pragma once #include @@ -215,5 +214,3 @@ namespace pcl #include // Definitions of templated and inline functions - -#endif //#ifndef PCL_RANGE_IMAGE_H_ diff --git a/common/include/pcl/range_image/range_image_spherical.h b/common/include/pcl/range_image/range_image_spherical.h index 82ea66373ba..f595d2e7f5b 100644 --- a/common/include/pcl/range_image/range_image_spherical.h +++ b/common/include/pcl/range_image/range_image_spherical.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RANGE_IMAGE_SPHERICAL_H_ -#define PCL_RANGE_IMAGE_SPHERICAL_H_ +#pragma once #include @@ -110,5 +109,3 @@ namespace pcl #include // Definitions of templated and inline functions - -#endif //#ifndef PCL_RANGE_IMAGE_SPHERICAL_H_ diff --git a/common/include/pcl/register_point_struct.h b/common/include/pcl/register_point_struct.h index 57a0e42634e..349063c97b8 100644 --- a/common/include/pcl/register_point_struct.h +++ b/common/include/pcl/register_point_struct.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTER_POINT_STRUCT_H_ -#define PCL_REGISTER_POINT_STRUCT_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -363,5 +362,3 @@ namespace pcl #if defined _MSC_VER #pragma warning (pop) #endif - -#endif //#ifndef PCL_REGISTER_POINT_STRUCT_H_ diff --git a/common/include/pcl/sse.h b/common/include/pcl/sse.h index dc84aa8deb9..54a139e41c4 100644 --- a/common/include/pcl/sse.h +++ b/common/include/pcl/sse.h @@ -36,8 +36,8 @@ * */ -#ifndef PCL_SSE_H_ -#define PCL_SSE_H_ +#pragma once + #if defined(__SSE2__) #include // SSE2:, SSE3:, SSE4: @@ -96,4 +96,3 @@ RETi sse_cvt( const __m128 x ) { return _mm_cvttps_epi32(x); } #undef RETf #undef RETi #endif /* defined(__SSE2__) */ -#endif /* PCL_SSE_H_ */ diff --git a/cuda/common/include/pcl/cuda/common/eigen.h b/cuda/common/include/pcl/cuda/common/eigen.h index f7d3c6bb83a..c28a2803743 100644 --- a/cuda/common/include/pcl/cuda/common/eigen.h +++ b/cuda/common/include/pcl/cuda/common/eigen.h @@ -87,8 +87,7 @@ // ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER // DEALINGS IN THE SOFTWARE. -#ifndef PCL_CUDA_EIGEN_H_ -#define PCL_CUDA_EIGEN_H_ +#pragma once #include #include @@ -770,5 +769,3 @@ namespace pcl } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_EIGEN_H_ diff --git a/cuda/common/include/pcl/cuda/common/point_type_rgb.h b/cuda/common/include/pcl/cuda/common/point_type_rgb.h index 6ab50abb772..ae606c19d09 100644 --- a/cuda/common/include/pcl/cuda/common/point_type_rgb.h +++ b/cuda/common/include/pcl/cuda/common/point_type_rgb.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_CUDA_COMMON_POINT_TYPE_RGB_H_ -#define PCL_CUDA_COMMON_POINT_TYPE_RGB_H_ +#pragma once #include #include @@ -118,5 +117,3 @@ namespace cuda } // namespace } // namespace -#endif //#ifndef PCL_CUDA_COMMON_POINT_TYPE_RGB_H_ - diff --git a/cuda/common/include/pcl/cuda/pcl_cuda_base.h b/cuda/common/include/pcl/cuda/pcl_cuda_base.h index 6ab94b2d368..596c1f81496 100644 --- a/cuda/common/include/pcl/cuda/pcl_cuda_base.h +++ b/cuda/common/include/pcl/cuda/pcl_cuda_base.h @@ -32,8 +32,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_CUDA_PCL_CUDA_BASE_H_ -#define PCL_CUDA_PCL_CUDA_BASE_H_ + +#pragma once #include #include @@ -95,5 +95,3 @@ namespace cuda }; } // namespace } // namespace - -#endif //#ifndef PCL_PCL_BASE_H_ diff --git a/cuda/common/include/pcl/cuda/point_cloud.h b/cuda/common/include/pcl/cuda/point_cloud.h index e47630a9bfc..88c583de0f3 100644 --- a/cuda/common/include/pcl/cuda/point_cloud.h +++ b/cuda/common/include/pcl/cuda/point_cloud.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_POINT_CLOUD_H_ -#define PCL_CUDA_POINT_CLOUD_H_ +#pragma once #include #include @@ -382,5 +381,3 @@ namespace pcl } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_POINT_CLOUD_H_ diff --git a/cuda/common/include/pcl/cuda/point_types.h b/cuda/common/include/pcl/cuda/point_types.h index 645fef05c15..cc6554f1f3c 100644 --- a/cuda/common/include/pcl/cuda/point_types.h +++ b/cuda/common/include/pcl/cuda/point_types.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_POINT_TYPES_H_ -#define PCL_CUDA_POINT_TYPES_H_ +#pragma once #include #include @@ -201,6 +200,3 @@ namespace cuda }; } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_POINT_TYPES_H_ - diff --git a/cuda/common/include/pcl/cuda/thrust.h b/cuda/common/include/pcl/cuda/thrust.h index 57586abefc9..bba05d96113 100644 --- a/cuda/common/include/pcl/cuda/thrust.h +++ b/cuda/common/include/pcl/cuda/thrust.h @@ -37,14 +37,10 @@ * */ -#ifndef PCL_CUDA_COMMON_THRUST_H_ -#define PCL_CUDA_COMMON_THRUST_H_ +#pragma once #include #include #include #include #include - -#endif // PCL_CUDA_COMMON_THRUST_H_ - diff --git a/cuda/common/include/pcl/cuda/time_cpu.h b/cuda/common/include/pcl/cuda/time_cpu.h index be9d0b872a9..e116b17c870 100644 --- a/cuda/common/include/pcl/cuda/time_cpu.h +++ b/cuda/common/include/pcl/cuda/time_cpu.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_CUDA_TIME_CPU_H_ -#define PCL_CUDA_TIME_CPU_H_ +#pragma once #include #include @@ -136,5 +135,3 @@ inline pcl::cuda::ScopeTimeCPU::~ScopeTimeCPU () double duration = end_time - start_time_; std::cerr << title_ << " took " << 1000 * duration << "ms. " << std::endl; } - -#endif //#ifndef PCL_NORMS_H_ diff --git a/cuda/common/include/pcl/cuda/time_gpu.h b/cuda/common/include/pcl/cuda/time_gpu.h index b177bd3920d..73deef9a1b3 100644 --- a/cuda/common/include/pcl/cuda/time_gpu.h +++ b/cuda/common/include/pcl/cuda/time_gpu.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_TIME_GPU_H_ -#define PCL_CUDA_TIME_GPU_H_ +#pragma once #include #include @@ -111,5 +110,3 @@ namespace pcl }; } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_TIMER_H_ diff --git a/cuda/features/include/pcl/cuda/features/normal_3d.h b/cuda/features/include/pcl/cuda/features/normal_3d.h index 68c41d13ace..b3da2c9b50a 100644 --- a/cuda/features/include/pcl/cuda/features/normal_3d.h +++ b/cuda/features/include/pcl/cuda/features/normal_3d.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_NORMAL_3D_H_ -#define PCL_CUDA_NORMAL_3D_H_ +#pragma once #include @@ -69,7 +68,3 @@ namespace pcl boost::shared_ptr::type> computeWeirdPointNormals (InputIteratorT begin, InputIteratorT end, float focallength, const boost::shared_ptr > &input, float radius, int desired_number_neighbors); } // namespace } // namespace - -#endif - - diff --git a/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h b/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h index 10ce06cf31d..c1c867f0af7 100644 --- a/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h +++ b/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_NORMAL_3D_H_ -#define PCL_CUDA_NORMAL_3D_H_ +#pragma once #include @@ -200,7 +199,3 @@ namespace pcl } // namespace } // namespace - -#endif - - diff --git a/cuda/filters/include/pcl/cuda/filters/filter.h b/cuda/filters/include/pcl/cuda/filters/filter.h index 28d21771886..f080ac71ed3 100644 --- a/cuda/filters/include/pcl/cuda/filters/filter.h +++ b/cuda/filters/include/pcl/cuda/filters/filter.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_CUDA_FILTER_H_ -#define PCL_CUDA_FILTER_H_ +#pragma once #include #include @@ -176,5 +175,3 @@ namespace pcl_cuda getClassName () const { return (filter_name_); } }; } - -#endif //#ifndef PCL_FILTER_H_ diff --git a/cuda/filters/include/pcl/cuda/filters/passthrough.h b/cuda/filters/include/pcl/cuda/filters/passthrough.h index 4fcde670561..f7d375555a7 100644 --- a/cuda/filters/include/pcl/cuda/filters/passthrough.h +++ b/cuda/filters/include/pcl/cuda/filters/passthrough.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_CUDA_FILTERS_PASSTHROUGH_H_ -#define PCL_CUDA_FILTERS_PASSTHROUGH_H_ +#pragma once #include #include @@ -201,5 +200,3 @@ namespace pcl_cuda bool zip_; }; } - -#endif //#ifndef PCL_FILTERS_PASSTHROUGH_H_ diff --git a/cuda/filters/include/pcl/cuda/filters/voxel_grid.h b/cuda/filters/include/pcl/cuda/filters/voxel_grid.h index 3bab1bb39eb..ba3a90d53fa 100644 --- a/cuda/filters/include/pcl/cuda/filters/voxel_grid.h +++ b/cuda/filters/include/pcl/cuda/filters/voxel_grid.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_CUDA_FILTERS_VOXELGRID_H_ -#define PCL_CUDA_FILTERS_VOXELGRID_H_ +#pragma once #include #include @@ -165,5 +164,3 @@ namespace pcl_cuda bool zip_; }; } - -#endif //#ifndef PCL_FILTERS_VOXELGRID_H_ diff --git a/cuda/io/include/pcl/cuda/io/cloud_to_pcl.h b/cuda/io/include/pcl/cuda/io/cloud_to_pcl.h index 722300ff912..7c34e812257 100644 --- a/cuda/io/include/pcl/cuda/io/cloud_to_pcl.h +++ b/cuda/io/include/pcl/cuda/io/cloud_to_pcl.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_CLOUD_TO_PCL_H_ -#define PCL_CUDA_CLOUD_TO_PCL_H_ +#pragma once #include @@ -71,5 +70,3 @@ namespace pcl fromPCL (const pcl::PointCloud &input, PointCloudAOS &output); } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_CLOUD_TO_PCL_H_ diff --git a/cuda/io/include/pcl/cuda/io/debayering.h b/cuda/io/include/pcl/cuda/io/debayering.h index 979b5f4cd02..0f6feda63fe 100644 --- a/cuda/io/include/pcl/cuda/io/debayering.h +++ b/cuda/io/include/pcl/cuda/io/debayering.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_DEBAYERING_H_ -#define PCL_CUDA_DEBAYERING_H_ +#pragma once #include #include @@ -138,5 +137,3 @@ namespace pcl } // namespace } // namespace - -#endif diff --git a/cuda/io/include/pcl/cuda/io/disparity_to_cloud.h b/cuda/io/include/pcl/cuda/io/disparity_to_cloud.h index ce752492d85..f999fa7db24 100644 --- a/cuda/io/include/pcl/cuda/io/disparity_to_cloud.h +++ b/cuda/io/include/pcl/cuda/io/disparity_to_cloud.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_DISPARITY_TO_CLOUD_H_ -#define PCL_CUDA_DISPARITY_TO_CLOUD_H_ +#pragma once #include #include @@ -153,5 +152,3 @@ namespace cuda } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_DISPARITY_TO_CLOUD_H_ diff --git a/cuda/io/include/pcl/cuda/io/extract_indices.h b/cuda/io/include/pcl/cuda/io/extract_indices.h index ac1d988615a..f22f4eadc5f 100644 --- a/cuda/io/include/pcl/cuda/io/extract_indices.h +++ b/cuda/io/include/pcl/cuda/io/extract_indices.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_EXTRACT_INDICES_H_ -#define PCL_CUDA_EXTRACT_INDICES_H_ +#pragma once #include @@ -81,6 +80,3 @@ namespace cuda typename Storage::type &colors); } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_EXTRACT_INDICES_H_ - diff --git a/cuda/io/include/pcl/cuda/io/host_device.h b/cuda/io/include/pcl/cuda/io/host_device.h index 467fe14f012..85f0b2af86e 100644 --- a/cuda/io/include/pcl/cuda/io/host_device.h +++ b/cuda/io/include/pcl/cuda/io/host_device.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_HOST_DEVICE_H_ -#define PCL_CUDA_HOST_DEVICE_H_ +#pragma once #include @@ -61,5 +60,3 @@ namespace pcl } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_HOST_DEVICE_H_ diff --git a/cuda/io/include/pcl/cuda/io/kinect_smoothing.h b/cuda/io/include/pcl/cuda/io/kinect_smoothing.h index 6749a80ee7f..8f70ad30e9f 100644 --- a/cuda/io/include/pcl/cuda/io/kinect_smoothing.h +++ b/cuda/io/include/pcl/cuda/io/kinect_smoothing.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_KINECT_SMOOTHING_H_ -#define PCL_CUDA_KINECT_SMOOTHING_H_ +#pragma once #include #include @@ -293,6 +292,3 @@ namespace pcl } // namespace } // namespace - -#endif - diff --git a/cuda/io/include/pcl/cuda/io/predicate.h b/cuda/io/include/pcl/cuda/io/predicate.h index 322f4303e4e..aad8b87f3cd 100644 --- a/cuda/io/include/pcl/cuda/io/predicate.h +++ b/cuda/io/include/pcl/cuda/io/predicate.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_PREDICATE_H_ -#define PCL_CUDA_PREDICATE_H_ +#pragma once //#if THRUST_DEVICE_COMPILER == THRUST_DEVICE_COMPILER_NVCC //#undef __MMX__ @@ -91,7 +90,3 @@ namespace cuda } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_PREDICATE_H_ - - diff --git a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/msac.h b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/msac.h index 953769a705a..3a4af5cbfe7 100644 --- a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/msac.h +++ b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/msac.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MSAC_H_ -#define PCL_CUDA_SAMPLE_CONSENSUS_MSAC_H_ +#pragma once #include #include @@ -92,6 +91,3 @@ namespace pcl_cuda computeModel (int debug_verbosity_level = 0); }; } - -#endif //#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MSAC_H_ - diff --git a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/multi_ransac.h b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/multi_ransac.h index c038fed2558..fe143b284be 100644 --- a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/multi_ransac.h +++ b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/multi_ransac.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_SAMPLE_CONSENSUS_RANSAC_H_ -#define PCL_CUDA_SAMPLE_CONSENSUS_RANSAC_H_ +#pragma once #include #include @@ -175,6 +174,3 @@ namespace pcl } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_SAMPLE_CONSENSUS_RANSAC_H_ - diff --git a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/ransac.h b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/ransac.h index fa89eb9ed0a..7d20fe88faa 100644 --- a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/ransac.h +++ b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/ransac.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_SAMPLE_CONSENSUS_RANSAC_H_ -#define PCL_CUDA_SAMPLE_CONSENSUS_RANSAC_H_ +#pragma once #include #include @@ -101,6 +100,3 @@ namespace pcl }; } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_SAMPLE_CONSENSUS_RANSAC_H_ - diff --git a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac.h b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac.h index a6e4ed7aa08..d94024a7fb3 100644 --- a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac.h +++ b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_SAMPLE_CONSENSUS_H_ -#define PCL_CUDA_SAMPLE_CONSENSUS_H_ +#pragma once #include #include @@ -197,5 +196,3 @@ namespace pcl }; } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_SAMPLE_CONSENSUS_H_ diff --git a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model.h b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model.h index 2ca6c5e4fd1..a79a41bed10 100644 --- a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model.h +++ b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MODEL_H_ -#define PCL_CUDA_SAMPLE_CONSENSUS_MODEL_H_ +#pragma once #include #include @@ -419,5 +418,3 @@ namespace pcl // }; } // namespace_ } // namespace_ - -#endif //#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MODEL_H_ diff --git a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_1point_plane.h b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_1point_plane.h index 7d2680fb7ab..8a1a6fa5df9 100644 --- a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_1point_plane.h +++ b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_1point_plane.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MODEL_1POINT_PLANE_H_ -#define PCL_CUDA_SAMPLE_CONSENSUS_MODEL_1POINT_PLANE_H_ +#pragma once #include #include @@ -314,5 +313,3 @@ namespace pcl } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MODEL_PLANE_H_ diff --git a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_plane.h b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_plane.h index bd2f77d7e77..38ff5121092 100644 --- a/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_plane.h +++ b/cuda/sample_consensus/include/pcl/cuda/sample_consensus/sac_model_plane.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MODEL_PLANE_H_ -#define PCL_CUDA_SAMPLE_CONSENSUS_MODEL_PLANE_H_ +#pragma once #include @@ -271,5 +270,3 @@ namespace pcl } // namespace } // namespace - -#endif //#ifndef PCL_CUDA_SAMPLE_CONSENSUS_MODEL_PLANE_H_ diff --git a/features/include/pcl/features/3dsc.h b/features/include/pcl/features/3dsc.h index c9fcde4535d..7fb08c03d2c 100644 --- a/features/include/pcl/features/3dsc.h +++ b/features/include/pcl/features/3dsc.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FEATURES_3DSC_H_ -#define PCL_FEATURES_3DSC_H_ +#pragma once #include #include @@ -238,5 +237,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_3DSC_H_ diff --git a/features/include/pcl/features/board.h b/features/include/pcl/features/board.h index a9e1b4961ca..826996907de 100644 --- a/features/include/pcl/features/board.h +++ b/features/include/pcl/features/board.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_BOARD_H_ -#define PCL_BOARD_H_ +#pragma once #include #include @@ -365,5 +364,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_BOARD_H_ diff --git a/features/include/pcl/features/boost.h b/features/include/pcl/features/boost.h index 1ff472084e8..de8005034cf 100644 --- a/features/include/pcl/features/boost.h +++ b/features/include/pcl/features/boost.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FEATURES_BOOST_H_ -#define PCL_FEATURES_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -51,5 +50,3 @@ #include //#include //#include - -#endif // PCL_FEATURES_BOOST_H_ diff --git a/features/include/pcl/features/boundary.h b/features/include/pcl/features/boundary.h index 10fb3fedf55..fb33fdb235d 100644 --- a/features/include/pcl/features/boundary.h +++ b/features/include/pcl/features/boundary.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_BOUNDARY_H_ -#define PCL_BOUNDARY_H_ +#pragma once #include #include @@ -183,5 +182,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_BOUNDARY_H_ diff --git a/features/include/pcl/features/brisk_2d.h b/features/include/pcl/features/brisk_2d.h index a58c24e5556..b2b7edea58c 100644 --- a/features/include/pcl/features/brisk_2d.h +++ b/features/include/pcl/features/brisk_2d.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FEATURES_BRISK_2D_H_ -#define PCL_FEATURES_BRISK_2D_H_ +#pragma once // PCL includes #include @@ -262,5 +261,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_FEATURES_BRISK_2D_H_ diff --git a/features/include/pcl/features/cppf.h b/features/include/pcl/features/cppf.h index 4f44aaf2bc0..930f11fb691 100755 --- a/features/include/pcl/features/cppf.h +++ b/features/include/pcl/features/cppf.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_CPPF_H_ -#define PCL_CPPF_H_ +#pragma once #include #include @@ -116,5 +115,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_CPPF_H_ diff --git a/features/include/pcl/features/crh.h b/features/include/pcl/features/crh.h index 8feebe0e38d..81859a35727 100644 --- a/features/include/pcl/features/crh.h +++ b/features/include/pcl/features/crh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FEATURES_CRH_H_ -#define PCL_FEATURES_CRH_H_ +#pragma once #include @@ -141,5 +140,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FEATURES_CRH_H_ diff --git a/features/include/pcl/features/cvfh.h b/features/include/pcl/features/cvfh.h index 2ed5738ae6e..317fcbe34b7 100644 --- a/features/include/pcl/features/cvfh.h +++ b/features/include/pcl/features/cvfh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FEATURES_CVFH_H_ -#define PCL_FEATURES_CVFH_H_ +#pragma once #include #include @@ -289,5 +288,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FEATURES_CVFH_H_ diff --git a/features/include/pcl/features/don.h b/features/include/pcl/features/don.h index 4ebdd7b243c..08dcd5b3213 100644 --- a/features/include/pcl/features/don.h +++ b/features/include/pcl/features/don.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_FILTERS_DON_H_ -#define PCL_FILTERS_DON_H_ + +#pragma once #include @@ -141,5 +141,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_DON_H_ diff --git a/features/include/pcl/features/eigen.h b/features/include/pcl/features/eigen.h index bde61949c80..3fcbb2784f1 100644 --- a/features/include/pcl/features/eigen.h +++ b/features/include/pcl/features/eigen.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FEATURES_EIGEN_H_ -#define PCL_FEATURES_EIGEN_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -46,5 +45,3 @@ #include #include - -#endif // PCL_FEATURES_EIGEN_H_ diff --git a/features/include/pcl/features/esf.h b/features/include/pcl/features/esf.h index 8a840fa7317..469445514b9 100644 --- a/features/include/pcl/features/esf.h +++ b/features/include/pcl/features/esf.h @@ -37,8 +37,8 @@ * $Id: pfh.hpp 5027 2012-03-12 03:10:45Z rusu $ * */ -#ifndef PCL_ESF_H_ -#define PCL_ESF_H_ + +#pragma once #include #define GRIDSIZE 64 @@ -139,5 +139,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // # diff --git a/features/include/pcl/features/feature.h b/features/include/pcl/features/feature.h index b0bcec04968..8b887f67650 100644 --- a/features/include/pcl/features/feature.h +++ b/features/include/pcl/features/feature.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FEATURE_H_ -#define PCL_FEATURE_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -496,5 +495,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_FEATURE_H_ diff --git a/features/include/pcl/features/flare.h b/features/include/pcl/features/flare.h index 45948b5fe7d..21e4f47087e 100644 --- a/features/include/pcl/features/flare.h +++ b/features/include/pcl/features/flare.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_FLARE_H_ -#define PCL_FLARE_H_ +#pragma once #include #include @@ -289,5 +288,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FLARE_H_ diff --git a/features/include/pcl/features/fpfh.h b/features/include/pcl/features/fpfh.h index b53103bf33c..fed0e37d5fa 100644 --- a/features/include/pcl/features/fpfh.h +++ b/features/include/pcl/features/fpfh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FPFH_H_ -#define PCL_FPFH_H_ +#pragma once #include #include @@ -222,5 +221,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FPFH_H_ diff --git a/features/include/pcl/features/fpfh_omp.h b/features/include/pcl/features/fpfh_omp.h index 5a8d779248a..3b7dff0a7d5 100644 --- a/features/include/pcl/features/fpfh_omp.h +++ b/features/include/pcl/features/fpfh_omp.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FPFH_OMP_H_ -#define PCL_FPFH_OMP_H_ +#pragma once #include #include @@ -129,5 +128,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FPFH_OMP_H_ diff --git a/features/include/pcl/features/from_meshes.h b/features/include/pcl/features/from_meshes.h index f938e66f97c..675e29a0668 100644 --- a/features/include/pcl/features/from_meshes.h +++ b/features/include/pcl/features/from_meshes.h @@ -1,5 +1,4 @@ -#ifndef PCL_FEATURES_FROM_MESHES_H_ -#define PCL_FEATURES_FROM_MESHES_H_ +#pragma once #include "pcl/features/normal_3d.h" #include "pcl/Vertices.h" @@ -99,8 +98,3 @@ namespace pcl } } - - -#endif // PCL_FEATURES_FROM_MESHES_H_ - - diff --git a/features/include/pcl/features/gasd.h b/features/include/pcl/features/gasd.h index a6f3d9c74b7..be0b9a24848 100644 --- a/features/include/pcl/features/gasd.h +++ b/features/include/pcl/features/gasd.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_FEATURES_GASD_H_ -#define PCL_FEATURES_GASD_H_ +#pragma once #include #include @@ -362,5 +361,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FEATURES_GASD_H_ diff --git a/features/include/pcl/features/gfpfh.h b/features/include/pcl/features/gfpfh.h index 9eaa40b3be4..05919d3c806 100644 --- a/features/include/pcl/features/gfpfh.h +++ b/features/include/pcl/features/gfpfh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GFPFH_H_ -#define PCL_GFPFH_H_ +#pragma once #include @@ -175,5 +174,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_GFPFH_H_ diff --git a/features/include/pcl/features/grsd.h b/features/include/pcl/features/grsd.h index 7aeeda528d0..b39a6d9c103 100644 --- a/features/include/pcl/features/grsd.h +++ b/features/include/pcl/features/grsd.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_FEATURES_GRSD_H_ -#define PCL_FEATURES_GRSD_H_ +#pragma once #include #include @@ -147,5 +146,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* PCL_FEATURES_GRSD_H_ */ diff --git a/features/include/pcl/features/integral_image2D.h b/features/include/pcl/features/integral_image2D.h index 33a3f10e76c..a9815430c36 100644 --- a/features/include/pcl/features/integral_image2D.h +++ b/features/include/pcl/features/integral_image2D.h @@ -37,8 +37,7 @@ * $Id: feature.h 2784 2011-10-15 22:05:38Z aichim $ */ -#ifndef PCL_INTEGRAL_IMAGE2D_H_ -#define PCL_INTEGRAL_IMAGE2D_H_ +#pragma once #include @@ -341,6 +340,3 @@ namespace pcl } #include - -#endif // PCL_INTEGRAL_IMAGE2D_H_ - diff --git a/features/include/pcl/features/integral_image_normal.h b/features/include/pcl/features/integral_image_normal.h index 4404f29f726..f588db3f726 100644 --- a/features/include/pcl/features/integral_image_normal.h +++ b/features/include/pcl/features/integral_image_normal.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_INTEGRALIMAGE_BASED_NORMAL_ESTIMATOR_H_ -#define PCL_INTEGRALIMAGE_BASED_NORMAL_ESTIMATOR_H_ +#pragma once #include #include @@ -478,6 +477,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/features/include/pcl/features/intensity_gradient.h b/features/include/pcl/features/intensity_gradient.h index 7f14ea8e033..2219f185180 100644 --- a/features/include/pcl/features/intensity_gradient.h +++ b/features/include/pcl/features/intensity_gradient.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_INTENSITY_GRADIENT_H_ -#define PCL_INTENSITY_GRADIENT_H_ + +#pragma once #include #include @@ -115,5 +115,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // #ifndef PCL_INTENSITY_GRADIENT_H_ diff --git a/features/include/pcl/features/intensity_spin.h b/features/include/pcl/features/intensity_spin.h index 715db9e5f19..0846342062d 100644 --- a/features/include/pcl/features/intensity_spin.h +++ b/features/include/pcl/features/intensity_spin.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_INTENSITY_SPIN_H_ -#define PCL_INTENSITY_SPIN_H_ + +#pragma once #include @@ -149,4 +149,6 @@ namespace pcl #include #endif -#endif // #ifndef PCL_INTENSITY_SPIN_H_ + + + diff --git a/features/include/pcl/features/linear_least_squares_normal.h b/features/include/pcl/features/linear_least_squares_normal.h index dbe5ca26503..4cb314b12a1 100644 --- a/features/include/pcl/features/linear_least_squares_normal.h +++ b/features/include/pcl/features/linear_least_squares_normal.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_H_ -#define PCL_FEATURES_LINEAR_LEAST_SQUARES_NORMAL_H_ +#pragma once #include #include @@ -147,6 +146,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/features/include/pcl/features/moment_invariants.h b/features/include/pcl/features/moment_invariants.h index 8edd073750e..ed9057de4d3 100644 --- a/features/include/pcl/features/moment_invariants.h +++ b/features/include/pcl/features/moment_invariants.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_MOMENT_INVARIANTS_H_ -#define PCL_MOMENT_INVARIANTS_H_ +#pragma once #include @@ -116,5 +115,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_MOMENT_INVARIANTS_H_ diff --git a/features/include/pcl/features/moment_of_inertia_estimation.h b/features/include/pcl/features/moment_of_inertia_estimation.h index e36c1286b7f..6a5c7a43c09 100644 --- a/features/include/pcl/features/moment_of_inertia_estimation.h +++ b/features/include/pcl/features/moment_of_inertia_estimation.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_MOMENT_OF_INERTIA_ESIMATION_H_ -#define PCL_MOMENT_OF_INERTIA_ESIMATION_H_ +#pragma once #include #include @@ -358,5 +357,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/features/include/pcl/features/multiscale_feature_persistence.h b/features/include/pcl/features/multiscale_feature_persistence.h index 0beea6b5608..8aa95255e8f 100644 --- a/features/include/pcl/features/multiscale_feature_persistence.h +++ b/features/include/pcl/features/multiscale_feature_persistence.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ -#define PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ +#pragma once #include #include @@ -205,5 +204,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* PCL_MULTISCALE_FEATURE_PERSISTENCE_H_ */ diff --git a/features/include/pcl/features/narf.h b/features/include/pcl/features/narf.h index 335c44fdf93..e3955d4ddef 100644 --- a/features/include/pcl/features/narf.h +++ b/features/include/pcl/features/narf.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_NARF_H_ -#define PCL_NARF_H_ +#pragma once #include #include @@ -289,5 +288,3 @@ namespace pcl } // end namespace pcl #include - -#endif //#ifndef PCL_NARF_H_ diff --git a/features/include/pcl/features/narf_descriptor.h b/features/include/pcl/features/narf_descriptor.h index 7c9ebd4eb7a..4d90770eefd 100644 --- a/features/include/pcl/features/narf_descriptor.h +++ b/features/include/pcl/features/narf_descriptor.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_NARF_DESCRIPTOR_H_ -#define PCL_NARF_DESCRIPTOR_H_ +#pragma once #include #include @@ -107,5 +106,3 @@ namespace pcl #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3 #pragma GCC diagnostic warning "-Weffc++" #endif - -#endif //#ifndef PCL_NARF_DESCRIPTOR_H_ diff --git a/features/include/pcl/features/normal_3d.h b/features/include/pcl/features/normal_3d.h index 8512d3951da..b14feafc794 100644 --- a/features/include/pcl/features/normal_3d.h +++ b/features/include/pcl/features/normal_3d.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_NORMAL_3D_H_ -#define PCL_NORMAL_3D_H_ +#pragma once #include #include @@ -423,6 +422,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_NORMAL_3D_H_ - diff --git a/features/include/pcl/features/normal_3d_omp.h b/features/include/pcl/features/normal_3d_omp.h index 66256991407..ee8844f8be8 100644 --- a/features/include/pcl/features/normal_3d_omp.h +++ b/features/include/pcl/features/normal_3d_omp.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_NORMAL_3D_OMP_H_ -#define PCL_NORMAL_3D_OMP_H_ +#pragma once #include @@ -104,5 +103,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_NORMAL_3D_OMP_H_ diff --git a/features/include/pcl/features/normal_based_signature.h b/features/include/pcl/features/normal_based_signature.h index f5773dfe35d..3296732120e 100644 --- a/features/include/pcl/features/normal_based_signature.h +++ b/features/include/pcl/features/normal_based_signature.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_NORMAL_BASED_SIGNATURE_H_ -#define PCL_NORMAL_BASED_SIGNATURE_H_ +#pragma once #include @@ -161,5 +160,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* PCL_NORMAL_BASED_SIGNATURE_H_ */ diff --git a/features/include/pcl/features/organized_edge_detection.h b/features/include/pcl/features/organized_edge_detection.h index b27ed07db0c..d57f6d90b8a 100644 --- a/features/include/pcl/features/organized_edge_detection.h +++ b/features/include/pcl/features/organized_edge_detection.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_ORGANIZED_EDGE_DETECTION_H_ -#define PCL_FEATURES_ORGANIZED_EDGE_DETECTION_H_ +#pragma once #include #include @@ -428,5 +427,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FEATURES_ORGANIZED_EDGE_DETECTION_H_ diff --git a/features/include/pcl/features/our_cvfh.h b/features/include/pcl/features/our_cvfh.h index 60ef67a3aad..515b85531a1 100644 --- a/features/include/pcl/features/our_cvfh.h +++ b/features/include/pcl/features/our_cvfh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FEATURES_OURCVFH_H_ -#define PCL_FEATURES_OURCVFH_H_ +#pragma once #include #include @@ -408,5 +407,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FEATURES_VFH_H_ diff --git a/features/include/pcl/features/pfh.h b/features/include/pcl/features/pfh.h index fa1355c9057..d2babc56ce7 100644 --- a/features/include/pcl/features/pfh.h +++ b/features/include/pcl/features/pfh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_PFH_H_ -#define PCL_PFH_H_ +#pragma once #include #include @@ -224,6 +223,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_PFH_H_ - diff --git a/features/include/pcl/features/pfh_tools.h b/features/include/pcl/features/pfh_tools.h index 24dc2fdbb76..d647f3412c1 100644 --- a/features/include/pcl/features/pfh_tools.h +++ b/features/include/pcl/features/pfh_tools.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_PFH_TOOLS_H_ -#define PCL_FEATURES_PFH_TOOLS_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -74,6 +73,3 @@ namespace pcl float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7); } - -#endif //#ifndef PCL_FEATURES_PFH_TOOLS_H_ - diff --git a/features/include/pcl/features/pfhrgb.h b/features/include/pcl/features/pfhrgb.h index 0222bcca564..2ec795a961e 100644 --- a/features/include/pcl/features/pfhrgb.h +++ b/features/include/pcl/features/pfhrgb.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_PFHRGB_H_ -#define PCL_PFHRGB_H_ +#pragma once #include #include @@ -100,5 +99,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* PCL_PFHRGB_H_ */ diff --git a/features/include/pcl/features/ppf.h b/features/include/pcl/features/ppf.h index fb898c24720..1c653f8b1a4 100644 --- a/features/include/pcl/features/ppf.h +++ b/features/include/pcl/features/ppf.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_PPF_H_ -#define PCL_PPF_H_ +#pragma once #include #include @@ -105,5 +104,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_PPF_H_ diff --git a/features/include/pcl/features/ppfrgb.h b/features/include/pcl/features/ppfrgb.h index 34f59be0e81..6c541ff4bd7 100644 --- a/features/include/pcl/features/ppfrgb.h +++ b/features/include/pcl/features/ppfrgb.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_PPFRGB_H_ -#define PCL_PPFRGB_H_ +#pragma once #include #include @@ -96,5 +95,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_PPFRGB_H_ diff --git a/features/include/pcl/features/principal_curvatures.h b/features/include/pcl/features/principal_curvatures.h index 8f682039786..eb347cd9c26 100644 --- a/features/include/pcl/features/principal_curvatures.h +++ b/features/include/pcl/features/principal_curvatures.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_PRINCIPAL_CURVATURES_H_ -#define PCL_PRINCIPAL_CURVATURES_H_ +#pragma once #include #include @@ -137,5 +136,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_PRINCIPAL_CURVATURES_H_ diff --git a/features/include/pcl/features/range_image_border_extractor.h b/features/include/pcl/features/range_image_border_extractor.h index 9f55cb7946c..35d03f763bf 100644 --- a/features/include/pcl/features/range_image_border_extractor.h +++ b/features/include/pcl/features/range_image_border_extractor.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_ -#define PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_ +#pragma once #include #include @@ -359,5 +358,3 @@ namespace pcl #endif #include // Definitions of templated and inline functions - -#endif //#ifndef PCL_RANGE_IMAGE_BORDER_EXTRACTOR_H_ diff --git a/features/include/pcl/features/rift.h b/features/include/pcl/features/rift.h index f21f09cb6d5..d0409d6d234 100644 --- a/features/include/pcl/features/rift.h +++ b/features/include/pcl/features/rift.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_RIFT_H_ -#define PCL_RIFT_H_ +#pragma once #include @@ -155,5 +154,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // #ifndef PCL_RIFT_H_ diff --git a/features/include/pcl/features/rops_estimation.h b/features/include/pcl/features/rops_estimation.h index 8e6a8a56807..6ba5dffa5c6 100644 --- a/features/include/pcl/features/rops_estimation.h +++ b/features/include/pcl/features/rops_estimation.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_ROPS_ESIMATION_H_ -#define PCL_ROPS_ESIMATION_H_ +#pragma once #include #include @@ -232,5 +231,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/features/include/pcl/features/rsd.h b/features/include/pcl/features/rsd.h index 3d648c0a8ae..c297e2e7fdc 100644 --- a/features/include/pcl/features/rsd.h +++ b/features/include/pcl/features/rsd.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_RSD_H_ -#define PCL_RSD_H_ +#pragma once #include @@ -234,5 +233,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_RSD_H_ diff --git a/features/include/pcl/features/shot.h b/features/include/pcl/features/shot.h index 91caa748588..b376013dc48 100644 --- a/features/include/pcl/features/shot.h +++ b/features/include/pcl/features/shot.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SHOT_H_ -#define PCL_SHOT_H_ +#pragma once #include #include @@ -409,5 +408,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SHOT_H_ diff --git a/features/include/pcl/features/shot_lrf.h b/features/include/pcl/features/shot_lrf.h index ecc1f2cedc6..28768200732 100644 --- a/features/include/pcl/features/shot_lrf.h +++ b/features/include/pcl/features/shot_lrf.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_FEATURES_SHOT_LRF_H_ -#define PCL_FEATURES_SHOT_LRF_H_ +#pragma once #include #include @@ -108,6 +107,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FEATURES_SHOT_LRF_H_ - diff --git a/features/include/pcl/features/shot_lrf_omp.h b/features/include/pcl/features/shot_lrf_omp.h index 1b6a03582fb..ea1782cd777 100644 --- a/features/include/pcl/features/shot_lrf_omp.h +++ b/features/include/pcl/features/shot_lrf_omp.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_FEATURES_SHOT_LRF_OMP_H_ -#define PCL_FEATURES_SHOT_LRF_OMP_H_ +#pragma once #include #include @@ -114,6 +113,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FEATURES_SHOT_LRF_H_ - diff --git a/features/include/pcl/features/shot_omp.h b/features/include/pcl/features/shot_omp.h index 97b999bee80..e690c26932f 100644 --- a/features/include/pcl/features/shot_omp.h +++ b/features/include/pcl/features/shot_omp.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SHOT_OMP_H_ -#define PCL_SHOT_OMP_H_ +#pragma once #include #include @@ -215,5 +214,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SHOT_OMP_H_ diff --git a/features/include/pcl/features/spin_image.h b/features/include/pcl/features/spin_image.h index abf4703a239..1ae890306ff 100644 --- a/features/include/pcl/features/spin_image.h +++ b/features/include/pcl/features/spin_image.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_SPIN_IMAGE_H_ -#define PCL_SPIN_IMAGE_H_ +#pragma once #include #include @@ -283,6 +282,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SPIN_IMAGE_H_ - diff --git a/features/include/pcl/features/usc.h b/features/include/pcl/features/usc.h index de096b32b58..7a510bcadbd 100644 --- a/features/include/pcl/features/usc.h +++ b/features/include/pcl/features/usc.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FEATURES_USC_H_ -#define PCL_FEATURES_USC_H_ +#pragma once #include #include @@ -193,5 +192,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_USC_H_ diff --git a/features/include/pcl/features/vfh.h b/features/include/pcl/features/vfh.h index ec7501e2763..b1a5fe15914 100644 --- a/features/include/pcl/features/vfh.h +++ b/features/include/pcl/features/vfh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FEATURES_VFH_H_ -#define PCL_FEATURES_VFH_H_ +#pragma once #include #include @@ -272,5 +271,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FEATURES_VFH_H_ diff --git a/filters/include/pcl/filters/approximate_voxel_grid.h b/filters/include/pcl/filters/approximate_voxel_grid.h index 06210ac46cc..7789db2a87e 100644 --- a/filters/include/pcl/filters/approximate_voxel_grid.h +++ b/filters/include/pcl/filters/approximate_voxel_grid.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_APPROXIMATE_VOXEL_GRID_MAP_H_ -#define PCL_FILTERS_APPROXIMATE_VOXEL_GRID_MAP_H_ +#pragma once #include #include @@ -246,5 +245,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_ diff --git a/filters/include/pcl/filters/bilateral.h b/filters/include/pcl/filters/bilateral.h index 9341d783267..304cc51e85e 100644 --- a/filters/include/pcl/filters/bilateral.h +++ b/filters/include/pcl/filters/bilateral.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_BILATERAL_H_ -#define PCL_FILTERS_BILATERAL_H_ +#pragma once #include #include @@ -146,5 +145,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_BILATERAL_H_ diff --git a/filters/include/pcl/filters/boost.h b/filters/include/pcl/filters/boost.h index 47c274a1a8e..b7feccf8fb2 100644 --- a/filters/include/pcl/filters/boost.h +++ b/filters/include/pcl/filters/boost.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FILTERS_BOOST_H_ -#define PCL_FILTERS_BOOST_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -57,5 +56,3 @@ #include #include #include - -#endif // PCL_FILTERS_BOOST_H_ diff --git a/filters/include/pcl/filters/box_clipper3D.h b/filters/include/pcl/filters/box_clipper3D.h index 7e50ab38c51..e8104470015 100644 --- a/filters/include/pcl/filters/box_clipper3D.h +++ b/filters/include/pcl/filters/box_clipper3D.h @@ -35,8 +35,8 @@ * */ -#ifndef PCL_BOX_CLIPPER3D_H_ -#define PCL_BOX_CLIPPER3D_H_ +#pragma once + #include "clipper3D.h" namespace pcl @@ -123,5 +123,3 @@ namespace pcl } #include - -#endif // PCL_BOX_CLIPPER3D_H_ diff --git a/filters/include/pcl/filters/clipper3D.h b/filters/include/pcl/filters/clipper3D.h index 5aa7a29e8fd..befdbafe5aa 100644 --- a/filters/include/pcl/filters/clipper3D.h +++ b/filters/include/pcl/filters/clipper3D.h @@ -35,8 +35,8 @@ * */ -#ifndef PCL_CLIPPER3D_H_ -#define PCL_CLIPPER3D_H_ +#pragma once + #include #include #include @@ -112,5 +112,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif // PCL_CLIPPER3D_H_ diff --git a/filters/include/pcl/filters/conditional_removal.h b/filters/include/pcl/filters/conditional_removal.h index 3e3f326320e..6a73fb9f8e0 100644 --- a/filters/include/pcl/filters/conditional_removal.h +++ b/filters/include/pcl/filters/conditional_removal.h @@ -35,8 +35,8 @@ * */ -#ifndef PCL_FILTER_FIELD_VAL_CONDITION_H_ -#define PCL_FILTER_FIELD_VAL_CONDITION_H_ +#pragma once + #include #include @@ -690,5 +690,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/filters/include/pcl/filters/convolution.h b/filters/include/pcl/filters/convolution.h index b5120d7e719..fcc63195d66 100644 --- a/filters/include/pcl/filters/convolution.h +++ b/filters/include/pcl/filters/convolution.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_CONVOLUTION_H_ -#define PCL_FILTERS_CONVOLUTION_H_ +#pragma once #include #include @@ -235,5 +234,3 @@ namespace pcl } #include - -#endif diff --git a/filters/include/pcl/filters/convolution_3d.h b/filters/include/pcl/filters/convolution_3d.h index ccf4d7abdb4..6147e79e50f 100644 --- a/filters/include/pcl/filters/convolution_3d.h +++ b/filters/include/pcl/filters/convolution_3d.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_CONVOLUTION_3D_H -#define PCL_FILTERS_CONVOLUTION_3D_H +#pragma once #include #include @@ -288,5 +287,3 @@ namespace pcl } #include - -#endif // PCL_FILTERS_CONVOLUTION_3D_H diff --git a/filters/include/pcl/filters/covariance_sampling.h b/filters/include/pcl/filters/covariance_sampling.h index fc3151235ed..69f6c3038c0 100644 --- a/filters/include/pcl/filters/covariance_sampling.h +++ b/filters/include/pcl/filters/covariance_sampling.h @@ -38,9 +38,7 @@ * */ - -#ifndef PCL_FILTERS_COVARIANCE_SAMPLING_H_ -#define PCL_FILTERS_COVARIANCE_SAMPLING_H_ +#pragma once #include @@ -167,6 +165,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - - -#endif /* PCL_FILTERS_COVARIANCE_SAMPLING_H_ */ diff --git a/filters/include/pcl/filters/crop_box.h b/filters/include/pcl/filters/crop_box.h index cfec365bd55..3d8f6655b0e 100644 --- a/filters/include/pcl/filters/crop_box.h +++ b/filters/include/pcl/filters/crop_box.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_CROP_BOX_H_ -#define PCL_FILTERS_CROP_BOX_H_ +#pragma once #include #include @@ -344,5 +343,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_CROP_BOX_H_ diff --git a/filters/include/pcl/filters/crop_hull.h b/filters/include/pcl/filters/crop_hull.h index 7cd60a031cc..0931a2884d9 100644 --- a/filters/include/pcl/filters/crop_hull.h +++ b/filters/include/pcl/filters/crop_hull.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_CROP_HULL_H_ -#define PCL_FILTERS_CROP_HULL_H_ +#pragma once #include #include @@ -239,5 +238,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // ifndef PCL_FILTERS_CROP_HULL_H_ diff --git a/filters/include/pcl/filters/extract_indices.h b/filters/include/pcl/filters/extract_indices.h index dbadbcd1c47..f5bbc765777 100644 --- a/filters/include/pcl/filters/extract_indices.h +++ b/filters/include/pcl/filters/extract_indices.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_EXTRACT_INDICES_H_ -#define PCL_FILTERS_EXTRACT_INDICES_H_ +#pragma once #include @@ -199,6 +198,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_EXTRACT_INDICES_H_ - diff --git a/filters/include/pcl/filters/fast_bilateral.h b/filters/include/pcl/filters/fast_bilateral.h index e6bdf8046c1..67d98d5b3df 100644 --- a/filters/include/pcl/filters/fast_bilateral.h +++ b/filters/include/pcl/filters/fast_bilateral.h @@ -38,9 +38,7 @@ * */ - -#ifndef PCL_FILTERS_FAST_BILATERAL_H_ -#define PCL_FILTERS_FAST_BILATERAL_H_ +#pragma once #include @@ -194,6 +192,3 @@ namespace pcl #else #define PCL_INSTANTIATE_FastBilateralFilter(T) template class PCL_EXPORTS pcl::FastBilateralFilter; #endif - - -#endif /* PCL_FILTERS_FAST_BILATERAL_H_ */ diff --git a/filters/include/pcl/filters/fast_bilateral_omp.h b/filters/include/pcl/filters/fast_bilateral_omp.h index dc9b6194228..9dbdca39eb5 100644 --- a/filters/include/pcl/filters/fast_bilateral_omp.h +++ b/filters/include/pcl/filters/fast_bilateral_omp.h @@ -38,9 +38,7 @@ * */ - -#ifndef PCL_FILTERS_FAST_BILATERAL_OMP_H_ -#define PCL_FILTERS_FAST_BILATERAL_OMP_H_ +#pragma once #include #include @@ -102,7 +100,3 @@ namespace pcl #else #define PCL_INSTANTIATE_FastBilateralFilterOMP(T) template class PCL_EXPORTS pcl::FastBilateralFilterOMP; #endif - - -#endif /* PCL_FILTERS_FAST_BILATERAL_OMP_H_ */ - diff --git a/filters/include/pcl/filters/filter.h b/filters/include/pcl/filters/filter.h index ef30ed703c2..e1638d63ad2 100644 --- a/filters/include/pcl/filters/filter.h +++ b/filters/include/pcl/filters/filter.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTER_H_ -#define PCL_FILTER_H_ +#pragma once #include #include @@ -269,5 +268,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTER_H_ diff --git a/filters/include/pcl/filters/filter_indices.h b/filters/include/pcl/filters/filter_indices.h index 874bf1bf9b1..0aee6fcda82 100644 --- a/filters/include/pcl/filters/filter_indices.h +++ b/filters/include/pcl/filters/filter_indices.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_FILTER_INDICES_H_ -#define PCL_FILTERS_FILTER_INDICES_H_ +#pragma once #include @@ -308,6 +307,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_FILTER_INDICES_H_ - diff --git a/filters/include/pcl/filters/frustum_culling.h b/filters/include/pcl/filters/frustum_culling.h index 9069a6d0c96..a0f07da3ade 100644 --- a/filters/include/pcl/filters/frustum_culling.h +++ b/filters/include/pcl/filters/frustum_culling.h @@ -35,9 +35,7 @@ * */ - -#ifndef PCL_FILTERS_FRUSTUM_CULLING_H_ -#define PCL_FILTERS_FRUSTUM_CULLING_H_ +#pragma once #include #include @@ -238,5 +236,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/filters/include/pcl/filters/grid_minimum.h b/filters/include/pcl/filters/grid_minimum.h index 5d4a5995f54..c89e5af517d 100644 --- a/filters/include/pcl/filters/grid_minimum.h +++ b/filters/include/pcl/filters/grid_minimum.h @@ -39,8 +39,7 @@ * */ -#ifndef PCL_FILTERS_VOXEL_GRID_MINIMUM_H_ -#define PCL_FILTERS_VOXEL_GRID_MINIMUM_H_ +#pragma once #include #include @@ -132,6 +131,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_VOXEL_GRID_MINIMUM_H_ - diff --git a/filters/include/pcl/filters/local_maximum.h b/filters/include/pcl/filters/local_maximum.h index 8a8cf28f58f..d183c59a0ac 100644 --- a/filters/include/pcl/filters/local_maximum.h +++ b/filters/include/pcl/filters/local_maximum.h @@ -39,8 +39,7 @@ * */ -#ifndef PCL_FILTERS_LOCAL_MAXIMUM_H_ -#define PCL_FILTERS_LOCAL_MAXIMUM_H_ +#pragma once #include #include @@ -128,6 +127,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_LOCAL_MAXIMUM_H_ - diff --git a/filters/include/pcl/filters/median_filter.h b/filters/include/pcl/filters/median_filter.h index 89378821aea..92cfbf2c418 100644 --- a/filters/include/pcl/filters/median_filter.h +++ b/filters/include/pcl/filters/median_filter.h @@ -37,9 +37,7 @@ * */ - -#ifndef PCL_FILTERS_MEDIAN_FILTER_H_ -#define PCL_FILTERS_MEDIAN_FILTER_H_ +#pragma once #include @@ -116,4 +114,3 @@ namespace pcl #else #define PCL_INSTANTIATE_MedianFilter(T) template class PCL_EXPORTS pcl::MedianFilter; #endif -#endif /* PCL_FILTERS_MEDIAN_FILTER_H_ */ diff --git a/filters/include/pcl/filters/model_outlier_removal.h b/filters/include/pcl/filters/model_outlier_removal.h index 5587d9f1803..f4e1e7cf5e8 100644 --- a/filters/include/pcl/filters/model_outlier_removal.h +++ b/filters/include/pcl/filters/model_outlier_removal.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_FILTERS_MODEL_OUTLIER_REMOVAL_H_ -#define PCL_FILTERS_MODEL_OUTLIER_REMOVAL_H_ +#pragma once #include #include @@ -253,5 +252,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_MODEL_OUTLIER_REMOVAL_H_ diff --git a/filters/include/pcl/filters/morphological_filter.h b/filters/include/pcl/filters/morphological_filter.h index 4ea8dda338f..eb18f28a3e1 100644 --- a/filters/include/pcl/filters/morphological_filter.h +++ b/filters/include/pcl/filters/morphological_filter.h @@ -39,8 +39,7 @@ * */ -#ifndef PCL_FILTERS_MORPHOLOGICAL_FILTER_H_ -#define PCL_FILTERS_MORPHOLOGICAL_FILTER_H_ +#pragma once #include #include @@ -77,6 +76,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_MORPHOLOGICAL_FILTER_H_ - diff --git a/filters/include/pcl/filters/normal_refinement.h b/filters/include/pcl/filters/normal_refinement.h index 657a947936e..6807e37221c 100644 --- a/filters/include/pcl/filters/normal_refinement.h +++ b/filters/include/pcl/filters/normal_refinement.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_NORMAL_REFINEMENT_H_ -#define PCL_FILTERS_NORMAL_REFINEMENT_H_ +#pragma once #include @@ -304,5 +303,3 @@ namespace pcl #else #define PCL_INSTANTIATE_NormalRefinement(T) template class PCL_EXPORTS pcl::NormalRefinement; #endif - -#endif diff --git a/filters/include/pcl/filters/normal_space.h b/filters/include/pcl/filters/normal_space.h index e7b60129b99..1177925921c 100644 --- a/filters/include/pcl/filters/normal_space.h +++ b/filters/include/pcl/filters/normal_space.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_NORMAL_SUBSAMPLE_H_ -#define PCL_FILTERS_NORMAL_SUBSAMPLE_H_ +#pragma once #include #include @@ -205,5 +204,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_NORMAL_SPACE_SUBSAMPLE_H_ diff --git a/filters/include/pcl/filters/passthrough.h b/filters/include/pcl/filters/passthrough.h index f1163c85f8b..f0b06b67aff 100644 --- a/filters/include/pcl/filters/passthrough.h +++ b/filters/include/pcl/filters/passthrough.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_PASSTHROUGH_H_ -#define PCL_FILTERS_PASSTHROUGH_H_ +#pragma once #include @@ -378,6 +377,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_PASSTHROUGH_H_ - diff --git a/filters/include/pcl/filters/plane_clipper3D.h b/filters/include/pcl/filters/plane_clipper3D.h index 3f16c6342fd..8435af4cec4 100644 --- a/filters/include/pcl/filters/plane_clipper3D.h +++ b/filters/include/pcl/filters/plane_clipper3D.h @@ -35,8 +35,8 @@ * */ -#ifndef PCL_PLANE_CLIPPER3D_H_ -#define PCL_PLANE_CLIPPER3D_H_ +#pragma once + #include "clipper3D.h" namespace pcl @@ -103,5 +103,3 @@ namespace pcl } #include - -#endif // PCL_PLANE_CLIPPER3D_H_ diff --git a/filters/include/pcl/filters/project_inliers.h b/filters/include/pcl/filters/project_inliers.h index bed7b96b586..4808525f887 100644 --- a/filters/include/pcl/filters/project_inliers.h +++ b/filters/include/pcl/filters/project_inliers.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_PROJECT_INLIERS_H_ -#define PCL_FILTERS_PROJECT_INLIERS_H_ +#pragma once #include #include @@ -288,5 +287,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_PROJECT_INLIERS_H_ diff --git a/filters/include/pcl/filters/pyramid.h b/filters/include/pcl/filters/pyramid.h index 4b6c52e7889..2561d0dc137 100644 --- a/filters/include/pcl/filters/pyramid.h +++ b/filters/include/pcl/filters/pyramid.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_PYRAMID_H_ -#define PCL_FILTERS_PYRAMID_H_ +#pragma once #include #include @@ -165,5 +164,3 @@ namespace pcl }; } } - -#endif diff --git a/filters/include/pcl/filters/radius_outlier_removal.h b/filters/include/pcl/filters/radius_outlier_removal.h index 1f1024b554d..51898122733 100644 --- a/filters/include/pcl/filters/radius_outlier_removal.h +++ b/filters/include/pcl/filters/radius_outlier_removal.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_ -#define PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_ +#pragma once #include #include @@ -269,6 +268,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_RADIUS_OUTLIER_REMOVAL_H_ - diff --git a/filters/include/pcl/filters/random_sample.h b/filters/include/pcl/filters/random_sample.h index 65b2e2a9cd6..4ee19a43cfc 100644 --- a/filters/include/pcl/filters/random_sample.h +++ b/filters/include/pcl/filters/random_sample.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_RANDOM_SUBSAMPLE_H_ -#define PCL_FILTERS_RANDOM_SUBSAMPLE_H_ +#pragma once #include #include @@ -239,5 +238,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_RANDOM_SUBSAMPLE_H_ diff --git a/filters/include/pcl/filters/sampling_surface_normal.h b/filters/include/pcl/filters/sampling_surface_normal.h index dd8f6eb2dc9..99b278de089 100644 --- a/filters/include/pcl/filters/sampling_surface_normal.h +++ b/filters/include/pcl/filters/sampling_surface_normal.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_SAMPLING_SURFACE_NORMAL_H_ -#define PCL_FILTERS_SAMPLING_SURFACE_NORMAL_H_ +#pragma once #include #include @@ -249,5 +248,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_SAMPLING_SURFACE_NORMAL_H_ diff --git a/filters/include/pcl/filters/shadowpoints.h b/filters/include/pcl/filters/shadowpoints.h index 1f2733ec545..2c6913b2dd8 100644 --- a/filters/include/pcl/filters/shadowpoints.h +++ b/filters/include/pcl/filters/shadowpoints.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FILTERS_SHADOW_POINTS_FILTER_H_ -#define PCL_FILTERS_SHADOW_POINTS_FILTER_H_ +#pragma once #include #include @@ -129,5 +128,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_SHADOW_POINTS_FILTER_H_ diff --git a/filters/include/pcl/filters/statistical_outlier_removal.h b/filters/include/pcl/filters/statistical_outlier_removal.h index 3dcad2df23f..2a234213467 100644 --- a/filters/include/pcl/filters/statistical_outlier_removal.h +++ b/filters/include/pcl/filters/statistical_outlier_removal.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ -#define PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ +#pragma once #include #include @@ -288,6 +287,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_FILTERS_STATISTICAL_OUTLIER_REMOVAL_H_ - diff --git a/filters/include/pcl/filters/uniform_sampling.h b/filters/include/pcl/filters/uniform_sampling.h index 7e14ebde892..6d251ee2712 100644 --- a/filters/include/pcl/filters/uniform_sampling.h +++ b/filters/include/pcl/filters/uniform_sampling.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_UNIFORM_SAMPLING_H_ -#define PCL_FILTERS_UNIFORM_SAMPLING_H_ +#pragma once #include #include @@ -141,6 +140,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_UNIFORM_SAMPLING_H_ - diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 2e5230e00ef..8e8b41553f7 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_ -#define PCL_FILTERS_VOXEL_GRID_MAP_H_ +#pragma once #include #include @@ -853,5 +852,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_VOXEL_GRID_MAP_H_ diff --git a/filters/include/pcl/filters/voxel_grid_covariance.h b/filters/include/pcl/filters/voxel_grid_covariance.h index e181986da84..9e077cc0692 100644 --- a/filters/include/pcl/filters/voxel_grid_covariance.h +++ b/filters/include/pcl/filters/voxel_grid_covariance.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_VOXEL_GRID_COVARIANCE_H_ -#define PCL_VOXEL_GRID_COVARIANCE_H_ +#pragma once #include #include @@ -543,5 +542,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_VOXEL_GRID_COVARIANCE_H_ diff --git a/filters/include/pcl/filters/voxel_grid_label.h b/filters/include/pcl/filters/voxel_grid_label.h index aa76f187a30..2002724e784 100644 --- a/filters/include/pcl/filters/voxel_grid_label.h +++ b/filters/include/pcl/filters/voxel_grid_label.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_VOXEL_GRID_LABEL_H_ -#define PCL_VOXEL_GRID_LABEL_H_ +#pragma once #include #include @@ -71,5 +70,3 @@ namespace pcl }; } - -#endif //#ifndef PCL_VOXEL_GRID_LABEL_H_ diff --git a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h index 857dd11ef7a..075f2d8f63a 100644 --- a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h +++ b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_FILTERS_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ -#define PCL_FILTERS_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ +#pragma once #include @@ -249,5 +248,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_FILTERS_VOXEL_GRID_OCCLUSION_ESTIMATION_H_ diff --git a/geometry/include/pcl/geometry/boost.h b/geometry/include/pcl/geometry/boost.h index e7ec3e8c1d4..fabd2ac6211 100644 --- a/geometry/include/pcl/geometry/boost.h +++ b/geometry/include/pcl/geometry/boost.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_BOOST_H -#define PCL_GEOMETRY_BOOST_H +#pragma once #ifdef __GNUC__ # pragma GCC system_header @@ -51,5 +50,3 @@ #include #include #include - -#endif // PCL_GEOMETRY_BOOST_H diff --git a/geometry/include/pcl/geometry/eigen.h b/geometry/include/pcl/geometry/eigen.h index caa8f3e71b8..8975e64aad5 100644 --- a/geometry/include/pcl/geometry/eigen.h +++ b/geometry/include/pcl/geometry/eigen.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_EIGEN_H -#define PCL_GEOMETRY_EIGEN_H +#pragma once #ifdef __GNUC__ # pragma GCC system_header @@ -47,5 +46,3 @@ #include #include - -#endif // PCL_GEOMETRY_EIGEN_H diff --git a/geometry/include/pcl/geometry/get_boundary.h b/geometry/include/pcl/geometry/get_boundary.h index ec08121e772..d2e97a98e1a 100644 --- a/geometry/include/pcl/geometry/get_boundary.h +++ b/geometry/include/pcl/geometry/get_boundary.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_GET_BOUNDARY_H -#define PCL_GEOMETRY_GET_BOUNDARY_H +#pragma once #include @@ -91,5 +90,3 @@ namespace pcl } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_GET_BOUNDARY_H diff --git a/geometry/include/pcl/geometry/mesh_base.h b/geometry/include/pcl/geometry/mesh_base.h index ec003dc8800..f60e3d87257 100644 --- a/geometry/include/pcl/geometry/mesh_base.h +++ b/geometry/include/pcl/geometry/mesh_base.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_MESH_BASE_H -#define PCL_GEOMETRY_MESH_BASE_H +#pragma once #include @@ -2151,5 +2150,3 @@ namespace pcl }; } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_MESH_BASE_H diff --git a/geometry/include/pcl/geometry/mesh_circulators.h b/geometry/include/pcl/geometry/mesh_circulators.h index a52b2e14989..f2f0c0a38f4 100644 --- a/geometry/include/pcl/geometry/mesh_circulators.h +++ b/geometry/include/pcl/geometry/mesh_circulators.h @@ -40,8 +40,7 @@ // NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_circulators.py' -#ifndef PCL_GEOMETRY_MESH_CIRCULATORS_H -#define PCL_GEOMETRY_MESH_CIRCULATORS_H +#pragma once #include #include @@ -911,5 +910,3 @@ namespace pcl }; } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_MESH_CIRCULATORS_H diff --git a/geometry/include/pcl/geometry/mesh_conversion.h b/geometry/include/pcl/geometry/mesh_conversion.h index 64f0003426b..186563b4708 100644 --- a/geometry/include/pcl/geometry/mesh_conversion.h +++ b/geometry/include/pcl/geometry/mesh_conversion.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_MESH_CONVERSION_H -#define PCL_GEOMETRY_MESH_CONVERSION_H +#pragma once #include #include @@ -130,5 +129,3 @@ namespace pcl } } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_MESH_CONVERSION_H diff --git a/geometry/include/pcl/geometry/mesh_elements.h b/geometry/include/pcl/geometry/mesh_elements.h index bbdb404ed82..23ce44f16a1 100644 --- a/geometry/include/pcl/geometry/mesh_elements.h +++ b/geometry/include/pcl/geometry/mesh_elements.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_MESH_ELEMENTS_H -#define PCL_GEOMETRY_MESH_ELEMENTS_H +#pragma once #include @@ -186,5 +185,3 @@ namespace pcl }; } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_MESH_ELEMENTS_H diff --git a/geometry/include/pcl/geometry/mesh_indices.h b/geometry/include/pcl/geometry/mesh_indices.h index 36f82b758f3..e3b5036d808 100644 --- a/geometry/include/pcl/geometry/mesh_indices.h +++ b/geometry/include/pcl/geometry/mesh_indices.h @@ -40,8 +40,7 @@ // NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_indices.py' -#ifndef PCL_GEOMETRY_MESH_INDICES_H -#define PCL_GEOMETRY_MESH_INDICES_H +#pragma once #include @@ -629,5 +628,3 @@ namespace pcl } } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_MESH_INDICES_H diff --git a/geometry/include/pcl/geometry/mesh_io.h b/geometry/include/pcl/geometry/mesh_io.h index 148b44bd1f6..56692382887 100644 --- a/geometry/include/pcl/geometry/mesh_io.h +++ b/geometry/include/pcl/geometry/mesh_io.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_MESH_IO_H -#define PCL_GEOMETRY_MESH_IO_H +#pragma once #include #include @@ -261,5 +260,3 @@ namespace pcl } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_MESH_IO_H diff --git a/geometry/include/pcl/geometry/mesh_traits.h b/geometry/include/pcl/geometry/mesh_traits.h index 01a34a92bb5..85c708ee8b1 100644 --- a/geometry/include/pcl/geometry/mesh_traits.h +++ b/geometry/include/pcl/geometry/mesh_traits.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_MESH_TRAITS_H -#define PCL_GEOMETRY_MESH_TRAITS_H +#pragma once #include @@ -82,5 +81,3 @@ namespace pcl }; } // End namespace geometry } // End namespace pcl - -#endif // PCL_GEOMETRY_MESH_TRAITS_H diff --git a/geometry/include/pcl/geometry/planar_polygon.h b/geometry/include/pcl/geometry/planar_polygon.h index 1619e48112d..8f7246fd2c2 100644 --- a/geometry/include/pcl/geometry/planar_polygon.h +++ b/geometry/include/pcl/geometry/planar_polygon.h @@ -37,9 +37,7 @@ * */ -#ifndef PCL_GEOMETRY_PLANAR_POLYGON_H_ -#define PCL_GEOMETRY_PLANAR_POLYGON_H_ - +#pragma once #include #include @@ -140,6 +138,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif //#ifndef PCL_GEOMETRY_PLANAR_POLYGON_H_ - diff --git a/geometry/include/pcl/geometry/polygon_mesh.h b/geometry/include/pcl/geometry/polygon_mesh.h index 1171565db21..71825f95f4e 100644 --- a/geometry/include/pcl/geometry/polygon_mesh.h +++ b/geometry/include/pcl/geometry/polygon_mesh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_POLYGON_MESH_H -#define PCL_GEOMETRY_POLYGON_MESH_H +#pragma once #include @@ -199,5 +198,3 @@ namespace pcl }; } // End namespace geom } // End namespace pcl - -#endif // PCL_GEOMETRY_POLYGON_MESH_H diff --git a/geometry/include/pcl/geometry/polygon_operations.h b/geometry/include/pcl/geometry/polygon_operations.h index ec6c1a7690a..f43540ca06f 100644 --- a/geometry/include/pcl/geometry/polygon_operations.h +++ b/geometry/include/pcl/geometry/polygon_operations.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_GEOMETRY_POLYGON_OPERATORS_H -#define PCL_GEOMETRY_POLYGON_OPERATORS_H +#pragma once #include "planar_polygon.h" #include @@ -69,4 +68,3 @@ namespace pcl } // namespace pcl #include "impl/polygon_operations.hpp" -#endif // PCL_GEOMETRY_POLYGON_OPERATORS_H======= diff --git a/geometry/include/pcl/geometry/quad_mesh.h b/geometry/include/pcl/geometry/quad_mesh.h index 9f5ae7586d8..90ec9d65350 100644 --- a/geometry/include/pcl/geometry/quad_mesh.h +++ b/geometry/include/pcl/geometry/quad_mesh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_QUAD_MESH_H -#define PCL_GEOMETRY_QUAD_MESH_H +#pragma once #include @@ -173,5 +172,3 @@ namespace pcl }; } // End namespace geom } // End namespace pcl - -#endif // PCL_GEOMETRY_QUAD_MESH_H diff --git a/geometry/include/pcl/geometry/triangle_mesh.h b/geometry/include/pcl/geometry/triangle_mesh.h index ae331e75e69..3bce6be7972 100644 --- a/geometry/include/pcl/geometry/triangle_mesh.h +++ b/geometry/include/pcl/geometry/triangle_mesh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GEOMETRY_TRIANGLE_MESH_H -#define PCL_GEOMETRY_TRIANGLE_MESH_H +#pragma once #include @@ -357,5 +356,3 @@ namespace pcl }; } // End namespace geom } // End namespace pcl - -#endif // PCL_GEOMETRY_TRIANGLE_MESH_H diff --git a/gpu/containers/include/pcl/gpu/containers/device_array.h b/gpu/containers/include/pcl/gpu/containers/device_array.h index c1ed2ebbbd3..4f2b9ea844a 100644 --- a/gpu/containers/include/pcl/gpu/containers/device_array.h +++ b/gpu/containers/include/pcl/gpu/containers/device_array.h @@ -34,8 +34,7 @@ * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ -#ifndef PCL_GPU_CONTAINER_DEVICE_ARRAY_HPP_ -#define PCL_GPU_CONTAINER_DEVICE_ARRAY_HPP_ +#pragma once #include #include @@ -267,5 +266,3 @@ namespace pcl } #include - -#endif /* PCL_GPU_CONTAINER_DEVICE_ARRAY_HPP_ */ diff --git a/gpu/containers/include/pcl/gpu/containers/device_memory.h b/gpu/containers/include/pcl/gpu/containers/device_memory.h index 032813af29b..ffd3d4b9622 100644 --- a/gpu/containers/include/pcl/gpu/containers/device_memory.h +++ b/gpu/containers/include/pcl/gpu/containers/device_memory.h @@ -34,8 +34,7 @@ * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ -#ifndef PCL_GPU_CONTAINERS_DEVICE_MEMORY_HPP_ -#define PCL_GPU_CONTAINERS_DEVICE_MEMORY_HPP_ +#pragma once #include #include @@ -256,5 +255,3 @@ namespace pcl } #include - -#endif /* PCL_GPU_CONTAINERS_DEVICE_MEMORY_HPP_ */ diff --git a/gpu/containers/include/pcl/gpu/containers/initialization.h b/gpu/containers/include/pcl/gpu/containers/initialization.h index 6a6ef72bddc..191e748a7f6 100644 --- a/gpu/containers/include/pcl/gpu/containers/initialization.h +++ b/gpu/containers/include/pcl/gpu/containers/initialization.h @@ -34,8 +34,7 @@ * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ -#ifndef PCL_GPU_CONTAINERS_INITIALISATION_H_ -#define PCL_GPU_CONTAINERS_INITIALISATION_H_ +#pragma once #include #include @@ -72,5 +71,3 @@ namespace pcl void PCL_EXPORTS error(const char *error_string, const char *file, const int line, const char *func = ""); } } - -#endif /* PCL_GPU_CONTAINERS_INITIALISATION_H_ */ diff --git a/gpu/containers/include/pcl/gpu/containers/kernel_containers.h b/gpu/containers/include/pcl/gpu/containers/kernel_containers.h index d656f1cd2bd..a7667b2c747 100644 --- a/gpu/containers/include/pcl/gpu/containers/kernel_containers.h +++ b/gpu/containers/include/pcl/gpu/containers/kernel_containers.h @@ -34,10 +34,7 @@ * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ - -#ifndef PCL_GPU_CONTAINERS_KERNEL_CONTAINERS_HPP_ -#define PCL_GPU_CONTAINERS_KERNEL_CONTAINERS_HPP_ - +#pragma once #if defined(__CUDACC__) #define __PCL_GPU_HOST_DEVICE__ __host__ __device__ __forceinline__ @@ -109,6 +106,3 @@ namespace pcl } #undef __PCL_GPU_HOST_DEVICE__ - -#endif /* PCL_GPU_CONTAINERS_KERNEL_CONTAINERS_HPP_ */ - diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/color_volume.h b/gpu/kinfu/include/pcl/gpu/kinfu/color_volume.h index 3e7d60f4987..5b651a9305a 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/color_volume.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/color_volume.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_COLOR_VOLUME_H_ -#define PCL_KINFU_COLOR_VOLUME_H_ +#pragma once #include #include @@ -106,5 +105,3 @@ namespace pcl }; } } - -#endif /* PCL_KINFU_COLOR_VOLUME_H_ */ \ No newline at end of file diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h b/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h index c7f8ddef475..40337b82867 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_KINFUTRACKER_HPP_ -#define PCL_KINFU_KINFUTRACKER_HPP_ +#pragma once #include #include @@ -302,5 +301,3 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } }; - -#endif /* PCL_KINFU_KINFUTRACKER_HPP_ */ diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h b/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h index 3e3a8b56094..89df691c9fe 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_TSDF_MARCHING_CUBES_H_ -#define PCL_KINFU_TSDF_MARCHING_CUBES_H_ +#pragma once #include #include @@ -97,5 +96,3 @@ namespace pcl }; } } - -#endif /* PCL_KINFU_MARCHING_CUBES_H_ */ diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/pixel_rgb.h b/gpu/kinfu/include/pcl/gpu/kinfu/pixel_rgb.h index 53d20939268..3961d8dd5cf 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/pixel_rgb.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/pixel_rgb.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_PIXEL_RGB_HPP_ -#define PCL_KINFU_PIXEL_RGB_HPP_ +#pragma once namespace pcl { @@ -50,5 +49,3 @@ namespace pcl }; } } - -#endif /* PCL_KINFU_PIXEL_RGB_HPP_ */ \ No newline at end of file diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/raycaster.h b/gpu/kinfu/include/pcl/gpu/kinfu/raycaster.h index 9c8e701d4a0..8e62636a1ec 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/raycaster.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/raycaster.h @@ -35,10 +35,7 @@ * */ - -#ifndef PCL_KINFU_TSDF_RAYCASTER_H_ -#define PCL_KINFU_TSDF_RAYCASTER_H_ - +#pragma once #include #include @@ -150,5 +147,3 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW void convertMapToOranizedCloud(const RayCaster::MapArr& map, DeviceArray2D& cloud); } } - -#endif /* PCL_KINFU_TSDF_RAYCASTER_H_ */ diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/tsdf_volume.h b/gpu/kinfu/include/pcl/gpu/kinfu/tsdf_volume.h index f81f41fd6eb..2ad9775e861 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/tsdf_volume.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/tsdf_volume.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_TSDF_VOLUME_H_ -#define PCL_KINFU_TSDF_VOLUME_H_ +#pragma once #include #include @@ -165,5 +164,3 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } } - -#endif /* PCL_KINFU_TSDF_VOLUME_H_ */ \ No newline at end of file diff --git a/gpu/kinfu/src/internal.h b/gpu/kinfu/src/internal.h index aee57c81308..28df9ae2901 100644 --- a/gpu/kinfu/src/internal.h +++ b/gpu/kinfu/src/internal.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_INTERNAL_HPP_ -#define PCL_KINFU_INTERNAL_HPP_ +#pragma once #include //#include @@ -438,5 +437,3 @@ namespace pcl generateTriangles(const PtrStep& volume, const DeviceArray2D& occupied_voxels, const float3& volume_size, DeviceArray& output); } } - -#endif /* PCL_KINFU_INTERNAL_HPP_ */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/color_volume.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/color_volume.h index 9f0f2f948bc..b9d727e0d9c 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/color_volume.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/color_volume.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_COLOR_VOLUME_H_ -#define PCL_KINFU_COLOR_VOLUME_H_ +#pragma once #include #include @@ -109,5 +108,3 @@ namespace pcl } } } - -#endif /* PCL_KINFU_COLOR_VOLUME_H_ */ \ No newline at end of file diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h index 09d13a6b6ae..83495a2942c 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h @@ -35,9 +35,7 @@ * */ - -#ifndef PCL_CYCLICAL_BUFFER_IMPL_H_ -#define PCL_CYCLICAL_BUFFER_IMPL_H_ +#pragma once #include #include @@ -270,5 +268,3 @@ namespace pcl } } } - -#endif // PCL_CYCLICAL_BUFFER_IMPL_H_ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/device.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/device.h index 153097c3a58..06436985e3f 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/device.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/device.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_DEVICE_H_ -#define PCL_KINFU_DEVICE_H_ +#pragma once #include #include // used by operator << in Struct Intr @@ -107,5 +106,3 @@ namespace pcl } } } - -#endif /* PCL_KINFU_DEVICE_H_ */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h index 99403541c9f..60dc4204e36 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_KINFUTRACKER_HPP_ -#define PCL_KINFU_KINFUTRACKER_HPP_ +#pragma once #include #include @@ -458,5 +457,3 @@ namespace pcl } } }; - -#endif /* PCL_KINFU_KINFUTRACKER_HPP_ */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h index b484d1849df..813c638e418 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_TSDF_MARCHING_CUBES_H_ -#define PCL_KINFU_TSDF_MARCHING_CUBES_H_ +#pragma once #include #include @@ -102,5 +101,3 @@ namespace pcl } } } - -#endif /* PCL_KINFU_MARCHING_CUBES_H_ */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/pixel_rgb.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/pixel_rgb.h index 1070f9f5669..56bd7c8de76 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/pixel_rgb.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/pixel_rgb.h @@ -35,8 +35,8 @@ * */ -#ifndef PCL_KINFU_PIXEL_RGB_HPP_ -#define PCL_KINFU_PIXEL_RGB_HPP_ +#pragma once + //#include namespace pcl @@ -54,5 +54,3 @@ namespace pcl } } } - -#endif /* PCL_KINFU_PIXEL_RGB_HPP_ */ \ No newline at end of file diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h index d65ef493bde..3c8b473f323 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h @@ -34,15 +34,13 @@ * POSSIBILITY OF SUCH DAMAGE. * */ + +#pragma once #include #include #include - -#ifndef PCL_KINFU_POINT_INTENSITY_ -#define PCL_KINFU_POINT_INTENSITY_ - struct EIGEN_ALIGN16 PointIntensity { @@ -60,5 +58,3 @@ struct EIGEN_ALIGN16 PointIntensity POINT_CLOUD_REGISTER_POINT_STRUCT( PointIntensity, (float, intensity, intensity) ) - -#endif diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/raycaster.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/raycaster.h index 3375626ee41..d12a81b7409 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/raycaster.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/raycaster.h @@ -35,10 +35,7 @@ * */ - -#ifndef PCL_KINFU_TSDF_RAYCASTERLS_H_ -#define PCL_KINFU_TSDF_RAYCASTERLS_H_ - +#pragma once #include #include @@ -159,5 +156,3 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW } } } - -#endif /* PCL_KINFU_TSDF_RAYCASTER_H_ */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h index 4d91bbab79f..071cfb2d186 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h @@ -36,8 +36,7 @@ * Author: Francisco, Technical University Eindhoven, (f.j.mysurname.soriano tue.nl) */ -#ifndef PCL_SCREENSHOT_MANAGER_H_ -#define PCL_SCREENSHOT_MANAGER_H_ +#pragma once #include #include @@ -103,5 +102,3 @@ namespace pcl }; } } - -#endif // PCL_SCREENSHOT_MANAGER_H_ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h index 8e42e3c4b5a..9a80b9b9763 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h @@ -35,8 +35,7 @@ * */ - #ifndef PCL_STANDALONE_MARCHING_CUBES_H_ - #define PCL_STANDALONE_MARCHING_CUBES_H_ +#pragma once //General includes and I/O @@ -169,6 +168,3 @@ namespace pcl } #define PCL_INSTANTIATE_StandaloneMarchingCubes(PointT) template class PCL_EXPORTS pcl::gpu::kinfuLS::StandaloneMarchingCubes; - -#endif // PCL_STANDALONE_MARCHING_CUBES_H_ - diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_buffer.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_buffer.h index f0c6e156355..7023c1fffae 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_buffer.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_buffer.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_TSDF_BUFFER_STRUCT_H_ -#define PCL_TSDF_BUFFER_STRUCT_H_ +#pragma once #include //#include @@ -83,5 +82,3 @@ namespace pcl } } } - -#endif /*PCL_TSDF_BUFFER_STRUCT_H_*/ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_volume.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_volume.h index 7d009726613..c72cf702709 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_volume.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_volume.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_TSDF_VOLUME_H_ -#define PCL_KINFU_TSDF_VOLUME_H_ +#pragma once #include #include @@ -290,5 +289,3 @@ EIGEN_MAKE_ALIGNED_OPERATOR_NEW } } } - -#endif /* PCL_KINFU_TSDF_VOLUME_H_ */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h index e0dff28af39..012b04ae511 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h @@ -36,8 +36,7 @@ * Author: Raphael Favier, Technical University Eindhoven, (r.mysurname tue.nl) */ -#ifndef PCL_WORLD_MODEL_H_ -#define PCL_WORLD_MODEL_H_ +#pragma once #include #include @@ -180,5 +179,3 @@ namespace pcl }; } } - -#endif // PCL_WORLD_MODEL_H_ diff --git a/gpu/kinfu_large_scale/src/estimate_combined.h b/gpu/kinfu_large_scale/src/estimate_combined.h index 1344af0e3e9..897b6844c88 100644 --- a/gpu/kinfu_large_scale/src/estimate_combined.h +++ b/gpu/kinfu_large_scale/src/estimate_combined.h @@ -35,10 +35,7 @@ * */ -#ifndef PCL_GPU_KINFU_LARGE_SCALE_CUDA_ESTIMATE_COMBINED_H_ -#define PCL_GPU_KINFU_LARGE_SCALE_CUDA_ESTIMATE_COMBINED_H_ +#pragma once #define ESTIMATE_COMBINED_CUDA_GRID_X 32 #define ESTIMATE_COMBINED_CUDA_GRID_Y 8 - -#endif // PCL_GPU_KINFU_LARGE_SCALE_CUDA_ESTIMATE_COMBINED_H_ diff --git a/gpu/kinfu_large_scale/src/internal.h b/gpu/kinfu_large_scale/src/internal.h index eaa0afe29b2..815d99dba75 100644 --- a/gpu/kinfu_large_scale/src/internal.h +++ b/gpu/kinfu_large_scale/src/internal.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KINFU_INTERNAL_HPP_ -#define PCL_KINFU_INTERNAL_HPP_ +#pragma once #include #include @@ -455,5 +454,3 @@ namespace pcl } } } - -#endif /* PCL_KINFU_INTERNAL_HPP_ */ diff --git a/gpu/people/include/pcl/gpu/people/bodyparts_detector.h b/gpu/people/include/pcl/gpu/people/bodyparts_detector.h index aeafde62c7a..9171bfec920 100644 --- a/gpu/people/include/pcl/gpu/people/bodyparts_detector.h +++ b/gpu/people/include/pcl/gpu/people/bodyparts_detector.h @@ -34,9 +34,7 @@ * @author: Koen Buys, Anatoly Baksheev */ - -#ifndef PCL_GPU_PEOPLE_RDF_BODYPARTS_DETECTOR_H -#define PCL_GPU_PEOPLE_RDF_BODYPARTS_DETECTOR_H +#pragma once #include #include @@ -155,5 +153,3 @@ namespace pcl } } } - -#endif /* PCL_GPU_PEOPLE_RDF_BODYPARTS_DETECTOR_H */ diff --git a/gpu/people/include/pcl/gpu/people/colormap.h b/gpu/people/include/pcl/gpu/people/colormap.h index 2736fc09449..1c8d363df99 100644 --- a/gpu/people/include/pcl/gpu/people/colormap.h +++ b/gpu/people/include/pcl/gpu/people/colormap.h @@ -37,8 +37,7 @@ * @author: Koen Buys, Anatoly Baksheev */ -#ifndef PCL_GPU_PEOPLE_COLORMAP_H_ -#define PCL_GPU_PEOPLE_COLORMAP_H_ +#pragma once #include #include @@ -91,4 +90,3 @@ namespace pcl } // end namespace people } // end namespace gpu } // end namespace pcl -#endif //PCL_GPU_PEOPLE_COLORMAP_H_ diff --git a/gpu/people/include/pcl/gpu/people/face_detector.h b/gpu/people/include/pcl/gpu/people/face_detector.h index 66d1a7b4c5b..cb1a63b87be 100644 --- a/gpu/people/include/pcl/gpu/people/face_detector.h +++ b/gpu/people/include/pcl/gpu/people/face_detector.h @@ -34,8 +34,7 @@ * @author: Koen Buys */ -#ifndef PCL_GPU_PEOPLE_FACE_DETECTOR_H_ -#define PCL_GPU_PEOPLE_FACE_DETECTOR_H_ +#pragma once #include #include @@ -197,6 +196,3 @@ namespace pcl } } } - - -#endif /* PCL_GPU_PEOPLE_FACE_DETECTOR_H_ */ diff --git a/gpu/people/include/pcl/gpu/people/label_blob2.h b/gpu/people/include/pcl/gpu/people/label_blob2.h index e101ea188f9..1ce46a7f836 100644 --- a/gpu/people/include/pcl/gpu/people/label_blob2.h +++ b/gpu/people/include/pcl/gpu/people/label_blob2.h @@ -39,8 +39,7 @@ * @brief This file contains the Blob2 structure and the inline <<-operator for it */ -#ifndef PCL_GPU_PEOPLE_LABEL_BLOB2_H_ -#define PCL_GPU_PEOPLE_LABEL_BLOB2_H_ +#pragma once #include #include @@ -96,5 +95,3 @@ namespace pcl } // end namespace people } // end namespace gpu } // end namespace pcl - -#endif diff --git a/gpu/people/include/pcl/gpu/people/label_common.h b/gpu/people/include/pcl/gpu/people/label_common.h index 02f65c36f23..434beecc4c4 100644 --- a/gpu/people/include/pcl/gpu/people/label_common.h +++ b/gpu/people/include/pcl/gpu/people/label_common.h @@ -37,8 +37,7 @@ * @author: Koen Buys */ -#ifndef PCL_GPU_PEOPLE_LABEL_COMMON_H_ -#define PCL_GPU_PEOPLE_LABEL_COMMON_H_ +#pragma once #include #include // for float4, uchar4, delete this in future @@ -282,5 +281,3 @@ inline std::ostream& operator << (std::ostream& os, const part_t& p) return (os); } **/ - -#endif diff --git a/gpu/people/include/pcl/gpu/people/label_segment.h b/gpu/people/include/pcl/gpu/people/label_segment.h index 74839bb6b1e..c5d17320231 100644 --- a/gpu/people/include/pcl/gpu/people/label_segment.h +++ b/gpu/people/include/pcl/gpu/people/label_segment.h @@ -39,8 +39,7 @@ * @brief This file contains the function prototypes for the segmentation functions */ -#ifndef PCL_GPU_PEOPLE_LABEL_SEGMENT_H_ -#define PCL_GPU_PEOPLE_LABEL_SEGMENT_H_ +#pragma once // our headers #include "pcl/gpu/people/label_blob2.h" @@ -397,5 +396,3 @@ namespace pcl } // end namespace people } // end namespace gpu } // end namespace pcl - -#endif //#ifndef LABELSKEL_SEGMENT_H diff --git a/gpu/people/include/pcl/gpu/people/label_tree.h b/gpu/people/include/pcl/gpu/people/label_tree.h index 01f6e4e4a14..7c39fd6cb60 100644 --- a/gpu/people/include/pcl/gpu/people/label_tree.h +++ b/gpu/people/include/pcl/gpu/people/label_tree.h @@ -39,8 +39,7 @@ * @brief This file contains the function prototypes for the tree building functions. */ -#ifndef PCL_GPU_PEOPLE_LABEL_TREE_H_ -#define PCL_GPU_PEOPLE_LABEL_TREE_H_ +#pragma once // our headers #include "pcl/gpu/people/label_blob2.h" //this one defines the blob structure @@ -667,4 +666,3 @@ namespace pcl } //end namespace people } // end namespace gpu } // end namespace pcl -#endif diff --git a/gpu/people/include/pcl/gpu/people/organized_plane_detector.h b/gpu/people/include/pcl/gpu/people/organized_plane_detector.h index a8dbb28aed1..9187053a0b3 100644 --- a/gpu/people/include/pcl/gpu/people/organized_plane_detector.h +++ b/gpu/people/include/pcl/gpu/people/organized_plane_detector.h @@ -34,8 +34,7 @@ * @author: Koen Buys */ -#ifndef PCL_GPU_PEOPLE_ORGANIZED_PLANE_DETECTOR_H_ -#define PCL_GPU_PEOPLE_ORGANIZED_PLANE_DETECTOR_H_ +#pragma once #include #include @@ -170,5 +169,3 @@ namespace pcl } } } - -#endif /* PCL_GPU_PEOPLE_FACE_DETECTOR_H_ */ diff --git a/gpu/people/include/pcl/gpu/people/people_detector.h b/gpu/people/include/pcl/gpu/people/people_detector.h index 226e1de11ee..d95a755e908 100644 --- a/gpu/people/include/pcl/gpu/people/people_detector.h +++ b/gpu/people/include/pcl/gpu/people/people_detector.h @@ -34,8 +34,7 @@ * @author: Koen Buys */ -#ifndef PCL_GPU_PEOPLE_PERSON_H_ -#define PCL_GPU_PEOPLE_PERSON_H_ +#pragma once #include #include @@ -171,4 +170,3 @@ namespace pcl } } } -#endif // PCL_GPU_PEOPLE_PERSON_H_ diff --git a/gpu/people/include/pcl/gpu/people/probability_processor.h b/gpu/people/include/pcl/gpu/people/probability_processor.h index 159e081013c..5d8d7d63990 100644 --- a/gpu/people/include/pcl/gpu/people/probability_processor.h +++ b/gpu/people/include/pcl/gpu/people/probability_processor.h @@ -34,8 +34,7 @@ * @author: Koen Buys */ -#ifndef PCL_GPU_PROBABILITY_PROCESSOR_H_ -#define PCL_GPU_PROBABILITY_PROCESSOR_H_ +#pragma once #include #include @@ -110,5 +109,3 @@ namespace pcl } } } - -#endif // PCL_GPU_PROBABILITY_PROCESSOR_H_ diff --git a/gpu/people/include/pcl/gpu/people/tree.h b/gpu/people/include/pcl/gpu/people/tree.h index 49983d5c8ff..022c716abe1 100644 --- a/gpu/people/include/pcl/gpu/people/tree.h +++ b/gpu/people/include/pcl/gpu/people/tree.h @@ -37,8 +37,7 @@ * @authors: Cedric Cagniart, Koen Buys */ -#ifndef PCL_GPU_PEOPLE_TREE_H_ -#define PCL_GPU_PEOPLE_TREE_H_ +#pragma once #include "label_common.h" #include @@ -137,4 +136,3 @@ namespace pcl } // end namespace people } // end namespace gpu } // end namespace pcl -#endif // PCL_GPU_PEOPLE_TREES_TREE_H_ diff --git a/gpu/people/include/pcl/gpu/people/tree_train.h b/gpu/people/include/pcl/gpu/people/tree_train.h index e6663c5b876..7720d71fa46 100644 --- a/gpu/people/include/pcl/gpu/people/tree_train.h +++ b/gpu/people/include/pcl/gpu/people/tree_train.h @@ -5,8 +5,7 @@ * Author : Cedric Cagniart * ************************************************* */ -#ifndef PCL_GPU_PEOPLE_TREE_TRAIN_H_ -#define PCL_GPU_PEOPLE_TREE_TRAIN_H_ +#pragma once #include "tree.h" #include @@ -227,4 +226,3 @@ namespace pcl } // end namespace people } // end namespace gpu } // end namespace pcl -#endif diff --git a/gpu/people/src/cuda/device.h b/gpu/people/src/cuda/device.h index 33257496a07..cd46df606f8 100644 --- a/gpu/people/src/cuda/device.h +++ b/gpu/people/src/cuda/device.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GPU_PEOPLE_CUDA_DEVICE_H_ -#define PCL_GPU_PEOPLE_CUDA_DEVICE_H_ +#pragma once #include @@ -75,5 +74,3 @@ namespace pcl } } } - -#endif /* PCL_GPU_PEOPLE_CUDA_DEVICE_H_ */ \ No newline at end of file diff --git a/gpu/people/src/cuda_async_copy.h b/gpu/people/src/cuda_async_copy.h index 173eeedf86f..aaf491dc354 100644 --- a/gpu/people/src/cuda_async_copy.h +++ b/gpu/people/src/cuda_async_copy.h @@ -36,9 +36,7 @@ * @authors: Anatoly Baksheev */ - -#ifndef PCL_GPU_PEOPLE_CUDA_ASYNC_COPY_H_ -#define PCL_GPU_PEOPLE_CUDA_ASYNC_COPY_H_ +#pragma once #include #include @@ -104,6 +102,3 @@ namespace pcl using pcl::gpu::AsyncCopy; } } - -#endif /* PCL_GPU_PEOPLE_CUDA_ASYNC_COPY_H_ */ - diff --git a/gpu/people/src/internal.h b/gpu/people/src/internal.h index 2accc07eb4d..aa5e3e88378 100644 --- a/gpu/people/src/internal.h +++ b/gpu/people/src/internal.h @@ -36,8 +36,7 @@ * @authors: Cedric Cagniart, Koen Buys, Anatoly Baksheev */ -#ifndef PCL_GPU_PEOPLE_INTERNAL_H_ -#define PCL_GPU_PEOPLE_INTERNAL_H_ +#pragma once #include #include @@ -195,5 +194,3 @@ namespace pcl }; } } - -#endif /* PCL_GPU_PEOPLE_INTERNAL_H_ */ diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h index 101ca4aef2a..b6b7f807e5e 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h @@ -37,8 +37,7 @@ * @author: Koen Buys */ -#ifndef PCL_GPU_EXTRACT_CLUSTERS_H_ -#define PCL_GPU_EXTRACT_CLUSTERS_H_ +#pragma once #include #include @@ -165,9 +164,3 @@ namespace pcl } } } - -#endif //PCL_GPU_EXTRACT_CLUSTERS_H_ - - - - diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h index 520c97b73c2..5e94a61100e 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h @@ -37,15 +37,13 @@ * */ -#ifndef PCL_GPU_EXTRACT_LABELED_CLUSTERS_H_ -#define PCL_GPU_EXTRACT_LABELED_CLUSTERS_H_ +#pragma once #include #include #include #include #include -#include namespace pcl { @@ -160,5 +158,3 @@ namespace pcl } } } - -#endif //PCL_GPU_EXTRACT_LABELED_CLUSTERS_H_ diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h index f4d0c5ce4be..c795d70026c 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h @@ -37,15 +37,12 @@ * */ -#ifndef PCL_GPU_SEEDED_HUE_SEGMENTATION_H_ -#define PCL_GPU_SEEDED_HUE_SEGMENTATION_H_ +#pragma once #include #include #include #include -#include -#include namespace pcl { @@ -147,9 +144,3 @@ namespace pcl } } } - -#endif //PCL_GPU_SEEDED_HUE_SEGMENTATION_H_ - - - - diff --git a/gpu/surface/include/pcl/gpu/surface/convex_hull.h b/gpu/surface/include/pcl/gpu/surface/convex_hull.h index 0e6109162d7..1a00dcce321 100644 --- a/gpu/surface/include/pcl/gpu/surface/convex_hull.h +++ b/gpu/surface/include/pcl/gpu/surface/convex_hull.h @@ -35,9 +35,7 @@ * */ - -#ifndef PCL_GPU_SURFACE_CONVEX_HULL_HPP_ -#define PCL_GPU_SURFACE_CONVEX_HULL_HPP_ +#pragma once #include #include @@ -74,5 +72,3 @@ namespace pcl }; } } - -#endif /* PCL_GPU_SURFACE_CONVEX_HULL_HPP_*/ \ No newline at end of file diff --git a/gpu/surface/src/cuda/device.h b/gpu/surface/src/cuda/device.h index c2da470a206..405b90d700f 100644 --- a/gpu/surface/src/cuda/device.h +++ b/gpu/surface/src/cuda/device.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_GPU_SURFACE_DEVICE_H_ -#define PCL_GPU_SURFACE_DEVICE_H_ +#pragma once #include "internal.h" #include @@ -86,5 +85,3 @@ namespace pcl } }; - -#endif /* PCL_GPU_SURFACE_DEVICE_H_ */ diff --git a/gpu/surface/src/internal.h b/gpu/surface/src/internal.h index 2a1e7b29a8b..d23d352245b 100644 --- a/gpu/surface/src/internal.h +++ b/gpu/surface/src/internal.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_GPU_SURFACE_INTERNAL_H_ -#define PCL_GPU_SURFACE_INTERNAL_H_ +#pragma once #include #include @@ -120,5 +119,3 @@ namespace pcl void pack_hull(const DeviceArray& points, const DeviceArray& indeces, DeviceArray& output); } } - -#endif /* PCL_GPU_SURFACE_INTERNAL_H_ */ diff --git a/gpu/tracking/include/pcl/gpu/tracking/particle_filter.h b/gpu/tracking/include/pcl/gpu/tracking/particle_filter.h index 0cf84f6ba87..848398c4701 100644 --- a/gpu/tracking/include/pcl/gpu/tracking/particle_filter.h +++ b/gpu/tracking/include/pcl/gpu/tracking/particle_filter.h @@ -1,5 +1,4 @@ -#ifndef PCL_GPU_TRACKING_PARTICLE_FILTER_H_ -#define PCL_GPU_TRACKING_PARTICLE_FILTER_H_ +#pragma once #include #include @@ -148,5 +147,3 @@ namespace pcl }; } } - -#endif // PCL_GPU_TRACKING_PARTICLE_FILTER_H_ diff --git a/gpu/tracking/src/internal.h b/gpu/tracking/src/internal.h index dbbd5a89159..3cd5b842500 100644 --- a/gpu/tracking/src/internal.h +++ b/gpu/tracking/src/internal.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_INTERNAL_H_ -#define PCL_TRACKING_INTERNAL_H_ +#pragma once #include #include @@ -48,6 +47,3 @@ namespace pcl */ } } - - -#endif // PCL_TRACKING_INTERNAL_H_ diff --git a/io/include/pcl/compression/organized_pointcloud_compression.h b/io/include/pcl/compression/organized_pointcloud_compression.h index d75f13277cb..abbb7567083 100644 --- a/io/include/pcl/compression/organized_pointcloud_compression.h +++ b/io/include/pcl/compression/organized_pointcloud_compression.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_ORGANIZED_POINT_COMPRESSION_H_ -#define PCL_ORGANIZED_POINT_COMPRESSION_H_ +#pragma once #include #include @@ -151,5 +150,3 @@ namespace pcl const char* OrganizedPointCloudCompression::frameHeaderIdentifier_ = ""; } } - -#endif diff --git a/io/include/pcl/compression/organized_pointcloud_conversion.h b/io/include/pcl/compression/organized_pointcloud_conversion.h index 5e737ea304d..571f1b56017 100644 --- a/io/include/pcl/compression/organized_pointcloud_conversion.h +++ b/io/include/pcl/compression/organized_pointcloud_conversion.h @@ -37,8 +37,7 @@ * Authors: Julius Kammerl (julius@kammerl.de) */ -#ifndef PCL_ORGANIZED_CONVERSION_H_ -#define PCL_ORGANIZED_CONVERSION_H_ +#pragma once #include #include @@ -582,6 +581,3 @@ namespace pcl } } - - -#endif diff --git a/io/include/pcl/io/ascii_io.h b/io/include/pcl/io/ascii_io.h index 927b6e53205..c8c787e5f46 100644 --- a/io/include/pcl/io/ascii_io.h +++ b/io/include/pcl/io/ascii_io.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_ASCII_IO_H_ -#define PCL_IO_ASCII_IO_H_ +#pragma once #include #include @@ -164,9 +163,4 @@ namespace pcl }; } - - - #include - -#endif // PCL_IO_ASCII_IO_H_ diff --git a/io/include/pcl/io/auto_io.h b/io/include/pcl/io/auto_io.h index 566c5e2f9dd..2b04f669cf6 100644 --- a/io/include/pcl/io/auto_io.h +++ b/io/include/pcl/io/auto_io.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_AUTO_IO_H_ -#define PCL_IO_AUTO_IO_H_ +#pragma once #include #include @@ -121,5 +120,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_IO_AUTO_IO_H_ diff --git a/io/include/pcl/io/buffers.h b/io/include/pcl/io/buffers.h index 3e9cdc43409..d5034ed48c6 100644 --- a/io/include/pcl/io/buffers.h +++ b/io/include/pcl/io/buffers.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_BUFFERS_H -#define PCL_IO_BUFFERS_H +#pragma once #include #include @@ -278,6 +277,3 @@ namespace pcl } #include - -#endif /* PCL_IO_BUFFERS_H */ - diff --git a/io/include/pcl/io/debayer.h b/io/include/pcl/io/debayer.h index c3a6f4dada4..c427a2488cc 100644 --- a/io/include/pcl/io/debayer.h +++ b/io/include/pcl/io/debayer.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_DEBAYER_H -#define PCL_IO_DEBAYER_H +#pragma once #include #include @@ -79,6 +78,3 @@ namespace pcl }; } } - -#endif // PCL_IO_DEBAYER_H - diff --git a/io/include/pcl/io/depth_sense/depth_sense_device_manager.h b/io/include/pcl/io/depth_sense/depth_sense_device_manager.h index 846e60ad965..d2b432f0238 100644 --- a/io/include/pcl/io/depth_sense/depth_sense_device_manager.h +++ b/io/include/pcl/io/depth_sense/depth_sense_device_manager.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_DEPTH_SENSE_DEVICE_MANAGER_H -#define PCL_IO_DEPTH_SENSE_DEVICE_MANAGER_H +#pragma once #include #include @@ -156,6 +155,3 @@ namespace pcl } // namespace io } // namespace pcl - -#endif /* PCL_IO_DEPTH_SENSE_DEVICE_MANAGER_H */ - diff --git a/io/include/pcl/io/depth_sense/depth_sense_grabber_impl.h b/io/include/pcl/io/depth_sense/depth_sense_grabber_impl.h index 4e7de968967..1749d095f89 100644 --- a/io/include/pcl/io/depth_sense/depth_sense_grabber_impl.h +++ b/io/include/pcl/io/depth_sense/depth_sense_grabber_impl.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_DEPTH_SENSE_GRABBER_IMPL_H -#define PCL_IO_DEPTH_SENSE_GRABBER_IMPL_H +#pragma once #include @@ -155,6 +154,3 @@ namespace pcl } } - -#endif /* PCL_IO_DEPTH_SENSE_GRABBER_IMPL_H */ - diff --git a/io/include/pcl/io/depth_sense_grabber.h b/io/include/pcl/io/depth_sense_grabber.h index 4473d1a1db4..c8a6ac676ba 100644 --- a/io/include/pcl/io/depth_sense_grabber.h +++ b/io/include/pcl/io/depth_sense_grabber.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_DEPTH_SENSE_GRABBER_H -#define PCL_IO_DEPTH_SENSE_GRABBER_H +#pragma once #include #include @@ -150,6 +149,3 @@ namespace pcl }; } - -#endif /* PCL_IO_DEPTH_SENSE_GRABBER_H */ - diff --git a/io/include/pcl/io/dinast_grabber.h b/io/include/pcl/io/dinast_grabber.h index 429a2287ee1..3cd6790eafd 100644 --- a/io/include/pcl/io/dinast_grabber.h +++ b/io/include/pcl/io/dinast_grabber.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_IO_DINAST_GRABBER_ -#define PCL_IO_DINAST_GRABBER_ +#pragma once #include #include @@ -213,5 +212,3 @@ namespace pcl boost::signals2::signal* point_cloud_signal_; }; } //namespace pcl - -#endif // PCL_IO_DINAST_GRABBER_ diff --git a/io/include/pcl/io/file_grabber.h b/io/include/pcl/io/file_grabber.h index 7a0812b886a..7db4740e57d 100644 --- a/io/include/pcl/io/file_grabber.h +++ b/io/include/pcl/io/file_grabber.h @@ -40,8 +40,6 @@ */ #pragma once -#ifndef PCL_IO_FILE_GRABBER_H_ -#define PCL_IO_FILE_GRABBER_H_ #include @@ -88,5 +86,3 @@ namespace pcl } }; } -#endif//PCL_IO_FILE_GRABBER_H_ - diff --git a/io/include/pcl/io/file_io.h b/io/include/pcl/io/file_io.h index c1c613e22b4..2e742597423 100644 --- a/io/include/pcl/io/file_io.h +++ b/io/include/pcl/io/file_io.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_FILE_IO_H_ -#define PCL_IO_FILE_IO_H_ +#pragma once #include #include @@ -391,5 +390,3 @@ namespace pcl } } - -#endif //#ifndef PCL_IO_FILE_IO_H_ diff --git a/io/include/pcl/io/hdl_grabber.h b/io/include/pcl/io/hdl_grabber.h index 682628e32cd..63deadb31ae 100644 --- a/io/include/pcl/io/hdl_grabber.h +++ b/io/include/pcl/io/hdl_grabber.h @@ -36,10 +36,9 @@ * */ -#include "pcl/pcl_config.h" +#pragma once -#ifndef PCL_IO_HDL_GRABBER_H_ -#define PCL_IO_HDL_GRABBER_H_ +#include "pcl/pcl_config.h" #include #include @@ -337,5 +336,3 @@ namespace pcl }; } - -#endif /* PCL_IO_HDL_GRABBER_H_ */ diff --git a/io/include/pcl/io/ifs_io.h b/io/include/pcl/io/ifs_io.h index 7eb9450d660..40694744f06 100644 --- a/io/include/pcl/io/ifs_io.h +++ b/io/include/pcl/io/ifs_io.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_IFS_IO_H_ -#define PCL_IO_IFS_IO_H_ +#pragma once #include #include @@ -254,5 +253,3 @@ namespace pcl } } } - -#endif //#ifndef PCL_IO_IFS_IO_H_ diff --git a/io/include/pcl/io/image.h b/io/include/pcl/io/image.h index e03f1ba4542..5c4115193c0 100644 --- a/io/include/pcl/io/image.h +++ b/io/include/pcl/io/image.h @@ -33,9 +33,10 @@ * POSSIBILITY OF SUCH DAMAGE. * */ + +#pragma once + #include -#ifndef PCL_IO_IMAGE_H_ -#define PCL_IO_IMAGE_H_ #include #include @@ -211,5 +212,3 @@ namespace pcl } // namespace } - -#endif //PCL_IO_IMAGE_H_ diff --git a/io/include/pcl/io/image_depth.h b/io/include/pcl/io/image_depth.h index 1b8d5e69c6a..c9e2fc07c0c 100644 --- a/io/include/pcl/io/image_depth.h +++ b/io/include/pcl/io/image_depth.h @@ -35,11 +35,10 @@ * POSSIBILITY OF SUCH DAMAGE. * */ + #pragma once -#include -#ifndef PCL_IO_IMAGE_DEPTH_H_ -#define PCL_IO_IMAGE_DEPTH_H_ +#include #include #include @@ -187,5 +186,3 @@ namespace pcl }; }} // namespace - -#endif // PCL_IO_IMAGE_DEPTH_H_ diff --git a/io/include/pcl/io/image_ir.h b/io/include/pcl/io/image_ir.h index ce6a14eaa32..72acff69eeb 100644 --- a/io/include/pcl/io/image_ir.h +++ b/io/include/pcl/io/image_ir.h @@ -33,8 +33,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_IO_IMAGE_IR_H_ -#define PCL_IO_IMAGE_IR_H_ + +#pragma once #include #include @@ -110,5 +110,3 @@ namespace pcl } // namespace } - -#endif // PCL_IO_IMAGE_IR_H_ diff --git a/io/include/pcl/io/image_metadata_wrapper.h b/io/include/pcl/io/image_metadata_wrapper.h index 19dcb827c8a..fdee257569c 100644 --- a/io/include/pcl/io/image_metadata_wrapper.h +++ b/io/include/pcl/io/image_metadata_wrapper.h @@ -38,8 +38,6 @@ */ #pragma once -#ifndef PCL_IO_IMAGE_METADATA_WRAPPER_H_ -#define PCL_IO_IMAGE_METADATA_WRAPPER_H_ #include #include @@ -79,5 +77,3 @@ namespace pcl } // namespace } - -#endif // PCL_IO_IMAGE_METADATA_WRAPPER_H_ diff --git a/io/include/pcl/io/image_rgb24.h b/io/include/pcl/io/image_rgb24.h index 41c155dfb57..73e31e67c9f 100644 --- a/io/include/pcl/io/image_rgb24.h +++ b/io/include/pcl/io/image_rgb24.h @@ -33,10 +33,10 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#include + +#pragma once -#ifndef PCL_IO_IMAGE_RGB_H_ -#define PCL_IO_IMAGE_RGB_H_ +#include #include #include @@ -87,5 +87,3 @@ namespace pcl } // namespace } - -#endif // PCL_IO_IMAGE_RGB_H_ diff --git a/io/include/pcl/io/image_yuv422.h b/io/include/pcl/io/image_yuv422.h index 61ecdd74eda..990b90b5547 100644 --- a/io/include/pcl/io/image_yuv422.h +++ b/io/include/pcl/io/image_yuv422.h @@ -33,10 +33,10 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#include -#ifndef PCL_IO_IMAGE_YUV422_H_ -#define PCL_IO_IMAGE_YUV422_H_ +#pragma once + +#include #include #include @@ -75,5 +75,3 @@ namespace pcl } // namespace } - -#endif // PCL_IO_IMAGE_YUV22_H_ diff --git a/io/include/pcl/io/io.h b/io/include/pcl/io/io.h index 25923d04a6a..e579aab7aa0 100644 --- a/io/include/pcl/io/io.h +++ b/io/include/pcl/io/io.h @@ -37,10 +37,6 @@ * */ -#ifndef PCL_IO_IO_H_ -#define PCL_IO_IO_H_ +#pragma once #include - -#endif //#ifndef PCL_IO_IO_H_ - diff --git a/io/include/pcl/io/io_exception.h b/io/include/pcl/io/io_exception.h index 0586cf480d2..d97ef06c4fc 100644 --- a/io/include/pcl/io/io_exception.h +++ b/io/include/pcl/io/io_exception.h @@ -33,10 +33,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include +#pragma once -#ifndef PCL_IO_EXCEPTION_H_ -#define PCL_IO_EXCEPTION_H_ +#include #include #include @@ -104,4 +103,3 @@ namespace pcl } } // namespace } -#endif // PCL_IO_EXCEPTION_H_ diff --git a/io/include/pcl/io/lzf.h b/io/include/pcl/io/lzf.h index 86c1c11f6cd..ad98999cad4 100644 --- a/io/include/pcl/io/lzf.h +++ b/io/include/pcl/io/lzf.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_LZF_H -#define PCL_IO_LZF_H +#pragma once #include @@ -87,6 +86,3 @@ namespace pcl lzfDecompress (const void *const in_data, unsigned int in_len, void *out_data, unsigned int out_len); } - -#endif /* PCL_IO_LZF */ - diff --git a/io/include/pcl/io/lzf_image_io.h b/io/include/pcl/io/lzf_image_io.h index bdee43774a2..ae54898e7c6 100644 --- a/io/include/pcl/io/lzf_image_io.h +++ b/io/include/pcl/io/lzf_image_io.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_LZF_IMAGE_IO_H_ -#define PCL_LZF_IMAGE_IO_H_ +#pragma once #include #include @@ -632,5 +631,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_LZF_IMAGE_IO_H_ diff --git a/io/include/pcl/io/openni2/openni.h b/io/include/pcl/io/openni2/openni.h index b9f43dea345..bb31ef39870 100644 --- a/io/include/pcl/io/openni2/openni.h +++ b/io/include/pcl/io/openni2/openni.h @@ -34,11 +34,12 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#include + +#pragma once + #ifdef HAVE_OPENNI2 - -#ifndef PCL_IO_OPENNI2_OPENNI_H_ -#define PCL_IO_OPENNI2_OPENNI_H_ + +#include #if defined __GNUC__ # pragma GCC system_header @@ -83,5 +84,4 @@ #define XN_DV_X_RES 960 #define XN_DV_Y_RES 720 -#endif // PCL_IO_OPENNI2_OPENNI_H_ #endif // HAVE_OPENNI2 diff --git a/io/include/pcl/io/openni2/openni2_convert.h b/io/include/pcl/io/openni2/openni2_convert.h index bfc439e31f3..fe1fe677405 100644 --- a/io/include/pcl/io/openni2/openni2_convert.h +++ b/io/include/pcl/io/openni2/openni2_convert.h @@ -30,8 +30,7 @@ */ -#ifndef PCL_IO_OPENNI2_CONVERT_H_ -#define PCL_IO_OPENNI2_CONVERT_H_ +#pragma once #include "pcl/io/openni2/openni2_device_info.h" #include "pcl/io/openni2/openni2_video_mode.h" @@ -61,5 +60,3 @@ namespace pcl } // namespace } } - -#endif // PCL_IO_OPENNI2_CONVERT_H_ diff --git a/io/include/pcl/io/openni2/openni2_device.h b/io/include/pcl/io/openni2/openni2_device.h index 4ae70f0b35a..499f233dc51 100644 --- a/io/include/pcl/io/openni2/openni2_device.h +++ b/io/include/pcl/io/openni2/openni2_device.h @@ -28,8 +28,7 @@ * */ -#ifndef PCL_IO_OPENNI2_DEVICE_H_ -#define PCL_IO_OPENNI2_DEVICE_H_ +#pragma once #include #include "openni.h" @@ -330,5 +329,3 @@ namespace pcl } // namespace } } - -#endif // PCL_IO_OPENNI2_DEVICE_H_ diff --git a/io/include/pcl/io/openni2/openni2_device_info.h b/io/include/pcl/io/openni2/openni2_device_info.h index 2954e45e1a2..26b0b12a122 100644 --- a/io/include/pcl/io/openni2/openni2_device_info.h +++ b/io/include/pcl/io/openni2/openni2_device_info.h @@ -29,8 +29,7 @@ * Author: Julius Kammerl (jkammerl@willowgarage.com) */ -#ifndef PCL_IO_OPENNI2_DEVICE_INFO_H_ -#define PCL_IO_OPENNI2_DEVICE_INFO_H_ +#pragma once #include @@ -58,5 +57,3 @@ namespace pcl } // namespace } } - -#endif // PCL_IO_OPENNI2_DEVICE_INFO_H_ diff --git a/io/include/pcl/io/openni2/openni2_device_manager.h b/io/include/pcl/io/openni2/openni2_device_manager.h index e4bee57094a..ee5ddd5a84b 100644 --- a/io/include/pcl/io/openni2/openni2_device_manager.h +++ b/io/include/pcl/io/openni2/openni2_device_manager.h @@ -29,8 +29,7 @@ * Author: Julius Kammerl (jkammerl@willowgarage.com) */ -#ifndef PCL_IO_OPENNI2_DEVICE_MANAGER_H_ -#define PCL_IO_OPENNI2_DEVICE_MANAGER_H_ +#pragma once #include #include "pcl/io/openni2/openni2_device_info.h" @@ -98,5 +97,3 @@ namespace pcl } // namespace } } - -#endif // PCL_IO_OPENNI2_DEVICE_MANAGER_H_ diff --git a/io/include/pcl/io/openni2/openni2_frame_listener.h b/io/include/pcl/io/openni2/openni2_frame_listener.h index 6dfcb886910..0ee8551577d 100644 --- a/io/include/pcl/io/openni2/openni2_frame_listener.h +++ b/io/include/pcl/io/openni2/openni2_frame_listener.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_IO_OPENNI2_FRAME_LISTENER_H_ -#define PCL_IO_OPENNI2_FRAME_LISTENER_H_ +#pragma once #include @@ -85,5 +84,3 @@ namespace pcl } // namespace } } - -#endif // PCL_IO_OPENNI2_FRAME_LISTENER_H_ diff --git a/io/include/pcl/io/openni2/openni2_metadata_wrapper.h b/io/include/pcl/io/openni2/openni2_metadata_wrapper.h index 4e1cc6c5365..77d574d3b53 100644 --- a/io/include/pcl/io/openni2/openni2_metadata_wrapper.h +++ b/io/include/pcl/io/openni2/openni2_metadata_wrapper.h @@ -38,13 +38,11 @@ */ #pragma once -#ifndef PCL_IO_OPENNI2_METADATA_WRAPPER_H_ -#define PCL_IO_OPENNI2_METADATA_WRAPPER_H_ - -#include #if defined(HAVE_OPENNI2) +#include + #include #include @@ -112,5 +110,3 @@ namespace pcl } } #endif // HAVE_OPENNI2 - -#endif // PCL_IO_OPENNI2_METADATA_WRAPPER_H_ diff --git a/io/include/pcl/io/openni2/openni2_timer_filter.h b/io/include/pcl/io/openni2/openni2_timer_filter.h index c2d78c0ffa0..50d6433e515 100644 --- a/io/include/pcl/io/openni2/openni2_timer_filter.h +++ b/io/include/pcl/io/openni2/openni2_timer_filter.h @@ -29,8 +29,7 @@ * Author: Julius Kammerl (jkammerl@willowgarage.com) */ -#ifndef PCL_IO_OPENNI2_TIME_FILTER_H_ -#define PCL_IO_OPENNI2_TIME_FILTER_H_ +#pragma once #include @@ -70,5 +69,3 @@ namespace pcl } // namespace } } - -#endif // PCL_IO_OPENNI2_TIME_FILTER_H_ diff --git a/io/include/pcl/io/openni2/openni2_video_mode.h b/io/include/pcl/io/openni2/openni2_video_mode.h index 7c6fdd8ca10..f3b6edf1c90 100644 --- a/io/include/pcl/io/openni2/openni2_video_mode.h +++ b/io/include/pcl/io/openni2/openni2_video_mode.h @@ -29,8 +29,7 @@ * Author: Julius Kammerl (jkammerl@willowgarage.com) */ -#ifndef PCL_IO_OPENNI2_VIDEO_MODE_H_ -#define PCL_IO_OPENNI2_VIDEO_MODE_H_ +#pragma once #include #include @@ -89,5 +88,3 @@ namespace pcl } // namespace } } - -#endif diff --git a/io/include/pcl/io/openni2_grabber.h b/io/include/pcl/io/openni2_grabber.h index 2a113d5de4c..98620c0d587 100644 --- a/io/include/pcl/io/openni2_grabber.h +++ b/io/include/pcl/io/openni2_grabber.h @@ -37,11 +37,10 @@ * */ -#include +#pragma once + #ifdef HAVE_OPENNI2 - -#ifndef PCL_IO_OPENNI2_GRABBER_H_ -#define PCL_IO_OPENNI2_GRABBER_H_ +#include #include #include @@ -504,5 +503,4 @@ namespace pcl } // namespace } -#endif // PCL_IO_OPENNI2_GRABBER_H_ #endif // HAVE_OPENNI2 diff --git a/io/include/pcl/io/pcd_grabber.h b/io/include/pcl/io/pcd_grabber.h index 38f2633f951..251b7e81710 100644 --- a/io/include/pcl/io/pcd_grabber.h +++ b/io/include/pcl/io/pcd_grabber.h @@ -35,10 +35,9 @@ * */ -#include +#pragma once -#ifndef PCL_IO_PCD_GRABBER_H_ -#define PCL_IO_PCD_GRABBER_H_ +#include #include #include @@ -307,4 +306,3 @@ namespace pcl #endif } } -#endif diff --git a/io/include/pcl/io/pcd_io.h b/io/include/pcl/io/pcd_io.h index b6a24c2f913..96d4e24ee98 100644 --- a/io/include/pcl/io/pcd_io.h +++ b/io/include/pcl/io/pcd_io.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_IO_PCD_IO_H_ -#define PCL_IO_PCD_IO_H_ +#pragma once #include #include @@ -789,5 +788,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_IO_PCD_IO_H_ diff --git a/io/include/pcl/io/ply/byte_order.h b/io/include/pcl/io/ply/byte_order.h index 2af95d01131..067bf7e932d 100644 --- a/io/include/pcl/io/ply/byte_order.h +++ b/io/include/pcl/io/ply/byte_order.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_IO_PLY_BYTE_ORDER_H -#define PCL_IO_PLY_BYTE_ORDER_H +#pragma once #include @@ -105,5 +104,3 @@ namespace pcl } // namespace ply } // namespace io } // namespace pcl - -#endif // PLY_BYTE_ORDER_H diff --git a/io/include/pcl/io/ply/io_operators.h b/io/include/pcl/io/ply/io_operators.h index 24e16700c2a..31a0fb07fcd 100644 --- a/io/include/pcl/io/ply/io_operators.h +++ b/io/include/pcl/io/ply/io_operators.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_IO_PLY_IO_OPERATORS_H -#define PCL_IO_PLY_IO_OPERATORS_H +#pragma once #include #include @@ -98,5 +97,3 @@ namespace pcl } // namespace ply } // namespace io } // namespace pcl - -#endif // PLY_IO_OPERATORS_H diff --git a/io/include/pcl/io/ply/ply_parser.h b/io/include/pcl/io/ply/ply_parser.h index 4405d1a4090..33c107f78f4 100644 --- a/io/include/pcl/io/ply/ply_parser.h +++ b/io/include/pcl/io/ply/ply_parser.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_IO_PLY_PLY_PARSER_H -#define PCL_IO_PLY_PLY_PARSER_H +#pragma once #include #include @@ -726,5 +725,3 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s # pragma warning(pop) # endif #endif - -#endif // PCL_IO_PLY_PLY_PARSER_H diff --git a/io/include/pcl/io/ply_io.h b/io/include/pcl/io/ply_io.h index 3b525a845d4..e8316d9987b 100644 --- a/io/include/pcl/io/ply_io.h +++ b/io/include/pcl/io/ply_io.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_IO_PLY_IO_H_ -#define PCL_IO_PLY_IO_H_ +#pragma once #include #include @@ -896,5 +895,3 @@ namespace pcl savePLYFileBinary (const std::string &file_name, const pcl::PolygonMesh &mesh); } } - -#endif //#ifndef PCL_IO_PLY_IO_H_ diff --git a/io/include/pcl/io/png_io.h b/io/include/pcl/io/png_io.h index 20814cacdb4..8a5df825ab0 100644 --- a/io/include/pcl/io/png_io.h +++ b/io/include/pcl/io/png_io.h @@ -37,8 +37,7 @@ * Authors: Anatoly Baksheev */ -#ifndef PCL_IO_PNG_IO_H_ -#define PCL_IO_PNG_IO_H_ +#pragma once #include #include @@ -162,5 +161,3 @@ namespace pcl } } - -#endif //#ifndef PCL_IO_PNG_IO_H_ diff --git a/io/include/pcl/io/point_cloud_image_extractors.h b/io/include/pcl/io/point_cloud_image_extractors.h index 0fc4bcbdea1..1ca8e9ce2da 100644 --- a/io/include/pcl/io/point_cloud_image_extractors.h +++ b/io/include/pcl/io/point_cloud_image_extractors.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_POINT_CLOUD_IMAGE_EXTRACTORS_H_ -#define PCL_POINT_CLOUD_IMAGE_EXTRACTORS_H_ + +#pragma once #include #include @@ -436,5 +436,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_POINT_CLOUD_IMAGE_EXTRACTORS_H_ diff --git a/io/include/pcl/io/real_sense/real_sense_device_manager.h b/io/include/pcl/io/real_sense/real_sense_device_manager.h index 4cbb5dd9b53..6d089c92a15 100644 --- a/io/include/pcl/io/real_sense/real_sense_device_manager.h +++ b/io/include/pcl/io/real_sense/real_sense_device_manager.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_REAL_SENSE_DEVICE_MANAGER_H -#define PCL_IO_REAL_SENSE_DEVICE_MANAGER_H +#pragma once #include #include @@ -170,6 +169,3 @@ namespace pcl } // namespace io } // namespace pcl - -#endif /* PCL_IO_REAL_SENSE_DEVICE_MANAGER_H */ - diff --git a/io/include/pcl/io/real_sense_grabber.h b/io/include/pcl/io/real_sense_grabber.h index 583a1ade2c7..635212453d1 100644 --- a/io/include/pcl/io/real_sense_grabber.h +++ b/io/include/pcl/io/real_sense_grabber.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_REAL_SENSE_GRABBER_H -#define PCL_IO_REAL_SENSE_GRABBER_H +#pragma once #include #include @@ -275,6 +274,3 @@ namespace pcl }; } - -#endif /* PCL_IO_REAL_SENSE_GRABBER_H */ - diff --git a/io/include/pcl/io/robot_eye_grabber.h b/io/include/pcl/io/robot_eye_grabber.h index c3c3950645e..6af9e6a646e 100644 --- a/io/include/pcl/io/robot_eye_grabber.h +++ b/io/include/pcl/io/robot_eye_grabber.h @@ -35,10 +35,9 @@ * */ -#include "pcl/pcl_config.h" +#pragma once -#ifndef PCL_IO_ROBOT_EYE_GRABBER_H_ -#define PCL_IO_ROBOT_EYE_GRABBER_H_ +#include "pcl/pcl_config.h" #include #include @@ -148,5 +147,3 @@ namespace pcl void computeTimestamp (boost::uint32_t& timestamp, unsigned char* point_data); }; } - -#endif /* PCL_IO_ROBOT_EYE_GRABBER_H_ */ diff --git a/io/include/pcl/io/tar.h b/io/include/pcl/io/tar.h index 18e95fdf9ad..210ecc96820 100644 --- a/io/include/pcl/io/tar.h +++ b/io/include/pcl/io/tar.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_IO_TAR_H_ -#define PCL_IO_TAR_H_ +#pragma once #include @@ -98,5 +97,3 @@ namespace pcl } } } -#endif // PCL_IO_TAR_H_ - diff --git a/io/include/pcl/io/vlp_grabber.h b/io/include/pcl/io/vlp_grabber.h index 64ee63dcff3..3589455a68f 100644 --- a/io/include/pcl/io/vlp_grabber.h +++ b/io/include/pcl/io/vlp_grabber.h @@ -36,10 +36,9 @@ * */ -#include "pcl/pcl_config.h" +#pragma once -#ifndef PCL_IO_VLP_GRABBER_H_ -#define PCL_IO_VLP_GRABBER_H_ +#include "pcl/pcl_config.h" #include #include @@ -124,5 +123,3 @@ namespace pcl }; } - -#endif /* PCL_IO_VLP_GRABBER_H_ */ diff --git a/io/include/pcl/io/vtk_io.h b/io/include/pcl/io/vtk_io.h index b965646df6c..a97654e352d 100644 --- a/io/include/pcl/io/vtk_io.h +++ b/io/include/pcl/io/vtk_io.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_IO_VTK_IO_H_ -#define PCL_IO_VTK_IO_H_ +#pragma once #include #include @@ -71,5 +70,3 @@ namespace pcl saveVTKFile (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, unsigned precision = 5); } } - -#endif //#ifndef PCL_IO_VTK_IO_H_ diff --git a/io/include/pcl/io/vtk_lib_io.h b/io/include/pcl/io/vtk_lib_io.h index 9dc7a0e3d48..19cc492d920 100644 --- a/io/include/pcl/io/vtk_lib_io.h +++ b/io/include/pcl/io/vtk_lib_io.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_IO_VTK_LIB_IO_H_ -#define PCL_IO_VTK_LIB_IO_H_ +#pragma once #include #include @@ -270,5 +269,3 @@ namespace pcl } #include - -#endif /* PLC_IO_VTK_LIB_IO_H_ */ diff --git a/kdtree/include/pcl/kdtree/flann.h b/kdtree/include/pcl/kdtree/flann.h index 5bbb666c17a..8e3d42d114c 100644 --- a/kdtree/include/pcl/kdtree/flann.h +++ b/kdtree/include/pcl/kdtree/flann.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_KDTREE_FLANN_H_ -#define PCL_KDTREE_FLANN_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -52,7 +51,3 @@ #if defined _MSC_VER # pragma warning(default: 4267) #endif - -#endif // PCL_KDTREE_FLANN_H_ - - diff --git a/kdtree/include/pcl/kdtree/io.h b/kdtree/include/pcl/kdtree/io.h index 68a2a2f7988..a3ebb21f808 100644 --- a/kdtree/include/pcl/kdtree/io.h +++ b/kdtree/include/pcl/kdtree/io.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_KDTREE_IO_H_ -#define PCL_KDTREE_IO_H_ +#pragma once #include @@ -74,6 +73,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_KDTREE_IO_H_ - diff --git a/kdtree/include/pcl/kdtree/kdtree.h b/kdtree/include/pcl/kdtree/kdtree.h index 586e4945e1f..52c9b320da5 100644 --- a/kdtree/include/pcl/kdtree/kdtree.h +++ b/kdtree/include/pcl/kdtree/kdtree.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_KDTREE_KDTREE_H_ -#define PCL_KDTREE_KDTREE_H_ +#pragma once #include #include @@ -363,5 +362,3 @@ namespace pcl getName () const = 0; }; } - -#endif //#ifndef _PCL_KDTREE_KDTREE_H_ diff --git a/kdtree/include/pcl/kdtree/kdtree_flann.h b/kdtree/include/pcl/kdtree/kdtree_flann.h index 448a937abe8..14127e759cc 100644 --- a/kdtree/include/pcl/kdtree/kdtree_flann.h +++ b/kdtree/include/pcl/kdtree/kdtree_flann.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_KDTREE_KDTREE_FLANN_H_ -#define PCL_KDTREE_KDTREE_FLANN_H_ +#pragma once #include #include @@ -237,5 +236,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/keypoints/include/pcl/keypoints/agast_2d.h b/keypoints/include/pcl/keypoints/agast_2d.h index a5779f9dfe5..7316775c83d 100644 --- a/keypoints/include/pcl/keypoints/agast_2d.h +++ b/keypoints/include/pcl/keypoints/agast_2d.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_KEYPOINTS_AGAST_KEYPOINT_2D_H_ -#define PCL_KEYPOINTS_AGAST_KEYPOINT_2D_H_ +#pragma once #include #include @@ -837,6 +836,3 @@ namespace pcl } #include - -#endif - diff --git a/keypoints/include/pcl/keypoints/brisk_2d.h b/keypoints/include/pcl/keypoints/brisk_2d.h index 74a592194d7..64d31bbe514 100644 --- a/keypoints/include/pcl/keypoints/brisk_2d.h +++ b/keypoints/include/pcl/keypoints/brisk_2d.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_KEYPOINTS_BRISK_KEYPOINT_2D_H_ -#define PCL_KEYPOINTS_BRISK_KEYPOINT_2D_H_ +#pragma once #include @@ -483,5 +482,3 @@ namespace pcl } #include - -#endif diff --git a/keypoints/include/pcl/keypoints/harris_2d.h b/keypoints/include/pcl/keypoints/harris_2d.h index a966307033b..1bedb993431 100644 --- a/keypoints/include/pcl/keypoints/harris_2d.h +++ b/keypoints/include/pcl/keypoints/harris_2d.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_HARRIS_KEYPOINT_2D_H_ -#define PCL_HARRIS_KEYPOINT_2D_H_ +#pragma once #include #include @@ -194,5 +193,3 @@ namespace pcl } #include - -#endif // #ifndef PCL_HARRIS_KEYPOINT_2D_H_ diff --git a/keypoints/include/pcl/keypoints/harris_3d.h b/keypoints/include/pcl/keypoints/harris_3d.h index b037155760b..2f03a4455fa 100644 --- a/keypoints/include/pcl/keypoints/harris_3d.h +++ b/keypoints/include/pcl/keypoints/harris_3d.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_HARRIS_KEYPOINT_3D_H_ -#define PCL_HARRIS_KEYPOINT_3D_H_ +#pragma once #include @@ -181,6 +180,3 @@ namespace pcl } #include - -#endif // #ifndef PCL_HARRIS_KEYPOINT_3D_H_ - diff --git a/keypoints/include/pcl/keypoints/harris_6d.h b/keypoints/include/pcl/keypoints/harris_6d.h index 37c0e729f60..c1561ef1333 100644 --- a/keypoints/include/pcl/keypoints/harris_6d.h +++ b/keypoints/include/pcl/keypoints/harris_6d.h @@ -34,8 +34,7 @@ * @author Suat Gedikli */ -#ifndef PCL_HARRIS_KEYPOINT_6D_H_ -#define PCL_HARRIS_KEYPOINT_6D_H_ +#pragma once #include @@ -139,6 +138,3 @@ namespace pcl } #include - -#endif // #ifndef PCL_HARRIS_KEYPOINT_6D_H_ - diff --git a/keypoints/include/pcl/keypoints/iss_3d.h b/keypoints/include/pcl/keypoints/iss_3d.h index 85a70c76368..7ab252280f4 100644 --- a/keypoints/include/pcl/keypoints/iss_3d.h +++ b/keypoints/include/pcl/keypoints/iss_3d.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_ISS_3D_H_ -#define PCL_ISS_3D_H_ +#pragma once #include @@ -272,5 +271,3 @@ namespace pcl } #include - -#endif /* PCL_ISS_3D_H_ */ diff --git a/keypoints/include/pcl/keypoints/keypoint.h b/keypoints/include/pcl/keypoints/keypoint.h index 52fdb281e29..e47f39a4cf9 100644 --- a/keypoints/include/pcl/keypoints/keypoint.h +++ b/keypoints/include/pcl/keypoints/keypoint.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_KEYPOINT_H_ -#define PCL_KEYPOINT_H_ +#pragma once // PCL includes #include @@ -207,5 +206,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_KEYPOINT_H_ diff --git a/keypoints/include/pcl/keypoints/narf_keypoint.h b/keypoints/include/pcl/keypoints/narf_keypoint.h index d4815183427..c0db076b31a 100644 --- a/keypoints/include/pcl/keypoints/narf_keypoint.h +++ b/keypoints/include/pcl/keypoints/narf_keypoint.h @@ -35,8 +35,7 @@ /* \author Bastian Steder */ -#ifndef PCL_NARF_KEYPOINT_H_ -#define PCL_NARF_KEYPOINT_H_ +#pragma once #include #include @@ -202,5 +201,3 @@ inline std::ostream& } } // end namespace pcl - -#endif //#ifndef PCL_NARF_KEYPOINT_H_ diff --git a/keypoints/include/pcl/keypoints/sift_keypoint.h b/keypoints/include/pcl/keypoints/sift_keypoint.h index 636f3ba78b0..a9a64052c9e 100644 --- a/keypoints/include/pcl/keypoints/sift_keypoint.h +++ b/keypoints/include/pcl/keypoints/sift_keypoint.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_SIFT_KEYPOINT_H_ -#define PCL_SIFT_KEYPOINT_H_ +#pragma once #include @@ -202,5 +201,3 @@ namespace pcl } #include - -#endif // #ifndef PCL_SIFT_KEYPOINT_H_ diff --git a/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h b/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h index 489e9bd72d8..45b62b7546d 100644 --- a/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h +++ b/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h @@ -35,8 +35,7 @@ * $Id$ */ -#ifndef PCL_SMOOTHEDSURFACESKEYPOINT_H_ -#define PCL_SMOOTHEDSURFACESKEYPOINT_H_ +#pragma once #include @@ -132,5 +131,3 @@ namespace pcl const std::pair &b) { return a.first < b.first; } }; } - -#endif /* PCL_SMOOTHEDSURFACESKEYPOINT_H_ */ diff --git a/keypoints/include/pcl/keypoints/susan.h b/keypoints/include/pcl/keypoints/susan.h index 3a833e7e9ff..6aba0eb5a88 100644 --- a/keypoints/include/pcl/keypoints/susan.h +++ b/keypoints/include/pcl/keypoints/susan.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_SUSAN_KEYPOINT_H_ -#define PCL_SUSAN_KEYPOINT_H_ +#pragma once #include #include @@ -200,5 +199,3 @@ namespace pcl } #include - -#endif // #ifndef PCL_SUSAN_KEYPOINT_H_ diff --git a/keypoints/include/pcl/keypoints/trajkovic_2d.h b/keypoints/include/pcl/keypoints/trajkovic_2d.h index 7458f96b9b9..575401649ee 100644 --- a/keypoints/include/pcl/keypoints/trajkovic_2d.h +++ b/keypoints/include/pcl/keypoints/trajkovic_2d.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_TRAJKOVIC_KEYPOINT_2D_H_ -#define PCL_TRAJKOVIC_KEYPOINT_2D_H_ +#pragma once #include #include @@ -172,5 +171,3 @@ namespace pcl } #include - -#endif // #ifndef PCL_TRAJKOVIC_KEYPOINT_2D_H_ diff --git a/keypoints/include/pcl/keypoints/trajkovic_3d.h b/keypoints/include/pcl/keypoints/trajkovic_3d.h index 8a58e464b85..6c1e71fe9e2 100644 --- a/keypoints/include/pcl/keypoints/trajkovic_3d.h +++ b/keypoints/include/pcl/keypoints/trajkovic_3d.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_TRAJKOVIC_KEYPOINT_3D_H_ -#define PCL_TRAJKOVIC_KEYPOINT_3D_H_ +#pragma once #include #include @@ -214,5 +213,3 @@ namespace pcl } #include - -#endif // #ifndef PCL_TRAJKOVIC_KEYPOINT_3D_H_ diff --git a/keypoints/include/pcl/keypoints/uniform_sampling.h b/keypoints/include/pcl/keypoints/uniform_sampling.h index 4e080d9fb34..7266dcfe159 100644 --- a/keypoints/include/pcl/keypoints/uniform_sampling.h +++ b/keypoints/include/pcl/keypoints/uniform_sampling.h @@ -37,14 +37,10 @@ * */ -#ifndef PCL_KEYPOINTS_UNIFORM_SAMPLING_H_ -#define PCL_KEYPOINTS_UNIFORM_SAMPLING_H_ +#pragma once #ifdef __DEPRECATED #warning UniformSampling is not a Keypoint anymore, use instead. #endif #include - -#endif //#ifndef PCL_KEYPOINTS_UNIFORM_SAMPLING_H_ - diff --git a/ml/include/pcl/ml/branch_estimator.h b/ml/include/pcl/ml/branch_estimator.h index 62a291d04d6..859f38816d1 100644 --- a/ml/include/pcl/ml/branch_estimator.h +++ b/ml/include/pcl/ml/branch_estimator.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_BRANCH_ESTIMATOR_H_ -#define PCL_ML_BRANCH_ESTIMATOR_H_ +#pragma once #include #include @@ -145,5 +144,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/densecrf.h b/ml/include/pcl/ml/densecrf.h index 7b7f9da44a6..976bbc00788 100644 --- a/ml/include/pcl/ml/densecrf.h +++ b/ml/include/pcl/ml/densecrf.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_DENSE_CRF_H_ -#define PCL_DENSE_CRF_H_ +#pragma once #include #include @@ -162,9 +161,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - - - - - -#endif diff --git a/ml/include/pcl/ml/dt/decision_forest.h b/ml/include/pcl/ml/dt/decision_forest.h index e281400a5c4..5917e7ade33 100644 --- a/ml/include/pcl/ml/dt/decision_forest.h +++ b/ml/include/pcl/ml/dt/decision_forest.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_DECISION_FOREST_H_ -#define PCL_ML_DT_DECISION_FOREST_H_ +#pragma once #include @@ -131,5 +130,3 @@ namespace pcl } - -#endif diff --git a/ml/include/pcl/ml/dt/decision_forest_evaluator.h b/ml/include/pcl/ml/dt/decision_forest_evaluator.h index 2dc648be6dc..7d38ae5cd1f 100644 --- a/ml/include/pcl/ml/dt/decision_forest_evaluator.h +++ b/ml/include/pcl/ml/dt/decision_forest_evaluator.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_DECISION_FOREST_EVALUATOR_H_ -#define PCL_ML_DT_DECISION_FOREST_EVALUATOR_H_ +#pragma once #include @@ -106,5 +105,3 @@ namespace pcl } #include - -#endif diff --git a/ml/include/pcl/ml/dt/decision_forest_trainer.h b/ml/include/pcl/ml/dt/decision_forest_trainer.h index 563dc260793..28cbf0caf08 100644 --- a/ml/include/pcl/ml/dt/decision_forest_trainer.h +++ b/ml/include/pcl/ml/dt/decision_forest_trainer.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_DECISION_FOREST_TRAINER_H_ -#define PCL_ML_DT_DECISION_FOREST_TRAINER_H_ +#pragma once #include @@ -205,5 +204,3 @@ namespace pcl } #include - -#endif diff --git a/ml/include/pcl/ml/dt/decision_tree.h b/ml/include/pcl/ml/dt/decision_tree.h index f0b8c8f9f86..b3343d19e98 100644 --- a/ml/include/pcl/ml/dt/decision_tree.h +++ b/ml/include/pcl/ml/dt/decision_tree.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_DECISION_TREE -#define PCL_ML_DT_DECISION_TREE +#pragma once #include @@ -101,5 +100,3 @@ namespace pcl } - -#endif diff --git a/ml/include/pcl/ml/dt/decision_tree_evaluator.h b/ml/include/pcl/ml/dt/decision_tree_evaluator.h index 1ce4c6e785a..1c739e00ed2 100644 --- a/ml/include/pcl/ml/dt/decision_tree_evaluator.h +++ b/ml/include/pcl/ml/dt/decision_tree_evaluator.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_DECISION_TREE_EVALUATOR_H_ -#define PCL_ML_DT_DECISION_TREE_EVALUATOR_H_ +#pragma once #include @@ -136,5 +135,3 @@ namespace pcl } #include - -#endif diff --git a/ml/include/pcl/ml/dt/decision_tree_trainer.h b/ml/include/pcl/ml/dt/decision_tree_trainer.h index 33c326053c2..7264c0fd27f 100644 --- a/ml/include/pcl/ml/dt/decision_tree_trainer.h +++ b/ml/include/pcl/ml/dt/decision_tree_trainer.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_DECISION_TREE_TRAINER_H_ -#define PCL_ML_DT_DECISION_TREE_TRAINER_H_ +#pragma once #include @@ -242,5 +241,3 @@ namespace pcl } #include - -#endif diff --git a/ml/include/pcl/ml/feature_handler.h b/ml/include/pcl/ml/feature_handler.h index ed5309f5948..744bb6a2ca1 100644 --- a/ml/include/pcl/ml/feature_handler.h +++ b/ml/include/pcl/ml/feature_handler.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_FEATURE_HANDLER_H_ -#define PCL_ML_DT_FEATURE_HANDLER_H_ +#pragma once #include @@ -105,5 +104,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/ferns/fern.h b/ml/include/pcl/ml/ferns/fern.h index beedaf5518f..67f8c65abac 100644 --- a/ml/include/pcl/ml/ferns/fern.h +++ b/ml/include/pcl/ml/ferns/fern.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_FERNS_FERN -#define PCL_ML_FERNS_FERN +#pragma once #include @@ -211,5 +210,3 @@ namespace pcl } - -#endif diff --git a/ml/include/pcl/ml/ferns/fern_evaluator.h b/ml/include/pcl/ml/ferns/fern_evaluator.h index 1f43760114c..2c479a86d56 100644 --- a/ml/include/pcl/ml/ferns/fern_evaluator.h +++ b/ml/include/pcl/ml/ferns/fern_evaluator.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_FERNS_FERN_EVALUATOR_H_ -#define PCL_ML_FERNS_FERN_EVALUATOR_H_ +#pragma once #include @@ -120,5 +119,3 @@ namespace pcl } #include - -#endif diff --git a/ml/include/pcl/ml/ferns/fern_trainer.h b/ml/include/pcl/ml/ferns/fern_trainer.h index 3f5f48f9f55..eaf35e1d9cf 100644 --- a/ml/include/pcl/ml/ferns/fern_trainer.h +++ b/ml/include/pcl/ml/ferns/fern_trainer.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_FERNS_FERN_TRAINER_H_ -#define PCL_ML_FERNS_FERN_TRAINER_H_ +#pragma once #include @@ -178,5 +177,3 @@ namespace pcl } #include - -#endif diff --git a/ml/include/pcl/ml/kmeans.h b/ml/include/pcl/ml/kmeans.h index 459ecb3001a..efa7a6f071e 100644 --- a/ml/include/pcl/ml/kmeans.h +++ b/ml/include/pcl/ml/kmeans.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_KMEANS_H_ -#define PCL_KMEANS_H_ +#pragma once #include @@ -205,5 +204,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif diff --git a/ml/include/pcl/ml/multi_channel_2d_comparison_feature.h b/ml/include/pcl/ml/multi_channel_2d_comparison_feature.h index b8cede5f6f5..eceb155c050 100644 --- a/ml/include/pcl/ml/multi_channel_2d_comparison_feature.h +++ b/ml/include/pcl/ml/multi_channel_2d_comparison_feature.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_MULTI_CHANNEL_2D_COMPARISON_FEATURE_H_ -#define PCL_ML_MULTI_CHANNEL_2D_COMPARISON_FEATURE_H_ +#pragma once #include @@ -89,5 +88,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/multi_channel_2d_comparison_feature_handler.h b/ml/include/pcl/ml/multi_channel_2d_comparison_feature_handler.h index 7650ab13a4d..62f6b05518b 100644 --- a/ml/include/pcl/ml/multi_channel_2d_comparison_feature_handler.h +++ b/ml/include/pcl/ml/multi_channel_2d_comparison_feature_handler.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_MULTI_CHANNEL_2D_COMPARISON_FEATURE_HANDLER_H_ -#define PCL_ML_MULTI_CHANNEL_2D_COMPARISON_FEATURE_HANDLER_H_ +#pragma once #include @@ -394,5 +393,3 @@ namespace pcl typedef ScaledMultiChannel2DComparisonFeatureHandlerCCodeGenerator ScaledDepth2DComparisonFeatureHandlerCCodeGenerator; } - -#endif diff --git a/ml/include/pcl/ml/multi_channel_2d_data_set.h b/ml/include/pcl/ml/multi_channel_2d_data_set.h index 99e6d094d13..e971b566e12 100644 --- a/ml/include/pcl/ml/multi_channel_2d_data_set.h +++ b/ml/include/pcl/ml/multi_channel_2d_data_set.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_MULTI_CHANNEL_2D_DATA_SET_H_ -#define PCL_ML_MULTI_CHANNEL_2D_DATA_SET_H_ +#pragma once #include @@ -232,5 +231,3 @@ namespace pcl typedef MultiChannel2DDataSet RGBD2DDataSet; } - -#endif diff --git a/ml/include/pcl/ml/multiple_data_2d_example_index.h b/ml/include/pcl/ml/multiple_data_2d_example_index.h index 239eb708d29..e77879e0bed 100644 --- a/ml/include/pcl/ml/multiple_data_2d_example_index.h +++ b/ml/include/pcl/ml/multiple_data_2d_example_index.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_MULTIPLE_DATA_2D_EXAMPLE_INDEX_H_ -#define PCL_ML_MULTIPLE_DATA_2D_EXAMPLE_INDEX_H_ +#pragma once #include @@ -59,5 +58,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/pairwise_potential.h b/ml/include/pcl/ml/pairwise_potential.h index a9e3b458ff9..2d1391408a9 100644 --- a/ml/include/pcl/ml/pairwise_potential.h +++ b/ml/include/pcl/ml/pairwise_potential.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_PAIRWISE_POTENTIAL_H_ -#define PCL_PAIRWISE_POTENTIAL_H_ +#pragma once #include @@ -84,5 +83,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/permutohedral.h b/ml/include/pcl/ml/permutohedral.h index 09976933bd1..cb28ae59088 100644 --- a/ml/include/pcl/ml/permutohedral.h +++ b/ml/include/pcl/ml/permutohedral.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_PERMUTOHEDRAL_H_ -#define PCL_ML_PERMUTOHEDRAL_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -269,5 +268,3 @@ namespace pcl };*/ } - -#endif diff --git a/ml/include/pcl/ml/point_xy_32f.h b/ml/include/pcl/ml/point_xy_32f.h index a01cb290a0b..86d79606a93 100644 --- a/ml/include/pcl/ml/point_xy_32f.h +++ b/ml/include/pcl/ml/point_xy_32f.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_POINT_XY_32F_H_ -#define PCL_ML_POINT_XY_32F_H_ +#pragma once #include @@ -92,5 +91,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/point_xy_32i.h b/ml/include/pcl/ml/point_xy_32i.h index 6e96fb62192..4abac33af96 100644 --- a/ml/include/pcl/ml/point_xy_32i.h +++ b/ml/include/pcl/ml/point_xy_32i.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_POINT_XY_32I_H_ -#define PCL_ML_POINT_XY_32I_H_ +#pragma once #include @@ -92,5 +91,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/regression_variance_stats_estimator.h b/ml/include/pcl/ml/regression_variance_stats_estimator.h index ef7c247877f..d306cddab18 100644 --- a/ml/include/pcl/ml/regression_variance_stats_estimator.h +++ b/ml/include/pcl/ml/regression_variance_stats_estimator.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_REGRESSION_VARIANCE_STATS_ESTIMATOR_H_ -#define PCL_ML_REGRESSION_VARIANCE_STATS_ESTIMATOR_H_ +#pragma once #include #include @@ -325,5 +324,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/stats_estimator.h b/ml/include/pcl/ml/stats_estimator.h index 374e1334e82..cd54e800012 100644 --- a/ml/include/pcl/ml/stats_estimator.h +++ b/ml/include/pcl/ml/stats_estimator.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_ML_DT_STATS_ESTIMATOR_H_ -#define PCL_ML_DT_STATS_ESTIMATOR_H_ +#pragma once #include @@ -141,5 +140,3 @@ namespace pcl }; } - -#endif diff --git a/ml/include/pcl/ml/svm_wrapper.h b/ml/include/pcl/ml/svm_wrapper.h index 6ddc7ed7e6a..34f0bfcf69f 100755 --- a/ml/include/pcl/ml/svm_wrapper.h +++ b/ml/include/pcl/ml/svm_wrapper.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_SVM_WRAPPER_H_ -#define PCL_SVM_WRAPPER_H_ +#pragma once #include #include @@ -533,5 +532,3 @@ namespace pcl }; }; } - -#endif // PCL_SVM_WRAPPER_H_ diff --git a/octree/include/pcl/octree/boost.h b/octree/include/pcl/octree/boost.h index f1c8c18bcea..f5cde574898 100644 --- a/octree/include/pcl/octree/boost.h +++ b/octree/include/pcl/octree/boost.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_OCTREE_BOOST_H_ -#define PCL_OCTREE_BOOST_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -47,4 +46,3 @@ // Marking all Boost headers as system headers to remove warnings #include #include -#endif // PCL_OCTREE_BOOST_H_ diff --git a/octree/include/pcl/octree/octree.h b/octree/include/pcl/octree/octree.h index e66298900da..b35781765dd 100644 --- a/octree/include/pcl/octree/octree.h +++ b/octree/include/pcl/octree/octree.h @@ -36,9 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_H -#define PCL_OCTREE_H - +#pragma once #include #include @@ -54,5 +52,3 @@ #include #include - -#endif diff --git a/octree/include/pcl/octree/octree2buf_base.h b/octree/include/pcl/octree/octree2buf_base.h index 15b678de82f..8043b30ee5c 100644 --- a/octree/include/pcl/octree/octree2buf_base.h +++ b/octree/include/pcl/octree/octree2buf_base.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_TREE_2BUF_BASE_H -#define PCL_OCTREE_TREE_2BUF_BASE_H +#pragma once #include @@ -962,6 +961,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/octree/include/pcl/octree/octree_base.h b/octree/include/pcl/octree/octree_base.h index 0a4b2133cd3..4eb7f0e2ebe 100644 --- a/octree/include/pcl/octree/octree_base.h +++ b/octree/include/pcl/octree/octree_base.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_TREE_BASE_H -#define PCL_OCTREE_TREE_BASE_H +#pragma once #include @@ -679,6 +678,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/octree/include/pcl/octree/octree_container.h b/octree/include/pcl/octree/octree_container.h index be62dd80c0f..87b43ca6297 100644 --- a/octree/include/pcl/octree/octree_container.h +++ b/octree/include/pcl/octree/octree_container.h @@ -36,8 +36,7 @@ * $Id: octree_nodes.h 5596 2012-04-17 15:09:31Z jkammerl $ */ -#ifndef PCL_OCTREE_CONTAINER_H -#define PCL_OCTREE_CONTAINER_H +#pragma once #include #include @@ -395,5 +394,3 @@ namespace pcl } } - -#endif diff --git a/octree/include/pcl/octree/octree_impl.h b/octree/include/pcl/octree/octree_impl.h index 54a495c09ea..0a6f3075802 100644 --- a/octree/include/pcl/octree/octree_impl.h +++ b/octree/include/pcl/octree/octree_impl.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_IMPL_H -#define PCL_OCTREE_IMPL_H +#pragma once #include @@ -46,5 +45,3 @@ #include #include #include - -#endif diff --git a/octree/include/pcl/octree/octree_iterator.h b/octree/include/pcl/octree/octree_iterator.h index cef9a9890bf..e604240718e 100644 --- a/octree/include/pcl/octree/octree_iterator.h +++ b/octree/include/pcl/octree/octree_iterator.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_ITERATOR_H -#define PCL_OCTREE_ITERATOR_H +#pragma once #include #include @@ -824,6 +823,3 @@ namespace pcl * Note: Since octree iterators depend on octrees, don't precompile them. */ #include - -#endif - diff --git a/octree/include/pcl/octree/octree_key.h b/octree/include/pcl/octree/octree_key.h index dbde982185f..85c85872de3 100644 --- a/octree/include/pcl/octree/octree_key.h +++ b/octree/include/pcl/octree/octree_key.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_OCTREE_KEY_H -#define PCL_OCTREE_KEY_H +#pragma once namespace pcl { @@ -159,5 +158,3 @@ namespace pcl }; } } - -#endif diff --git a/octree/include/pcl/octree/octree_node_pool.h b/octree/include/pcl/octree/octree_node_pool.h index 62568c82826..7d54ea16818 100644 --- a/octree/include/pcl/octree/octree_node_pool.h +++ b/octree/include/pcl/octree/octree_node_pool.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_OCTREE_NODE_POOL_H -#define PCL_OCTREE_NODE_POOL_H +#pragma once #include @@ -125,5 +124,3 @@ namespace pcl } } - -#endif diff --git a/octree/include/pcl/octree/octree_nodes.h b/octree/include/pcl/octree/octree_nodes.h index 07ce67d66e5..8c7aefcaa84 100644 --- a/octree/include/pcl/octree/octree_nodes.h +++ b/octree/include/pcl/octree/octree_nodes.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_NODE_H -#define PCL_OCTREE_NODE_H +#pragma once #include @@ -396,5 +395,3 @@ namespace pcl }; } } - -#endif diff --git a/octree/include/pcl/octree/octree_pointcloud.h b/octree/include/pcl/octree/octree_pointcloud.h index ba9e37d0b97..edaffa5967d 100644 --- a/octree/include/pcl/octree/octree_pointcloud.h +++ b/octree/include/pcl/octree/octree_pointcloud.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_POINTCLOUD_H -#define PCL_OCTREE_POINTCLOUD_H +#pragma once #include @@ -550,6 +549,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/octree/include/pcl/octree/octree_pointcloud_adjacency.h b/octree/include/pcl/octree/octree_pointcloud_adjacency.h index d7a894fe30a..ad253ce47af 100644 --- a/octree/include/pcl/octree/octree_pointcloud_adjacency.h +++ b/octree/include/pcl/octree/octree_pointcloud_adjacency.h @@ -37,8 +37,7 @@ * Email : jpapon@gmail.com */ -#ifndef PCL_OCTREE_POINTCLOUD_ADJACENCY_H_ -#define PCL_OCTREE_POINTCLOUD_ADJACENCY_H_ +#pragma once #include #include @@ -227,6 +226,3 @@ namespace pcl // Note: Do not precompile this octree type because it is typically used with custom leaf containers. #include - -#endif // PCL_OCTREE_POINTCLOUD_ADJACENCY_H_ - diff --git a/octree/include/pcl/octree/octree_pointcloud_adjacency_container.h b/octree/include/pcl/octree/octree_pointcloud_adjacency_container.h index 45782b236c1..e98f403e4b0 100644 --- a/octree/include/pcl/octree/octree_pointcloud_adjacency_container.h +++ b/octree/include/pcl/octree/octree_pointcloud_adjacency_container.h @@ -37,8 +37,7 @@ * Email : jpapon@gmail.com */ -#ifndef PCL_OCTREE_POINTCLOUD_ADJACENCY_CONTAINER_H_ -#define PCL_OCTREE_POINTCLOUD_ADJACENCY_CONTAINER_H_ +#pragma once namespace pcl { @@ -196,5 +195,3 @@ namespace pcl }; } } - -#endif diff --git a/octree/include/pcl/octree/octree_pointcloud_changedetector.h b/octree/include/pcl/octree/octree_pointcloud_changedetector.h index 3de95ad9766..4dc6a0c52f4 100644 --- a/octree/include/pcl/octree/octree_pointcloud_changedetector.h +++ b/octree/include/pcl/octree/octree_pointcloud_changedetector.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_CHANGEDETECTOR_H -#define PCL_OCTREE_CHANGEDETECTOR_H +#pragma once #include #include @@ -110,6 +109,3 @@ namespace pcl } #define PCL_INSTANTIATE_OctreePointCloudChangeDetector(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudChangeDetector; - -#endif - diff --git a/octree/include/pcl/octree/octree_pointcloud_density.h b/octree/include/pcl/octree/octree_pointcloud_density.h index 9137a39bd8c..2dbf347fa80 100644 --- a/octree/include/pcl/octree/octree_pointcloud_density.h +++ b/octree/include/pcl/octree/octree_pointcloud_density.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_DENSITY_H -#define PCL_OCTREE_DENSITY_H +#pragma once #include @@ -157,6 +156,3 @@ namespace pcl } #define PCL_INSTANTIATE_OctreePointCloudDensity(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudDensity; - -#endif - diff --git a/octree/include/pcl/octree/octree_pointcloud_occupancy.h b/octree/include/pcl/octree/octree_pointcloud_occupancy.h index 7510257d13c..f65987142ca 100644 --- a/octree/include/pcl/octree/octree_pointcloud_occupancy.h +++ b/octree/include/pcl/octree/octree_pointcloud_occupancy.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_OCCUPANCY_H -#define PCL_OCTREE_OCCUPANCY_H +#pragma once #include @@ -127,6 +126,3 @@ namespace pcl } #define PCL_INSTANTIATE_OctreePointCloudOccupancy(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudOccupancy; - -#endif - diff --git a/octree/include/pcl/octree/octree_pointcloud_pointvector.h b/octree/include/pcl/octree/octree_pointcloud_pointvector.h index d5b6a140a80..0cdb3c0bb97 100644 --- a/octree/include/pcl/octree/octree_pointcloud_pointvector.h +++ b/octree/include/pcl/octree/octree_pointcloud_pointvector.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_POINT_VECTOR_H -#define PCL_OCTREE_POINT_VECTOR_H +#pragma once #include @@ -88,5 +87,3 @@ namespace pcl } #define PCL_INSTANTIATE_OctreePointCloudPointVector(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudPointVector; - -#endif diff --git a/octree/include/pcl/octree/octree_pointcloud_singlepoint.h b/octree/include/pcl/octree/octree_pointcloud_singlepoint.h index 7300ac030bb..3c95e44df33 100644 --- a/octree/include/pcl/octree/octree_pointcloud_singlepoint.h +++ b/octree/include/pcl/octree/octree_pointcloud_singlepoint.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_SINGLE_POINT_H -#define PCL_OCTREE_SINGLE_POINT_H +#pragma once #include @@ -89,5 +88,3 @@ namespace pcl } #define PCL_INSTANTIATE_OctreePointCloudSinglePoint(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudSinglePoint; - -#endif diff --git a/octree/include/pcl/octree/octree_pointcloud_voxelcentroid.h b/octree/include/pcl/octree/octree_pointcloud_voxelcentroid.h index 68840f9400c..86377d9cfad 100644 --- a/octree/include/pcl/octree/octree_pointcloud_voxelcentroid.h +++ b/octree/include/pcl/octree/octree_pointcloud_voxelcentroid.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_VOXELCENTROID_H -#define PCL_OCTREE_VOXELCENTROID_H +#pragma once #include @@ -230,6 +229,3 @@ namespace pcl // Note: Don't precompile this octree type to speed up compilation. It's probably rarely used. #include - -#endif - diff --git a/octree/include/pcl/octree/octree_search.h b/octree/include/pcl/octree/octree_search.h index 165f7faf437..e464a704f9c 100644 --- a/octree/include/pcl/octree/octree_search.h +++ b/octree/include/pcl/octree/octree_search.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OCTREE_SEARCH_H_ -#define PCL_OCTREE_SEARCH_H_ +#pragma once #include @@ -603,5 +602,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_OCTREE_SEARCH_H_ diff --git a/outofcore/include/pcl/outofcore/boost.h b/outofcore/include/pcl/outofcore/boost.h index 951fffb78a5..e0e1e65daf8 100644 --- a/outofcore/include/pcl/outofcore/boost.h +++ b/outofcore/include/pcl/outofcore/boost.h @@ -36,8 +36,7 @@ * $Id: boost.h 6913 2012-08-22 09:37:26Z stfox88 $ */ -#ifndef PCL_OUTOFCORE_BOOST_H_ -#define PCL_OUTOFCORE_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -54,5 +53,3 @@ #include #include #include - -#endif //PCL_OUTOFCORE_BOOST_H_ diff --git a/outofcore/include/pcl/outofcore/metadata.h b/outofcore/include/pcl/outofcore/metadata.h index 6f68d8ad06a..dfe0694c689 100644 --- a/outofcore/include/pcl/outofcore/metadata.h +++ b/outofcore/include/pcl/outofcore/metadata.h @@ -36,9 +36,7 @@ * $Id$ */ - -#ifndef PCL_OUTOFCORE_METADATA_H_ -#define PCL_OUTOFCORE_METADATA_H_ +#pragma once #include #include @@ -94,5 +92,3 @@ namespace pcl }//namespace outofcore }//namespace pcl - -#endif //PCL_OUTOFCORE_METADATA_H_ diff --git a/outofcore/include/pcl/outofcore/octree_abstract_node_container.h b/outofcore/include/pcl/outofcore/octree_abstract_node_container.h index 8aeef7a25b7..a54fc6d2be8 100644 --- a/outofcore/include/pcl/outofcore/octree_abstract_node_container.h +++ b/outofcore/include/pcl/outofcore/octree_abstract_node_container.h @@ -36,8 +36,7 @@ * $Id: octree_abstract_node_container.h 6802M 2012-08-25 00:11:05Z (local) $ */ -#ifndef PCL_OUTOFCORE_OCTREE_ABSTRACT_NODE_CONTAINER_H_ -#define PCL_OUTOFCORE_OCTREE_ABSTRACT_NODE_CONTAINER_H_ +#pragma once #include #include @@ -101,5 +100,3 @@ namespace pcl }; }//namespace outofcore }//namespace pcl - -#endif //PCL_OUTOFCORE_OCTREE_ABSTRACT_CONTAINER_H_ diff --git a/outofcore/include/pcl/outofcore/octree_base.h b/outofcore/include/pcl/outofcore/octree_base.h index 261600e96e2..e9dfabb698a 100644 --- a/outofcore/include/pcl/outofcore/octree_base.h +++ b/outofcore/include/pcl/outofcore/octree_base.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_OUTOFCORE_OUTOFCOREOCTREEBASE_H_ -#define PCL_OUTOFCORE_OUTOFCOREOCTREEBASE_H_ +#pragma once #include #include @@ -662,6 +661,3 @@ namespace pcl }; } } - - -#endif // PCL_OUTOFCORE_OUTOFCOREOCTREEBASE_H_ diff --git a/outofcore/include/pcl/outofcore/octree_base_node.h b/outofcore/include/pcl/outofcore/octree_base_node.h index a39202ac540..c216de97b5c 100644 --- a/outofcore/include/pcl/outofcore/octree_base_node.h +++ b/outofcore/include/pcl/outofcore/octree_base_node.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_OUTOFCORE_OCTREE_BASE_NODE_H_ -#define PCL_OUTOFCORE_OCTREE_BASE_NODE_H_ +#pragma once #include #include @@ -573,5 +572,3 @@ namespace pcl }; }//namespace outofcore }//namespace pcl - -#endif //PCL_OUTOFCORE_OCTREE_BASE_NODE_H_ diff --git a/outofcore/include/pcl/outofcore/octree_disk_container.h b/outofcore/include/pcl/outofcore/octree_disk_container.h index d10af697bf0..f72458ef11f 100644 --- a/outofcore/include/pcl/outofcore/octree_disk_container.h +++ b/outofcore/include/pcl/outofcore/octree_disk_container.h @@ -37,8 +37,7 @@ * $Id: octree_disk_container.h 6927M 2012-08-24 13:26:40Z (local) $ */ -#ifndef PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_ -#define PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_ +#pragma once // C++ #include @@ -301,5 +300,3 @@ namespace pcl }; } //namespace outofcore } //namespace pcl - -#endif //PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_ diff --git a/outofcore/include/pcl/outofcore/octree_ram_container.h b/outofcore/include/pcl/outofcore/octree_ram_container.h index 2ab72bfa5a0..021ec0c6a6a 100644 --- a/outofcore/include/pcl/outofcore/octree_ram_container.h +++ b/outofcore/include/pcl/outofcore/octree_ram_container.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_OUTOFCORE_OCTREE_RAM_CONTAINER_H_ -#define PCL_OUTOFCORE_OCTREE_RAM_CONTAINER_H_ +#pragma once // C++ #include @@ -170,5 +169,3 @@ namespace pcl }; } } - -#endif //PCL_OUTOFCORE_OCTREE_RAM_CONTAINER_H_ diff --git a/outofcore/include/pcl/outofcore/outofcore_base_data.h b/outofcore/include/pcl/outofcore/outofcore_base_data.h index 8c2fd70d9f1..b9c20ff9cdc 100644 --- a/outofcore/include/pcl/outofcore/outofcore_base_data.h +++ b/outofcore/include/pcl/outofcore/outofcore_base_data.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OUTOFCORE_OCTREE_BASE_METADATA_H_ -#define PCL_OUTOFCORE_OCTREE_BASE_METADATA_H_ +#pragma once #include #include @@ -219,5 +218,3 @@ namespace pcl }; }//namespace outofcore }//namespace pcl - -#endif // PCL_OUTOFCORE_OCTREE_BASE_METADATA_H_ diff --git a/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h b/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h index 3961519095b..ed2a108e829 100644 --- a/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h +++ b/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h @@ -36,8 +36,7 @@ * $Id: outofcore_depth_first_iterator.h 7938 2012-11-14 06:27:39Z jrosen $ */ -#ifndef PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_H_ -#define PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_H_ +#pragma once #include namespace pcl @@ -105,5 +104,3 @@ namespace pcl }; } } - -#endif //PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_H_ diff --git a/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h b/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h index e110fb5583d..1a01e547b09 100644 --- a/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h +++ b/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_H_ -#define PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_H_ +#pragma once #include namespace pcl @@ -86,5 +85,3 @@ namespace pcl }; } } - -#endif //PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_H_ diff --git a/outofcore/include/pcl/outofcore/outofcore_iterator_base.h b/outofcore/include/pcl/outofcore/outofcore_iterator_base.h index a409395a8a1..aeae9841f55 100644 --- a/outofcore/include/pcl/outofcore/outofcore_iterator_base.h +++ b/outofcore/include/pcl/outofcore/outofcore_iterator_base.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_OUTOFCORE_ITERATOR_BASE_H_ -#define PCL_OUTOFCORE_ITERATOR_BASE_H_ +#pragma once #include @@ -155,5 +154,3 @@ namespace pcl #endif } } - -#endif //PCL_OUTOFCORE_ITERATOR_BASE_H_ diff --git a/outofcore/include/pcl/outofcore/outofcore_node_data.h b/outofcore/include/pcl/outofcore/outofcore_node_data.h index 0e3febb8fab..e9f7ba855ad 100644 --- a/outofcore/include/pcl/outofcore/outofcore_node_data.h +++ b/outofcore/include/pcl/outofcore/outofcore_node_data.h @@ -36,8 +36,7 @@ * $Id: outofcore_node_data.h 6915 2012-08-22 10:54:21Z stfox88 $ */ -#ifndef PCL_OUTOFCORE_OCTREE_NODE_METADATA_H_ -#define PCL_OUTOFCORE_OCTREE_NODE_METADATA_H_ +#pragma once #include #include @@ -186,5 +185,3 @@ namespace pcl }; }//namespace outofcore }//namespace pcl - -#endif // PCL_OUTOFCORE_OCTREE_NODE_METADATA_H_ diff --git a/outofcore/include/pcl/outofcore/visualization/axes.h b/outofcore/include/pcl/outofcore/visualization/axes.h index e4c2bf76f53..50cc88bb7fb 100644 --- a/outofcore/include/pcl/outofcore/visualization/axes.h +++ b/outofcore/include/pcl/outofcore/visualization/axes.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_AXES_H_ -#define PCL_OUTOFCORE_AXES_H_ +#pragma once // C++ #include @@ -93,6 +92,3 @@ class Axes : public Object vtkSmartPointer axes_actor_; }; - -#endif - diff --git a/outofcore/include/pcl/outofcore/visualization/camera.h b/outofcore/include/pcl/outofcore/visualization/camera.h index 53dde35540a..9f7bb33f48d 100644 --- a/outofcore/include/pcl/outofcore/visualization/camera.h +++ b/outofcore/include/pcl/outofcore/visualization/camera.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_CAMERA_H_ -#define PCL_OUTOFCORE_CAMERA_H_ +#pragma once // C++ #include @@ -149,5 +148,3 @@ class Camera : public Object double prevFocal_[3]; double prevPos_[3]; }; - -#endif diff --git a/outofcore/include/pcl/outofcore/visualization/common.h b/outofcore/include/pcl/outofcore/visualization/common.h index aec5e58a0f6..e8b36e85baa 100644 --- a/outofcore/include/pcl/outofcore/visualization/common.h +++ b/outofcore/include/pcl/outofcore/visualization/common.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_COMMON_H_ -#define PCL_OUTOFCORE_COMMON_H_ +#pragma once // VTK #include @@ -7,5 +6,3 @@ vtkSmartPointer getVtkCube (double x_min, double x_max, double y_min, double y_max, double z_min, double z_max); - -#endif diff --git a/outofcore/include/pcl/outofcore/visualization/geometry.h b/outofcore/include/pcl/outofcore/visualization/geometry.h index 7990384ffa9..13cdd7fa9fe 100644 --- a/outofcore/include/pcl/outofcore/visualization/geometry.h +++ b/outofcore/include/pcl/outofcore/visualization/geometry.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_GEOMETRY_H_ -#define PCL_OUTOFCORE_GEOMETRY_H_ +#pragma once // C++ #include @@ -39,5 +38,3 @@ class Geometry : public Object } }; - -#endif diff --git a/outofcore/include/pcl/outofcore/visualization/grid.h b/outofcore/include/pcl/outofcore/visualization/grid.h index b9aa3449a46..052abf07742 100644 --- a/outofcore/include/pcl/outofcore/visualization/grid.h +++ b/outofcore/include/pcl/outofcore/visualization/grid.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_GRID_H_ -#define PCL_OUTOFCORE_GRID_H_ +#pragma once // C++ #include @@ -50,5 +49,3 @@ class Grid : public Object vtkSmartPointer grid_actor_; }; - -#endif diff --git a/outofcore/include/pcl/outofcore/visualization/object.h b/outofcore/include/pcl/outofcore/visualization/object.h index c6cf208293e..2518efef948 100644 --- a/outofcore/include/pcl/outofcore/visualization/object.h +++ b/outofcore/include/pcl/outofcore/visualization/object.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_OBJECT_H_ -#define PCL_OUTOFCORE_OBJECT_H_ +#pragma once // C++ #include @@ -67,5 +66,3 @@ class Object std::map > associated_renderers_; }; - -#endif diff --git a/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h b/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h index ee65e140f18..aa36dfaa28c 100644 --- a/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h +++ b/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_OUTOFCORE_CLOUD_H_ -#define PCL_OUTOFCORE_OUTOFCORE_CLOUD_H_ +#pragma once #include @@ -292,5 +291,3 @@ class OutofcoreCloud : public Object public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; - -#endif diff --git a/outofcore/include/pcl/outofcore/visualization/scene.h b/outofcore/include/pcl/outofcore/visualization/scene.h index 438a3ce855c..c47b4df7c1e 100644 --- a/outofcore/include/pcl/outofcore/visualization/scene.h +++ b/outofcore/include/pcl/outofcore/visualization/scene.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_SCENE_H_ -#define PCL_OUTOFCORE_SCENE_H_ +#pragma once // PCL #include "camera.h" @@ -86,5 +85,3 @@ class Scene boost::mutex render_mutex_; }; - -#endif diff --git a/outofcore/include/pcl/outofcore/visualization/viewport.h b/outofcore/include/pcl/outofcore/visualization/viewport.h index 2072567daec..c847dbf40f3 100644 --- a/outofcore/include/pcl/outofcore/visualization/viewport.h +++ b/outofcore/include/pcl/outofcore/visualization/viewport.h @@ -1,5 +1,4 @@ -#ifndef PCL_OUTOFCORE_VIEWPORT_H_ -#define PCL_OUTOFCORE_VIEWPORT_H_ +#pragma once // C++ #include @@ -78,5 +77,3 @@ class Viewport vtkSmartPointer fps_hud_actor_; vtkSmartPointer points_hud_actor_; }; - -#endif diff --git a/people/include/pcl/people/ground_based_people_detection_app.h b/people/include/pcl/people/ground_based_people_detection_app.h index 9c07db1f492..45d3efa9b29 100644 --- a/people/include/pcl/people/ground_based_people_detection_app.h +++ b/people/include/pcl/people/ground_based_people_detection_app.h @@ -38,8 +38,7 @@ * Author: Matteo Munaro */ -#ifndef PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_ -#define PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_ +#pragma once #include #include @@ -372,4 +371,3 @@ namespace pcl } /* namespace people */ } /* namespace pcl */ #include -#endif /* PCL_PEOPLE_GROUND_BASED_PEOPLE_DETECTION_APP_H_ */ diff --git a/people/include/pcl/people/head_based_subcluster.h b/people/include/pcl/people/head_based_subcluster.h index 0a60bbcfd72..cf838032ba2 100644 --- a/people/include/pcl/people/head_based_subcluster.h +++ b/people/include/pcl/people/head_based_subcluster.h @@ -38,8 +38,7 @@ * Author: Matteo Munaro */ -#ifndef PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_ -#define PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_ +#pragma once #include #include @@ -228,4 +227,3 @@ namespace pcl } /* namespace people */ } /* namespace pcl */ #include -#endif /* PCL_PEOPLE_HEAD_BASED_SUBCLUSTER_H_ */ diff --git a/people/include/pcl/people/height_map_2d.h b/people/include/pcl/people/height_map_2d.h index 4f8c1afef38..0b9b722d6ef 100644 --- a/people/include/pcl/people/height_map_2d.h +++ b/people/include/pcl/people/height_map_2d.h @@ -38,8 +38,7 @@ * Author: Matteo Munaro */ -#ifndef PCL_PEOPLE_HEIGHT_MAP_2D_H_ -#define PCL_PEOPLE_HEIGHT_MAP_2D_H_ +#pragma once #include #include @@ -206,4 +205,3 @@ namespace pcl } /* namespace people */ } /* namespace pcl */ #include -#endif /* PCL_PEOPLE_HEIGHT_MAP_2D_H_ */ diff --git a/people/include/pcl/people/hog.h b/people/include/pcl/people/hog.h index 98025517d4c..aba84e46433 100644 --- a/people/include/pcl/people/hog.h +++ b/people/include/pcl/people/hog.h @@ -38,8 +38,7 @@ * Non-SSE version of the code provided by Matteo Munaro, Stefano Ghidoni and Stefano Michieletto */ -#ifndef PCL_PEOPLE_HOG_H_ -#define PCL_PEOPLE_HOG_H_ +#pragma once #include @@ -186,4 +185,3 @@ namespace pcl }; } /* namespace people */ } /* namespace pcl */ -#endif /* PCL_PEOPLE_HOG_H_ */ diff --git a/people/include/pcl/people/person_classifier.h b/people/include/pcl/people/person_classifier.h index 910b46f98d1..e7359a78b95 100644 --- a/people/include/pcl/people/person_classifier.h +++ b/people/include/pcl/people/person_classifier.h @@ -38,8 +38,7 @@ * Author: Matteo Munaro */ -#ifndef PCL_PEOPLE_PERSON_CLASSIFIER_H_ -#define PCL_PEOPLE_PERSON_CLASSIFIER_H_ +#pragma once #include #include @@ -164,4 +163,3 @@ namespace pcl } /* namespace people */ } /* namespace pcl */ #include -#endif /* PCL_PEOPLE_PERSON_CLASSIFIER_H_ */ diff --git a/people/include/pcl/people/person_cluster.h b/people/include/pcl/people/person_cluster.h index 13d2cbf92e0..1987f2cc303 100644 --- a/people/include/pcl/people/person_cluster.h +++ b/people/include/pcl/people/person_cluster.h @@ -38,8 +38,7 @@ * Author: Matteo Munaro */ -#ifndef PCL_PEOPLE_PERSON_CLUSTER_H_ -#define PCL_PEOPLE_PERSON_CLUSTER_H_ +#pragma once #include #include @@ -328,4 +327,3 @@ namespace pcl } /* namespace people */ } /* namespace pcl */ #include -#endif /* PCL_PEOPLE_PERSON_CLUSTER_H_ */ diff --git a/recognition/include/pcl/recognition/boost.h b/recognition/include/pcl/recognition/boost.h index f3bb93d40c4..67d98ea15d7 100644 --- a/recognition/include/pcl/recognition/boost.h +++ b/recognition/include/pcl/recognition/boost.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_RECOGNITION_BOOST_H_ -#define PCL_RECOGNITION_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -47,5 +46,3 @@ #include #include //#include - -#endif // PCL_RECOGNITION_BOOST_H_ diff --git a/recognition/include/pcl/recognition/cg/correspondence_grouping.h b/recognition/include/pcl/recognition/cg/correspondence_grouping.h index e92a6f83fbf..bfc882aa0b8 100644 --- a/recognition/include/pcl/recognition/cg/correspondence_grouping.h +++ b/recognition/include/pcl/recognition/cg/correspondence_grouping.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_RECOGNITION_CORRESPONDENCE_GROUPING_H_ -#define PCL_RECOGNITION_CORRESPONDENCE_GROUPING_H_ +#pragma once #include #include @@ -198,5 +197,3 @@ namespace pcl } #include - -#endif // PCL_RECOGNITION_CORRESPONDENCE_GROUPING_H_ diff --git a/recognition/include/pcl/recognition/cg/geometric_consistency.h b/recognition/include/pcl/recognition/cg/geometric_consistency.h index 4be2d36802a..ff0cdabc68f 100644 --- a/recognition/include/pcl/recognition/cg/geometric_consistency.h +++ b/recognition/include/pcl/recognition/cg/geometric_consistency.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_H_ -#define PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_H_ +#pragma once #include #include @@ -154,5 +153,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_RECOGNITION_GEOMETRIC_CONSISTENCY_H_ diff --git a/recognition/include/pcl/recognition/cg/hough_3d.h b/recognition/include/pcl/recognition/cg/hough_3d.h index 1f5ff11b89e..47fdcc36110 100644 --- a/recognition/include/pcl/recognition/cg/hough_3d.h +++ b/recognition/include/pcl/recognition/cg/hough_3d.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_RECOGNITION_HOUGH_3D_H_ -#define PCL_RECOGNITION_HOUGH_3D_H_ +#pragma once #include #include @@ -514,5 +513,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_RECOGNITION_HOUGH_3D_H_ diff --git a/recognition/include/pcl/recognition/color_gradient_dot_modality.h b/recognition/include/pcl/recognition/color_gradient_dot_modality.h index a9a3ce753ce..4b6fb451e2e 100644 --- a/recognition/include/pcl/recognition/color_gradient_dot_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_dot_modality.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_COLOR_GRADIENT_DOT_MODALITY -#define PCL_FEATURES_COLOR_GRADIENT_DOT_MODALITY +#pragma once #include #include @@ -698,5 +697,3 @@ computeInvariantQuantizedMap (const MaskMap & mask, return map; } - -#endif diff --git a/recognition/include/pcl/recognition/color_gradient_modality.h b/recognition/include/pcl/recognition/color_gradient_modality.h index 566d4622168..110e82f06c0 100644 --- a/recognition/include/pcl/recognition/color_gradient_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_modality.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_COLOR_GRADIENT_MODALITY -#define PCL_RECOGNITION_COLOR_GRADIENT_MODALITY +#pragma once #include @@ -1120,5 +1119,3 @@ erode (const pcl::MaskMap & mask_in, } } } - -#endif diff --git a/recognition/include/pcl/recognition/color_modality.h b/recognition/include/pcl/recognition/color_modality.h index 9b704d8273a..07168e5c264 100644 --- a/recognition/include/pcl/recognition/color_modality.h +++ b/recognition/include/pcl/recognition/color_modality.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_COLOR_MODALITY -#define PCL_RECOGNITION_COLOR_MODALITY +#pragma once #include #include @@ -547,6 +546,3 @@ pcl::ColorModality::computeDistanceMap (const MaskMap & input, current_row -= width; } } - - -#endif diff --git a/recognition/include/pcl/recognition/dense_quantized_multi_mod_template.h b/recognition/include/pcl/recognition/dense_quantized_multi_mod_template.h index b9f4ac745b8..064621686b9 100644 --- a/recognition/include/pcl/recognition/dense_quantized_multi_mod_template.h +++ b/recognition/include/pcl/recognition/dense_quantized_multi_mod_template.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_DENSE_QUANTIZED_MULTI_MOD_TEMPLATE -#define PCL_FEATURES_DENSE_QUANTIZED_MULTI_MOD_TEMPLATE +#pragma once #include @@ -113,5 +112,3 @@ namespace pcl }; } - -#endif \ No newline at end of file diff --git a/recognition/include/pcl/recognition/distance_map.h b/recognition/include/pcl/recognition/distance_map.h index ac68e5b4ed8..cc411467ed9 100644 --- a/recognition/include/pcl/recognition/distance_map.h +++ b/recognition/include/pcl/recognition/distance_map.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_DISTANCE_MAP -#define PCL_RECOGNITION_DISTANCE_MAP +#pragma once namespace pcl { @@ -115,6 +114,3 @@ namespace pcl }; } - - -#endif diff --git a/recognition/include/pcl/recognition/dot_modality.h b/recognition/include/pcl/recognition/dot_modality.h index 0f66b922825..f07106e34f9 100644 --- a/recognition/include/pcl/recognition/dot_modality.h +++ b/recognition/include/pcl/recognition/dot_modality.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_DOT_MODALITY -#define PCL_FEATURES_DOT_MODALITY +#pragma once #include #include @@ -64,5 +63,3 @@ namespace pcl }; } - -#endif // PCL_FEATURES_DOT_MODALITY diff --git a/recognition/include/pcl/recognition/dotmod.h b/recognition/include/pcl/recognition/dotmod.h index 96a0be4860f..eb87ebdce31 100644 --- a/recognition/include/pcl/recognition/dotmod.h +++ b/recognition/include/pcl/recognition/dotmod.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_DOTMOD -#define PCL_RECOGNITION_DOTMOD +#pragma once #include #include @@ -127,5 +126,3 @@ namespace pcl }; } - -#endif diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h index 2729db06578..f282c70bdce 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h @@ -5,8 +5,7 @@ * Author: Aitor Aldoma */ -#ifndef PCL_RF_FACE_DETECTOR_TRAINER_H_ -#define PCL_RF_FACE_DETECTOR_TRAINER_H_ +#pragma once #include "pcl/recognition/face_detection/face_detector_data_provider.h" #include "pcl/recognition/face_detection/rf_face_utils.h" @@ -259,5 +258,3 @@ namespace pcl void detectFaces(); }; } - -#endif /* PCL_RF_FACE_DETECTOR_TRAINER_H_ */ diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_utils.h b/recognition/include/pcl/recognition/face_detection/rf_face_utils.h index 71104b98958..e4e9f870807 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_utils.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_utils.h @@ -5,8 +5,7 @@ * Author: Aitor Aldoma */ -#ifndef PCL_RF_FACE_UTILS_H_ -#define PCL_RF_FACE_UTILS_H_ +#pragma once #include "pcl/recognition/face_detection/face_common.h" #include @@ -536,5 +535,3 @@ namespace pcl }; } } - -#endif /* PCL_RF_FACE_UTILS_H_ */ diff --git a/recognition/include/pcl/recognition/hv/greedy_verification.h b/recognition/include/pcl/recognition/hv/greedy_verification.h index 03148bd23fe..4399a8c4e66 100644 --- a/recognition/include/pcl/recognition/hv/greedy_verification.h +++ b/recognition/include/pcl/recognition/hv/greedy_verification.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RECOGNITION_HV_GREEDY_H_ -#define PCL_RECOGNITION_HV_GREEDY_H_ +#pragma once #include #include @@ -180,5 +179,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* PCL_RECOGNITION_HV_GREEDY_H_ */ diff --git a/recognition/include/pcl/recognition/hv/hv_papazov.h b/recognition/include/pcl/recognition/hv/hv_papazov.h index 5d4db89f617..b6ea593c478 100644 --- a/recognition/include/pcl/recognition/hv/hv_papazov.h +++ b/recognition/include/pcl/recognition/hv/hv_papazov.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RECOGNITION_HV_PAPAZOV_H_ -#define PCL_RECOGNITION_HV_PAPAZOV_H_ +#pragma once #include #include @@ -119,5 +118,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* PCL_RECOGNITION_HV_PAPAZOV_H_ */ diff --git a/recognition/include/pcl/recognition/hv/hypotheses_verification.h b/recognition/include/pcl/recognition/hv/hypotheses_verification.h index bc8e20d3182..194dceb4540 100644 --- a/recognition/include/pcl/recognition/hv/hypotheses_verification.h +++ b/recognition/include/pcl/recognition/hv/hypotheses_verification.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_ -#define PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_ +#pragma once #include #include "pcl/recognition/hv/occlusion_reasoning.h" @@ -326,5 +325,3 @@ namespace pcl }; } - -#endif /* PCL_RECOGNITION_HYPOTHESIS_VERIFICATION_H_ */ diff --git a/recognition/include/pcl/recognition/hv/occlusion_reasoning.h b/recognition/include/pcl/recognition/hv/occlusion_reasoning.h index 09fbec485a7..858086cdd63 100644 --- a/recognition/include/pcl/recognition/hv/occlusion_reasoning.h +++ b/recognition/include/pcl/recognition/hv/occlusion_reasoning.h @@ -34,8 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_RECOGNITION_OCCLUSION_REASONING_H_ -#define PCL_RECOGNITION_OCCLUSION_REASONING_H_ +#pragma once #include #include @@ -214,5 +213,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* PCL_RECOGNITION_OCCLUSION_REASONING_H_ */ diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h index 845923c929c..dd9d379fbf8 100644 --- a/recognition/include/pcl/recognition/implicit_shape_model.h +++ b/recognition/include/pcl/recognition/implicit_shape_model.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_IMPLICIT_SHAPE_MODEL_H_ -#define PCL_IMPLICIT_SHAPE_MODEL_H_ +#pragma once #include #include @@ -625,5 +624,3 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ISMPeak, (float, density, ism_density) (float, class_id, ism_class_id) ) - -#endif //#ifndef PCL_IMPLICIT_SHAPE_MODEL_H_ diff --git a/recognition/include/pcl/recognition/linemod.h b/recognition/include/pcl/recognition/linemod.h index 54ffc28e7cf..021e9eca5e5 100644 --- a/recognition/include/pcl/recognition/linemod.h +++ b/recognition/include/pcl/recognition/linemod.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_LINEMOD -#define PCL_RECOGNITION_LINEMOD +#pragma once #include #include @@ -475,5 +474,3 @@ namespace pcl }; } - -#endif diff --git a/recognition/include/pcl/recognition/linemod/line_rgbd.h b/recognition/include/pcl/recognition/linemod/line_rgbd.h index c0d6dcecd3e..1ef8dbaff86 100644 --- a/recognition/include/pcl/recognition/linemod/line_rgbd.h +++ b/recognition/include/pcl/recognition/linemod/line_rgbd.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_LINEMOD_LINE_RGBD -#define PCL_RECOGNITION_LINEMOD_LINE_RGBD +#pragma once #include #include @@ -316,5 +315,3 @@ namespace pcl } #include - -#endif diff --git a/recognition/include/pcl/recognition/mask_map.h b/recognition/include/pcl/recognition/mask_map.h index 9f7571774e2..e8d0c40186a 100644 --- a/recognition/include/pcl/recognition/mask_map.h +++ b/recognition/include/pcl/recognition/mask_map.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_MASK_MAP -#define PCL_FEATURES_MASK_MAP +#pragma once #include #include @@ -118,5 +117,3 @@ namespace pcl }; } - -#endif diff --git a/recognition/include/pcl/recognition/point_types.h b/recognition/include/pcl/recognition/point_types.h index 869eca8b67c..5ebbbb7fb89 100644 --- a/recognition/include/pcl/recognition/point_types.h +++ b/recognition/include/pcl/recognition/point_types.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_POINT_TYPES -#define PCL_RECOGNITION_POINT_TYPES +#pragma once #include #include @@ -75,5 +74,3 @@ namespace pcl } } - -#endif diff --git a/recognition/include/pcl/recognition/quantizable_modality.h b/recognition/include/pcl/recognition/quantizable_modality.h index c7dcaee146b..61553fd0c70 100644 --- a/recognition/include/pcl/recognition/quantizable_modality.h +++ b/recognition/include/pcl/recognition/quantizable_modality.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_QUANTIZABLE_MODALITY -#define PCL_FEATURES_QUANTIZABLE_MODALITY +#pragma once #include #include @@ -88,5 +87,3 @@ namespace pcl std::vector & features) const = 0; }; } - -#endif diff --git a/recognition/include/pcl/recognition/quantized_map.h b/recognition/include/pcl/recognition/quantized_map.h index c61a44911d0..a4f2b921753 100644 --- a/recognition/include/pcl/recognition/quantized_map.h +++ b/recognition/include/pcl/recognition/quantized_map.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_QUANTIZED_MAP -#define PCL_FEATURES_QUANTIZED_MAP +#pragma once #include #include @@ -151,5 +150,3 @@ namespace pcl }; } - -#endif diff --git a/recognition/include/pcl/recognition/ransac_based/auxiliary.h b/recognition/include/pcl/recognition/ransac_based/auxiliary.h index 43a6c809ff1..9b16222fc11 100644 --- a/recognition/include/pcl/recognition/ransac_based/auxiliary.h +++ b/recognition/include/pcl/recognition/ransac_based/auxiliary.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_RANSAC_BASED_AUX_H_ -#define PCL_RECOGNITION_RANSAC_BASED_AUX_H_ +#pragma once #include #include @@ -463,5 +462,3 @@ namespace pcl } // namespace aux } // namespace recognition } // namespace pcl - -#endif // AUX_H_ diff --git a/recognition/include/pcl/recognition/ransac_based/bvh.h b/recognition/include/pcl/recognition/ransac_based/bvh.h index bf6e88903a2..084c0d5ee1d 100644 --- a/recognition/include/pcl/recognition/ransac_based/bvh.h +++ b/recognition/include/pcl/recognition/ransac_based/bvh.h @@ -43,8 +43,7 @@ * Author: papazov */ -#ifndef PCL_RECOGNITION_BVH_H_ -#define PCL_RECOGNITION_BVH_H_ +#pragma once #include #include @@ -312,5 +311,3 @@ namespace pcl }; } // namespace recognition } // namespace pcl - -#endif /* PCL_RECOGNITION_BVH_H_ */ diff --git a/recognition/include/pcl/recognition/ransac_based/hypothesis.h b/recognition/include/pcl/recognition/ransac_based/hypothesis.h index 4ac961add06..758557104f2 100644 --- a/recognition/include/pcl/recognition/ransac_based/hypothesis.h +++ b/recognition/include/pcl/recognition/ransac_based/hypothesis.h @@ -43,8 +43,7 @@ * Author: papazov */ -#ifndef PCL_RECOGNITION_HYPOTHESIS_H_ -#define PCL_RECOGNITION_HYPOTHESIS_H_ +#pragma once #include #include @@ -156,5 +155,3 @@ namespace pcl }; } // namespace recognition } // namespace pcl - -#endif /* PCL_RECOGNITION_HYPOTHESIS_H_ */ diff --git a/recognition/include/pcl/recognition/ransac_based/model_library.h b/recognition/include/pcl/recognition/ransac_based/model_library.h index c1dc136959d..221e262b69c 100644 --- a/recognition/include/pcl/recognition/ransac_based/model_library.h +++ b/recognition/include/pcl/recognition/ransac_based/model_library.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_RECOGNITION_MODEL_LIBRARY_H_ -#define PCL_RECOGNITION_MODEL_LIBRARY_H_ +#pragma once #include "auxiliary.h" #include @@ -270,5 +269,3 @@ namespace pcl }; } // namespace recognition } // namespace pcl - -#endif // PCL_RECOGNITION_MODEL_LIBRARY_H_ diff --git a/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h b/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h index fe1ed3896ce..651014bbfde 100644 --- a/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h +++ b/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_RECOGNITION_OBJ_REC_RANSAC_H_ -#define PCL_RECOGNITION_OBJ_REC_RANSAC_H_ +#pragma once #include #include @@ -480,5 +479,3 @@ namespace pcl }; } // namespace recognition } // namespace pcl - -#endif // PCL_RECOGNITION_OBJ_REC_RANSAC_H_ diff --git a/recognition/include/pcl/recognition/ransac_based/orr_graph.h b/recognition/include/pcl/recognition/ransac_based/orr_graph.h index 351d6adbae7..85b6121b840 100644 --- a/recognition/include/pcl/recognition/ransac_based/orr_graph.h +++ b/recognition/include/pcl/recognition/ransac_based/orr_graph.h @@ -43,8 +43,7 @@ * Author: papazov */ -#ifndef PCL_RECOGNITION_ORR_GRAPH_H_ -#define PCL_RECOGNITION_ORR_GRAPH_H_ +#pragma once #include @@ -221,5 +220,3 @@ namespace pcl }; } // namespace recognition } // namespace pcl - -#endif /* PCL_RECOGNITION_ORR_GRAPH_H_ */ diff --git a/recognition/include/pcl/recognition/ransac_based/orr_octree.h b/recognition/include/pcl/recognition/ransac_based/orr_octree.h index 8eaad540dec..bb9536935bb 100644 --- a/recognition/include/pcl/recognition/ransac_based/orr_octree.h +++ b/recognition/include/pcl/recognition/ransac_based/orr_octree.h @@ -43,8 +43,7 @@ * Author: papazov */ -#ifndef PCL_RECOGNITION_ORR_OCTREE_H_ -#define PCL_RECOGNITION_ORR_OCTREE_H_ +#pragma once #include "auxiliary.h" #include @@ -488,5 +487,3 @@ namespace pcl }; } // namespace recognition } // namespace pcl - -#endif /* PCL_RECOGNITION_ORR_OCTREE_H_ */ diff --git a/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h b/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h index 86574b0185d..eb8211d483d 100644 --- a/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h +++ b/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h @@ -43,8 +43,7 @@ * Author: papazov */ -#ifndef PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ -#define PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ +#pragma once #include "simple_octree.h" #include "model_library.h" @@ -410,5 +409,3 @@ namespace pcl }; // class RigidTransformSpace } // namespace recognition } // namespace pcl - -#endif /* PCL_RECOGNITION_RIGID_TRANSFORM_SPACE_H_ */ diff --git a/recognition/include/pcl/recognition/ransac_based/voxel_structure.h b/recognition/include/pcl/recognition/ransac_based/voxel_structure.h index b3819031b66..0aaac6102de 100644 --- a/recognition/include/pcl/recognition/ransac_based/voxel_structure.h +++ b/recognition/include/pcl/recognition/ransac_based/voxel_structure.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_RECOGNITION_VOXEL_STRUCTURE_H_ -#define PCL_RECOGNITION_VOXEL_STRUCTURE_H_ +#pragma once #include @@ -167,5 +166,3 @@ namespace pcl } // namespace pcl #include - -#endif // PCL_RECOGNITION_VOXEL_STRUCTURE_H_ diff --git a/recognition/include/pcl/recognition/region_xy.h b/recognition/include/pcl/recognition/region_xy.h index 8576d1cc583..78d413cdeb0 100644 --- a/recognition/include/pcl/recognition/region_xy.h +++ b/recognition/include/pcl/recognition/region_xy.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_REGION_XY_ -#define PCL_FEATURES_REGION_XY_ +#pragma once #include @@ -117,5 +116,3 @@ namespace pcl }; } - -#endif // PCL_FEATURES_REGION_XY_ diff --git a/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h b/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h index 3f68d87af2f..d9ea979517c 100644 --- a/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h +++ b/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_FEATURES_SPARSE_QUANTIZED_MULTI_MOD_TEMPLATE -#define PCL_FEATURES_SPARSE_QUANTIZED_MULTI_MOD_TEMPLATE +#pragma once #include @@ -152,5 +151,3 @@ namespace pcl }; } - -#endif diff --git a/recognition/include/pcl/recognition/surface_normal_modality.h b/recognition/include/pcl/recognition/surface_normal_modality.h index 4e4f876ff62..72c334a5b68 100644 --- a/recognition/include/pcl/recognition/surface_normal_modality.h +++ b/recognition/include/pcl/recognition/surface_normal_modality.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_RECOGNITION_SURFACE_NORMAL_MODALITY -#define PCL_RECOGNITION_SURFACE_NORMAL_MODALITY +#pragma once #include #include @@ -1639,6 +1638,3 @@ pcl::SurfaceNormalModality::computeDistanceMap (const MaskMap & input, current_row -= width; } } - - -#endif diff --git a/registration/include/pcl/registration/bfgs.h b/registration/include/pcl/registration/bfgs.h index 42cfd2ae189..16b3173ce8a 100644 --- a/registration/include/pcl/registration/bfgs.h +++ b/registration/include/pcl/registration/bfgs.h @@ -1,5 +1,4 @@ -#ifndef PCL_FOR_EIGEN_BFGS_H -#define PCL_FOR_EIGEN_BFGS_H +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -614,5 +613,3 @@ BFGS::lineSearch(Scalar rho, Scalar sigma, } return BFGSSpace::Success; } -#endif // PCL_FOR_EIGEN_BFGS_H - diff --git a/registration/include/pcl/registration/boost.h b/registration/include/pcl/registration/boost.h index e5ae80f1d27..7a9214e89c7 100644 --- a/registration/include/pcl/registration/boost.h +++ b/registration/include/pcl/registration/boost.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGISTRATION_BOOST_H_ -#define PCL_REGISTRATION_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -54,5 +53,3 @@ #include #include #include - -#endif // PCL_REGISTRATION_BOOST_H_ diff --git a/registration/include/pcl/registration/boost_graph.h b/registration/include/pcl/registration/boost_graph.h index 0948d930944..4098837bffa 100644 --- a/registration/include/pcl/registration/boost_graph.h +++ b/registration/include/pcl/registration/boost_graph.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGISTRATION_BOOST_GRAPH_H_ -#define PCL_REGISTRATION_BOOST_GRAPH_H_ +#pragma once #include #include @@ -99,5 +98,3 @@ namespace boost }; } } - -#endif // PCL_REGISTRATION_BOOST_GRAPH_H_ diff --git a/registration/include/pcl/registration/convergence_criteria.h b/registration/include/pcl/registration/convergence_criteria.h index 0e51b9fb02a..4cf8f9da344 100644 --- a/registration/include/pcl/registration/convergence_criteria.h +++ b/registration/include/pcl/registration/convergence_criteria.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGISTRATION_CONVERGENCE_CRIERIA_H_ -#define PCL_REGISTRATION_CONVERGENCE_CRIERIA_H_ +#pragma once #include @@ -85,6 +84,3 @@ namespace pcl }; } } - -#endif // PCL_REGISTRATION_CONVERGENCE_CRIERIA_H_ - diff --git a/registration/include/pcl/registration/correspondence_estimation.h b/registration/include/pcl/registration/correspondence_estimation.h index fa8b487b4bf..ed25aa4e6a6 100644 --- a/registration/include/pcl/registration/correspondence_estimation.h +++ b/registration/include/pcl/registration/correspondence_estimation.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_H_ +#pragma once #include @@ -436,5 +435,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_H_ */ diff --git a/registration/include/pcl/registration/correspondence_estimation_backprojection.h b/registration/include/pcl/registration/correspondence_estimation_backprojection.h index ccce9f2b5f1..0a5da9213ca 100644 --- a/registration/include/pcl/registration/correspondence_estimation_backprojection.h +++ b/registration/include/pcl/registration/correspondence_estimation_backprojection.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_ +#pragma once #include #include @@ -224,5 +223,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_BACK_PROJECTION_H_ */ diff --git a/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h b/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h index 7dbc82f9b41..8863b5996d2 100644 --- a/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h +++ b/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ +#pragma once #include #include @@ -217,5 +216,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ */ diff --git a/registration/include/pcl/registration/correspondence_estimation_organized_projection.h b/registration/include/pcl/registration/correspondence_estimation_organized_projection.h index a6ba9fdd21a..9bf5a5d03be 100644 --- a/registration/include/pcl/registration/correspondence_estimation_organized_projection.h +++ b/registration/include/pcl/registration/correspondence_estimation_organized_projection.h @@ -37,9 +37,7 @@ * */ - -#ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_H_ +#pragma once #include @@ -206,5 +204,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_ORGANIZED_PROJECTION_H_ */ diff --git a/registration/include/pcl/registration/correspondence_rejection.h b/registration/include/pcl/registration/correspondence_rejection.h index 9094e4e861c..b2638cfe790 100644 --- a/registration/include/pcl/registration/correspondence_rejection.h +++ b/registration/include/pcl/registration/correspondence_rejection.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_ +#pragma once #include #include @@ -404,6 +403,3 @@ namespace pcl }; } } - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_H_ */ - diff --git a/registration/include/pcl/registration/correspondence_rejection_distance.h b/registration/include/pcl/registration/correspondence_rejection_distance.h index cbbe5f484f9..01a1cc12768 100644 --- a/registration/include/pcl/registration/correspondence_rejection_distance.h +++ b/registration/include/pcl/registration/correspondence_rejection_distance.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_DISTANCE_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_DISTANCE_H_ + +#pragma once #include @@ -206,5 +206,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_DISTANCE_H_ */ diff --git a/registration/include/pcl/registration/correspondence_rejection_features.h b/registration/include/pcl/registration/correspondence_rejection_features.h index e69a6dbd3fd..6c2c1941671 100644 --- a/registration/include/pcl/registration/correspondence_rejection_features.h +++ b/registration/include/pcl/registration/correspondence_rejection_features.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_FEATURES_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_FEATURES_H_ + +#pragma once #include #include @@ -299,5 +299,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_FEATURES_H_ */ diff --git a/registration/include/pcl/registration/correspondence_rejection_median_distance.h b/registration/include/pcl/registration/correspondence_rejection_median_distance.h index 71655f912b6..0954aca4fb2 100644 --- a/registration/include/pcl/registration/correspondence_rejection_median_distance.h +++ b/registration/include/pcl/registration/correspondence_rejection_median_distance.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_H_ + +#pragma once #include #include @@ -209,5 +209,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_H_ diff --git a/registration/include/pcl/registration/correspondence_rejection_one_to_one.h b/registration/include/pcl/registration/correspondence_rejection_one_to_one.h index 5e08e1531c4..1e9da236d00 100644 --- a/registration/include/pcl/registration/correspondence_rejection_one_to_one.h +++ b/registration/include/pcl/registration/correspondence_rejection_one_to_one.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ONE_TO_ONE_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ONE_TO_ONE_H_ + +#pragma once #include @@ -94,5 +94,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ONE_TO_ONE_H_ diff --git a/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h b/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h index 4ceec18552d..0f30cc7f390 100644 --- a/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h +++ b/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h @@ -36,8 +36,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_H_ +#pragma once #include @@ -144,6 +143,3 @@ namespace pcl } #include - - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_H_ */ diff --git a/registration/include/pcl/registration/correspondence_rejection_poly.h b/registration/include/pcl/registration/correspondence_rejection_poly.h index 4be18370e1a..eebc84fa6fe 100644 --- a/registration/include/pcl/registration/correspondence_rejection_poly.h +++ b/registration/include/pcl/registration/correspondence_rejection_poly.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_ + +#pragma once #include #include @@ -381,5 +381,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_POLY_H_ diff --git a/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h b/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h index fe9bb0ba727..12d3b5bfe86 100644 --- a/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h +++ b/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_ + +#pragma once #include @@ -245,5 +245,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_ diff --git a/registration/include/pcl/registration/correspondence_rejection_sample_consensus_2d.h b/registration/include/pcl/registration/correspondence_rejection_sample_consensus_2d.h index cfbd9fa0ca4..ba1cea1f541 100644 --- a/registration/include/pcl/registration/correspondence_rejection_sample_consensus_2d.h +++ b/registration/include/pcl/registration/correspondence_rejection_sample_consensus_2d.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_H_ +#pragma once #include @@ -160,6 +159,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_2D_H_ - diff --git a/registration/include/pcl/registration/correspondence_rejection_surface_normal.h b/registration/include/pcl/registration/correspondence_rejection_surface_normal.h index 9eda90b7c7b..032816cc42b 100644 --- a/registration/include/pcl/registration/correspondence_rejection_surface_normal.h +++ b/registration/include/pcl/registration/correspondence_rejection_surface_normal.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_H_ + +#pragma once #include #include @@ -321,5 +321,3 @@ namespace pcl } #include - -#endif diff --git a/registration/include/pcl/registration/correspondence_rejection_trimmed.h b/registration/include/pcl/registration/correspondence_rejection_trimmed.h index d92c66f065f..70a2aca2d7a 100644 --- a/registration/include/pcl/registration/correspondence_rejection_trimmed.h +++ b/registration/include/pcl/registration/correspondence_rejection_trimmed.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_TRIMMED_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_TRIMMED_H_ + +#pragma once #include @@ -137,5 +137,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_TRIMMED_H_ diff --git a/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h b/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h index 5a92a66739b..6df0d705705 100644 --- a/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h +++ b/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_VAR_TRIMMED_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_VAR_TRIMMED_H_ + +#pragma once #include #include @@ -251,5 +251,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_VAR_TRIMMED_H_ diff --git a/registration/include/pcl/registration/correspondence_sorting.h b/registration/include/pcl/registration/correspondence_sorting.h index 83eb64e07f8..e9c6f8596a3 100644 --- a/registration/include/pcl/registration/correspondence_sorting.h +++ b/registration/include/pcl/registration/correspondence_sorting.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_SORTING_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_SORTING_H_ + +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -140,5 +140,3 @@ namespace pcl } } - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_SORTING_H_ */ diff --git a/registration/include/pcl/registration/correspondence_types.h b/registration/include/pcl/registration/correspondence_types.h index 57649923a04..7a3ad204bee 100644 --- a/registration/include/pcl/registration/correspondence_types.h +++ b/registration/include/pcl/registration/correspondence_types.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_CORRESPONDENCE_TYPES_H_ -#define PCL_REGISTRATION_CORRESPONDENCE_TYPES_H_ + +#pragma once #include @@ -75,5 +75,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_CORRESPONDENCE_TYPES_H_ */ diff --git a/registration/include/pcl/registration/default_convergence_criteria.h b/registration/include/pcl/registration/default_convergence_criteria.h index 32f623e83e4..606fd5208f6 100644 --- a/registration/include/pcl/registration/default_convergence_criteria.h +++ b/registration/include/pcl/registration/default_convergence_criteria.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_H_ -#define PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_H_ +#pragma once #include #include @@ -276,6 +275,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_DEFAULT_CONVERGENCE_CRITERIA_H_ - diff --git a/registration/include/pcl/registration/distances.h b/registration/include/pcl/registration/distances.h index a6886a80c59..3fd6cdbd259 100644 --- a/registration/include/pcl/registration/distances.h +++ b/registration/include/pcl/registration/distances.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_DISTANCES_H -#define PCL_REGISTRATION_DISTANCES_H + +#pragma once #include #include @@ -141,5 +141,3 @@ namespace pcl } } } - -#endif diff --git a/registration/include/pcl/registration/edge_measurements.h b/registration/include/pcl/registration/edge_measurements.h index 5499bdef426..148872f5ec4 100644 --- a/registration/include/pcl/registration/edge_measurements.h +++ b/registration/include/pcl/registration/edge_measurements.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_EDGE_MEASUREMENTS_H_ -#define PCL_EDGE_MEASUREMENTS_H_ +#pragma once namespace pcl { @@ -69,5 +68,3 @@ namespace pcl }; } } - -#endif // PCL_EDGE_MEASUREMENTS_H_ diff --git a/registration/include/pcl/registration/eigen.h b/registration/include/pcl/registration/eigen.h index fdfa07aff11..3f1c831ca7b 100644 --- a/registration/include/pcl/registration/eigen.h +++ b/registration/include/pcl/registration/eigen.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGISTRATION_EIGEN_H_ -#define PCL_REGISTRATION_EIGEN_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -48,5 +47,3 @@ #include #include #include - -#endif // PCL_REGISTRATION_EIGEN_H_ diff --git a/registration/include/pcl/registration/elch.h b/registration/include/pcl/registration/elch.h index aa45b3ea701..6c7ffd6ec68 100644 --- a/registration/include/pcl/registration/elch.h +++ b/registration/include/pcl/registration/elch.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_ELCH_H_ -#define PCL_ELCH_H_ +#pragma once #include #include @@ -255,5 +254,3 @@ namespace pcl } #include - -#endif // PCL_ELCH_H_ diff --git a/registration/include/pcl/registration/exceptions.h b/registration/include/pcl/registration/exceptions.h index 875d441758c..327202edd8e 100644 --- a/registration/include/pcl/registration/exceptions.h +++ b/registration/include/pcl/registration/exceptions.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_EXCEPTIONS_H_ -#define PCL_REGISTRATION_EXCEPTIONS_H_ + +#pragma once #include @@ -73,4 +73,3 @@ namespace pcl : pcl::PCLException (error_description, file_name, function_name, line_number) { } } ; } -#endif//PCL_REGISTRATION_EXCEPTIONS_H_ diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 3f1c064382c..cf2453d6a9e 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GICP_H_ -#define PCL_GICP_H_ +#pragma once #include #include @@ -364,5 +363,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_GICP_H_ diff --git a/registration/include/pcl/registration/gicp6d.h b/registration/include/pcl/registration/gicp6d.h index 6f0bd3b6a00..16caa435451 100644 --- a/registration/include/pcl/registration/gicp6d.h +++ b/registration/include/pcl/registration/gicp6d.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_GICP6D_H_ -#define PCL_GICP6D_H_ +#pragma once #include #include @@ -206,5 +205,3 @@ namespace pcl MyPointRepresentation point_rep_; }; } - -#endif //#ifndef PCL_GICP6D_H_ diff --git a/registration/include/pcl/registration/graph_handler.h b/registration/include/pcl/registration/graph_handler.h index 814bb09a598..476f3725e01 100644 --- a/registration/include/pcl/registration/graph_handler.h +++ b/registration/include/pcl/registration/graph_handler.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GRAPH_HANDLER_H_ -#define PCL_GRAPH_HANDLER_H_ +#pragma once #include #include @@ -212,5 +211,3 @@ namespace pcl }; } } - -#endif // PCL_GRAPH_HANDLER_H_ diff --git a/registration/include/pcl/registration/graph_optimizer.h b/registration/include/pcl/registration/graph_optimizer.h index 73f867d68a4..eee576d2cf9 100644 --- a/registration/include/pcl/registration/graph_optimizer.h +++ b/registration/include/pcl/registration/graph_optimizer.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GRAPH_OPTIMIZER_H_ -#define PCL_GRAPH_OPTIMIZER_H_ +#pragma once #include @@ -67,5 +66,3 @@ namespace pcl }; } } - -#endif // PCL_GRAPH_OPTIMIZER_H_ diff --git a/registration/include/pcl/registration/graph_registration.h b/registration/include/pcl/registration/graph_registration.h index 7e98c785307..ff944d09077 100644 --- a/registration/include/pcl/registration/graph_registration.h +++ b/registration/include/pcl/registration/graph_registration.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_GRAPH_REGISTRATION_H_ -#define PCL_GRAPH_REGISTRATION_H_ +#pragma once #include #include @@ -123,5 +122,3 @@ namespace pcl computeRegistration () = 0; }; } - -#endif // PCL_GRAPH_REGISTRATION_H_ diff --git a/registration/include/pcl/registration/ia_fpcs.h b/registration/include/pcl/registration/ia_fpcs.h index 6691f24627d..4bdc73268bd 100644 --- a/registration/include/pcl/registration/ia_fpcs.h +++ b/registration/include/pcl/registration/ia_fpcs.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_REGISTRATION_IA_FPCS_H_ -#define PCL_REGISTRATION_IA_FPCS_H_ +#pragma once #include #include @@ -566,5 +565,3 @@ namespace pcl }; // namespace pcl #include - -#endif // PCL_REGISTRATION_IA_FPCS_H_ diff --git a/registration/include/pcl/registration/ia_kfpcs.h b/registration/include/pcl/registration/ia_kfpcs.h index 5b57f17153a..3a09d1dbe53 100644 --- a/registration/include/pcl/registration/ia_kfpcs.h +++ b/registration/include/pcl/registration/ia_kfpcs.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_REGISTRATION_IA_KFPCS_H_ -#define PCL_REGISTRATION_IA_KFPCS_H_ +#pragma once #include @@ -258,5 +257,3 @@ namespace pcl }; // namespace pcl #include - -#endif // PCL_REGISTRATION_IA_KFPCS_H_ diff --git a/registration/include/pcl/registration/icp.h b/registration/include/pcl/registration/icp.h index 536fd5a6e60..72899c312b0 100644 --- a/registration/include/pcl/registration/icp.h +++ b/registration/include/pcl/registration/icp.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_ICP_H_ -#define PCL_ICP_H_ +#pragma once // PCL includes #include @@ -335,5 +334,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_ICP_H_ diff --git a/registration/include/pcl/registration/icp_nl.h b/registration/include/pcl/registration/icp_nl.h index 30b21e374e4..cd80d7c8685 100644 --- a/registration/include/pcl/registration/icp_nl.h +++ b/registration/include/pcl/registration/icp_nl.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_ICP_NL_H_ -#define PCL_ICP_NL_H_ +#pragma once // PCL includes #include @@ -89,5 +88,3 @@ namespace pcl } }; } - -#endif //#ifndef PCL_ICP_NL_H_ diff --git a/registration/include/pcl/registration/incremental_registration.h b/registration/include/pcl/registration/incremental_registration.h index 6e6c9da83b8..fa5cce46d20 100644 --- a/registration/include/pcl/registration/incremental_registration.h +++ b/registration/include/pcl/registration/incremental_registration.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_REGISTRATION_INCREMENTAL_REGISTRATION_H_ -#define PCL_REGISTRATION_INCREMENTAL_REGISTRATION_H_ +#pragma once #include #include @@ -126,5 +125,3 @@ namespace pcl { } #include - -#endif /*PCL_REGISTRATION_INCREMENTAL_REGISTRATION_H_*/ diff --git a/registration/include/pcl/registration/joint_icp.h b/registration/include/pcl/registration/joint_icp.h index d51d76b551e..85231e3a7f4 100644 --- a/registration/include/pcl/registration/joint_icp.h +++ b/registration/include/pcl/registration/joint_icp.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_JOINT_ICP_H_ -#define PCL_JOINT_ICP_H_ +#pragma once // PCL includes #include @@ -227,7 +226,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_JOINT_ICP_H_ - - diff --git a/registration/include/pcl/registration/lum.h b/registration/include/pcl/registration/lum.h index 6b488074c8f..b11330ee3b0 100644 --- a/registration/include/pcl/registration/lum.h +++ b/registration/include/pcl/registration/lum.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTRATION_LUM_H_ -#define PCL_REGISTRATION_LUM_H_ +#pragma once #include #include @@ -342,6 +341,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_REGISTRATION_LUM_H_ - diff --git a/registration/include/pcl/registration/matching_candidate.h b/registration/include/pcl/registration/matching_candidate.h index 8389540a038..0dccb3e03e4 100644 --- a/registration/include/pcl/registration/matching_candidate.h +++ b/registration/include/pcl/registration/matching_candidate.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_REGISTRATION_MATCHING_CANDIDATE_H_ -#define PCL_REGISTRATION_MATCHING_CANDIDATE_H_ +#pragma once #include #include @@ -99,6 +98,3 @@ namespace pcl }; // namespace registration }; // namespace pcl - - -#endif // PCL_REGISTRATION_MATCHING_CANDIDATE_H_ diff --git a/registration/include/pcl/registration/meta_registration.h b/registration/include/pcl/registration/meta_registration.h index 6d51c649085..925ba786753 100644 --- a/registration/include/pcl/registration/meta_registration.h +++ b/registration/include/pcl/registration/meta_registration.h @@ -35,8 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_REGISTRATION_META_REGISTRATION_H_ -#define PCL_REGISTRATION_META_REGISTRATION_H_ +#pragma once #include #include @@ -127,5 +126,3 @@ namespace pcl { } #include - -#endif /*PCL_REGISTRATION_META_REGISTRATION_H_*/ diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h index 3c9fa05c3df..0a62b48cf1a 100644 --- a/registration/include/pcl/registration/ndt.h +++ b/registration/include/pcl/registration/ndt.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTRATION_NDT_H_ -#define PCL_REGISTRATION_NDT_H_ +#pragma once #include #include @@ -466,5 +465,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_NDT_H_ diff --git a/registration/include/pcl/registration/ndt_2d.h b/registration/include/pcl/registration/ndt_2d.h index a0643b78150..5e369b45e02 100644 --- a/registration/include/pcl/registration/ndt_2d.h +++ b/registration/include/pcl/registration/ndt_2d.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_NDT_2D_H_ -#define PCL_NDT_2D_H_ +#pragma once #include @@ -153,6 +152,3 @@ namespace pcl } // namespace pcl #include - -#endif // ndef PCL_NDT_2D_H_ - diff --git a/registration/include/pcl/registration/pairwise_graph_registration.h b/registration/include/pcl/registration/pairwise_graph_registration.h index cf83619883c..3cfc5596fba 100644 --- a/registration/include/pcl/registration/pairwise_graph_registration.h +++ b/registration/include/pcl/registration/pairwise_graph_registration.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_PAIRWISE_GRAPH_REGISTRATION_H_ -#define PCL_PAIRWISE_GRAPH_REGISTRATION_H_ +#pragma once #include #include @@ -114,5 +113,3 @@ namespace pcl } #include - -#endif // PCL_PAIRWISE_GRAPH_REGISTRATION_H_ diff --git a/registration/include/pcl/registration/ppf_registration.h b/registration/include/pcl/registration/ppf_registration.h index 2560ec6fd63..9966cc01f6b 100644 --- a/registration/include/pcl/registration/ppf_registration.h +++ b/registration/include/pcl/registration/ppf_registration.h @@ -38,9 +38,7 @@ * */ - -#ifndef PCL_PPF_REGISTRATION_H_ -#define PCL_PPF_REGISTRATION_H_ +#pragma once #include #include @@ -287,5 +285,3 @@ namespace pcl } #include - -#endif // PCL_PPF_REGISTRATION_H_ diff --git a/registration/include/pcl/registration/pyramid_feature_matching.h b/registration/include/pcl/registration/pyramid_feature_matching.h index dda7e14e4e0..30c0ce9283b 100644 --- a/registration/include/pcl/registration/pyramid_feature_matching.h +++ b/registration/include/pcl/registration/pyramid_feature_matching.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_PYRAMID_FEATURE_MATCHING_H_ -#define PCL_PYRAMID_FEATURE_MATCHING_H_ +#pragma once #include #include @@ -198,5 +197,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_PYRAMID_FEATURE_MATCHING_H_ diff --git a/registration/include/pcl/registration/registration.h b/registration/include/pcl/registration/registration.h index d291d73ee22..907860583ac 100644 --- a/registration/include/pcl/registration/registration.h +++ b/registration/include/pcl/registration/registration.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTRATION_H_ -#define PCL_REGISTRATION_H_ +#pragma once // PCL includes #include @@ -610,5 +609,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_REGISTRATION_H_ diff --git a/registration/include/pcl/registration/sample_consensus_prerejective.h b/registration/include/pcl/registration/sample_consensus_prerejective.h index 8ef2ada3f0e..16083124431 100644 --- a/registration/include/pcl/registration/sample_consensus_prerejective.h +++ b/registration/include/pcl/registration/sample_consensus_prerejective.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_REGISTRATION_SAMPLE_CONSENSUS_PREREJECTIVE_H_ -#define PCL_REGISTRATION_SAMPLE_CONSENSUS_PREREJECTIVE_H_ +#pragma once #include #include @@ -316,5 +315,3 @@ namespace pcl } #include - -#endif diff --git a/registration/include/pcl/registration/transformation_estimation.h b/registration/include/pcl/registration/transformation_estimation.h index 55e390c235e..2c07eeefa39 100644 --- a/registration/include/pcl/registration/transformation_estimation.h +++ b/registration/include/pcl/registration/transformation_estimation.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_H_ + +#pragma once #include #include @@ -125,5 +125,3 @@ namespace pcl }; } } - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_H_ */ diff --git a/registration/include/pcl/registration/transformation_estimation_2D.h b/registration/include/pcl/registration/transformation_estimation_2D.h index 4bdd96fbd96..a597e789cd1 100644 --- a/registration/include/pcl/registration/transformation_estimation_2D.h +++ b/registration/include/pcl/registration/transformation_estimation_2D.h @@ -35,8 +35,8 @@ * * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_H_ + +#pragma once #include @@ -151,5 +151,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_2D_H_ */ diff --git a/registration/include/pcl/registration/transformation_estimation_3point.h b/registration/include/pcl/registration/transformation_estimation_3point.h index 43226fb762c..8cf88094e19 100644 --- a/registration/include/pcl/registration/transformation_estimation_3point.h +++ b/registration/include/pcl/registration/transformation_estimation_3point.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_3POINT_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_3POINT_H_ + +#pragma once #include @@ -141,5 +141,3 @@ namespace pcl }; // namespace registration #include - -#endif // PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_3POINT_H_ diff --git a/registration/include/pcl/registration/transformation_estimation_dq.h b/registration/include/pcl/registration/transformation_estimation_dq.h index 27bad867cc9..c4c5423f939 100644 --- a/registration/include/pcl/registration/transformation_estimation_dq.h +++ b/registration/include/pcl/registration/transformation_estimation_dq.h @@ -36,8 +36,8 @@ * * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ + +#pragma once #include #include @@ -138,5 +138,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ */ diff --git a/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h b/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h index 6d49aaf212c..d0b03922c67 100644 --- a/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h +++ b/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h @@ -36,8 +36,8 @@ * * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ + +#pragma once #include #include @@ -138,5 +138,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_DQ_H_ */ diff --git a/registration/include/pcl/registration/transformation_estimation_lm.h b/registration/include/pcl/registration/transformation_estimation_lm.h index 601b3fc5b21..cd18d98528c 100644 --- a/registration/include/pcl/registration/transformation_estimation_lm.h +++ b/registration/include/pcl/registration/transformation_estimation_lm.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_ + +#pragma once #include #include @@ -351,6 +351,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_H_ */ - diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane.h index 9b6c00dad65..50559b9c09b 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_ + +#pragma once #include #include @@ -96,6 +96,3 @@ namespace pcl }; } } - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_ */ - diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h index 6b10cde6a80..1f49401db8d 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_H_ + +#pragma once #include #include @@ -154,5 +154,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_H_LLS_ */ diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h index 6af60f0d31a..1f113571abb 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_H_ + +#pragma once #include #include @@ -165,5 +165,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_LLS_WEIGHTED_H_ */ diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h index 42931cb03c2..98e15ef7fda 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h @@ -36,9 +36,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ - -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_H_ +#pragma once #include #include @@ -336,6 +334,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_POINT_TO_PLANE_WEIGHTED_H_ */ - diff --git a/registration/include/pcl/registration/transformation_estimation_svd.h b/registration/include/pcl/registration/transformation_estimation_svd.h index ba082c14c16..6ecb19ac8d6 100644 --- a/registration/include/pcl/registration/transformation_estimation_svd.h +++ b/registration/include/pcl/registration/transformation_estimation_svd.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_H_ + +#pragma once #include #include @@ -157,5 +157,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_H_ */ diff --git a/registration/include/pcl/registration/transformation_estimation_svd_scale.h b/registration/include/pcl/registration/transformation_estimation_svd_scale.h index 045c830ea9a..e59a1fb1a8e 100644 --- a/registration/include/pcl/registration/transformation_estimation_svd_scale.h +++ b/registration/include/pcl/registration/transformation_estimation_svd_scale.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_H_ -#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_H_ + +#pragma once #include @@ -88,5 +88,3 @@ namespace pcl } #include - -#endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_SCALE_H_ */ diff --git a/registration/include/pcl/registration/transformation_validation.h b/registration/include/pcl/registration/transformation_validation.h index 41f5628d1db..9d93b42db13 100644 --- a/registration/include/pcl/registration/transformation_validation.h +++ b/registration/include/pcl/registration/transformation_validation.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_VALIDATION_H_ -#define PCL_REGISTRATION_TRANSFORMATION_VALIDATION_H_ + +#pragma once #include #include @@ -127,5 +127,3 @@ namespace pcl }; } } - -#endif // PCL_REGISTRATION_TRANSFORMATION_VALIDATION_H_ diff --git a/registration/include/pcl/registration/transformation_validation_euclidean.h b/registration/include/pcl/registration/transformation_validation_euclidean.h index ce2d37467fb..21b466e8b12 100644 --- a/registration/include/pcl/registration/transformation_validation_euclidean.h +++ b/registration/include/pcl/registration/transformation_validation_euclidean.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_H_ -#define PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_H_ + +#pragma once #include #include @@ -265,6 +265,3 @@ namespace pcl } #include - -#endif // PCL_REGISTRATION_TRANSFORMATION_VALIDATION_EUCLIDEAN_H_ - diff --git a/registration/include/pcl/registration/transforms.h b/registration/include/pcl/registration/transforms.h index 3937c832384..3101974d530 100644 --- a/registration/include/pcl/registration/transforms.h +++ b/registration/include/pcl/registration/transforms.h @@ -37,9 +37,7 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_TRANSFORMS_H_ -#define PCL_REGISTRATION_TRANSFORMS_H_ -#include +#pragma once -#endif // PCL_REGISTRATION_TRANSFORMS_H_ +#include diff --git a/registration/include/pcl/registration/vertex_estimates.h b/registration/include/pcl/registration/vertex_estimates.h index 40812e69157..71603533e3b 100644 --- a/registration/include/pcl/registration/vertex_estimates.h +++ b/registration/include/pcl/registration/vertex_estimates.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_VERTEX_ESTIMATES_H_ -#define PCL_VERTEX_ESTIMATES_H_ +#pragma once #include @@ -70,5 +69,3 @@ namespace pcl }; } } - -#endif // PCL_VERTEX_ESTIMATES_H_ diff --git a/registration/include/pcl/registration/warp_point_rigid.h b/registration/include/pcl/registration/warp_point_rigid.h index efdcfa79b19..4ad391d0fd3 100644 --- a/registration/include/pcl/registration/warp_point_rigid.h +++ b/registration/include/pcl/registration/warp_point_rigid.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_WARP_POINT_RIGID_H_ -#define PCL_WARP_POINT_RIGID_H_ +#pragma once #include @@ -129,5 +128,3 @@ namespace pcl }; } // namespace registration } // namespace pcl - -#endif diff --git a/registration/include/pcl/registration/warp_point_rigid_3d.h b/registration/include/pcl/registration/warp_point_rigid_3d.h index 0a0731f1346..094e073edb0 100644 --- a/registration/include/pcl/registration/warp_point_rigid_3d.h +++ b/registration/include/pcl/registration/warp_point_rigid_3d.h @@ -38,9 +38,7 @@ * */ - -#ifndef PCL_WARP_POINT_RIGID_3D_H_ -#define PCL_WARP_POINT_RIGID_3D_H_ +#pragma once #include #include @@ -95,6 +93,3 @@ namespace pcl }; } } - -#endif - diff --git a/registration/include/pcl/registration/warp_point_rigid_6d.h b/registration/include/pcl/registration/warp_point_rigid_6d.h index 84b1c0dbf9e..9e23f3b95fb 100644 --- a/registration/include/pcl/registration/warp_point_rigid_6d.h +++ b/registration/include/pcl/registration/warp_point_rigid_6d.h @@ -38,9 +38,7 @@ * */ - -#ifndef PCL_WARP_POINT_RIGID_6D_H_ -#define PCL_WARP_POINT_RIGID_6D_H_ +#pragma once #include @@ -97,6 +95,3 @@ namespace pcl }; } } - -#endif - diff --git a/sample_consensus/include/pcl/sample_consensus/boost.h b/sample_consensus/include/pcl/sample_consensus/boost.h index 991ebb4e2ce..4afdf893184 100644 --- a/sample_consensus/include/pcl/sample_consensus/boost.h +++ b/sample_consensus/include/pcl/sample_consensus/boost.h @@ -37,13 +37,10 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_BOOST_H_ -#define PCL_SAMPLE_CONSENSUS_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header #endif #include - -#endif // PCL_SAMPLE_CONSENSUS_BOOST_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/eigen.h b/sample_consensus/include/pcl/sample_consensus/eigen.h index 674717c1f07..6d4f64900b5 100644 --- a/sample_consensus/include/pcl/sample_consensus/eigen.h +++ b/sample_consensus/include/pcl/sample_consensus/eigen.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_EIGEN_H_ -#define PCL_SAMPLE_CONSENSUS_EIGEN_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -46,5 +45,3 @@ #include #include - -#endif // PCL_SAMPLE_CONSENSUS_EIGEN_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/lmeds.h b/sample_consensus/include/pcl/sample_consensus/lmeds.h index 81f224f836b..b59f87fc295 100644 --- a/sample_consensus/include/pcl/sample_consensus/lmeds.h +++ b/sample_consensus/include/pcl/sample_consensus/lmeds.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_LMEDS_H_ -#define PCL_SAMPLE_CONSENSUS_LMEDS_H_ +#pragma once #include #include @@ -102,6 +101,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_LMEDS_H_ - diff --git a/sample_consensus/include/pcl/sample_consensus/method_types.h b/sample_consensus/include/pcl/sample_consensus/method_types.h index 85786eb9684..0eb0e472478 100644 --- a/sample_consensus/include/pcl/sample_consensus/method_types.h +++ b/sample_consensus/include/pcl/sample_consensus/method_types.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_METHOD_TYPES_H_ -#define PCL_SAMPLE_CONSENSUS_METHOD_TYPES_H_ +#pragma once namespace pcl { @@ -51,5 +50,3 @@ namespace pcl const static int SAC_MLESAC = 5; const static int SAC_PROSAC = 6; } - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_METHOD_TYPES_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/mlesac.h b/sample_consensus/include/pcl/sample_consensus/mlesac.h index 3634175bd4f..cfd7448e7a1 100644 --- a/sample_consensus/include/pcl/sample_consensus/mlesac.h +++ b/sample_consensus/include/pcl/sample_consensus/mlesac.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MLESAC_H_ -#define PCL_SAMPLE_CONSENSUS_MLESAC_H_ +#pragma once #include #include @@ -160,5 +159,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MLESAC_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/model_types.h b/sample_consensus/include/pcl/sample_consensus/model_types.h index 4584aa988cf..27670b65ce7 100644 --- a/sample_consensus/include/pcl/sample_consensus/model_types.h +++ b/sample_consensus/include/pcl/sample_consensus/model_types.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_TYPES_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_TYPES_H_ +#pragma once namespace pcl { @@ -65,5 +64,3 @@ namespace pcl SACMODEL_STICK }; } - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_TYPES_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/msac.h b/sample_consensus/include/pcl/sample_consensus/msac.h index 38166176ccc..decd3f22cda 100644 --- a/sample_consensus/include/pcl/sample_consensus/msac.h +++ b/sample_consensus/include/pcl/sample_consensus/msac.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MSAC_H_ -#define PCL_SAMPLE_CONSENSUS_MSAC_H_ +#pragma once #include #include @@ -103,5 +102,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MSAC_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/prosac.h b/sample_consensus/include/pcl/sample_consensus/prosac.h index 491daa585fd..4c310e955d4 100644 --- a/sample_consensus/include/pcl/sample_consensus/prosac.h +++ b/sample_consensus/include/pcl/sample_consensus/prosac.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_PROSAC_H_ -#define PCL_SAMPLE_CONSENSUS_PROSAC_H_ +#pragma once #include #include @@ -102,5 +101,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_PROSAC_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/ransac.h b/sample_consensus/include/pcl/sample_consensus/ransac.h index e010f1c0060..d09b12846c0 100644 --- a/sample_consensus/include/pcl/sample_consensus/ransac.h +++ b/sample_consensus/include/pcl/sample_consensus/ransac.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_RANSAC_H_ -#define PCL_SAMPLE_CONSENSUS_RANSAC_H_ +#pragma once #include #include @@ -102,6 +101,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_RANSAC_H_ - diff --git a/sample_consensus/include/pcl/sample_consensus/rmsac.h b/sample_consensus/include/pcl/sample_consensus/rmsac.h index 69656f100a7..0fbfb3cb170 100644 --- a/sample_consensus/include/pcl/sample_consensus/rmsac.h +++ b/sample_consensus/include/pcl/sample_consensus/rmsac.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_RMSAC_H_ -#define PCL_SAMPLE_CONSENSUS_RMSAC_H_ +#pragma once #include #include @@ -120,5 +119,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_RMSAC_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/rransac.h b/sample_consensus/include/pcl/sample_consensus/rransac.h index b9f0aa6f1d2..6ef4daf76c0 100644 --- a/sample_consensus/include/pcl/sample_consensus/rransac.h +++ b/sample_consensus/include/pcl/sample_consensus/rransac.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_RRANSAC_H_ -#define PCL_SAMPLE_CONSENSUS_RRANSAC_H_ +#pragma once #include #include @@ -119,6 +118,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_RRANSAC_H_ - diff --git a/sample_consensus/include/pcl/sample_consensus/sac.h b/sample_consensus/include/pcl/sample_consensus/sac.h index 1b4d50a3d0e..7ac96ce9f77 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac.h +++ b/sample_consensus/include/pcl/sample_consensus/sac.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_H_ -#define PCL_SAMPLE_CONSENSUS_H_ +#pragma once #include #include @@ -344,5 +343,3 @@ namespace pcl } }; } - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model.h b/sample_consensus/include/pcl/sample_consensus/sac_model.h index 1af4891ad43..64b0c490f87 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_H_ +#pragma once #include #include @@ -681,5 +680,3 @@ namespace pcl const int m_data_points_; }; } - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_circle.h b/sample_consensus/include/pcl/sample_consensus/sac_model_circle.h index 07762ea258c..d75dde518ff 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_circle.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_circle.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE2D_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE2D_H_ +#pragma once #include #include @@ -260,5 +259,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE2D_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h b/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h index af50086fc1e..42b842b427f 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE3D_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE3D_H_ +#pragma once #include #include @@ -271,5 +270,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CIRCLE3D_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h index 187083064b0..1d4a2f5f832 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_ +#pragma once #include #include @@ -362,5 +361,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h index c347c00f0fd..477ec1582ee 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CYLINDER_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_CYLINDER_H_ +#pragma once #include #include @@ -345,5 +344,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CYLINDER_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_line.h b/sample_consensus/include/pcl/sample_consensus/sac_model_line.h index 7b383465294..e59100350d1 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_line.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_line.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_LINE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_LINE_H_ +#pragma once #include #include @@ -196,5 +195,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_LINE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_normal_parallel_plane.h b/sample_consensus/include/pcl/sample_consensus/sac_model_normal_parallel_plane.h index b828bbd5a77..c7e5277e5e5 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_normal_parallel_plane.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_normal_parallel_plane.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_ +#pragma once #include #include @@ -218,5 +217,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_normal_plane.h b/sample_consensus/include/pcl/sample_consensus/sac_model_normal_plane.h index 509f94a7933..a9533a02eb7 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_normal_plane.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_normal_plane.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPLANE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_NORMALPLANE_H_ +#pragma once #include #include @@ -169,5 +168,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPLANE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_normal_sphere.h b/sample_consensus/include/pcl/sample_consensus/sac_model_normal_sphere.h index ef5f27e5796..7c0eda2e208 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_normal_sphere.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_normal_sphere.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALSPHERE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_NORMALSPHERE_H_ +#pragma once #include #include @@ -169,5 +168,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALSPHERE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_line.h b/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_line.h index afff15c1690..4f5a9003694 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_line.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_line.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLEL_LINE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_PARALLEL_LINE_H_ +#pragma once #include @@ -181,5 +180,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLEL_LINE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_plane.h b/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_plane.h index 4807be6c935..589b40bff4b 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_plane.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_parallel_plane.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_ +#pragma once #include #include @@ -188,5 +187,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_perpendicular_plane.h b/sample_consensus/include/pcl/sample_consensus/sac_model_perpendicular_plane.h index 91ff7bcf8a1..7e2ae1f4460 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_perpendicular_plane.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_perpendicular_plane.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_ +#pragma once #include #include @@ -188,5 +187,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h b/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h index e95d422415c..a7a70af88db 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_ +#pragma once #include #include @@ -270,5 +269,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h b/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h index 5d88cca3294..7e543377cbc 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_ +#pragma once #include #include @@ -331,5 +330,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_registration_2d.h b/sample_consensus/include/pcl/sample_consensus/sac_model_registration_2d.h index 1268d63a46e..539852cb2ae 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_registration_2d.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_registration_2d.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_2D_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_2D_H_ +#pragma once #include @@ -221,6 +220,3 @@ namespace pcl } #include - -#endif // PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_2D_H_ - diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h index 330de6df66f..6a680f62e05 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_ +#pragma once #include #include @@ -276,5 +275,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h b/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h index 3755d64e5f8..018e92e67a5 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SAMPLE_CONSENSUS_MODEL_STICK_H_ -#define PCL_SAMPLE_CONSENSUS_MODEL_STICK_H_ +#pragma once #include #include @@ -200,5 +199,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_STICK_H_ diff --git a/search/include/pcl/search/brute_force.h b/search/include/pcl/search/brute_force.h index 4bed1ea5144..723a5e0bcf6 100644 --- a/search/include/pcl/search/brute_force.h +++ b/search/include/pcl/search/brute_force.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEARCH_BRUTE_FORCE_H_ -#define PCL_SEARCH_BRUTE_FORCE_H_ +#pragma once #include @@ -145,5 +144,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SEARCH_BRUTE_FORCE_H_ diff --git a/search/include/pcl/search/flann_search.h b/search/include/pcl/search/flann_search.h index f411ce82d32..bafec67d284 100644 --- a/search/include/pcl/search/flann_search.h +++ b/search/include/pcl/search/flann_search.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_SEARCH_FLANN_SEARCH_H_ -#define PCL_SEARCH_FLANN_SEARCH_H_ +#pragma once #include #include @@ -370,6 +369,3 @@ namespace pcl } #define PCL_INSTANTIATE_FlannSearch(T) template class PCL_EXPORTS pcl::search::FlannSearch; - -#endif // PCL_SEARCH_KDTREE_H_ - diff --git a/search/include/pcl/search/kdtree.h b/search/include/pcl/search/kdtree.h index dac72543744..be1cadc0e7f 100644 --- a/search/include/pcl/search/kdtree.h +++ b/search/include/pcl/search/kdtree.h @@ -37,8 +37,7 @@ * $Id$ */ -#ifndef PCL_SEARCH_KDTREE_H_ -#define PCL_SEARCH_KDTREE_H_ +#pragma once #include #include @@ -178,6 +177,3 @@ namespace pcl #else #define PCL_INSTANTIATE_KdTree(T) template class PCL_EXPORTS pcl::search::KdTree; #endif - -#endif // PCL_SEARCH_KDTREE_H_ - diff --git a/search/include/pcl/search/octree.h b/search/include/pcl/search/octree.h index dc5f701a76c..0b9ce181f72 100644 --- a/search/include/pcl/search/octree.h +++ b/search/include/pcl/search/octree.h @@ -36,8 +36,7 @@ * $Id$ */ -#ifndef PCL_SEARCH_OCTREE_H -#define PCL_SEARCH_OCTREE_H +#pragma once #include #include @@ -289,5 +288,3 @@ namespace pcl #else #define PCL_INSTANTIATE_Octree(T) template class PCL_EXPORTS pcl::search::Octree; #endif - -#endif // PCL_SEARCH_OCTREE_H diff --git a/search/include/pcl/search/organized.h b/search/include/pcl/search/organized.h index 2f128bd815a..d3977eab984 100644 --- a/search/include/pcl/search/organized.h +++ b/search/include/pcl/search/organized.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEARCH_ORGANIZED_NEIGHBOR_SEARCH_H_ -#define PCL_SEARCH_ORGANIZED_NEIGHBOR_SEARCH_H_ +#pragma once #include #include @@ -284,6 +283,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/search/include/pcl/search/pcl_search.h b/search/include/pcl/search/pcl_search.h index 4d8c5370b29..42bcb10b978 100644 --- a/search/include/pcl/search/pcl_search.h +++ b/search/include/pcl/search/pcl_search.h @@ -37,13 +37,9 @@ * */ -#ifndef PCL_SEARCH_PCL_SEARCH_H_ -#define PCL_SEARCH_PCL_SEARCH_H_ +#pragma once #include #include #include #include - -#endif // PCL_SEARCH_PCL_SEARCH_H_ - diff --git a/search/include/pcl/search/search.h b/search/include/pcl/search/search.h index 1d362c1a841..cabdd7456b4 100644 --- a/search/include/pcl/search/search.h +++ b/search/include/pcl/search/search.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_SEARCH_SEARCH_H_ -#define PCL_SEARCH_SEARCH_H_ +#pragma once #include #include @@ -428,5 +427,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef _PCL_SEARCH_SEARCH_H_ diff --git a/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h b/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h index 88101e419dc..da0ed5241c3 100644 --- a/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h +++ b/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h @@ -36,8 +36,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ -#define PCL_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ +#pragma once #include #include @@ -173,6 +172,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/segmentation/include/pcl/segmentation/boost.h b/segmentation/include/pcl/segmentation/boost.h index f2baa9fbd49..92a03d468fe 100644 --- a/segmentation/include/pcl/segmentation/boost.h +++ b/segmentation/include/pcl/segmentation/boost.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SEGMENTATION_BOOST_H_ -#define PCL_SEGMENTATION_BOOST_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -57,5 +56,3 @@ #include #endif #endif - -#endif // PCL_SEGMENTATION_BOOST_H_ diff --git a/segmentation/include/pcl/segmentation/comparator.h b/segmentation/include/pcl/segmentation/comparator.h index ad12d3c1910..3e2a9dc6be7 100644 --- a/segmentation/include/pcl/segmentation/comparator.h +++ b/segmentation/include/pcl/segmentation/comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_COMPARATOR_H_ -#define PCL_SEGMENTATION_COMPARATOR_H_ +#pragma once #include @@ -101,5 +100,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif //#ifndef _PCL_SEGMENTATION_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h b/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h index eac5e3bec81..d1904322481 100644 --- a/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h +++ b/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_ -#define PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_ +#pragma once #include @@ -266,6 +265,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_ - diff --git a/segmentation/include/pcl/segmentation/cpc_segmentation.h b/segmentation/include/pcl/segmentation/cpc_segmentation.h index cc10277fd66..81043ef7343 100644 --- a/segmentation/include/pcl/segmentation/cpc_segmentation.h +++ b/segmentation/include/pcl/segmentation/cpc_segmentation.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENTATION_CPC_SEGMENTATION_H_ -#define PCL_SEGMENTATION_CPC_SEGMENTATION_H_ +#pragma once // common includes #include @@ -284,5 +283,3 @@ namespace pcl #include #include #endif // PCL_NO_PRECOMPILE / PCL_ONLY_CORE_POINT_TYPES - -#endif // PCL_SEGMENTATION_CPC_SEGMENTATION_H_ diff --git a/segmentation/include/pcl/segmentation/crf_normal_segmentation.h b/segmentation/include/pcl/segmentation/crf_normal_segmentation.h index d51606b1cd4..bb470693497 100644 --- a/segmentation/include/pcl/segmentation/crf_normal_segmentation.h +++ b/segmentation/include/pcl/segmentation/crf_normal_segmentation.h @@ -34,8 +34,7 @@ * */ -#ifndef PCL_CRF_NORMAL_SEGMENTATION_H_ -#define PCL_CRF_NORMAL_SEGMENTATION_H_ +#pragma once #include @@ -79,5 +78,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/segmentation/include/pcl/segmentation/crf_segmentation.h b/segmentation/include/pcl/segmentation/crf_segmentation.h index a84d3e33017..6f166423d3d 100644 --- a/segmentation/include/pcl/segmentation/crf_segmentation.h +++ b/segmentation/include/pcl/segmentation/crf_segmentation.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_CRF_SEGMENTATION_H_ -#define PCL_CRF_SEGMENTATION_H_ +#pragma once #include #include @@ -214,5 +213,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h b/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h index 7eb6d1c1645..075c369d6bc 100644 --- a/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h +++ b/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_EDGE_AWARE_PLANE_COMPARATOR_H_ -#define PCL_SEGMENTATION_EDGE_AWARE_PLANE_COMPARATOR_H_ +#pragma once #include #include @@ -210,5 +209,3 @@ namespace pcl float euclidean_distance_threshold_; }; } - -#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h index d7922308fb9..a0be09120e2 100644 --- a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_EUCLIDEAN_CLUSTER_COMPARATOR_H_ -#define PCL_SEGMENTATION_EUCLIDEAN_CLUSTER_COMPARATOR_H_ +#pragma once #include #include @@ -277,5 +276,3 @@ namespace pcl class EuclideanClusterComparator : public experimental::EuclideanClusterComparator {}; } - -#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h index 849a2b840f5..4c8aa33d3d9 100644 --- a/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_EUCLIDEAN_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ -#define PCL_EUCLIDEAN_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ +#pragma once #include #include @@ -97,5 +96,3 @@ namespace pcl } }; } - -#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/extract_clusters.h b/segmentation/include/pcl/segmentation/extract_clusters.h index 841c451d9a9..208550f4406 100644 --- a/segmentation/include/pcl/segmentation/extract_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_clusters.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_EXTRACT_CLUSTERS_H_ -#define PCL_EXTRACT_CLUSTERS_H_ +#pragma once #include @@ -424,5 +423,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_EXTRACT_CLUSTERS_H_ diff --git a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h index 648b5615262..586a507db3c 100644 --- a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_EXTRACT_LABELED_CLUSTERS_H_ -#define PCL_EXTRACT_LABELED_CLUSTERS_H_ +#pragma once #include #include @@ -189,5 +188,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_EXTRACT_LABELED_CLUSTERS_H_ diff --git a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h index d2b92fd72ac..8319cfc8060 100644 --- a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h +++ b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_ -#define PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_ +#pragma once #include #include @@ -213,5 +212,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_EXTRACT_POLYGONAL_PRISM_DATA_H_ diff --git a/segmentation/include/pcl/segmentation/grabcut_segmentation.h b/segmentation/include/pcl/segmentation/grabcut_segmentation.h index 7190a3bd8a1..6809fffd5b4 100644 --- a/segmentation/include/pcl/segmentation/grabcut_segmentation.h +++ b/segmentation/include/pcl/segmentation/grabcut_segmentation.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_GRABCUT -#define PCL_SEGMENTATION_GRABCUT +#pragma once #include #include @@ -480,5 +479,3 @@ namespace pcl } #include - -#endif diff --git a/segmentation/include/pcl/segmentation/ground_plane_comparator.h b/segmentation/include/pcl/segmentation/ground_plane_comparator.h index f96f38bfb52..5b0fd141c7c 100644 --- a/segmentation/include/pcl/segmentation/ground_plane_comparator.h +++ b/segmentation/include/pcl/segmentation/ground_plane_comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_GROUND_PLANE_COMPARATOR_H_ -#define PCL_SEGMENTATION_GROUND_PLANE_COMPARATOR_H_ +#pragma once #include #include @@ -246,5 +245,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif // PCL_SEGMENTATION_GROUND_PLANE_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/lccp_segmentation.h b/segmentation/include/pcl/segmentation/lccp_segmentation.h index bcba027912f..8ef04c69931 100644 --- a/segmentation/include/pcl/segmentation/lccp_segmentation.h +++ b/segmentation/include/pcl/segmentation/lccp_segmentation.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENTATION_LCCP_SEGMENTATION_H_ -#define PCL_SEGMENTATION_LCCP_SEGMENTATION_H_ +#pragma once #include #include @@ -354,5 +353,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SEGMENTATION_LCCP_SEGMENTATION_H_ diff --git a/segmentation/include/pcl/segmentation/min_cut_segmentation.h b/segmentation/include/pcl/segmentation/min_cut_segmentation.h index 884180d94f0..3a266282fae 100644 --- a/segmentation/include/pcl/segmentation/min_cut_segmentation.h +++ b/segmentation/include/pcl/segmentation/min_cut_segmentation.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_MIN_CUT_SEGMENTATION_H_ -#define PCL_MIN_CUT_SEGMENTATION_H_ +#pragma once #include #if (BOOST_VERSION >= 104400) @@ -327,4 +326,3 @@ namespace pcl #endif #endif -#endif diff --git a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h index d5ab2304be7..a25bbf9ec1e 100644 --- a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ -#define PCL_SEGMENTATION_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ +#pragma once #include #include @@ -151,5 +150,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_ diff --git a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h index f89805cfa17..8e29de7c6ea 100644 --- a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ -#define PCL_SEGMENTATION_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ +#pragma once #include #include @@ -320,5 +319,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SEGMENTATION_ORGANIZED_MULTI_PLANE_SEGMENTATION_H_ diff --git a/segmentation/include/pcl/segmentation/planar_polygon_fusion.h b/segmentation/include/pcl/segmentation/planar_polygon_fusion.h index 82bf51a51dc..8f06e790eeb 100644 --- a/segmentation/include/pcl/segmentation/planar_polygon_fusion.h +++ b/segmentation/include/pcl/segmentation/planar_polygon_fusion.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_H_ -#define PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_H_ +#pragma once #include #include @@ -86,5 +85,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SEGMENTATION_PLANAR_POLYGON_FUSION_H_ diff --git a/segmentation/include/pcl/segmentation/planar_region.h b/segmentation/include/pcl/segmentation/planar_region.h index d0b330009fc..3a809700335 100644 --- a/segmentation/include/pcl/segmentation/planar_region.h +++ b/segmentation/include/pcl/segmentation/planar_region.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENTATION_PLANAR_REGION_H_ -#define PCL_SEGMENTATION_PLANAR_REGION_H_ +#pragma once #include #include @@ -107,5 +106,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif //PCL_SEGMENTATION_PLANAR_REGION_H_ diff --git a/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h index a21725a40cb..6be6a1dbe2d 100644 --- a/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ -#define PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ +#pragma once #include #include @@ -211,5 +210,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/plane_refinement_comparator.h b/segmentation/include/pcl/segmentation/plane_refinement_comparator.h index ded8c76fb11..def8b41ca88 100644 --- a/segmentation/include/pcl/segmentation/plane_refinement_comparator.h +++ b/segmentation/include/pcl/segmentation/plane_refinement_comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_PLANAR_REFINEMENT_COMPARATOR_H_ -#define PCL_SEGMENTATION_PLANAR_REFINEMENT_COMPARATOR_H_ +#pragma once #include #include @@ -219,5 +218,3 @@ namespace pcl using PlaneCoefficientComparator::z_axis_; }; } - -#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/progressive_morphological_filter.h b/segmentation/include/pcl/segmentation/progressive_morphological_filter.h index 5935e8a755e..60433ce9f5a 100644 --- a/segmentation/include/pcl/segmentation/progressive_morphological_filter.h +++ b/segmentation/include/pcl/segmentation/progressive_morphological_filter.h @@ -36,8 +36,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ -#define PCL_PROGRESSIVE_MORPHOLOGICAL_FILTER_H_ +#pragma once #include #include @@ -164,6 +163,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/segmentation/include/pcl/segmentation/random_walker.h b/segmentation/include/pcl/segmentation/random_walker.h index af75d48de31..bd05f61accc 100644 --- a/segmentation/include/pcl/segmentation/random_walker.h +++ b/segmentation/include/pcl/segmentation/random_walker.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENTATION_RANDOM_WALKER_H -#define PCL_SEGMENTATION_RANDOM_WALKER_H +#pragma once #include #include @@ -139,6 +138,3 @@ namespace pcl } #include - -#endif /* PCL_SEGMENTATION_RANDOM_WALKER_H */ - diff --git a/segmentation/include/pcl/segmentation/region_3d.h b/segmentation/include/pcl/segmentation/region_3d.h index 52df2e3e424..45116180a08 100644 --- a/segmentation/include/pcl/segmentation/region_3d.h +++ b/segmentation/include/pcl/segmentation/region_3d.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENTATION_REGION_3D_H_ -#define PCL_SEGMENTATION_REGION_3D_H_ +#pragma once #include #include @@ -120,5 +119,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif //#ifndef PCL_SEGMENTATION_REGION_3D_H_ diff --git a/segmentation/include/pcl/segmentation/region_growing.h b/segmentation/include/pcl/segmentation/region_growing.h index 7a5afff88fb..b7eaa1e52a4 100644 --- a/segmentation/include/pcl/segmentation/region_growing.h +++ b/segmentation/include/pcl/segmentation/region_growing.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGION_GROWING_H_ -#define PCL_REGION_GROWING_H_ +#pragma once #include #include @@ -347,5 +346,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/segmentation/include/pcl/segmentation/region_growing_rgb.h b/segmentation/include/pcl/segmentation/region_growing_rgb.h index e4cee106b91..11b206b4879 100644 --- a/segmentation/include/pcl/segmentation/region_growing_rgb.h +++ b/segmentation/include/pcl/segmentation/region_growing_rgb.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_REGION_GROWING_RGB_H_ -#define PCL_REGION_GROWING_RGB_H_ +#pragma once #include @@ -281,5 +280,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h index 443a9e0ecc9..4a369f65849 100644 --- a/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_RGB_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ -#define PCL_RGB_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ +#pragma once #include #include @@ -131,5 +130,3 @@ namespace pcl float color_threshold_; }; } - -#endif // PCL_SEGMENTATION_PLANE_COEFFICIENT_COMPARATOR_H_ diff --git a/segmentation/include/pcl/segmentation/sac_segmentation.h b/segmentation/include/pcl/segmentation/sac_segmentation.h index c5e28e9bfd1..e260b99b714 100644 --- a/segmentation/include/pcl/segmentation/sac_segmentation.h +++ b/segmentation/include/pcl/segmentation/sac_segmentation.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_ -#define PCL_SEGMENTATION_SAC_SEGMENTATION_H_ +#pragma once #include #include @@ -429,5 +428,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SEGMENTATION_SAC_SEGMENTATION_H_ diff --git a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h index 23627c0e1cc..e25344a0ed0 100644 --- a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h +++ b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h @@ -36,8 +36,7 @@ * $id: $ */ -#ifndef PCL_SEEDED_HUE_SEGMENTATION_H_ -#define PCL_SEEDED_HUE_SEGMENTATION_H_ +#pragma once #include #include @@ -172,5 +171,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SEEDED_HUE_SEGMENTATION_H_ diff --git a/segmentation/include/pcl/segmentation/segment_differences.h b/segmentation/include/pcl/segmentation/segment_differences.h index cd1b95e359d..33351842457 100755 --- a/segmentation/include/pcl/segmentation/segment_differences.h +++ b/segmentation/include/pcl/segmentation/segment_differences.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SEGMENT_DIFFERENCES_H_ -#define PCL_SEGMENT_DIFFERENCES_H_ +#pragma once #include #include @@ -170,5 +169,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_SEGMENT_DIFFERENCES_H_ diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index 05e6002752c..eea81ef43fe 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SEGMENTATION_SUPERVOXEL_CLUSTERING_H_ -#define PCL_SEGMENTATION_SUPERVOXEL_CLUSTERING_H_ +#pragma once #include #include @@ -542,5 +541,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/segmentation/include/pcl/segmentation/unary_classifier.h b/segmentation/include/pcl/segmentation/unary_classifier.h index 163244a52b4..800dc3302a0 100644 --- a/segmentation/include/pcl/segmentation/unary_classifier.h +++ b/segmentation/include/pcl/segmentation/unary_classifier.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_UNARY_CLASSIFIER_H_ -#define PCL_UNARY_CLASSIFIER_H_ +#pragma once #include #include @@ -175,5 +174,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/simulation/include/pcl/simulation/camera.h b/simulation/include/pcl/simulation/camera.h index e94af9a596b..764eb66dbad 100644 --- a/simulation/include/pcl/simulation/camera.h +++ b/simulation/include/pcl/simulation/camera.h @@ -1,5 +1,4 @@ -#ifndef PCL_SIMULATION_CAMERA_HPP_ -#define PCL_SIMULATION_CAMERA_HPP_ +#pragma once #include #include @@ -118,5 +117,3 @@ namespace pcl }; } // namespace - simulation } // namespace - pcl - -#endif /* PCL_SIMULATION_CAMERA_HPP_ */ diff --git a/simulation/include/pcl/simulation/glsl_shader.h b/simulation/include/pcl/simulation/glsl_shader.h index fef5a6b8ea5..f22cbbbf7e2 100644 --- a/simulation/include/pcl/simulation/glsl_shader.h +++ b/simulation/include/pcl/simulation/glsl_shader.h @@ -5,8 +5,7 @@ * Author: Hordur Johannsson */ -#ifndef PCL_SIMULATION_GLSL_SHADER -#define PCL_SIMULATION_GLSL_SHADER +#pragma once #include @@ -102,5 +101,3 @@ namespace pcl } // namespace - gllib } // namespace - simulation } // namespace - pcl - -#endif /* PCL_SIMULATION_GLSL_SHADER_HPP_ */ diff --git a/simulation/include/pcl/simulation/model.h b/simulation/include/pcl/simulation/model.h index 2a6b5d4b4e5..1a643d590c9 100644 --- a/simulation/include/pcl/simulation/model.h +++ b/simulation/include/pcl/simulation/model.h @@ -1,5 +1,4 @@ -#ifndef PCL_MODEL_HPP_ -#define PCL_MODEL_HPP_ +#pragma once #if defined(_WIN32) && !defined(APIENTRY) && !defined(__CYGWIN__) # define WIN32_LEAN_AND_MEAN 1 @@ -207,5 +206,3 @@ namespace pcl }; } // namespace - simulation } // namespace - pcl - -#endif /* PCL_SIMULATION_MODEL_HPP_ */ diff --git a/simulation/include/pcl/simulation/range_likelihood.h b/simulation/include/pcl/simulation/range_likelihood.h index 39334f9030c..3ab4f702484 100644 --- a/simulation/include/pcl/simulation/range_likelihood.h +++ b/simulation/include/pcl/simulation/range_likelihood.h @@ -1,5 +1,4 @@ -#ifndef PCL_RANGE_LIKELIHOOD -#define PCL_RANGE_LIKELIHOOD +#pragma once #include @@ -269,5 +268,3 @@ namespace pcl } // namespace - simulation } // namespace - pcl - -#endif diff --git a/simulation/include/pcl/simulation/scene.h b/simulation/include/pcl/simulation/scene.h index 7d66acb6d63..c0f0308a9f9 100644 --- a/simulation/include/pcl/simulation/scene.h +++ b/simulation/include/pcl/simulation/scene.h @@ -5,8 +5,7 @@ * Author: Hordur Johannsson */ -#ifndef PCL_SIMULATION_SCENE_HPP_ -#define PCL_SIMULATION_SCENE_HPP_ +#pragma once #include @@ -44,5 +43,3 @@ namespace pcl } // namespace - simulation } // namespace - pcl - -#endif diff --git a/simulation/include/pcl/simulation/sum_reduce.h b/simulation/include/pcl/simulation/sum_reduce.h index bf53ac395a1..3864b980b43 100644 --- a/simulation/include/pcl/simulation/sum_reduce.h +++ b/simulation/include/pcl/simulation/sum_reduce.h @@ -5,8 +5,7 @@ * */ -#ifndef PCL_SIMULATION_SUM_REDUCE -#define PCL_SIMULATION_SUM_REDUCE +#pragma once #include @@ -62,5 +61,3 @@ namespace pcl }; } // namespace - simulation } // namespace - pcl - -#endif /* PCL_SIMULATION_SUM_REDUCE */ diff --git a/stereo/include/pcl/stereo/digital_elevation_map.h b/stereo/include/pcl/stereo/digital_elevation_map.h index 8cd847687cf..f7ba36f734f 100644 --- a/stereo/include/pcl/stereo/digital_elevation_map.h +++ b/stereo/include/pcl/stereo/digital_elevation_map.h @@ -33,8 +33,8 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_DIGITAL_ELEVATION_MAP_H_ -#define PCL_DIGITAL_ELEVATION_MAP_H_ + +#pragma once #include #include @@ -136,5 +136,3 @@ namespace pcl size_t min_points_in_cell_; }; } - -#endif // PCL_DIGITAL_ELEVATION_MAP_H_ diff --git a/stereo/include/pcl/stereo/disparity_map_converter.h b/stereo/include/pcl/stereo/disparity_map_converter.h index cf968ea7f76..7dcdae3d83a 100644 --- a/stereo/include/pcl/stereo/disparity_map_converter.h +++ b/stereo/include/pcl/stereo/disparity_map_converter.h @@ -33,8 +33,8 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef PCL_DISPARITY_MAP_CONVERTER_H_ -#define PCL_DISPARITY_MAP_CONVERTER_H_ + +#pragma once #include #include @@ -252,5 +252,3 @@ namespace pcl } #include - -#endif // PCL_DISPARITY_MAP_CONVERTER_H_ \ No newline at end of file diff --git a/stereo/include/pcl/stereo/stereo_grabber.h b/stereo/include/pcl/stereo/stereo_grabber.h index db753e767a5..ac32ac4286b 100644 --- a/stereo/include/pcl/stereo/stereo_grabber.h +++ b/stereo/include/pcl/stereo/stereo_grabber.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_STEREO_STEREO_GRABER_H_ -#define PCL_STEREO_STEREO_GRABER_H_ +#pragma once #include #include @@ -171,4 +170,3 @@ namespace pcl signal_->operator () (cloud); } } -#endif diff --git a/stereo/include/pcl/stereo/stereo_matching.h b/stereo/include/pcl/stereo/stereo_matching.h index 0c6d3d0a6a7..63b99b370a1 100644 --- a/stereo/include/pcl/stereo/stereo_matching.h +++ b/stereo/include/pcl/stereo/stereo_matching.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_STEREO_H_ -#define PCL_STEREO_H_ + +#pragma once #include #include @@ -509,5 +509,3 @@ namespace pcl int smoothness_weak_; }; } - -#endif diff --git a/surface/include/pcl/surface/bilateral_upsampling.h b/surface/include/pcl/surface/bilateral_upsampling.h index 98e4e0bd1e1..6360f3ac609 100644 --- a/surface/include/pcl/surface/bilateral_upsampling.h +++ b/surface/include/pcl/surface/bilateral_upsampling.h @@ -37,9 +37,7 @@ * */ - -#ifndef PCL_SURFACE_BILATERAL_UPSAMPLING_H_ -#define PCL_SURFACE_BILATERAL_UPSAMPLING_H_ +#pragma once #include @@ -160,5 +158,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif /* PCL_SURFACE_BILATERAL_UPSAMPLING_H_ */ diff --git a/surface/include/pcl/surface/boost.h b/surface/include/pcl/surface/boost.h index b8e4b66f6e7..e89e35e541f 100644 --- a/surface/include/pcl/surface/boost.h +++ b/surface/include/pcl/surface/boost.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SURFACE_BOOST_H_ -#define PCL_SURFACE_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -50,5 +49,3 @@ #include #include #include - -#endif // PCL_SURFACE_BOOST_H_ diff --git a/surface/include/pcl/surface/concave_hull.h b/surface/include/pcl/surface/concave_hull.h index 85b296b0c7e..bd40ccaa1dd 100644 --- a/surface/include/pcl/surface/concave_hull.h +++ b/surface/include/pcl/surface/concave_hull.h @@ -36,13 +36,12 @@ * $Id$ * */ + +#pragma once -#include #ifdef HAVE_QHULL -#ifndef PCL_CONCAVE_HULL_H -#define PCL_CONCAVE_HULL_H - +#include #include namespace pcl @@ -212,5 +211,4 @@ namespace pcl #include #endif -#endif //#ifndef PCL_CONCAVE_HULL #endif diff --git a/surface/include/pcl/surface/convex_hull.h b/surface/include/pcl/surface/convex_hull.h index 03ba9db69ea..c77ce8468bb 100644 --- a/surface/include/pcl/surface/convex_hull.h +++ b/surface/include/pcl/surface/convex_hull.h @@ -37,13 +37,12 @@ * */ -#include -#ifdef HAVE_QHULL +#pragma once -#ifndef PCL_CONVEX_HULL_2D_H_ -#define PCL_CONVEX_HULL_2D_H_ +#ifdef HAVE_QHULL // PCL includes +#include #include #include #include @@ -275,5 +274,4 @@ namespace pcl #include #endif -#endif //#ifndef PCL_CONVEX_HULL_2D_H_ #endif diff --git a/surface/include/pcl/surface/ear_clipping.h b/surface/include/pcl/surface/ear_clipping.h index 870608edc6c..05ce38f6580 100644 --- a/surface/include/pcl/surface/ear_clipping.h +++ b/surface/include/pcl/surface/ear_clipping.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SURFACE_EAR_CLIPPING_H_ -#define PCL_SURFACE_EAR_CLIPPING_H_ +#pragma once #include #include @@ -124,5 +123,3 @@ namespace pcl }; } - -#endif // #ifndef PCL_SURFACE_EAR_CLIPPING_H_ diff --git a/surface/include/pcl/surface/eigen.h b/surface/include/pcl/surface/eigen.h index 91f925e3a15..c1cad11d4ec 100644 --- a/surface/include/pcl/surface/eigen.h +++ b/surface/include/pcl/surface/eigen.h @@ -37,13 +37,10 @@ * */ -#ifndef PCL_SURFACE_EIGEN_H_ -#define PCL_SURFACE_EIGEN_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header #endif #include - -#endif // PCL_SURFACE_EIGEN_H_ diff --git a/surface/include/pcl/surface/gp3.h b/surface/include/pcl/surface/gp3.h index 192254aa310..4ff6aaea7d5 100644 --- a/surface/include/pcl/surface/gp3.h +++ b/surface/include/pcl/surface/gp3.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_GP3_H_ -#define PCL_GP3_H_ +#pragma once // PCL includes #include @@ -543,6 +542,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //#ifndef PCL_GP3_H_ - diff --git a/surface/include/pcl/surface/grid_projection.h b/surface/include/pcl/surface/grid_projection.h index 48807e9d7cc..ac593609bef 100644 --- a/surface/include/pcl/surface/grid_projection.h +++ b/surface/include/pcl/surface/grid_projection.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SURFACE_GRID_PROJECTION_H_ -#define PCL_SURFACE_GRID_PROJECTION_H_ +#pragma once #include #include @@ -501,6 +500,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif // PCL_SURFACE_GRID_PROJECTION_H_ - diff --git a/surface/include/pcl/surface/marching_cubes.h b/surface/include/pcl/surface/marching_cubes.h index d20f5c97684..3b9f128fc86 100644 --- a/surface/include/pcl/surface/marching_cubes.h +++ b/surface/include/pcl/surface/marching_cubes.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_SURFACE_MARCHING_CUBES_H_ -#define PCL_SURFACE_MARCHING_CUBES_H_ +#pragma once #include #include @@ -525,6 +524,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SURFACE_MARCHING_CUBES_H_ - diff --git a/surface/include/pcl/surface/marching_cubes_hoppe.h b/surface/include/pcl/surface/marching_cubes_hoppe.h index 6f14d139ce3..876f6717c10 100644 --- a/surface/include/pcl/surface/marching_cubes_hoppe.h +++ b/surface/include/pcl/surface/marching_cubes_hoppe.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_SURFACE_MARCHING_CUBES_HOPPE_H_ -#define PCL_SURFACE_MARCHING_CUBES_HOPPE_H_ +#pragma once #include #include @@ -118,6 +117,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SURFACE_MARCHING_CUBES_HOPPE_H_ - diff --git a/surface/include/pcl/surface/marching_cubes_rbf.h b/surface/include/pcl/surface/marching_cubes_rbf.h index a0a49a8aa0c..520941cce7b 100644 --- a/surface/include/pcl/surface/marching_cubes_rbf.h +++ b/surface/include/pcl/surface/marching_cubes_rbf.h @@ -33,8 +33,7 @@ * */ -#ifndef PCL_SURFACE_MARCHING_CUBES_RBF_H_ -#define PCL_SURFACE_MARCHING_CUBES_RBF_H_ +#pragma once #include #include @@ -120,6 +119,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SURFACE_MARCHING_CUBES_RBF_H_ - diff --git a/surface/include/pcl/surface/mls.h b/surface/include/pcl/surface/mls.h index 2e14f2bad33..6c8f84c08ab 100644 --- a/surface/include/pcl/surface/mls.h +++ b/surface/include/pcl/surface/mls.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_MLS_H_ -#define PCL_MLS_H_ +#pragma once // PCL includes #include @@ -770,5 +769,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif /* #ifndef PCL_MLS_H_ */ diff --git a/surface/include/pcl/surface/organized_fast_mesh.h b/surface/include/pcl/surface/organized_fast_mesh.h index 54bbd3ddd32..f90c9a6749d 100644 --- a/surface/include/pcl/surface/organized_fast_mesh.h +++ b/surface/include/pcl/surface/organized_fast_mesh.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_SURFACE_ORGANIZED_FAST_MESH_H_ -#define PCL_SURFACE_ORGANIZED_FAST_MESH_H_ +#pragma once #include #include @@ -488,5 +487,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SURFACE_ORGANIZED_FAST_MESH_H_ diff --git a/surface/include/pcl/surface/poisson.h b/surface/include/pcl/surface/poisson.h index c090e980947..fa731b651f6 100644 --- a/surface/include/pcl/surface/poisson.h +++ b/surface/include/pcl/surface/poisson.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SURFACE_POISSON_H_ -#define PCL_SURFACE_POISSON_H_ +#pragma once #include @@ -256,5 +255,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SURFACE_POISSON_H_ diff --git a/surface/include/pcl/surface/processing.h b/surface/include/pcl/surface/processing.h index bc4396c6278..6ddf54018bd 100644 --- a/surface/include/pcl/surface/processing.h +++ b/surface/include/pcl/surface/processing.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_MESH_PROCESSING_H_ -#define PCL_MESH_PROCESSING_H_ +#pragma once #include #include @@ -149,6 +148,3 @@ namespace pcl } #include "pcl/surface/impl/processing.hpp" - -#endif /* PCL_MESH_PROCESSING_H_ */ - diff --git a/surface/include/pcl/surface/qhull.h b/surface/include/pcl/surface/qhull.h index ac738991e71..93876a2471a 100644 --- a/surface/include/pcl/surface/qhull.h +++ b/surface/include/pcl/surface/qhull.h @@ -37,11 +37,11 @@ * */ -#include +#pragma once + #ifdef HAVE_QHULL -#ifndef PCL_QHULL_H -#define PCL_QHULL_H +#include #if defined __GNUC__ # pragma GCC system_header @@ -70,6 +70,4 @@ extern "C" #endif } -#endif // PCL_QHULL_H #endif - diff --git a/surface/include/pcl/surface/reconstruction.h b/surface/include/pcl/surface/reconstruction.h index 13a9bb38404..1bfcea711c9 100644 --- a/surface/include/pcl/surface/reconstruction.h +++ b/surface/include/pcl/surface/reconstruction.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SURFACE_RECONSTRUCTION_H_ -#define PCL_SURFACE_RECONSTRUCTION_H_ +#pragma once #include #include @@ -244,6 +243,3 @@ namespace pcl } #include - -#endif // PCL_SURFACE_RECONSTRUCTION_H_ - diff --git a/surface/include/pcl/surface/simplification_remove_unused_vertices.h b/surface/include/pcl/surface/simplification_remove_unused_vertices.h index 33a50e3ac78..5da9da7450c 100644 --- a/surface/include/pcl/surface/simplification_remove_unused_vertices.h +++ b/surface/include/pcl/surface/simplification_remove_unused_vertices.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_SURFACE_SIMPLIFICATION_REMOVE_UNUSED_VERTICES_H_ -#define PCL_SURFACE_SIMPLIFICATION_REMOVE_UNUSED_VERTICES_H_ +#pragma once #include #include @@ -79,5 +78,3 @@ namespace pcl }; } } - -#endif /* PCL_SURFACE_SIMPLIFICATION_REMOVE_UNUSED_VERTICES_H_ */ diff --git a/surface/include/pcl/surface/surfel_smoothing.h b/surface/include/pcl/surface/surfel_smoothing.h index a22c4af19f1..4bac249c0f7 100644 --- a/surface/include/pcl/surface/surfel_smoothing.h +++ b/surface/include/pcl/surface/surfel_smoothing.h @@ -35,8 +35,7 @@ * $Id$ */ -#ifndef PCL_SURFEL_SMOOTHING_H_ -#define PCL_SURFEL_SMOOTHING_H_ +#pragma once #include #include @@ -114,5 +113,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_SURFEL_SMOOTHING_H_ diff --git a/surface/include/pcl/surface/texture_mapping.h b/surface/include/pcl/surface/texture_mapping.h index 692536955d8..26bbb112918 100644 --- a/surface/include/pcl/surface/texture_mapping.h +++ b/surface/include/pcl/surface/texture_mapping.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_SURFACE_TEXTURE_MAPPING_H_ -#define PCL_SURFACE_TEXTURE_MAPPING_H_ +#pragma once #include #include @@ -422,6 +421,3 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } - -#endif /* TEXTURE_MAPPING_H_ */ - diff --git a/surface/include/pcl/surface/vtk_smoothing/vtk.h b/surface/include/pcl/surface/vtk_smoothing/vtk.h index 2721e373dd4..a86f10cfb85 100644 --- a/surface/include/pcl/surface/vtk_smoothing/vtk.h +++ b/surface/include/pcl/surface/vtk_smoothing/vtk.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_SURFACE_VTK_H_ -#define PCL_SURFACE_VTK_H_ + +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -45,6 +45,3 @@ #include #include - -#endif // PCL_SURFACE_VTK_H_ - diff --git a/test/common/boost.h b/test/common/boost.h index 547eac871cc..fff0c860769 100644 --- a/test/common/boost.h +++ b/test/common/boost.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_TEST_COMMON_BOOST_H_ -#define PCL_TEST_COMMON_BOOST_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -48,5 +47,3 @@ // Marking all Boost headers as system headers to remove warnings #include #include - -#endif // PCL_TEST_COMMON_BOOST_H_ diff --git a/test/geometry/test_mesh_common_functions.h b/test/geometry/test_mesh_common_functions.h index 561bf738714..fec5f375390 100644 --- a/test/geometry/test_mesh_common_functions.h +++ b/test/geometry/test_mesh_common_functions.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_TEST_GEOMETRY_TEST_MESH_COMMON_FUNCTIONS_H -#define PCL_TEST_GEOMETRY_TEST_MESH_COMMON_FUNCTIONS_H +#pragma once #include #include @@ -371,5 +370,3 @@ checkHalfEdge (const MeshT& mesh, } //////////////////////////////////////////////////////////////////////////////// - -#endif // PCL_TEST_GEOMETRY_TEST_MESH_COMMON_FUNCTIONS_H diff --git a/tools/boost.h b/tools/boost.h index f1b44dca3aa..6b382b520d9 100644 --- a/tools/boost.h +++ b/tools/boost.h @@ -38,8 +38,7 @@ * */ -#ifndef PCL_TOOLS_BOOST_H_ -#define PCL_TOOLS_BOOST_H_ +#pragma once #ifdef __GNUC__ #pragma GCC system_header @@ -59,5 +58,3 @@ //#include //#include #endif - -#endif // PCL_TOOLS_BOOST_H_ diff --git a/tracking/include/pcl/tracking/approx_nearest_pair_point_cloud_coherence.h b/tracking/include/pcl/tracking/approx_nearest_pair_point_cloud_coherence.h index 114d87dd878..b92de748495 100644 --- a/tracking/include/pcl/tracking/approx_nearest_pair_point_cloud_coherence.h +++ b/tracking/include/pcl/tracking/approx_nearest_pair_point_cloud_coherence.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_APPROX_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ -#define PCL_TRACKING_APPROX_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ +#pragma once #include #include @@ -50,6 +49,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif - diff --git a/tracking/include/pcl/tracking/boost.h b/tracking/include/pcl/tracking/boost.h index 24f3bb6b803..4afdf893184 100644 --- a/tracking/include/pcl/tracking/boost.h +++ b/tracking/include/pcl/tracking/boost.h @@ -37,13 +37,10 @@ * */ -#ifndef PCL_TRACKING_BOOST_H_ -#define PCL_TRACKING_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header #endif #include - -#endif // PCL_TRACKING_BOOST_H_ diff --git a/tracking/include/pcl/tracking/coherence.h b/tracking/include/pcl/tracking/coherence.h index e56ee3e21cf..cda4e1ebb1a 100644 --- a/tracking/include/pcl/tracking/coherence.h +++ b/tracking/include/pcl/tracking/coherence.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_COHERENCE_H_ -#define PCL_TRACKING_COHERENCE_H_ +#pragma once #include @@ -129,8 +128,4 @@ namespace pcl } } - #include - - -#endif diff --git a/tracking/include/pcl/tracking/distance_coherence.h b/tracking/include/pcl/tracking/distance_coherence.h index 9c7415a0645..c1efdd95eec 100644 --- a/tracking/include/pcl/tracking/distance_coherence.h +++ b/tracking/include/pcl/tracking/distance_coherence.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_DISTANCE_COHERENCE_H_ -#define PCL_TRACKING_DISTANCE_COHERENCE_H_ +#pragma once #include @@ -48,7 +47,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -// #include - -#endif diff --git a/tracking/include/pcl/tracking/hsv_color_coherence.h b/tracking/include/pcl/tracking/hsv_color_coherence.h index 1fb5092c30a..fb5de20582f 100644 --- a/tracking/include/pcl/tracking/hsv_color_coherence.h +++ b/tracking/include/pcl/tracking/hsv_color_coherence.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_HSV_COLOR_COHERENCE_H_ -#define PCL_TRACKING_HSV_COLOR_COHERENCE_H_ +#pragma once #include @@ -95,10 +94,6 @@ namespace pcl } } -// #include - #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h b/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h index 009013f752c..5dcb2d6a441 100644 --- a/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h +++ b/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_H_ -#define PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_H_ +#pragma once #include #include @@ -214,5 +213,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h b/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h index 45b8e24acc0..7113f935f5b 100644 --- a/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h +++ b/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_OMP_H_ -#define PCL_TRACKING_KLD_ADAPTIVE_PARTICLE_FILTER_OMP_H_ +#pragma once #include #include @@ -97,5 +96,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h index d2070f0549e..4b919b7a0e7 100644 --- a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h +++ b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ -#define PCL_TRACKING_NEAREST_PAIR_POINT_CLOUD_COHERENCE_H_ +#pragma once #include @@ -96,5 +95,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/tracking/include/pcl/tracking/normal_coherence.h b/tracking/include/pcl/tracking/normal_coherence.h index f693347199a..a8c9d2e50ed 100644 --- a/tracking/include/pcl/tracking/normal_coherence.h +++ b/tracking/include/pcl/tracking/normal_coherence.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_NORMAL_COHERENCE_H_ -#define PCL_TRACKING_NORMAL_COHERENCE_H_ +#pragma once #include namespace pcl @@ -49,5 +48,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/tracking/include/pcl/tracking/particle_filter.h b/tracking/include/pcl/tracking/particle_filter.h index 8a9d3382959..64bafcff04e 100644 --- a/tracking/include/pcl/tracking/particle_filter.h +++ b/tracking/include/pcl/tracking/particle_filter.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_PARTICLE_FILTER_H_ -#define PCL_TRACKING_PARTICLE_FILTER_H_ +#pragma once #include #include @@ -507,5 +506,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif //PCL_TRACKING_PARTICLE_FILTER_H_ diff --git a/tracking/include/pcl/tracking/particle_filter_omp.h b/tracking/include/pcl/tracking/particle_filter_omp.h index 4f52c6b74e0..e14b4f9642b 100644 --- a/tracking/include/pcl/tracking/particle_filter_omp.h +++ b/tracking/include/pcl/tracking/particle_filter_omp.h @@ -1,5 +1,4 @@ -#ifndef PCL_TRACKING_PARTICLE_FILTER_OMP_H_ -#define PCL_TRACKING_PARTICLE_FILTER_OMP_H_ +#pragma once #include #include @@ -93,5 +92,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/tracking/include/pcl/tracking/pyramidal_klt.h b/tracking/include/pcl/tracking/pyramidal_klt.h index 7eadd10d7f2..06b6475da91 100644 --- a/tracking/include/pcl/tracking/pyramidal_klt.h +++ b/tracking/include/pcl/tracking/pyramidal_klt.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_TRACKING_PYRAMIDAL_KLT_H -#define PCL_TRACKING_PYRAMIDAL_KLT_H +#pragma once #include #include @@ -374,4 +373,3 @@ namespace pcl } #include -#endif diff --git a/tracking/include/pcl/tracking/tracker.h b/tracking/include/pcl/tracking/tracker.h index 10ee2458d1d..b2467244dad 100644 --- a/tracking/include/pcl/tracking/tracker.h +++ b/tracking/include/pcl/tracking/tracker.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_TRACKING_TRACKER_H_ -#define PCL_TRACKING_TRACKER_H_ +#pragma once #include #include @@ -132,5 +131,3 @@ namespace pcl } #include - -#endif diff --git a/tracking/include/pcl/tracking/tracking.h b/tracking/include/pcl/tracking/tracking.h index 08f0aaf23af..110e14e686c 100644 --- a/tracking/include/pcl/tracking/tracking.h +++ b/tracking/include/pcl/tracking/tracking.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_TRACKING_TRACKING_H_ -#define PCL_TRACKING_TRACKING_H_ +#pragma once #include @@ -131,5 +130,3 @@ POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::tracking::ParticleXYZR, pcl::tracking::_ #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif diff --git a/visualization/include/pcl/visualization/area_picking_event.h b/visualization/include/pcl/visualization/area_picking_event.h index dd29530addb..0091aca41e9 100644 --- a/visualization/include/pcl/visualization/area_picking_event.h +++ b/visualization/include/pcl/visualization/area_picking_event.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_VISUALIZATION_AREA_PICKING_EVENT_H_ -#define PCL_VISUALIZATION_AREA_PICKING_EVENT_H_ +#pragma once #include @@ -73,5 +72,3 @@ namespace pcl }; } //namespace visualization } //namespace pcl - -#endif /* PCL_VISUALIZATION_AREA_PICKING_EVENT_H_ */ diff --git a/visualization/include/pcl/visualization/boost.h b/visualization/include/pcl/visualization/boost.h index c0019a90202..7f0de550e94 100644 --- a/visualization/include/pcl/visualization/boost.h +++ b/visualization/include/pcl/visualization/boost.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_VISUALIZATION_BOOST_H_ -#define PCL_VISUALIZATION_BOOST_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -65,5 +64,3 @@ #endif #include #endif - -#endif // PCL_VISUALIZATION_BOOST_H_ diff --git a/visualization/include/pcl/visualization/cloud_viewer.h b/visualization/include/pcl/visualization/cloud_viewer.h index c0f9edb7201..b96f3a9591f 100644 --- a/visualization/include/pcl/visualization/cloud_viewer.h +++ b/visualization/include/pcl/visualization/cloud_viewer.h @@ -33,8 +33,8 @@ * * */ -#ifndef PCL_CLOUD_VIEWER_H_ -#define PCL_CLOUD_VIEWER_H_ + +#pragma once #include //pcl vis #include // scoped_ptr for pre-C++11 @@ -213,5 +213,3 @@ namespace pcl }; } } - -#endif /* CLOUD_VIEWER_H_ */ diff --git a/visualization/include/pcl/visualization/common/actor_map.h b/visualization/include/pcl/visualization/common/actor_map.h index 1a9b1a0bac8..7f5a1c70843 100644 --- a/visualization/include/pcl/visualization/common/actor_map.h +++ b/visualization/include/pcl/visualization/common/actor_map.h @@ -34,8 +34,8 @@ * $Id$ * */ -#ifndef PCL_PCL_VISUALIZER_ACTOR_MAP_H_ -#define PCL_PCL_VISUALIZER_ACTOR_MAP_H_ + +#pragma once #include #include @@ -106,5 +106,3 @@ namespace pcl typedef boost::shared_ptr CoordinateActorMapPtr; } } - -#endif diff --git a/visualization/include/pcl/visualization/common/common.h b/visualization/include/pcl/visualization/common/common.h index 6c69e95322a..52c8b2208ac 100644 --- a/visualization/include/pcl/visualization/common/common.h +++ b/visualization/include/pcl/visualization/common/common.h @@ -34,8 +34,8 @@ * $Id$ * */ -#ifndef PCL_PCL_VISUALIZER_COMMON_H_ -#define PCL_PCL_VISUALIZER_COMMON_H_ + +#pragma once #if defined __GNUC__ #pragma GCC system_header @@ -213,5 +213,3 @@ namespace pcl } #include - -#endif diff --git a/visualization/include/pcl/visualization/common/float_image_utils.h b/visualization/include/pcl/visualization/common/float_image_utils.h index 2a89473723a..19bfd39da79 100644 --- a/visualization/include/pcl/visualization/common/float_image_utils.h +++ b/visualization/include/pcl/visualization/common/float_image_utils.h @@ -32,11 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include - -#ifndef PCL_VISUALIZATION_FLOAT_IMAGE_UTILS_H_ -#define PCL_VISUALIZATION_FLOAT_IMAGE_UTILS_H_ +#pragma once +#include #include #include @@ -98,6 +96,3 @@ namespace pcl } // namespace end } - -#endif //#ifndef PCL_VISUALIZATION_FLOAT_IMAGE_UTILS_H_ - diff --git a/visualization/include/pcl/visualization/common/io.h b/visualization/include/pcl/visualization/common/io.h index 6b2d826b873..78990d728ee 100644 --- a/visualization/include/pcl/visualization/common/io.h +++ b/visualization/include/pcl/visualization/common/io.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_PCL_VISUALIZER_COMMON_IO_H_ -#define PCL_PCL_VISUALIZER_COMMON_IO_H_ + +#pragma once #include #include @@ -70,5 +70,3 @@ namespace pcl savePointData (vtkPolyData* data, const std::string &out_file, const boost::shared_ptr &actors); } } - -#endif diff --git a/visualization/include/pcl/visualization/common/ren_win_interact_map.h b/visualization/include/pcl/visualization/common/ren_win_interact_map.h index f76046e3f7d..082bf53bff8 100644 --- a/visualization/include/pcl/visualization/common/ren_win_interact_map.h +++ b/visualization/include/pcl/visualization/common/ren_win_interact_map.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_PCL_VISUALIZER_REN_WIN_INTERACT_MAP_H_ -#define PCL_PCL_VISUALIZER_REN_WIN_INTERACT_MAP_H_ +#pragma once #include #include @@ -82,5 +81,3 @@ namespace pcl typedef std::map RenWinInteractMap; } } - -#endif diff --git a/visualization/include/pcl/visualization/common/shapes.h b/visualization/include/pcl/visualization/common/shapes.h index e97b028765e..67f7df8dcb0 100644 --- a/visualization/include/pcl/visualization/common/shapes.h +++ b/visualization/include/pcl/visualization/common/shapes.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_PCL_VISUALIZER_SHAPES_H_ -#define PCL_PCL_VISUALIZER_SHAPES_H_ + +#pragma once #include #include @@ -291,5 +291,3 @@ namespace pcl /*@}*/ #include - -#endif diff --git a/visualization/include/pcl/visualization/eigen.h b/visualization/include/pcl/visualization/eigen.h index 5408de4f969..4c32fbb90a4 100644 --- a/visualization/include/pcl/visualization/eigen.h +++ b/visualization/include/pcl/visualization/eigen.h @@ -37,8 +37,7 @@ * */ -#ifndef PCL_VISUALIZATION_EIGEN_H_ -#define PCL_VISUALIZATION_EIGEN_H_ +#pragma once #if defined __GNUC__ # pragma GCC system_header @@ -46,5 +45,3 @@ #include #include - -#endif // PCL_VISUALIZATION_EIGEN_H_ diff --git a/visualization/include/pcl/visualization/histogram_visualizer.h b/visualization/include/pcl/visualization/histogram_visualizer.h index cbcba84534d..a5b44c5958c 100644 --- a/visualization/include/pcl/visualization/histogram_visualizer.h +++ b/visualization/include/pcl/visualization/histogram_visualizer.h @@ -36,8 +36,8 @@ * $Id$ * */ -#ifndef PCL_PCL_HISTOGRAM_VISUALIZER_H_ -#define PCL_PCL_HISTOGRAM_VISUALIZER_H_ + +#pragma once #include #include @@ -265,5 +265,3 @@ namespace pcl } #include - -#endif diff --git a/visualization/include/pcl/visualization/image_viewer.h b/visualization/include/pcl/visualization/image_viewer.h index 21b060d6c32..049f92fae1e 100644 --- a/visualization/include/pcl/visualization/image_viewer.h +++ b/visualization/include/pcl/visualization/image_viewer.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_VISUALIZATION_IMAGE_VISUALIZER_H__ -#define PCL_VISUALIZATION_IMAGE_VISUALIZER_H__ +#pragma once #include #include @@ -1065,6 +1064,3 @@ namespace pcl } #include - -#endif /* __IMAGE_VISUALIZER_H__ */ - diff --git a/visualization/include/pcl/visualization/interactor.h b/visualization/include/pcl/visualization/interactor.h index 64a49523ced..61d5280e551 100644 --- a/visualization/include/pcl/visualization/interactor.h +++ b/visualization/include/pcl/visualization/interactor.h @@ -34,8 +34,8 @@ * $Id: interactor.h 2050 2011-08-12 15:26:19Z bouffa $ * */ -#ifndef PCL_PCL_VISUALIZER_INTERACTOR_H_ -#define PCL_PCL_VISUALIZER_INTERACTOR_H_ + +#pragma once #include @@ -103,5 +103,3 @@ namespace pcl }; } } - -#endif diff --git a/visualization/include/pcl/visualization/interactor_style.h b/visualization/include/pcl/visualization/interactor_style.h index f3b3d24be43..f9dbfb5c159 100644 --- a/visualization/include/pcl/visualization/interactor_style.h +++ b/visualization/include/pcl/visualization/interactor_style.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_PCL_VISUALIZER_INTERACTOR_STYLE_H_ -#define PCL_PCL_VISUALIZER_INTERACTOR_STYLE_H_ + +#pragma once #include #include @@ -439,5 +439,3 @@ namespace pcl }; } } - -#endif diff --git a/visualization/include/pcl/visualization/keyboard_event.h b/visualization/include/pcl/visualization/keyboard_event.h index 00ff6c0696b..042381893bd 100644 --- a/visualization/include/pcl/visualization/keyboard_event.h +++ b/visualization/include/pcl/visualization/keyboard_event.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_VISUALIZATION_KEYBOARD_EVENT_H_ -#define PCL_VISUALIZATION_KEYBOARD_EVENT_H_ +#pragma once #include @@ -177,6 +176,3 @@ namespace pcl } } // namespace visualization } // namespace pcl - -#endif /* PCL_VISUALIZATION_KEYBOARD_EVENT_H_ */ - diff --git a/visualization/include/pcl/visualization/mouse_event.h b/visualization/include/pcl/visualization/mouse_event.h index b4184dce00e..5a0e0771b29 100644 --- a/visualization/include/pcl/visualization/mouse_event.h +++ b/visualization/include/pcl/visualization/mouse_event.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_VISUALIZATION_MOUSE_EVENT_H_ -#define PCL_VISUALIZATION_MOUSE_EVENT_H_ +#pragma once #include @@ -208,6 +207,3 @@ namespace pcl } //namespace visualization } //namespace pcl - -#endif /* PCL_VISUALIZATION_MOUSE_EVENT_H_ */ - diff --git a/visualization/include/pcl/visualization/pcl_painter2D.h b/visualization/include/pcl/visualization/pcl_painter2D.h index d7cf85a7779..3c4795b714c 100644 --- a/visualization/include/pcl/visualization/pcl_painter2D.h +++ b/visualization/include/pcl/visualization/pcl_painter2D.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_VISUALUALIZATION_PCL_PAINTER2D_H_ -#define PCL_VISUALUALIZATION_PCL_PAINTER2D_H_ +#pragma once #include #include @@ -466,6 +465,3 @@ namespace pcl } } - -#endif /* PCL_VISUALUALIZATION_PCL_PAINTER2D_H_ */ - diff --git a/visualization/include/pcl/visualization/pcl_plotter.h b/visualization/include/pcl/visualization/pcl_plotter.h index 6b5f1e79f34..759b07f388e 100644 --- a/visualization/include/pcl/visualization/pcl_plotter.h +++ b/visualization/include/pcl/visualization/pcl_plotter.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_VISUALUALIZATION_PCL_PLOTTER_H_ -#define PCL_VISUALUALIZATION_PCL_PLOTTER_H_ + +#pragma once #include #include @@ -474,6 +474,3 @@ namespace pcl } #include - -#endif /* PCL_VISUALUALIZATION_PCL_PLOTTER_H_ */ - diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 3ae9a8d6f1f..5e6f340c2bc 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_PCL_VISUALIZER_H_ -#define PCL_PCL_VISUALIZER_H_ + +#pragma once // PCL includes #include @@ -2350,6 +2350,3 @@ namespace pcl } #include - -#endif - diff --git a/visualization/include/pcl/visualization/point_cloud_color_handlers.h b/visualization/include/pcl/visualization/point_cloud_color_handlers.h index 2ff26385a9c..b4d8f76f2e8 100644 --- a/visualization/include/pcl/visualization/point_cloud_color_handlers.h +++ b/visualization/include/pcl/visualization/point_cloud_color_handlers.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_POINT_CLOUD_COLOR_HANDLERS_H_ -#define PCL_POINT_CLOUD_COLOR_HANDLERS_H_ + +#pragma once #if defined __GNUC__ #pragma GCC system_header @@ -946,6 +946,3 @@ namespace pcl } #include - -#endif // PCL_POINT_CLOUD_COLOR_HANDLERS_H_ - diff --git a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h index 9c6fecd211d..aad3d0ce260 100644 --- a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h +++ b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_ -#define PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_ + +#pragma once #if defined __GNUC__ #pragma GCC system_header @@ -497,6 +497,3 @@ namespace pcl #ifdef PCL_NO_PRECOMPILE #include #endif - -#endif // PCL_POINT_CLOUD_GEOMETRY_HANDLERS_H_ - diff --git a/visualization/include/pcl/visualization/point_cloud_handlers.h b/visualization/include/pcl/visualization/point_cloud_handlers.h index ec42da5aee8..3edc43c6b05 100644 --- a/visualization/include/pcl/visualization/point_cloud_handlers.h +++ b/visualization/include/pcl/visualization/point_cloud_handlers.h @@ -35,10 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_POINT_CLOUD_HANDLERS_H_ -#define PCL_POINT_CLOUD_HANDLERS_H_ + +#pragma once #include #include - -#endif diff --git a/visualization/include/pcl/visualization/point_picking_event.h b/visualization/include/pcl/visualization/point_picking_event.h index 7506bc84269..dc64c739e06 100644 --- a/visualization/include/pcl/visualization/point_picking_event.h +++ b/visualization/include/pcl/visualization/point_picking_event.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_VISUALIZATION_POINT_PICKING_EVENT_H_ -#define PCL_VISUALIZATION_POINT_PICKING_EVENT_H_ +#pragma once #include #include @@ -162,6 +161,3 @@ namespace pcl }; } //namespace visualization } //namespace pcl - -#endif /* PCL_VISUALIZATION_POINT_PICKING_EVENT_H_ */ - diff --git a/visualization/include/pcl/visualization/range_image_visualizer.h b/visualization/include/pcl/visualization/range_image_visualizer.h index dc5305f396c..4a4ad1624f7 100644 --- a/visualization/include/pcl/visualization/range_image_visualizer.h +++ b/visualization/include/pcl/visualization/range_image_visualizer.h @@ -34,12 +34,10 @@ * */ -#include - -#ifndef PCL_VISUALIZATION_RANGE_IMAGE_VISUALIZER_H_ -#define PCL_VISUALIZATION_RANGE_IMAGE_VISUALIZER_H_ +#pragma once // PCL includes +#include #include #include @@ -113,5 +111,3 @@ namespace pcl }; } } - -#endif //#define PCL_VISUALIZATION_RANGE_IMAGE_VISUALIZER_H_ diff --git a/visualization/include/pcl/visualization/registration_visualizer.h b/visualization/include/pcl/visualization/registration_visualizer.h index 2b4f6080216..6bd9e0ebe13 100644 --- a/visualization/include/pcl/visualization/registration_visualizer.h +++ b/visualization/include/pcl/visualization/registration_visualizer.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_REGISTRATION_VISUALIZER_H_ -#define PCL_REGISTRATION_VISUALIZER_H_ +#pragma once // PCL #include @@ -206,5 +205,3 @@ namespace pcl } #include - -#endif //#ifndef PCL_REGISTRATION_VISUALIZER_H_ diff --git a/visualization/include/pcl/visualization/simple_buffer_visualizer.h b/visualization/include/pcl/visualization/simple_buffer_visualizer.h index d340a50db78..364a558201f 100644 --- a/visualization/include/pcl/visualization/simple_buffer_visualizer.h +++ b/visualization/include/pcl/visualization/simple_buffer_visualizer.h @@ -1,5 +1,4 @@ -#ifndef PCL_VISUALIZATION_SIMPLE_BUFF_H -#define PCL_VISUALIZATION_SIMPLE_BUFF_H +#pragma once #include @@ -224,5 +223,3 @@ namespace pcl }; } } - -#endif // PCL_VISUALIZATION_SIMPLE_BUFF_H diff --git a/visualization/include/pcl/visualization/vtk.h b/visualization/include/pcl/visualization/vtk.h index a6bb848ec22..022137d97a2 100644 --- a/visualization/include/pcl/visualization/vtk.h +++ b/visualization/include/pcl/visualization/vtk.h @@ -37,8 +37,8 @@ * $Id$ * */ -#ifndef PCL_PCL_VISUALIZER_VTK_H_ -#define PCL_PCL_VISUALIZER_VTK_H_ + +#pragma once #if defined __GNUC__ #pragma GCC system_header @@ -183,6 +183,3 @@ #define __DEPRECATED #undef __DEPRECATED_DISABLED__ #endif - -#endif // PCL_PCL_VISUALIZER_VTK_H_ - diff --git a/visualization/include/pcl/visualization/vtk/pcl_context_item.h b/visualization/include/pcl/visualization/vtk/pcl_context_item.h index cabc3ddc6f5..452f7792770 100644 --- a/visualization/include/pcl/visualization/vtk/pcl_context_item.h +++ b/visualization/include/pcl/visualization/vtk/pcl_context_item.h @@ -35,8 +35,7 @@ * */ -#ifndef PCL_VISUALIZATION_PCL_CONTEXT_ITEM_H_ -#define PCL_VISUALIZATION_PCL_CONTEXT_ITEM_H_ +#pragma once #include #include @@ -170,5 +169,3 @@ namespace pcl } } } - -#endif diff --git a/visualization/include/pcl/visualization/vtk/pcl_image_canvas_source_2d.h b/visualization/include/pcl/visualization/vtk/pcl_image_canvas_source_2d.h index 3f790124fc0..d3324b5f323 100644 --- a/visualization/include/pcl/visualization/vtk/pcl_image_canvas_source_2d.h +++ b/visualization/include/pcl/visualization/vtk/pcl_image_canvas_source_2d.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_VTK_IMAGE_CANVAS_SOURCE_2D_H_ -#define PCL_VTK_IMAGE_CANVAS_SOURCE_2D_H_ + +#pragma once #include #include @@ -58,5 +58,3 @@ namespace pcl }; } } - -#endif // PCL_VTK_IMAGE_CANVAS_SOURCE_2D_H_ diff --git a/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h b/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h index a2bf54bf358..b427e76d9d3 100644 --- a/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h +++ b/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h @@ -34,12 +34,9 @@ * POSSIBILITY OF SUCH DAMAGE. * */ -#ifndef PCL_VISUALIZATION_VTK_RENDER_WINDOW_FIX_H_ -#define PCL_VISUALIZATION_VTK_RENDER_WINDOW_FIX_H_ + +#pragma once #include vtkRenderWindowInteractor* vtkRenderWindowInteractorFixNew (); - -#endif // PCL_VISUALIZATION_VTK_RENDER_WINDOW_FIX_H_ - diff --git a/visualization/include/pcl/visualization/window.h b/visualization/include/pcl/visualization/window.h index c434343b072..cb13fd51a6c 100644 --- a/visualization/include/pcl/visualization/window.h +++ b/visualization/include/pcl/visualization/window.h @@ -36,8 +36,7 @@ * */ -#ifndef PCL_VISUALIZER_WINDOW_H__ -#define PCL_VISUALIZER_WINDOW_H__ +#pragma once #include #include @@ -228,6 +227,3 @@ namespace pcl }; } } - -#endif /* __WINDOW_H__ */ -