@@ -207,17 +207,6 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio
207
207
pub_velocity_limit_ = this ->create_publisher <VelocityLimit>(
208
208
" ~/output/max_velocity" , rclcpp::QoS{1 }.transient_local ());
209
209
210
- // Subscribers
211
- sub_pointcloud_ = this ->create_subscription <sensor_msgs::msg::PointCloud2>(
212
- " ~/input/pointcloud" , rclcpp::SensorDataQoS (),
213
- std::bind (&SurroundObstacleCheckerNode::onPointCloud, this , std::placeholders::_1));
214
- sub_dynamic_objects_ = this ->create_subscription <PredictedObjects>(
215
- " ~/input/objects" , 1 ,
216
- std::bind (&SurroundObstacleCheckerNode::onDynamicObjects, this , std::placeholders::_1));
217
- sub_odometry_ = this ->create_subscription <nav_msgs::msg::Odometry>(
218
- " ~/input/odometry" , 1 ,
219
- std::bind (&SurroundObstacleCheckerNode::onOdometry, this , std::placeholders::_1));
220
-
221
210
// Parameter callback
222
211
set_param_res_ = this ->add_on_set_parameters_callback (
223
212
std::bind (&SurroundObstacleCheckerNode::onParam, this , std::placeholders::_1));
@@ -283,6 +272,10 @@ rcl_interfaces::msg::SetParametersResult SurroundObstacleCheckerNode::onParam(
283
272
284
273
void SurroundObstacleCheckerNode::onTimer ()
285
274
{
275
+ odometry_ptr_ = sub_odometry_.takeData ();
276
+ pointcloud_ptr_ = sub_pointcloud_.takeData ();
277
+ object_ptr_ = sub_dynamic_objects_.takeData ();
278
+
286
279
if (!odometry_ptr_) {
287
280
RCLCPP_INFO_THROTTLE (
288
281
this ->get_logger (), *this ->get_clock (), 5000 /* ms */ , " waiting for current velocity..." );
@@ -378,22 +371,6 @@ void SurroundObstacleCheckerNode::onTimer()
378
371
debug_ptr_->publish ();
379
372
}
380
373
381
- void SurroundObstacleCheckerNode::onPointCloud (
382
- const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
383
- {
384
- pointcloud_ptr_ = msg;
385
- }
386
-
387
- void SurroundObstacleCheckerNode::onDynamicObjects (const PredictedObjects::ConstSharedPtr msg)
388
- {
389
- object_ptr_ = msg;
390
- }
391
-
392
- void SurroundObstacleCheckerNode::onOdometry (const nav_msgs::msg::Odometry::ConstSharedPtr msg)
393
- {
394
- odometry_ptr_ = msg;
395
- }
396
-
397
374
std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacle () const
398
375
{
399
376
const auto nearest_pointcloud = getNearestObstacleByPointCloud ();
0 commit comments