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::ExternalObjectListToDetectionListNode Class Reference

#include <external_object_list_to_detection_list_component.hpp>

Inheritance diagram for carma_cooperative_perception::ExternalObjectListToDetectionListNode:
Inheritance graph
Collaboration diagram for carma_cooperative_perception::ExternalObjectListToDetectionListNode:
Collaboration graph

Public Member Functions

 ExternalObjectListToDetectionListNode (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_detection_list (const input_msg_type &msg) const -> void
 
auto update_georeference (const std_msgs::msg::String &msg) -> void
 

Private Types

using input_msg_type = carma_perception_msgs::msg::ExternalObjectList
 
using input_msg_shared_pointer = typename input_msg_type::SharedPtr
 
using output_msg_type = carma_cooperative_perception_interfaces::msg::DetectionList
 

Private Attributes

rclcpp_lifecycle::LifecyclePublisher< output_msg_type >::SharedPtr publisher_ {nullptr}
 
rclcpp::Subscription< input_msg_type >::SharedPtr external_objects_subscription_ {nullptr}
 
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr georeference_subscription_ {nullptr}
 
std::string map_georeference_ {""}
 
MotionModelMapping motion_model_mapping_ {}
 
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_ {nullptr}
 

Detailed Description

Member Typedef Documentation

◆ input_msg_shared_pointer

◆ input_msg_type

using carma_cooperative_perception::ExternalObjectListToDetectionListNode::input_msg_type = carma_perception_msgs::msg::ExternalObjectList
private

◆ output_msg_type

using carma_cooperative_perception::ExternalObjectListToDetectionListNode::output_msg_type = carma_cooperative_perception_interfaces::msg::DetectionList
private

Constructor & Destructor Documentation

◆ ExternalObjectListToDetectionListNode()

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

Definition at line 75 of file external_object_list_to_detection_list_component.cpp.

77: CarmaLifecycleNode{options}
78{
79 lifecycle_publishers_.push_back(publisher_);
80 param_callback_handles_.push_back(on_set_parameters_callback_);
81}

References on_set_parameters_callback_, and publisher_.

Member Function Documentation

◆ handle_on_cleanup()

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

Definition at line 164 of file external_object_list_to_detection_list_component.cpp.

166{
167 // CarmaLifecycleNode does not handle subscriber pointer reseting for us
170
171 return carma_ros2_utils::CallbackReturn::SUCCESS;
172}

◆ handle_on_configure()

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

Definition at line 83 of file external_object_list_to_detection_list_component.cpp.

85{
86 publisher_ = create_publisher<output_msg_type>("output/detections", 1);
87
88 external_objects_subscription_ = create_subscription<input_msg_type>(
89 "input/external_objects", 1, [this](input_msg_shared_pointer msg_ptr) {
90 const auto current_state{this->get_current_state().label()};
91
92 if (current_state == "active") {
94 } else {
95 RCLCPP_WARN(
96 this->get_logger(),
97 "Trying to receive message on the topic '%s', but the containing node is not activated. "
98 "Current node state: '%s'",
99 this->external_objects_subscription_->get_topic_name(), current_state.c_str());
100 }
101 });
102
103 georeference_subscription_ = create_subscription<std_msgs::msg::String>(
104 "input/georeference", 1, [this](std_msgs::msg::String::SharedPtr msg_ptr) {
105 const auto current_state{this->get_current_state().label()};
106
107 if (current_state == "active") {
108 update_georeference(*msg_ptr);
109 } else {
110 RCLCPP_WARN(
111 this->get_logger(),
112 "Trying to receive message on the topic '%s', but the containing node is not activated. "
113 "Current node state: '%s'",
114 this->georeference_subscription_->get_topic_name(), current_state.c_str());
115 }
116 });
117
119 add_on_set_parameters_callback([this](const std::vector<rclcpp::Parameter> & parameters) {
120 rcl_interfaces::msg::SetParametersResult result;
121 result.successful = true;
122 result.reason = "success";
123
124 for (const auto & parameter : parameters) {
125 if (parameter.get_name() == "small_vehicle_motion_model") {
126 this->motion_model_mapping_.small_vehicle_model =
127 static_cast<std::uint8_t>(parameter.as_int());
128 } else if (parameter.get_name() == "large_vehicle_motion_model") {
129 this->motion_model_mapping_.large_vehicle_model =
130 static_cast<std::uint8_t>(parameter.as_int());
131 } else if (parameter.get_name() == "motorcycle_motion_model") {
132 this->motion_model_mapping_.motorcycle_model =
133 static_cast<std::uint8_t>(parameter.as_int());
134 } else if (parameter.get_name() == "pedestrian_motion_model") {
135 this->motion_model_mapping_.pedestrian_model =
136 static_cast<std::uint8_t>(parameter.as_int());
137 } else if (parameter.get_name() == "unknown_motion_model") {
138 this->motion_model_mapping_.unknown_model = static_cast<std::uint8_t>(parameter.as_int());
139 } else {
140 result.successful = false;
141 result.reason = "Unexpected parameter name '" + parameter.get_name() + '\'';
142 }
143 }
144
145 return result;
146 });
147
148 // TODO(Adam Morrissett): Look into how the motion model mapping can be re-architected
149 // to avoid requiring this sequence. Maybe something like a mapping class that calls the
150 // declared parameters. Then the to_detected_object() function could be templated on a
151 // mapping strategy.
152
153 // Declarations must come after on_set_parameters_callback_ assignment because the ROS
154 // runtime will call the callback if declare_parameter() succeeds.
155 declare_parameter("small_vehicle_motion_model", motion_model_mapping_.small_vehicle_model);
156 declare_parameter("large_vehicle_motion_model", motion_model_mapping_.large_vehicle_model);
157 declare_parameter("motorcycle_motion_model", motion_model_mapping_.motorcycle_model);
158 declare_parameter("pedestrian_motion_model", motion_model_mapping_.pedestrian_model);
159 declare_parameter("unknown_motion_model", motion_model_mapping_.unknown_model);
160
161 return carma_ros2_utils::CallbackReturn::SUCCESS;
162}

◆ handle_on_shutdown()

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

Definition at line 174 of file external_object_list_to_detection_list_component.cpp.

176{
177 // CarmaLifecycleNode does not handle subscriber pointer reseting for us
180
181 return carma_ros2_utils::CallbackReturn::SUCCESS;
182}

◆ publish_as_detection_list()

auto carma_cooperative_perception::ExternalObjectListToDetectionListNode::publish_as_detection_list ( const input_msg_type msg) const -> void

Definition at line 184 of file external_object_list_to_detection_list_component.cpp.

186{
187 try {
189 } catch (const std::invalid_argument & e) {
190 RCLCPP_ERROR(
191 this->get_logger(), "Could not convert external object list to detection list: %s", e.what());
192 }
193}
auto to_detection_list_msg(const carma_v2x_msgs::msg::SensorDataSharingMessage &sdsm, std::string_view georeference) -> carma_cooperative_perception_interfaces::msg::DetectionList

References carma_cooperative_perception::to_detection_list_msg().

Here is the call graph for this function:

◆ update_georeference()

auto carma_cooperative_perception::ExternalObjectListToDetectionListNode::update_georeference ( const std_msgs::msg::String &  msg) -> void

Member Data Documentation

◆ external_objects_subscription_

rclcpp::Subscription<input_msg_type>::SharedPtr carma_cooperative_perception::ExternalObjectListToDetectionListNode::external_objects_subscription_ {nullptr}
private

◆ georeference_subscription_

rclcpp::Subscription<std_msgs::msg::String>::SharedPtr carma_cooperative_perception::ExternalObjectListToDetectionListNode::georeference_subscription_ {nullptr}
private

◆ map_georeference_

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

◆ motion_model_mapping_

MotionModelMapping carma_cooperative_perception::ExternalObjectListToDetectionListNode::motion_model_mapping_ {}
private

◆ on_set_parameters_callback_

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

◆ publisher_

rclcpp_lifecycle::LifecyclePublisher<output_msg_type>::SharedPtr carma_cooperative_perception::ExternalObjectListToDetectionListNode::publisher_ {nullptr}
private

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