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.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <rclcpp/rclcpp.hpp>
18#include <carma_ros2_utils/carma_lifecycle_node.hpp>
20
22{
23 namespace std_ph = std::placeholders;
24
25 Node::Node(const rclcpp::NodeOptions &options)
26 : carma_ros2_utils::CarmaLifecycleNode(options)
27 {
28
29 }
30
31 void Node::external_object_callback(const carma_perception_msgs::msg::ExternalObjectList::UniquePtr msg)
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 }
45
46 carma_ros2_utils::CallbackReturn Node::handle_on_configure(const rclcpp_lifecycle::State &)
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 }
59
60}// motion_prediction_visualizer
61
62#include "rclcpp_components/register_node_macro.hpp"
63
64// Register the component with class_loader
65RCLCPP_COMPONENTS_REGISTER_NODE(motion_prediction_visualizer::Node)
66
67
Node(const rclcpp::NodeOptions &)
Node constructor.
carma_ros2_utils::SubPtr< carma_perception_msgs::msg::ExternalObjectList > external_object_sub_
void external_object_callback(const carma_perception_msgs::msg::ExternalObjectList::UniquePtr msg)
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
carma_ros2_utils::PubPtr< geometry_msgs::msg::PoseArray > pose_array_pub_