15#ifndef CARMA_COOPERATIVE_PERCEPTION__TRACK_LIST_TO_EXTERNAL_OBJECT_LIST_COMPONENT_HPP_
16#define CARMA_COOPERATIVE_PERCEPTION__TRACK_LIST_TO_EXTERNAL_OBJECT_LIST_COMPONENT_HPP_
20#include <carma_cooperative_perception_interfaces/msg/track_list.hpp>
21#include <carma_perception_msgs/msg/external_object_list.hpp>
22#include <carma_ros2_utils/carma_lifecycle_node.hpp>
23#include <rclcpp/rclcpp.hpp>
24#include <std_msgs/msg/string.hpp>
38 -> carma_ros2_utils::CallbackReturn
override;
41 -> carma_ros2_utils::CallbackReturn
override;
44 -> carma_ros2_utils::CallbackReturn
override;
47 const carma_cooperative_perception_interfaces::msg::TrackList & msg)
const -> void;
50 rclcpp_lifecycle::LifecyclePublisher<carma_perception_msgs::msg::ExternalObjectList>::SharedPtr
52 rclcpp::Subscription<carma_cooperative_perception_interfaces::msg::TrackList>::SharedPtr
rclcpp_lifecycle::LifecyclePublisher< carma_perception_msgs::msg::ExternalObjectList >::SharedPtr publisher_
auto handle_on_cleanup(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
auto handle_on_shutdown(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
rclcpp::Subscription< carma_cooperative_perception_interfaces::msg::TrackList >::SharedPtr track_list_subscription_
auto publish_as_external_object_list(const carma_cooperative_perception_interfaces::msg::TrackList &msg) const -> void
std::string map_georeference_
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_
auto handle_on_configure(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
TrackListToExternalObjectListNode(const rclcpp::NodeOptions &options)