17#include <rclcpp/rclcpp.hpp>
18#include <carma_ros2_utils/carma_lifecycle_node.hpp>
23 namespace std_ph = std::placeholders;
26 : carma_ros2_utils::CarmaLifecycleNode(options)
33 geometry_msgs::msg::PoseArray posearray;
34 posearray.header.stamp = this->now();
35 posearray.header.frame_id =
"map";
37 for (
auto& obj : msg->objects){
38 for (
auto& p : obj.predictions) {
39 posearray.poses.push_back(p.predicted_position);
49 external_object_sub_ = create_subscription<carma_perception_msgs::msg::ExternalObjectList>(
"external_objects", 1000,
53 pose_array_pub_ = create_publisher<geometry_msgs::msg::PoseArray>(
"motion_computation_visualize", 1);
56 return CallbackReturn::SUCCESS;
62#include "rclcpp_components/register_node_macro.hpp"
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_