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

#include <track_list_to_external_object_list_component.hpp>

Inheritance diagram for carma_cooperative_perception::TrackListToExternalObjectListNode:
Inheritance graph
Collaboration diagram for carma_cooperative_perception::TrackListToExternalObjectListNode:
Collaboration graph

Public Member Functions

 TrackListToExternalObjectListNode (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_external_object_list (const carma_cooperative_perception_interfaces::msg::TrackList &msg) const -> void
 

Private Attributes

rclcpp_lifecycle::LifecyclePublisher< carma_perception_msgs::msg::ExternalObjectList >::SharedPtr publisher_ {nullptr}
 
rclcpp::Subscription< carma_cooperative_perception_interfaces::msg::TrackList >::SharedPtr track_list_subscription_ {nullptr}
 
std::string map_georeference_ {""}
 
OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_ {nullptr}
 

Detailed Description

Constructor & Destructor Documentation

◆ TrackListToExternalObjectListNode()

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

Definition at line 28 of file track_list_to_external_object_list_component.cpp.

30: CarmaLifecycleNode{options}
31{
32 lifecycle_publishers_.push_back(publisher_);
33 param_callback_handles_.push_back(on_set_parameters_callback_);
34}
rclcpp_lifecycle::LifecyclePublisher< carma_perception_msgs::msg::ExternalObjectList >::SharedPtr publisher_

References on_set_parameters_callback_, and publisher_.

Member Function Documentation

◆ handle_on_cleanup()

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

Definition at line 60 of file track_list_to_external_object_list_component.cpp.

62{
63 // CarmaLifecycleNode does not handle subscriber pointer reseting for us
65
66 return carma_ros2_utils::CallbackReturn::SUCCESS;
67}
rclcpp::Subscription< carma_cooperative_perception_interfaces::msg::TrackList >::SharedPtr track_list_subscription_

◆ handle_on_configure()

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

Definition at line 36 of file track_list_to_external_object_list_component.cpp.

38{
39 publisher_ = create_publisher<carma_perception_msgs::msg::ExternalObjectList>(
40 "output/external_object_list", 1);
41
42 track_list_subscription_ = create_subscription<
43 carma_cooperative_perception_interfaces::msg::TrackList>(
44 "input/track_list", 1,
45 [this](const carma_cooperative_perception_interfaces::msg::TrackList::SharedPtr msg_ptr) {
46 if (const auto current_state{this->get_current_state().label()}; current_state == "active") {
48 } else {
49 RCLCPP_WARN(
50 this->get_logger(),
51 "Trying to receive message on the topic '%s', but the containing node is not activated. "
52 "Current node state: '%s'",
53 this->track_list_subscription_->get_topic_name(), current_state.c_str());
54 }
55 });
56
57 return carma_ros2_utils::CallbackReturn::SUCCESS;
58}
auto publish_as_external_object_list(const carma_cooperative_perception_interfaces::msg::TrackList &msg) const -> void

◆ handle_on_shutdown()

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

Definition at line 69 of file track_list_to_external_object_list_component.cpp.

71{
72 // CarmaLifecycleNode does not handle subscriber pointer reseting for us
74
75 return carma_ros2_utils::CallbackReturn::SUCCESS;
76}

◆ publish_as_external_object_list()

auto carma_cooperative_perception::TrackListToExternalObjectListNode::publish_as_external_object_list ( const carma_cooperative_perception_interfaces::msg::TrackList &  msg) const -> void

Definition at line 78 of file track_list_to_external_object_list_component.cpp.

80{
81 auto external_object_list{to_external_object_list_msg(msg)};
82 external_object_list.header.stamp = now();
83 external_object_list.header.frame_id = "map";
84
85 publisher_->publish(external_object_list);
86}
auto to_external_object_list_msg(const carma_cooperative_perception_interfaces::msg::TrackList &track_list) -> carma_perception_msgs::msg::ExternalObjectList

References carma_cooperative_perception::to_external_object_list_msg().

Here is the call graph for this function:

Member Data Documentation

◆ map_georeference_

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

◆ on_set_parameters_callback_

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

◆ publisher_

rclcpp_lifecycle::LifecyclePublisher<carma_perception_msgs::msg::ExternalObjectList>::SharedPtr carma_cooperative_perception::TrackListToExternalObjectListNode::publisher_ {nullptr}
private

◆ track_list_subscription_

rclcpp::Subscription<carma_cooperative_perception_interfaces::msg::TrackList>::SharedPtr carma_cooperative_perception::TrackListToExternalObjectListNode::track_list_subscription_ {nullptr}
private

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