File tree 5 files changed +13
-11
lines changed
common/tier4_autoware_utils/include/tier4_autoware_utils/ros
control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking
autoware_behavior_velocity_planner/src
autoware_surround_obstacle_checker/include/autoware_surround_obstacle_checker
motion_velocity_planner/autoware_motion_velocity_planner_node/src
5 files changed +13
-11
lines changed Original file line number Diff line number Diff line change 26
26
namespace tier4_autoware_utils
27
27
{
28
28
29
+ inline rclcpp::SensorDataQoS SingleDepthSensorQoS ()
30
+ {
31
+ rclcpp::SensorDataQoS qos;
32
+ qos.get_rmw_qos_profile ().depth = 1 ;
33
+ return qos;
34
+ }
35
+
29
36
template <typename T, int N = 1 , typename Enable = void >
30
37
class InterProcessPollingSubscriber ;
31
38
Original file line number Diff line number Diff line change @@ -229,21 +229,14 @@ class CollisionDataKeeper
229
229
rclcpp::Clock::SharedPtr clock_;
230
230
};
231
231
232
- static rclcpp::SensorDataQoS SingleDepthSensorQoS ()
233
- {
234
- rclcpp::SensorDataQoS qos;
235
- qos.get_rmw_qos_profile ().depth = 1 ;
236
- return qos;
237
- }
238
-
239
232
class AEB : public rclcpp ::Node
240
233
{
241
234
public:
242
235
explicit AEB (const rclcpp::NodeOptions & node_options);
243
236
244
237
// subscriber
245
238
tier4_autoware_utils::InterProcessPollingSubscriber<PointCloud2> sub_point_cloud_{
246
- this , " ~/input/pointcloud" , SingleDepthSensorQoS ()};
239
+ this , " ~/input/pointcloud" , tier4_autoware_utils:: SingleDepthSensorQoS ()};
247
240
tier4_autoware_utils::InterProcessPollingSubscriber<VelocityReport> sub_velocity_{
248
241
this , " ~/input/velocity" };
249
242
tier4_autoware_utils::InterProcessPollingSubscriber<Imu> sub_imu_{this , " ~/input/imu" };
Original file line number Diff line number Diff line change @@ -74,7 +74,8 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
74
74
sub_predicted_objects_{this , " ~/input/dynamic_objects" };
75
75
76
76
tier4_autoware_utils::InterProcessPollingSubscriber<sensor_msgs::msg::PointCloud2>
77
- sub_no_ground_pointcloud_{this , " ~/input/no_ground_pointcloud" };
77
+ sub_no_ground_pointcloud_{
78
+ this , " ~/input/no_ground_pointcloud" , tier4_autoware_utils::SingleDepthSensorQoS ()};
78
79
79
80
tier4_autoware_utils::InterProcessPollingSubscriber<nav_msgs::msg::Odometry>
80
81
sub_vehicle_odometry_{this , " ~/input/vehicle_odometry" };
Original file line number Diff line number Diff line change @@ -114,7 +114,7 @@ class SurroundObstacleCheckerNode : public rclcpp::Node
114
114
tier4_autoware_utils::InterProcessPollingSubscriber<nav_msgs::msg::Odometry> sub_odometry_{
115
115
this , " ~/input/odometry" };
116
116
tier4_autoware_utils::InterProcessPollingSubscriber<sensor_msgs::msg::PointCloud2>
117
- sub_pointcloud_{this , " ~/input/pointcloud" };
117
+ sub_pointcloud_{this , " ~/input/pointcloud" , tier4_autoware_utils::SingleDepthSensorQoS () };
118
118
tier4_autoware_utils::InterProcessPollingSubscriber<PredictedObjects> sub_dynamic_objects_{
119
119
this , " ~/input/objects" };
120
120
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticStatus>::SharedPtr pub_stop_reason_;
Original file line number Diff line number Diff line change @@ -66,7 +66,8 @@ class MotionVelocityPlannerNode : public rclcpp::Node
66
66
autoware_perception_msgs::msg::PredictedObjects>
67
67
sub_predicted_objects_{this , " ~/input/dynamic_objects" };
68
68
tier4_autoware_utils::InterProcessPollingSubscriber<sensor_msgs::msg::PointCloud2>
69
- sub_no_ground_pointcloud_{this , " ~/input/no_ground_pointcloud" };
69
+ sub_no_ground_pointcloud_{
70
+ this , " ~/input/no_ground_pointcloud" , tier4_autoware_utils::SingleDepthSensorQoS ()};
70
71
tier4_autoware_utils::InterProcessPollingSubscriber<nav_msgs::msg::Odometry>
71
72
sub_vehicle_odometry_{this , " ~/input/vehicle_odometry" };
72
73
tier4_autoware_utils::InterProcessPollingSubscriber<
You can’t perform that action at this time.
0 commit comments