15#ifndef ROADWAY_OBJECTS__ROADWAY_OBJECTS_COMPONENT_HPP_ 
   16#define ROADWAY_OBJECTS__ROADWAY_OBJECTS_COMPONENT_HPP_ 
   18#include <carma_perception_msgs/msg/roadway_obstacle_list.hpp> 
   19#include <carma_ros2_utils/carma_lifecycle_node.hpp> 
   22#include <rclcpp/rclcpp.hpp> 
   23#include <rclcpp_lifecycle/lifecycle_publisher.hpp> 
   40  auto publish_obstacles(
const carma_perception_msgs::msg::ExternalObjectList & msg) -> void;
 
   43    -> carma_ros2_utils::CallbackReturn 
override;
 
   46  rclcpp::Subscription<carma_perception_msgs::msg::ExternalObjectList>::SharedPtr
 
   49  rclcpp_lifecycle::LifecyclePublisher<carma_perception_msgs::msg::RoadwayObstacleList>::SharedPtr
 
The class responsible for converting detected objects into objects that are mapped onto specific lane...
 
auto publish_obstacles(const carma_perception_msgs::msg::ExternalObjectList &msg) -> void
 
std::shared_ptr< carma_wm::WMListener > wm_listener_
 
auto handle_on_configure(const rclcpp_lifecycle::State &) -> carma_ros2_utils::CallbackReturn override
 
rclcpp::Subscription< carma_perception_msgs::msg::ExternalObjectList >::SharedPtr external_objects_sub_
 
RoadwayObjectsNode(const rclcpp::NodeOptions &)
 
rclcpp_lifecycle::LifecyclePublisher< carma_perception_msgs::msg::RoadwayObstacleList >::SharedPtr roadway_obs_pub_