Skip to content

Commit 36debdd

Browse files
YoshiRianhnv3991
authored andcommitted
feat(pointcloud_preprocessor): enable to count empty pointclouds topic in concatenate pointclouds nodelet (autowarefoundation#6277)
* feat: enable to count empty pointclouds topic Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * fix: time sync function to adapt empty pc topic Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> --------- Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 3eb45ff commit 36debdd

File tree

2 files changed

+30
-8
lines changed

2 files changed

+30
-8
lines changed

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

+10-4
Original file line numberDiff line numberDiff line change
@@ -318,6 +318,9 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds(
318318
for (const auto & e : cloud_stdmap_) {
319319
transformed_clouds[e.first] = nullptr;
320320
if (e.second != nullptr) {
321+
if (e.second->data.size() == 0) {
322+
continue;
323+
}
321324
pc_stamps.push_back(rclcpp::Time(e.second->header.stamp));
322325
}
323326
}
@@ -332,6 +335,9 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds(
332335
// Step2. Calculate compensation transform and concatenate with the oldest stamp
333336
for (const auto & e : cloud_stdmap_) {
334337
if (e.second != nullptr) {
338+
if (e.second->data.size() == 0) {
339+
continue;
340+
}
335341
sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr(
336342
new sensor_msgs::msg::PointCloud2());
337343
transformPointCloud(e.second, transformed_cloud_ptr);
@@ -493,16 +499,16 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback(
493499
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr, const std::string & topic_name)
494500
{
495501
std::lock_guard<std::mutex> lock(mutex_);
502+
sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2());
496503
auto input = std::make_shared<sensor_msgs::msg::PointCloud2>(*input_ptr);
497504
if (input->data.empty()) {
498505
RCLCPP_WARN_STREAM_THROTTLE(
499506
this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!");
500-
return;
507+
} else {
508+
// convert to XYZI pointcloud if pointcloud is not empty
509+
convertToXYZICloud(input, xyzi_input_ptr);
501510
}
502511

503-
sensor_msgs::msg::PointCloud2::SharedPtr xyzi_input_ptr(new sensor_msgs::msg::PointCloud2());
504-
convertToXYZICloud(input, xyzi_input_ptr);
505-
506512
const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr);
507513
const bool is_already_subscribed_tmp = std::any_of(
508514
std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_),

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

+20-4
Original file line numberDiff line numberDiff line change
@@ -274,6 +274,9 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
274274
for (const auto & e : cloud_stdmap_) {
275275
transformed_clouds[e.first] = nullptr;
276276
if (e.second != nullptr) {
277+
if (e.second->data.size() == 0) {
278+
continue;
279+
}
277280
pc_stamps.push_back(rclcpp::Time(e.second->header.stamp));
278281
}
279282
}
@@ -288,11 +291,22 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
288291
// Step2. Calculate compensation transform and concatenate with the oldest stamp
289292
for (const auto & e : cloud_stdmap_) {
290293
if (e.second != nullptr) {
294+
// transform pointcloud
291295
sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr(
292296
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
293307
transformPointCloud(e.second, transformed_cloud_ptr);
294308

295-
// calculate transforms to oldest stamp
309+
// calculate transforms to oldest stamp and transform pointcloud to oldest stamp
296310
Eigen::Matrix4f adjust_to_old_data_transform = Eigen::Matrix4f::Identity();
297311
rclcpp::Time transformed_stamp = rclcpp::Time(e.second->header.stamp);
298312
for (const auto & stamp : pc_stamps) {
@@ -301,15 +315,15 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
301315
adjust_to_old_data_transform = new_to_old_transform * adjust_to_old_data_transform;
302316
transformed_stamp = std::min(transformed_stamp, stamp);
303317
}
304-
sensor_msgs::msg::PointCloud2::SharedPtr transformed_delay_compensated_cloud_ptr(
305-
new sensor_msgs::msg::PointCloud2());
306318
pcl_ros::transformPointCloud(
307319
adjust_to_old_data_transform, *transformed_cloud_ptr,
308320
*transformed_delay_compensated_cloud_ptr);
321+
309322
// gather transformed clouds
310323
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
311324
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
312325
transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr;
326+
313327
} else {
314328
not_subscribed_topic_names_.insert(e.first);
315329
}
@@ -414,7 +428,9 @@ void PointCloudDataSynchronizerComponent::cloud_callback(
414428
std::lock_guard<std::mutex> lock(mutex_);
415429
auto input = std::make_shared<sensor_msgs::msg::PointCloud2>(*input_ptr);
416430
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+
}
418434

419435
const bool is_already_subscribed_this = (cloud_stdmap_[topic_name] != nullptr);
420436
const bool is_already_subscribed_tmp = std::any_of(

0 commit comments

Comments
 (0)