.. _program_listing_file__tmp_ws_src_rtabmap_ros_rtabmap_util_include_rtabmap_util_point_cloud_assembler.hpp: Program Listing for File point_cloud_assembler.hpp ================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/rtabmap_ros/rtabmap_util/include/rtabmap_util/point_cloud_assembler.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* Copyright (c) 2010-2019, 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_util { class PointCloudAssembler : public rclcpp::Node { public: RTABMAP_UTIL_PUBLIC explicit PointCloudAssembler(const rclcpp::NodeOptions & options); virtual ~PointCloudAssembler(); private: void callbackCloudOdomInfo( const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloudMsg, const nav_msgs::msg::Odometry::ConstSharedPtr odomMsg, const rtabmap_msgs::msg::OdomInfo::ConstSharedPtr odomInfoMsg); void callbackCloudOdom( const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloudMsg, const nav_msgs::msg::Odometry::ConstSharedPtr odomMsg); void callbackCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloudMsg); private: std::thread * warningThread_; bool callbackCalled_; rclcpp::Subscription::SharedPtr cloudSub_; rclcpp::Publisher::SharedPtr cloudPub_; typedef message_filters::sync_policies::ExactTime syncPolicy; typedef message_filters::sync_policies::ExactTime syncInfoPolicy; message_filters::Synchronizer* exactSync_; message_filters::Synchronizer* exactInfoSync_; message_filters::Subscriber syncCloudSub_; message_filters::Subscriber syncOdomSub_; message_filters::Subscriber syncOdomInfoSub_; int maxClouds_; int skipClouds_; int cloudsSkipped_; bool circularBuffer_; double linearUpdate_; double angularUpdate_; double assemblingTime_; double waitForTransform_; double rangeMin_; double rangeMax_; double voxelSize_; double noiseRadius_; int noiseMinNeighbors_; bool removeZ_; std::string fixedFrameId_; std::string frameId_; std::shared_ptr tfBuffer_; std::shared_ptr tfListener_; rtabmap::Transform previousPose_; std::list clouds_; std::string subscribedTopicsMsg_; }; }