19#include <rclcpp/rclcpp.hpp> 
   21#include <autoware_auto_msgs/msg/detected_objects.hpp> 
   22#include <autoware_auto_msgs/msg/bounding_box_array.hpp> 
   24#include "carma_ros2_utils/carma_lifecycle_node.hpp" 
   28class Node : 
public carma_ros2_utils::CarmaLifecycleNode
 
   34  carma_ros2_utils::SubPtr<autoware_auto_msgs::msg::BoundingBoxArray> 
bbox_sub_;
 
   37  carma_ros2_utils::PubPtr<autoware_auto_msgs::msg::DetectedObjects> 
object_pub_;
 
   44  explicit Node(
const rclcpp::NodeOptions& );
 
   51  void bbox_callback(autoware_auto_msgs::msg::BoundingBoxArray::UniquePtr msg);
 
void bbox_callback(autoware_auto_msgs::msg::BoundingBoxArray::UniquePtr msg)
Callback for bounding box data to be converted. Publishes a DetectedObjects message from the bounding...
carma_ros2_utils::PubPtr< autoware_auto_msgs::msg::DetectedObjects > object_pub_
Node(const rclcpp::NodeOptions &)
carma_ros2_utils::SubPtr< autoware_auto_msgs::msg::BoundingBoxArray > bbox_sub_
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)