19#include <rclcpp/rclcpp.hpp>
21#include <geometry_msgs/msg/pose_array.hpp>
22#include <carma_perception_msgs/msg/external_object.hpp>
23#include <carma_perception_msgs/msg/external_object_list.hpp>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
31class Node :
public carma_ros2_utils::CarmaLifecycleNode
45 explicit Node(
const rclcpp::NodeOptions &);
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_