|
20 | 20 | #include <pcl_ros/transforms.hpp>
|
21 | 21 | #include <rclcpp/rclcpp.hpp>
|
22 | 22 | #include <tier4_autoware_utils/geometry/geometry.hpp>
|
| 23 | +#include <tier4_autoware_utils/ros/polling_subsriber.hpp> |
23 | 24 | #include <vehicle_info_util/vehicle_info_util.hpp>
|
24 | 25 |
|
25 | 26 | #include <autoware_auto_planning_msgs/msg/trajectory.hpp>
|
@@ -224,17 +225,28 @@ class CollisionDataKeeper
|
224 | 225 | rclcpp::Clock::SharedPtr clock_;
|
225 | 226 | };
|
226 | 227 |
|
| 228 | +static rclcpp::SensorDataQoS getSingleDepthSensorQoS() |
| 229 | +{ |
| 230 | + rclcpp::SensorDataQoS qos; |
| 231 | + qos.get_rmw_qos_profile().depth = 1; |
| 232 | + return qos; |
| 233 | +} |
| 234 | + |
227 | 235 | class AEB : public rclcpp::Node
|
228 | 236 | {
|
229 | 237 | public:
|
230 | 238 | explicit AEB(const rclcpp::NodeOptions & node_options);
|
231 | 239 |
|
232 | 240 | // subscriber
|
233 |
| - rclcpp::Subscription<PointCloud2>::SharedPtr sub_point_cloud_; |
234 |
| - rclcpp::Subscription<VelocityReport>::SharedPtr sub_velocity_; |
235 |
| - rclcpp::Subscription<Imu>::SharedPtr sub_imu_; |
236 |
| - rclcpp::Subscription<Trajectory>::SharedPtr sub_predicted_traj_; |
237 |
| - rclcpp::Subscription<AutowareState>::SharedPtr sub_autoware_state_; |
| 241 | + tier4_autoware_utils::InterProcessPollingSubscriber<PointCloud2> sub_point_cloud_{ |
| 242 | + this, "~/input/pointcloud", getSingleDepthSensorQoS()}; |
| 243 | + tier4_autoware_utils::InterProcessPollingSubscriber<VelocityReport> sub_veloclty_{ |
| 244 | + this, "~/input/velocity"}; |
| 245 | + tier4_autoware_utils::InterProcessPollingSubscriber<Imu> sub_imu_{this, "~/input/imu"}; |
| 246 | + tier4_autoware_utils::InterProcessPollingSubscriber<Trajectory> sub_predicted_traj_{ |
| 247 | + this, "~/input/predicted_trajectory"}; |
| 248 | + tier4_autoware_utils::InterProcessPollingSubscriber<AutowareState> sub_autoware_state_{ |
| 249 | + this, "/autoware/state"}; |
238 | 250 |
|
239 | 251 | // publisher
|
240 | 252 | rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_obstacle_pointcloud_;
|
|
0 commit comments