.. _program_listing_file__tmp_ws_src_webots_ros2_webots_ros2_driver_include_webots_ros2_driver_plugins_static_Ros2Receiver.hpp: Program Listing for File Ros2Receiver.hpp ========================================= |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/webots_ros2/webots_ros2_driver/include/webots_ros2_driver/plugins/static/Ros2Receiver.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef ROS2_RECEIVER_HPP #define ROS2_RECEIVER_HPP #include #include #include #include #include namespace webots_ros2_driver { class Ros2Receiver : public Ros2SensorPlugin { public: void step() override; void init(webots_ros2_driver::WebotsNode *node, std::unordered_map ¶meters) override; private: bool mustPublish(); void publishData(); // ROS2 topics rclcpp::Publisher::SharedPtr mDataPublisher; webots_ros2_msgs::msg::StringStamped mDataMessage; rclcpp::Publisher::SharedPtr mSignalPublisher; webots_ros2_msgs::msg::FloatStamped mSignalMessage; rclcpp::Publisher::SharedPtr mDirectionPublisher; geometry_msgs::msg::Vector3Stamped mDirectionMessage; // Device WbDeviceTag mReceiver; // Runtime vars std::string mDeviceName; int mDeviceChannel; bool mIsEnabled; }; } // namespace webots_ros2_driver #endif