.. _program_listing_file__tmp_ws_src_rtabmap_ros_rtabmap_odom_include_rtabmap_odom_rgbd_odometry.hpp: Program Listing for File rgbd_odometry.hpp ========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/rtabmap_ros/rtabmap_odom/include/rtabmap_odom/rgbd_odometry.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 "rclcpp/rclcpp.hpp" #include #include #include #include #include #include #include #include #include #include #include namespace rtabmap_odom { class RGBDOdometry : public rtabmap_odom::OdometryROS { public: RTABMAP_ODOM_PUBLIC explicit RGBDOdometry(const rclcpp::NodeOptions & options); virtual ~RGBDOdometry(); private: virtual void updateParameters(rtabmap::ParametersMap & parameters); virtual void onOdomInit(); void commonCallback( const std::vector & rgbImages, const std::vector & depthImages, const std::vector& cameraInfos); void callback( const sensor_msgs::msg::Image::ConstSharedPtr image, const sensor_msgs::msg::Image::ConstSharedPtr depth, const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfo); void callbackRGBDX( const rtabmap_msgs::msg::RGBDImages::ConstSharedPtr images); void callbackRGBD( const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image); void callbackRGBD2( const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image2); void callbackRGBD3( const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image2, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image3); void callbackRGBD4( const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image2, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image3, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image4); void callbackRGBD5( const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image2, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image3, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image4, const rtabmap_msgs::msg::RGBDImage::ConstSharedPtr image5); protected: virtual void flushCallbacks(); private: image_transport::SubscriberFilter image_mono_sub_; image_transport::SubscriberFilter image_depth_sub_; message_filters::Subscriber info_sub_; rclcpp::Subscription::SharedPtr rgbdSub_; rclcpp::Subscription::SharedPtr rgbdxSub_; message_filters::Subscriber rgbd_image1_sub_; message_filters::Subscriber rgbd_image2_sub_; message_filters::Subscriber rgbd_image3_sub_; message_filters::Subscriber rgbd_image4_sub_; message_filters::Subscriber rgbd_image5_sub_; typedef message_filters::sync_policies::ApproximateTime MyApproxSyncPolicy; message_filters::Synchronizer * approxSync_; typedef message_filters::sync_policies::ExactTime MyExactSyncPolicy; message_filters::Synchronizer * exactSync_; typedef message_filters::sync_policies::ApproximateTime MyApproxSync2Policy; message_filters::Synchronizer * approxSync2_; typedef message_filters::sync_policies::ExactTime MyExactSync2Policy; message_filters::Synchronizer * exactSync2_; typedef message_filters::sync_policies::ApproximateTime MyApproxSync3Policy; message_filters::Synchronizer * approxSync3_; typedef message_filters::sync_policies::ExactTime MyExactSync3Policy; message_filters::Synchronizer * exactSync3_; typedef message_filters::sync_policies::ApproximateTime MyApproxSync4Policy; message_filters::Synchronizer * approxSync4_; typedef message_filters::sync_policies::ExactTime MyExactSync4Policy; message_filters::Synchronizer * exactSync4_; typedef message_filters::sync_policies::ApproximateTime MyApproxSync5Policy; message_filters::Synchronizer * approxSync5_; typedef message_filters::sync_policies::ExactTime MyExactSync5Policy; message_filters::Synchronizer * exactSync5_; int queueSize_; bool keepColor_; }; }