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