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.
motion_prediction_visualizer::Node Class Reference

#include <motion_prediction_visualizer.hpp>

Inheritance diagram for motion_prediction_visualizer::Node:
Inheritance graph
Collaboration diagram for motion_prediction_visualizer::Node:
Collaboration graph

Public Member Functions

 Node (const rclcpp::NodeOptions &)
 Node constructor. More...
 
void external_object_callback (const carma_perception_msgs::msg::ExternalObjectList::UniquePtr msg)
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 

Private Attributes

carma_ros2_utils::SubPtr< carma_perception_msgs::msg::ExternalObjectList > external_object_sub_
 
carma_ros2_utils::PubPtr< geometry_msgs::msg::PoseArray > pose_array_pub_
 

Detailed Description

Definition at line 31 of file motion_prediction_visualizer.hpp.

Constructor & Destructor Documentation

◆ Node()

motion_prediction_visualizer::Node::Node ( const rclcpp::NodeOptions &  options)
explicit

Node constructor.

Definition at line 25 of file motion_prediction_visualizer_node.cpp.

26 : carma_ros2_utils::CarmaLifecycleNode(options)
27 {
28
29 }

Member Function Documentation

◆ external_object_callback()

void motion_prediction_visualizer::Node::external_object_callback ( const carma_perception_msgs::msg::ExternalObjectList::UniquePtr  msg)

Definition at line 31 of file motion_prediction_visualizer_node.cpp.

32 {
33 geometry_msgs::msg::PoseArray posearray;
34 posearray.header.stamp = this->now();
35 posearray.header.frame_id = "map";
36
37 for (auto& obj : msg->objects){
38 for (auto& p : obj.predictions) {
39 posearray.poses.push_back(p.predicted_position);
40 }
41 }
42
43 pose_array_pub_->publish(posearray);
44 }
carma_ros2_utils::PubPtr< geometry_msgs::msg::PoseArray > pose_array_pub_

References pose_array_pub_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn motion_prediction_visualizer::Node::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 46 of file motion_prediction_visualizer_node.cpp.

47 {
48 // Setup subscribers
49 external_object_sub_ = create_subscription<carma_perception_msgs::msg::ExternalObjectList>("external_objects", 1000,
50 std::bind(&Node::external_object_callback, this, std_ph::_1));
51
52 // Setup publishers
53 pose_array_pub_ = create_publisher<geometry_msgs::msg::PoseArray>("motion_computation_visualize", 1);
54
55 // Return success if everthing initialized successfully
56 return CallbackReturn::SUCCESS;
57
58 }
carma_ros2_utils::SubPtr< carma_perception_msgs::msg::ExternalObjectList > external_object_sub_
void external_object_callback(const carma_perception_msgs::msg::ExternalObjectList::UniquePtr msg)

References external_object_callback(), external_object_sub_, and pose_array_pub_.

Here is the call graph for this function:

Member Data Documentation

◆ external_object_sub_

carma_ros2_utils::SubPtr<carma_perception_msgs::msg::ExternalObjectList> motion_prediction_visualizer::Node::external_object_sub_
private

Definition at line 35 of file motion_prediction_visualizer.hpp.

Referenced by handle_on_configure().

◆ pose_array_pub_

carma_ros2_utils::PubPtr<geometry_msgs::msg::PoseArray> motion_prediction_visualizer::Node::pose_array_pub_
private

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