Skip to content

Commit 271e6f1

Browse files
committed
use InterProcessPollingSubscriber
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 61ebd85 commit 271e6f1

File tree

2 files changed

+17
-26
lines changed
  • control/autonomous_emergency_braking

2 files changed

+17
-26
lines changed

control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp

+17-5
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <pcl_ros/transforms.hpp>
2121
#include <rclcpp/rclcpp.hpp>
2222
#include <tier4_autoware_utils/geometry/geometry.hpp>
23+
#include <tier4_autoware_utils/ros/polling_subsriber.hpp>
2324
#include <vehicle_info_util/vehicle_info_util.hpp>
2425

2526
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
@@ -224,17 +225,28 @@ class CollisionDataKeeper
224225
rclcpp::Clock::SharedPtr clock_;
225226
};
226227

228+
static rclcpp::SensorDataQoS getSingleDepthSensorQoS()
229+
{
230+
rclcpp::SensorDataQoS qos;
231+
qos.get_rmw_qos_profile().depth = 1;
232+
return qos;
233+
}
234+
227235
class AEB : public rclcpp::Node
228236
{
229237
public:
230238
explicit AEB(const rclcpp::NodeOptions & node_options);
231239

232240
// 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"};
238250

239251
// publisher
240252
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_obstacle_pointcloud_;

control/autonomous_emergency_braking/src/node.cpp

-21
Original file line numberDiff line numberDiff line change
@@ -105,27 +105,6 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
105105
vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()),
106106
collision_data_keeper_(this->get_clock())
107107
{
108-
// Subscribers
109-
{
110-
sub_point_cloud_ = this->create_subscription<PointCloud2>(
111-
"~/input/pointcloud", rclcpp::SensorDataQoS(),
112-
std::bind(&AEB::onPointCloud, this, std::placeholders::_1));
113-
114-
sub_velocity_ = this->create_subscription<VelocityReport>(
115-
"~/input/velocity", rclcpp::QoS{1}, std::bind(&AEB::onVelocity, this, std::placeholders::_1));
116-
117-
sub_imu_ = this->create_subscription<Imu>(
118-
"~/input/imu", rclcpp::QoS{1}, std::bind(&AEB::onImu, this, std::placeholders::_1));
119-
120-
sub_predicted_traj_ = this->create_subscription<Trajectory>(
121-
"~/input/predicted_trajectory", rclcpp::QoS{1},
122-
std::bind(&AEB::onPredictedTrajectory, this, std::placeholders::_1));
123-
124-
sub_autoware_state_ = this->create_subscription<AutowareState>(
125-
"/autoware/state", rclcpp::QoS{1},
126-
std::bind(&AEB::onAutowareState, this, std::placeholders::_1));
127-
}
128-
129108
// Publisher
130109
{
131110
pub_obstacle_pointcloud_ =

0 commit comments

Comments
 (0)