15#ifndef CARMA_COOPERATIVE_PERCEPTION__EXTERNAL_OBJECT_LIST_TO_DETECTION_LIST_COMPONENT_HPP_
16#define CARMA_COOPERATIVE_PERCEPTION__EXTERNAL_OBJECT_LIST_TO_DETECTION_LIST_COMPONENT_HPP_
20#include <carma_cooperative_perception_interfaces/msg/detection_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>
26#include <gsl/pointers>
35 carma_cooperative_perception_interfaces::msg::DetectionList detection_list,
36 const std::string & map_origin) -> carma_cooperative_perception_interfaces::msg::DetectionList;
42 using output_msg_type = carma_cooperative_perception_interfaces::msg::DetectionList;
48 -> carma_ros2_utils::CallbackReturn
override;
51 -> carma_ros2_utils::CallbackReturn
override;
54 -> carma_ros2_utils::CallbackReturn
override;
61 rclcpp_lifecycle::LifecyclePublisher<output_msg_type>::SharedPtr
publisher_{
nullptr};
carma_cooperative_perception_interfaces::msg::DetectionList output_msg_type
auto handle_on_cleanup(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
auto handle_on_configure(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
auto update_georeference(const std_msgs::msg::String &msg) -> void
auto handle_on_shutdown(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
carma_perception_msgs::msg::ExternalObjectList input_msg_type
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_
typename input_msg_type::SharedPtr input_msg_shared_pointer
rclcpp_lifecycle::LifecyclePublisher< output_msg_type >::SharedPtr publisher_
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr georeference_subscription_
std::string map_georeference_
ExternalObjectListToDetectionListNode(const rclcpp::NodeOptions &options)
rclcpp::Subscription< input_msg_type >::SharedPtr external_objects_subscription_
MotionModelMapping motion_model_mapping_
auto publish_as_detection_list(const input_msg_type &msg) const -> void
auto transform_from_map_to_utm(carma_cooperative_perception_interfaces::msg::DetectionList detection_list, const std::string &map_origin) -> carma_cooperative_perception_interfaces::msg::DetectionList