15#ifndef CARMA_COOPERATIVE_PERCEPTION__EXTERNAL_OBJECT_LIST_TO_SDSM_COMPONENT_HPP_ 
   16#define CARMA_COOPERATIVE_PERCEPTION__EXTERNAL_OBJECT_LIST_TO_SDSM_COMPONENT_HPP_ 
   18#include <carma_perception_msgs/msg/external_object_list.hpp> 
   19#include <carma_ros2_utils/carma_lifecycle_node.hpp> 
   20#include <carma_v2x_msgs/msg/sensor_data_sharing_message.hpp> 
   21#include <rclcpp/rclcpp.hpp> 
   22#include <std_msgs/msg/string.hpp> 
   24#include <geometry_msgs/msg/pose_stamped.hpp> 
   26#include <lanelet2_core/geometry/Lanelet.h> 
   27#include <lanelet2_extension/projection/local_frame_projector.h> 
   46    -> carma_ros2_utils::CallbackReturn 
override;
 
   49    -> carma_ros2_utils::CallbackReturn 
override;
 
   52    -> carma_ros2_utils::CallbackReturn 
override;
 
   61  rclcpp_lifecycle::LifecyclePublisher<sdsm_msg_type>::SharedPtr 
sdsm_publisher_{
nullptr};
 
   70  std::shared_ptr<lanelet::projection::LocalFrameProjector> 
map_projector_{
nullptr};
 
ExternalObjectListToSdsmNode(const rclcpp::NodeOptions &options)
std_msgs::msg::String georeference_msg_type
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_
carma_perception_msgs::msg::ExternalObjectList external_objects_msg_type
auto update_current_pose(const pose_msg_type &pose) -> void
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_
geometry_msgs::msg::PoseStamped pose_msg_type
std::string map_georeference_
auto publish_as_sdsm(const external_objects_msg_type &msg) const -> void
auto handle_on_shutdown(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
geometry_msgs::msg::PoseStamped current_pose_
auto handle_on_cleanup(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
rclcpp::Subscription< external_objects_msg_type >::SharedPtr external_objects_subscription_
rclcpp::Subscription< georeference_msg_type >::SharedPtr georeference_subscription_
auto handle_on_configure(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
rclcpp::Subscription< pose_msg_type >::SharedPtr current_pose_subscription_
carma_v2x_msgs::msg::SensorDataSharingMessage sdsm_msg_type
auto update_georeference(const georeference_msg_type &proj_string) -> void
rclcpp_lifecycle::LifecyclePublisher< sdsm_msg_type >::SharedPtr sdsm_publisher_