Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
roadway_objects_component.hpp
Go to the documentation of this file.
1// Copyright 2019-2023 Leidos
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef ROADWAY_OBJECTS__ROADWAY_OBJECTS_COMPONENT_HPP_
16#define ROADWAY_OBJECTS__ROADWAY_OBJECTS_COMPONENT_HPP_
17
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>
24
25#include <memory>
26
28{
35class RoadwayObjectsNode : public carma_ros2_utils::CarmaLifecycleNode
36{
37public:
38 explicit RoadwayObjectsNode(const rclcpp::NodeOptions &);
39
40 auto publish_obstacles(const carma_perception_msgs::msg::ExternalObjectList & msg) -> void;
41
42 auto handle_on_configure(const rclcpp_lifecycle::State &)
43 -> carma_ros2_utils::CallbackReturn override;
44
45private:
46 rclcpp::Subscription<carma_perception_msgs::msg::ExternalObjectList>::SharedPtr
48
49 rclcpp_lifecycle::LifecyclePublisher<carma_perception_msgs::msg::RoadwayObstacleList>::SharedPtr
51
52 std::shared_ptr<carma_wm::WMListener> wm_listener_{nullptr};
53};
54
55} // namespace roadway_objects
56
57#endif // ROADWAY_OBJECTS__ROADWAY_OBJECTS_COMPONENT_HPP_
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_