.. _program_listing_file__tmp_ws_src_mola_mola_input_ros2_include_mola_input_ros2_InputROS2.h: Program Listing for File InputROS2.h ==================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/mola/mola_input_ros2/include/mola_input_ros2/InputROS2.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* ------------------------------------------------------------------------- * A Modular Optimization framework for Localization and mApping (MOLA) * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria * See LICENSE for license information. * ------------------------------------------------------------------------- */ #pragma once #include #include #include #include #include #include #include namespace mola { class InputROS2 : public RawDataSourceBase { DEFINE_MRPT_OBJECT(InputROS2, mola) public: InputROS2(); ~InputROS2() override = default; // See docs in base class void initialize(const Yaml& cfg) override; void spinOnce() override; private: std::thread rosNodeThread_; struct Params { std::string base_link_frame = "base_footprint"; std::string odom_frame = "odom"; bool publish_odometry_from_tf = false; int wait_for_tf_timeout_milliseconds = 100; }; Params params_; // Yaml is NOT a reference on purpose. void ros_node_thread_main(Yaml cfg); std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; rclcpp::Clock::SharedPtr ros_clock_; std::mutex ros_clock_mtx_; std::vector::SharedPtr> subsPointCloud_; std::vector::SharedPtr> subsLaserScan_; std::vector::SharedPtr> subsOdometry_; void callbackOnPointCloud2( const sensor_msgs::msg::PointCloud2& o, const std::string& outSensorLabel, const std::optional& fixedSensorPose); void callbackOnLaserScan( const sensor_msgs::msg::LaserScan& o, const std::string& outSensorLabel, const std::optional& fixedSensorPose); void callbackOnOdometry( const nav_msgs::msg::Odometry& o, const std::string& outSensorLabel); bool waitForTransform( mrpt::poses::CPose3D& des, const std::string& target_frame, const std::string& source_frame, const rclcpp::Time& time, const int timeoutMilliseconds, bool printErrors); void publishOdometry(); }; } // namespace mola