Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
carma_cooperative_perception::ExternalObjectListToSdsmNode Class Reference

#include <external_object_list_to_sdsm_component.hpp>

Inheritance diagram for carma_cooperative_perception::ExternalObjectListToSdsmNode:
Inheritance graph
Collaboration diagram for carma_cooperative_perception::ExternalObjectListToSdsmNode:
Collaboration graph

Public Member Functions

 ExternalObjectListToSdsmNode (const rclcpp::NodeOptions &options)
 
auto handle_on_configure (const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
 
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
 
auto publish_as_sdsm (const external_objects_msg_type &msg) const -> void
 
auto update_georeference (const georeference_msg_type &proj_string) -> void
 
auto update_current_pose (const pose_msg_type &pose) -> void
 

Private Types

using sdsm_msg_type = carma_v2x_msgs::msg::SensorDataSharingMessage
 
using external_objects_msg_type = carma_perception_msgs::msg::ExternalObjectList
 
using georeference_msg_type = std_msgs::msg::String
 
using pose_msg_type = geometry_msgs::msg::PoseStamped
 

Private Attributes

rclcpp_lifecycle::LifecyclePublisher< sdsm_msg_type >::SharedPtr sdsm_publisher_ {nullptr}
 
rclcpp::Subscription< external_objects_msg_type >::SharedPtr external_objects_subscription_
 
rclcpp::Subscription< georeference_msg_type >::SharedPtr georeference_subscription_ {nullptr}
 
rclcpp::Subscription< pose_msg_type >::SharedPtr current_pose_subscription_ {nullptr}
 
std::string map_georeference_ {""}
 
geometry_msgs::msg::PoseStamped current_pose_
 
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_ {nullptr}
 
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_ {nullptr}
 

Detailed Description

Definition at line 34 of file external_object_list_to_sdsm_component.hpp.

Member Typedef Documentation

◆ external_objects_msg_type

using carma_cooperative_perception::ExternalObjectListToSdsmNode::external_objects_msg_type = carma_perception_msgs::msg::ExternalObjectList
private

Definition at line 37 of file external_object_list_to_sdsm_component.hpp.

◆ georeference_msg_type

◆ pose_msg_type

using carma_cooperative_perception::ExternalObjectListToSdsmNode::pose_msg_type = geometry_msgs::msg::PoseStamped
private

Definition at line 40 of file external_object_list_to_sdsm_component.hpp.

◆ sdsm_msg_type

using carma_cooperative_perception::ExternalObjectListToSdsmNode::sdsm_msg_type = carma_v2x_msgs::msg::SensorDataSharingMessage
private

Definition at line 36 of file external_object_list_to_sdsm_component.hpp.

Constructor & Destructor Documentation

◆ ExternalObjectListToSdsmNode()

carma_cooperative_perception::ExternalObjectListToSdsmNode::ExternalObjectListToSdsmNode ( const rclcpp::NodeOptions &  options)
explicit

Definition at line 25 of file external_object_list_to_sdsm_component.cpp.

26: CarmaLifecycleNode{options}
27{
28 lifecycle_publishers_.push_back(sdsm_publisher_);
29 param_callback_handles_.push_back(on_set_parameters_callback_);
30}
rclcpp_lifecycle::LifecyclePublisher< sdsm_msg_type >::SharedPtr sdsm_publisher_

References on_set_parameters_callback_, and sdsm_publisher_.

Member Function Documentation

◆ handle_on_cleanup()

auto carma_cooperative_perception::ExternalObjectListToSdsmNode::handle_on_cleanup ( const rclcpp_lifecycle::State &  ) -> carma_ros2_utils::CallbackReturn
override

Definition at line 90 of file external_object_list_to_sdsm_component.cpp.

92{
93 RCLCPP_INFO(get_logger(), "Life cycle state transition: cleaning up");
94
95 sdsm_publisher_.reset();
98
100
101 return carma_ros2_utils::CallbackReturn::SUCCESS;
102}
rclcpp::Subscription< external_objects_msg_type >::SharedPtr external_objects_subscription_
rclcpp::Subscription< georeference_msg_type >::SharedPtr georeference_subscription_

◆ handle_on_configure()

auto carma_cooperative_perception::ExternalObjectListToSdsmNode::handle_on_configure ( const rclcpp_lifecycle::State &  ) -> carma_ros2_utils::CallbackReturn
override

Definition at line 32 of file external_object_list_to_sdsm_component.cpp.

34{
35 RCLCPP_INFO(get_logger(), "Life cycle state transition: configuring");
36
37 sdsm_publisher_ = create_publisher<sdsm_msg_type>("output/sdsms", 1);
38
39 external_objects_subscription_ = create_subscription<external_objects_msg_type>(
40 "input/external_objects", 1, [this](const external_objects_msg_type::SharedPtr msg_ptr) {
41 const auto current_state{this->get_current_state().label()};
42
43 if (current_state == "active") {
44 publish_as_sdsm(*msg_ptr);
45 } else {
46 RCLCPP_WARN(
47 this->get_logger(),
48 "Trying to receive message on the topic '%s', but the containing node is not activated. "
49 "Current node state: '%s'",
50 this->georeference_subscription_->get_topic_name(), current_state.c_str());
51 }
52 });
53
54 georeference_subscription_ = create_subscription<georeference_msg_type>(
55 "input/georeference", 1, [this](const georeference_msg_type::SharedPtr msg_ptr) {
56 const auto current_state{this->get_current_state().label()};
57
58 if (current_state == "active") {
59 update_georeference(*msg_ptr);
60 } else {
61 RCLCPP_WARN(
62 this->get_logger(),
63 "Trying to receive message on the topic '%s', but the containing node is not "
64 "activated. "
65 "Current node state: '%s'",
66 this->georeference_subscription_->get_topic_name(), current_state.c_str());
67 }
68 });
69
70 current_pose_subscription_ = create_subscription<pose_msg_type>(
71 "input/pose_stamped", 1, [this](const pose_msg_type::SharedPtr msg_ptr) {
72 const auto current_state{this->get_current_state().label()};
73
74 if (current_state == "active") {
75 update_current_pose(*msg_ptr);
76 } else {
77 RCLCPP_WARN(
78 this->get_logger(),
79 "Trying to recieve message on topic '%s', but the containing node is not activated."
80 "current node state: '%s'",
81 this->current_pose_subscription_->get_topic_name(), current_state.c_str());
82 }
83 });
84
85 RCLCPP_INFO(get_logger(), "Lifecycle transition: successfully configured");
86
87 return carma_ros2_utils::CallbackReturn::SUCCESS;
88}
auto publish_as_sdsm(const external_objects_msg_type &msg) const -> void
auto update_georeference(const georeference_msg_type &proj_string) -> void

◆ handle_on_shutdown()

auto carma_cooperative_perception::ExternalObjectListToSdsmNode::handle_on_shutdown ( const rclcpp_lifecycle::State &  ) -> carma_ros2_utils::CallbackReturn
override

Definition at line 104 of file external_object_list_to_sdsm_component.cpp.

106{
107 RCLCPP_INFO(get_logger(), "Life cycle state transition: shutting down");
108
109 sdsm_publisher_.reset();
112
114
115 return carma_ros2_utils::CallbackReturn::SUCCESS;
116}

◆ publish_as_sdsm()

auto carma_cooperative_perception::ExternalObjectListToSdsmNode::publish_as_sdsm ( const external_objects_msg_type msg) const -> void

Definition at line 118 of file external_object_list_to_sdsm_component.cpp.

120{
121 if (!map_projector_) {
122 // Set to DEBUG level because this node may start up before any georeference publisher. In that
123 // scenario, temporarily not having a georeference (and therefore, no projector) is expected.
124 RCLCPP_DEBUG(
125 this->get_logger(), "Could not convert external object list to SDSM: unknown georeference");
126
127 return;
128 }
129
130 try {
131 const auto sdsm_output{to_sdsm_msg(msg, current_pose_, map_projector_)};
132
133 sdsm_publisher_->publish(sdsm_output);
134 } catch (const std::invalid_argument & e) {
135 RCLCPP_ERROR(
136 this->get_logger(), "Could not convert external object list to SDSM: %s", e.what());
137 }
138}
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_
auto to_sdsm_msg(const carma_perception_msgs::msg::ExternalObjectList &external_object_list, const geometry_msgs::msg::PoseStamped &current_pose, const std::shared_ptr< lanelet::projection::LocalFrameProjector > &map_projection) -> carma_v2x_msgs::msg::SensorDataSharingMessage

References carma_cooperative_perception::to_sdsm_msg().

Here is the call graph for this function:

◆ update_current_pose()

auto carma_cooperative_perception::ExternalObjectListToSdsmNode::update_current_pose ( const pose_msg_type pose) -> void

Definition at line 149 of file external_object_list_to_sdsm_component.cpp.

150{
151 current_pose_ = msg;
152}

◆ update_georeference()

auto carma_cooperative_perception::ExternalObjectListToSdsmNode::update_georeference ( const georeference_msg_type proj_string) -> void

Definition at line 140 of file external_object_list_to_sdsm_component.cpp.

141{
142 if (map_georeference_ != msg.data)
143 {
144 map_georeference_ = msg.data;
145 map_projector_ = std::make_shared<lanelet::projection::LocalFrameProjector>(map_georeference_.c_str());
146 }
147}

Member Data Documentation

◆ current_pose_

geometry_msgs::msg::PoseStamped carma_cooperative_perception::ExternalObjectListToSdsmNode::current_pose_
private

Definition at line 68 of file external_object_list_to_sdsm_component.hpp.

◆ current_pose_subscription_

rclcpp::Subscription<pose_msg_type>::SharedPtr carma_cooperative_perception::ExternalObjectListToSdsmNode::current_pose_subscription_ {nullptr}
private

Definition at line 65 of file external_object_list_to_sdsm_component.hpp.

◆ external_objects_subscription_

rclcpp::Subscription<external_objects_msg_type>::SharedPtr carma_cooperative_perception::ExternalObjectListToSdsmNode::external_objects_subscription_
private
Initial value:
{
nullptr}

Definition at line 62 of file external_object_list_to_sdsm_component.hpp.

◆ georeference_subscription_

rclcpp::Subscription<georeference_msg_type>::SharedPtr carma_cooperative_perception::ExternalObjectListToSdsmNode::georeference_subscription_ {nullptr}
private

Definition at line 64 of file external_object_list_to_sdsm_component.hpp.

◆ map_georeference_

std::string carma_cooperative_perception::ExternalObjectListToSdsmNode::map_georeference_ {""}
private

Definition at line 67 of file external_object_list_to_sdsm_component.hpp.

◆ map_projector_

std::shared_ptr<lanelet::projection::LocalFrameProjector> carma_cooperative_perception::ExternalObjectListToSdsmNode::map_projector_ {nullptr}
private

Definition at line 70 of file external_object_list_to_sdsm_component.hpp.

◆ on_set_parameters_callback_

OnSetParametersCallbackHandle::SharedPtr carma_cooperative_perception::ExternalObjectListToSdsmNode::on_set_parameters_callback_ {nullptr}
private

◆ sdsm_publisher_

rclcpp_lifecycle::LifecyclePublisher<sdsm_msg_type>::SharedPtr carma_cooperative_perception::ExternalObjectListToSdsmNode::sdsm_publisher_ {nullptr}
private

The documentation for this class was generated from the following files: