Skip to content

Commit cc79cb8

Browse files
committed
feat(pointcloud_preprocessor): make concatenate node to publish pointclouds in sensor frame (autowarefoundation#6586)
* feat: make concatenate node to publish pointclouds in sensor frame Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * chore: disable frame transform if not necessary Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> --------- Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 5ebf86f commit cc79cb8

File tree

4 files changed

+50
-6
lines changed

4 files changed

+50
-6
lines changed

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -126,6 +126,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
126126
double timeout_sec_ = 0.1;
127127

128128
bool publish_synchronized_pointcloud_;
129+
bool keep_input_frame_in_synchronized_pointcloud_;
129130
std::string synchronized_pointcloud_postfix_;
130131

131132
std::set<std::string> not_subscribed_topic_names_;

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,7 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node
138138

139139
/** \brief Output TF frame the concatenated points should be transformed to. */
140140
std::string output_frame_;
141+
bool keep_input_frame_in_synchronized_pointcloud_;
141142

142143
/** \brief Input point cloud topics. */
143144
// XmlRpc::XmlRpcValue input_topics_;

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

+33-5
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,9 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
112112
}
113113

114114
// Check if publish synchronized pointcloud
115-
publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", false);
115+
publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", true);
116+
keep_input_frame_in_synchronized_pointcloud_ =
117+
declare_parameter("keep_input_frame_in_synchronized_pointcloud", true);
116118
synchronized_pointcloud_postfix_ =
117119
declare_parameter("synchronized_pointcloud_postfix", "pointcloud");
118120
}
@@ -391,10 +393,23 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds(
391393
pcl::concatenatePointCloud(
392394
*concat_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concat_cloud_ptr);
393395
}
394-
// gather transformed clouds
395-
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
396-
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
397-
transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr;
396+
// convert to original sensor frame if necessary
397+
bool need_transform_to_sensor_frame = (e.second->header.frame_id != output_frame_);
398+
if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) {
399+
sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame(
400+
new sensor_msgs::msg::PointCloud2());
401+
pcl_ros::transformPointCloud(
402+
(std::string)e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr,
403+
*transformed_cloud_ptr_in_sensor_frame, *tf2_buffer_);
404+
transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp;
405+
transformed_cloud_ptr_in_sensor_frame->header.frame_id = e.second->header.frame_id;
406+
transformed_clouds[e.first] = transformed_cloud_ptr_in_sensor_frame;
407+
} else {
408+
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
409+
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
410+
transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr;
411+
}
412+
398413
} else {
399414
not_subscribed_topic_names_.insert(e.first);
400415
}
@@ -449,6 +464,19 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
449464
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
450465
"debug/processing_time_ms", processing_time_ms);
451466
}
467+
for (const auto & e : cloud_stdmap_) {
468+
if (e.second != nullptr) {
469+
if (debug_publisher_) {
470+
const auto pipeline_latency_ms =
471+
std::chrono::duration<double, std::milli>(
472+
std::chrono::nanoseconds(
473+
(this->get_clock()->now() - e.second->header.stamp).nanoseconds()))
474+
.count();
475+
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
476+
"debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms);
477+
}
478+
}
479+
}
452480
}
453481

454482
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

+15-1
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,9 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
5858
std::string synchronized_pointcloud_postfix;
5959
{
6060
output_frame_ = static_cast<std::string>(declare_parameter("output_frame", ""));
61-
if (output_frame_.empty()) {
61+
keep_input_frame_in_synchronized_pointcloud_ =
62+
static_cast<bool>(declare_parameter("keep_input_frame_in_synchronized_pointcloud", false));
63+
if (output_frame_.empty() && !keep_input_frame_in_synchronized_pointcloud_) {
6264
RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!");
6365
return;
6466
}
@@ -339,6 +341,18 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
339341
pcl_ros::transformPointCloud(
340342
adjust_to_old_data_transform, *transformed_cloud_ptr,
341343
*transformed_delay_compensated_cloud_ptr);
344+
// transform to sensor frame if needed
345+
bool need_transform_to_sensor_frame = (e.second->header.frame_id != output_frame_);
346+
if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) {
347+
sensor_msgs::msg::PointCloud2::SharedPtr
348+
transformed_delay_compensated_cloud_ptr_in_input_frame(
349+
new sensor_msgs::msg::PointCloud2());
350+
transformPointCloud(
351+
transformed_delay_compensated_cloud_ptr,
352+
transformed_delay_compensated_cloud_ptr_in_input_frame, e.second->header.frame_id);
353+
transformed_delay_compensated_cloud_ptr =
354+
transformed_delay_compensated_cloud_ptr_in_input_frame;
355+
}
342356
// gather transformed clouds
343357
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
344358
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;

0 commit comments

Comments
 (0)