.. _program_listing_file__tmp_ws_src_transport_drivers_udp_driver_include_udp_driver_udp_receiver_node.hpp: Program Listing for File udp_receiver_node.hpp ============================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/transport_drivers/udp_driver/include/udp_driver/udp_receiver_node.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 LeoDrive, Copyright 2021 the Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef UDP_DRIVER__UDP_RECEIVER_NODE_HPP_ #define UDP_DRIVER__UDP_RECEIVER_NODE_HPP_ #include "udp_driver/udp_driver.hpp" #include #include #include #include #include #include #include #include "msg_converters/converters.hpp" namespace lc = rclcpp_lifecycle; using LNI = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface; namespace drivers { namespace udp_driver { class UdpReceiverNode final : public lc::LifecycleNode { public: explicit UdpReceiverNode(const rclcpp::NodeOptions & options); UdpReceiverNode( const rclcpp::NodeOptions &, const IoContext & ctx); ~UdpReceiverNode(); LNI::CallbackReturn on_configure(const lc::State & state) override; LNI::CallbackReturn on_activate(const lc::State & state) override; LNI::CallbackReturn on_deactivate(const lc::State & state) override; LNI::CallbackReturn on_cleanup(const lc::State & state) override; LNI::CallbackReturn on_shutdown(const lc::State & state) override; void receiver_callback(const std::vector & buffer); private: void get_params(); std::unique_ptr m_owned_ctx{}; std::string m_ip{}; uint16_t m_port{}; std::unique_ptr m_udp_driver; lc::LifecyclePublisher::SharedPtr m_publisher; }; // class UdpReceiverNode } // namespace udp_driver } // namespace drivers #endif // UDP_DRIVER__UDP_RECEIVER_NODE_HPP_