.. _program_listing_file__tmp_ws_src_rtabmap_ros_rtabmap_util_include_rtabmap_util_point_cloud_xyz.hpp: Program Listing for File point_cloud_xyz.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/rtabmap_ros/rtabmap_util/include/rtabmap_util/point_cloud_xyz.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the Universite de Sherbrooke nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ #include #include "rclcpp/rclcpp.hpp" #include #include #include #include #include #include #include #include #include #include #include #include namespace rtabmap_util { class PointCloudXYZ : public rclcpp::Node { public: RTABMAP_UTIL_PUBLIC explicit PointCloudXYZ(const rclcpp::NodeOptions & options); virtual ~PointCloudXYZ(); private: void callback( const sensor_msgs::msg::Image::ConstSharedPtr depth, const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfo); void callbackDisparity( const stereo_msgs::msg::DisparityImage::ConstSharedPtr disparityMsg, const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfo); void processAndPublish(pcl::PointCloud::Ptr & pclCloud, pcl::IndicesPtr & indices, const std_msgs::msg::Header & header); private: double maxDepth_; double minDepth_; double voxelSize_; int decimation_; double noiseFilterRadius_; int noiseFilterMinNeighbors_; int normalK_; double normalRadius_; bool filterNaNs_; std::vector roiRatios_; rclcpp::Publisher::SharedPtr cloudPub_; image_transport::SubscriberFilter imageDepthSub_; message_filters::Subscriber cameraInfoSub_; message_filters::Subscriber disparitySub_; message_filters::Subscriber disparityCameraInfoSub_; typedef message_filters::sync_policies::ApproximateTime MyApproxSyncDepthPolicy; message_filters::Synchronizer * approxSyncDepth_; typedef message_filters::sync_policies::ApproximateTime MyApproxSyncDisparityPolicy; message_filters::Synchronizer * approxSyncDisparity_; typedef message_filters::sync_policies::ExactTime MyExactSyncDepthPolicy; message_filters::Synchronizer * exactSyncDepth_; typedef message_filters::sync_policies::ExactTime MyExactSyncDisparityPolicy; message_filters::Synchronizer * exactSyncDisparity_; }; }