@@ -274,6 +274,9 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
274
274
for (const auto & e : cloud_stdmap_) {
275
275
transformed_clouds[e.first ] = nullptr ;
276
276
if (e.second != nullptr ) {
277
+ if (e.second ->data .size () == 0 ) {
278
+ continue ;
279
+ }
277
280
pc_stamps.push_back (rclcpp::Time (e.second ->header .stamp ));
278
281
}
279
282
}
@@ -288,11 +291,22 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
288
291
// Step2. Calculate compensation transform and concatenate with the oldest stamp
289
292
for (const auto & e : cloud_stdmap_) {
290
293
if (e.second != nullptr ) {
294
+ // transform pointcloud
291
295
sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr (
292
296
new sensor_msgs::msg::PointCloud2 ());
297
+ sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr (
298
+ new sensor_msgs::msg::PointCloud2 ());
299
+ if (e.second ->data .size () == 0 ) {
300
+ // gather transformed clouds
301
+ transformed_delay_compensated_cloud_ptr->header .stamp = oldest_stamp;
302
+ transformed_delay_compensated_cloud_ptr->header .frame_id = output_frame_;
303
+ transformed_clouds[e.first ] = transformed_delay_compensated_cloud_ptr;
304
+ continue ;
305
+ }
306
+ // transform pointcloud to output frame
293
307
transformPointCloud (e.second , transformed_cloud_ptr);
294
308
295
- // calculate transforms to oldest stamp
309
+ // calculate transforms to oldest stamp and transform pointcloud to oldest stamp
296
310
Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity ();
297
311
rclcpp::Time transformed_stamp = rclcpp::Time (e.second ->header .stamp );
298
312
for (const auto & stamp : pc_stamps) {
@@ -301,15 +315,15 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
301
315
adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform;
302
316
transformed_stamp = std::min (transformed_stamp, stamp);
303
317
}
304
- sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr (
305
- new sensor_msgs::msg::PointCloud2 ());
306
318
pcl_ros::transformPointCloud (
307
319
adjust_to_old_data_transform, *transformed_cloud_ptr,
308
320
*transformed_delay_compensated_cloud_ptr);
321
+
309
322
// gather transformed clouds
310
323
transformed_delay_compensated_cloud_ptr->header .stamp = oldest_stamp;
311
324
transformed_delay_compensated_cloud_ptr->header .frame_id = output_frame_;
312
325
transformed_clouds[e.first ] = transformed_delay_compensated_cloud_ptr;
326
+
313
327
} else {
314
328
not_subscribed_topic_names_.insert (e.first );
315
329
}
@@ -414,7 +428,9 @@ void PointCloudDataSynchronizerComponent::cloud_callback(
414
428
std::lock_guard<std::mutex> lock (mutex_);
415
429
auto input = std::make_shared<sensor_msgs::msg::PointCloud2>(*input_ptr);
416
430
sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr (new sensor_msgs::msg::PointCloud2 ());
417
- convertToXYZICloud (input, xyzi_input_ptr);
431
+ if (input->data .size () > 0 ) {
432
+ convertToXYZICloud (input, xyzi_input_ptr);
433
+ }
418
434
419
435
const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr );
420
436
const bool is_already_subscribed_tmp = std::any_of (
0 commit comments