The class responsible for converting detected objects into objects that are mapped onto specific lanelets.
More...
#include <roadway_objects_component.hpp>
The class responsible for converting detected objects into objects that are mapped onto specific lanelets.
Definition at line 35 of file roadway_objects_component.hpp.
◆ RoadwayObjectsNode()
roadway_objects::RoadwayObjectsNode::RoadwayObjectsNode |
( |
const rclcpp::NodeOptions & |
options | ) |
|
|
explicit |
◆ handle_on_configure()
auto roadway_objects::RoadwayObjectsNode::handle_on_configure |
( |
const rclcpp_lifecycle::State & |
| ) |
-> carma_ros2_utils::CallbackReturn |
|
override |
Definition at line 28 of file roadway_objects_component.cpp.
30{
31 RCLCPP_INFO_STREAM(get_logger(), "RoadwayObjectsNode trying to configure");
32
34 get_node_base_interface(), get_node_logging_interface(), get_node_topics_interface(),
35 get_node_parameters_interface());
36
38 create_publisher<carma_perception_msgs::msg::RoadwayObstacleList>("roadway_objects", 10);
39
41 "external_objects", 10,
42 [this](const carma_perception_msgs::msg::ExternalObjectList::SharedPtr msg_ptr) {
44 });
45
46 return CallbackReturn::SUCCESS;
47}
auto publish_obstacles(const carma_perception_msgs::msg::ExternalObjectList &msg) -> void
std::shared_ptr< carma_wm::WMListener > wm_listener_
rclcpp::Subscription< carma_perception_msgs::msg::ExternalObjectList >::SharedPtr external_objects_sub_
rclcpp_lifecycle::LifecyclePublisher< carma_perception_msgs::msg::RoadwayObstacleList >::SharedPtr roadway_obs_pub_
◆ publish_obstacles()
auto roadway_objects::RoadwayObjectsNode::publish_obstacles |
( |
const carma_perception_msgs::msg::ExternalObjectList & |
msg | ) |
-> void |
Definition at line 49 of file roadway_objects_component.cpp.
51{
52 carma_perception_msgs::msg::RoadwayObstacleList obstacle_list;
53
55
56 if (map == nullptr) {
57 RCLCPP_WARN(
58 get_logger(),
59 "roadway_objects could not process external objects as no semantic map was available");
60
61 return;
62 }
63
64 if (std::size(map->laneletLayer) == 0) {
65 RCLCPP_WARN(
66 get_logger(),
67 "roadway_objects could not process external objects as the semantic map does not contain any "
68 "lanelets");
69
70 return;
71 }
72
74 for (auto object : msg.objects) {
75 const auto obstacle{world_model->toRoadwayObstacle(object)};
76
77 if (!obstacle.has_value()) {
78 RCLCPP_DEBUG_STREAM(
79 get_logger(), "roadway_objects dropping detected object with id: "
80 << object.id << " as it is off the road.");
81
82 continue;
83 }
84
85 obstacle_list.roadway_obstacles.emplace_back(obstacle.get());
86 }
87
89}
◆ external_objects_sub_
rclcpp::Subscription<carma_perception_msgs::msg::ExternalObjectList>::SharedPtr roadway_objects::RoadwayObjectsNode::external_objects_sub_ {nullptr} |
|
private |
◆ roadway_obs_pub_
rclcpp_lifecycle::LifecyclePublisher<carma_perception_msgs::msg::RoadwayObstacleList>::SharedPtr roadway_objects::RoadwayObjectsNode::roadway_obs_pub_ {nullptr} |
|
private |
◆ wm_listener_
The documentation for this class was generated from the following files: