Autoware.Auto
object_collision_estimator_node.hpp
Go to the documentation of this file.
1 // Copyright 2020-2021 Arm Limited
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 #include <autoware_auto_planning_msgs/srv/modify_trajectory.hpp>
16 #include <autoware_auto_perception_msgs/msg/bounding_box_array.hpp>
17 #include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
18 #include <visualization_msgs/msg/marker_array.hpp>
19 #include <visualization_msgs/msg/marker.hpp>
20 #include <tf2_ros/transform_listener.h>
21 #include <tf2_ros/buffer.h>
22 #include <rclcpp/rclcpp.hpp>
23 #include <memory>
24 #include <string>
25 
28 
29 #ifndef OBJECT_COLLISION_ESTIMATOR_NODES__OBJECT_COLLISION_ESTIMATOR_NODE_HPP_
30 #define OBJECT_COLLISION_ESTIMATOR_NODES__OBJECT_COLLISION_ESTIMATOR_NODE_HPP_
31 
32 namespace motion
33 {
34 namespace planning
35 {
36 namespace object_collision_estimator_nodes
37 {
38 
41 using autoware_auto_perception_msgs::msg::PredictedObjects;
44 
45 
50 class OBJECT_COLLISION_ESTIMATOR_NODES_PUBLIC ObjectCollisionEstimatorNode : public rclcpp::Node
51 {
52 public:
55  explicit ObjectCollisionEstimatorNode(const rclcpp::NodeOptions & node_options);
56 
57 private:
63  void estimate_collision(
64  const std::shared_ptr<autoware_auto_planning_msgs::srv::ModifyTrajectory::Request> request,
65  std::shared_ptr<autoware_auto_planning_msgs::srv::ModifyTrajectory::Response> response);
66 
68  rclcpp::Subscription<BoundingBoxArray>::SharedPtr m_obstacles_sub{nullptr};
69 
71  rclcpp::Subscription<PredictedObjects>::SharedPtr m_predicted_objects_sub{nullptr};
72 
74  rclcpp::Publisher<MarkerArray>::SharedPtr m_trajectory_bbox_pub{nullptr};
75 
79  void on_predicted_object(const PredictedObjects::SharedPtr & msg);
80 
83  std::unique_ptr<ObjectCollisionEstimator> m_estimator{nullptr};
84 
88  std::string m_target_frame_id{};
89 
91  rclcpp::Service<autoware_auto_planning_msgs::srv::ModifyTrajectory>::SharedPtr
92  m_service_interface{nullptr};
93 
95  std::shared_ptr<tf2_ros::Buffer> m_tf_buffer;
96 
99  std::shared_ptr<tf2_ros::TransformListener> m_tf_listener;
100 
103  rclcpp::TimerBase::SharedPtr m_wall_timer{nullptr};
104 
106  rclcpp::Time m_last_obstacle_msg_time {0, 0, RCL_ROS_TIME};
107 
109  std::chrono::milliseconds m_staleness_threshold_ms{};
110 
112  static constexpr const char * OBJECT_COLLISION_ESTIMATOR_NODE_NAME =
113  "object_collision_estimator_node";
114 
116  static constexpr const char * OBSTACLE_TOPIC = "obstacle_topic";
117 };
118 
119 } // namespace object_collision_estimator_nodes
120 } // namespace planning
121 } // namespace motion
122 
123 #endif // OBJECT_COLLISION_ESTIMATOR_NODES__OBJECT_COLLISION_ESTIMATOR_NODE_HPP_
autoware::rviz_plugins::object_detection::detail::Marker
visualization_msgs::msg::Marker Marker
Definition: object_polygon_detail.cpp:31
autoware::off_map_obstacles_filter_nodes::MarkerArray
visualization_msgs::msg::MarkerArray MarkerArray
Definition: off_map_obstacles_filter_node.cpp:39
object_collision_estimator.hpp
visibility_control.hpp
motion::planning::object_collision_estimator_nodes::ObjectCollisionEstimatorNode
ROS2 interface to Object Collision Estimator Library. It has 2 main interfaces:
Definition: object_collision_estimator_node.hpp:50
BoundingBoxArray
autoware_auto_perception_msgs::msg::BoundingBoxArray BoundingBoxArray
Definition: tf2_autoware_auto_msgs.hpp:38
motion
Definition: controller_base.hpp:31
motion::planning::object_collision_estimator::ObjectCollisionEstimator
Given a trajectory and a list of obstacles, detect possible collision points between the ego vehicle ...
Definition: object_collision_estimator.hpp:79