.. _program_listing_file__tmp_ws_src_rtabmap_ros_include_rtabmap_ros_pointcloud_to_depthimage.hpp: Program Listing for File pointcloud_to_depthimage.hpp ===================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/rtabmap_ros/include/rtabmap_ros/pointcloud_to_depthimage.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 namespace rtabmap_ros { class PointCloudToDepthImage : public rclcpp::Node { public: RTABMAP_ROS_PUBLIC explicit PointCloudToDepthImage(const rclcpp::NodeOptions & options); virtual ~PointCloudToDepthImage(); private: void callback( const sensor_msgs::msg::PointCloud2::ConstSharedPtr pointCloud2Msg, const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg); private: image_transport::CameraPublisher depthImage16Pub_; image_transport::CameraPublisher depthImage32Pub_; rclcpp::Publisher::SharedPtr cameraInfo16Pub_; rclcpp::Publisher::SharedPtr cameraInfo32Pub_; rclcpp::Publisher::SharedPtr pointCloudTransformedPub_; message_filters::Subscriber pointCloudSub_; message_filters::Subscriber cameraInfoSub_; std::string fixedFrameId_; std::shared_ptr tfBuffer_; std::shared_ptr tfListener_; double waitForTransform_; int fillHolesSize_; double fillHolesError_; int fillIterations_; int decimation_; bool upscale_; double upscaleDepthErrorRatio_; typedef message_filters::sync_policies::ApproximateTime MyApproxSyncPolicy; message_filters::Synchronizer * approxSync_; typedef message_filters::sync_policies::ExactTime MyExactSyncPolicy; message_filters::Synchronizer * exactSync_; }; }