Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(pointcloud_preprocessor): make concatenate node to publish pointclouds in sensor frame #6586

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
double timeout_sec_ = 0.1;

bool publish_synchronized_pointcloud_;
bool keep_input_frame_in_synchronized_pointcloud_;
std::string synchronized_pointcloud_postfix_;

std::set<std::string> not_subscribed_topic_names_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,7 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node

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

/** \brief Input point cloud topics. */
// XmlRpc::XmlRpcValue input_topics_;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.92 to 6.08, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -112,7 +112,9 @@
}

// Check if publish synchronized pointcloud
publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", false);
publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", true);
keep_input_frame_in_synchronized_pointcloud_ =
declare_parameter("keep_input_frame_in_synchronized_pointcloud", true);

Check warning on line 117 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L115-L117

Added lines #L115 - L117 were not covered by tests
synchronized_pointcloud_postfix_ =
declare_parameter("synchronized_pointcloud_postfix", "pointcloud");
}
Expand Down Expand Up @@ -397,10 +399,23 @@
pcl::concatenatePointCloud(
*concat_cloud_ptr, *transformed_delay_compensated_cloud_ptr, *concat_cloud_ptr);
}
// gather transformed clouds
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr;
// convert to original sensor frame if necessary
bool need_transform_to_sensor_frame = (e.second->header.frame_id != output_frame_);
if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) {

Check warning on line 404 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L403-L404

Added lines #L403 - L404 were not covered by tests
sensor_msgs::msg::PointCloud2::SharedPtr transformed_cloud_ptr_in_sensor_frame(
new sensor_msgs::msg::PointCloud2());
pcl_ros::transformPointCloud(
(std::string)e.second->header.frame_id, *transformed_delay_compensated_cloud_ptr,

Check warning on line 408 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L406-L408

Added lines #L406 - L408 were not covered by tests
*transformed_cloud_ptr_in_sensor_frame, *tf2_buffer_);
transformed_cloud_ptr_in_sensor_frame->header.stamp = oldest_stamp;
transformed_cloud_ptr_in_sensor_frame->header.frame_id = e.second->header.frame_id;
transformed_clouds[e.first] = transformed_cloud_ptr_in_sensor_frame;
} else {
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
transformed_clouds[e.first] = transformed_delay_compensated_cloud_ptr;

Check warning on line 416 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L410-L416

Added lines #L410 - L416 were not covered by tests
}

Check warning on line 418 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PointCloudConcatenateDataSynchronizerComponent::combineClouds increases in cyclomatic complexity from 12 to 14, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
} else {
not_subscribed_topic_names_.insert(e.first);
}
Expand All @@ -418,20 +433,6 @@
const auto & transformed_raw_points =
PointCloudConcatenateDataSynchronizerComponent::combineClouds(concat_cloud_ptr);

for (const auto & e : cloud_stdmap_) {
if (e.second != nullptr) {
if (debug_publisher_) {
const auto pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - e.second->header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms);
}
}
}

// publish concatenated pointcloud
if (concat_cloud_ptr) {
auto output = std::make_unique<sensor_msgs::msg::PointCloud2>(*concat_cloud_ptr);
Expand Down Expand Up @@ -469,6 +470,19 @@
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug/processing_time_ms", processing_time_ms);
}
for (const auto & e : cloud_stdmap_) {
if (e.second != nullptr) {
if (debug_publisher_) {

Check warning on line 475 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L473-L475

Added lines #L473 - L475 were not covered by tests
const auto pipeline_latency_ms =
std::chrono::duration<double, std::milli>(
std::chrono::nanoseconds(
(this->get_clock()->now() - e.second->header.stamp).nanoseconds()))
.count();
debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>(
"debug" + e.first + "/pipeline_latency_ms", pipeline_latency_ms);

Check warning on line 482 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp#L479-L482

Added lines #L479 - L482 were not covered by tests
}
}
}
}

///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.08 to 5.23, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -58,7 +58,9 @@
std::string synchronized_pointcloud_postfix;
{
output_frame_ = static_cast<std::string>(declare_parameter("output_frame", ""));
if (output_frame_.empty()) {
keep_input_frame_in_synchronized_pointcloud_ =
static_cast<bool>(declare_parameter("keep_input_frame_in_synchronized_pointcloud", false));
if (output_frame_.empty() && !keep_input_frame_in_synchronized_pointcloud_) {

Check warning on line 63 in sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp#L61-L63

Added lines #L61 - L63 were not covered by tests
RCLCPP_ERROR(get_logger(), "Need an 'output_frame' parameter to be set before continuing!");
return;
}
Expand Down Expand Up @@ -351,7 +353,18 @@
pcl_ros::transformPointCloud(
adjust_to_old_data_transform, *transformed_cloud_ptr,
*transformed_delay_compensated_cloud_ptr);

// transform to sensor frame if needed
bool need_transform_to_sensor_frame = (e.second->header.frame_id != output_frame_);
if (keep_input_frame_in_synchronized_pointcloud_ && need_transform_to_sensor_frame) {

Check warning on line 358 in sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp#L357-L358

Added lines #L357 - L358 were not covered by tests
sensor_msgs::msg::PointCloud2::SharedPtr
transformed_delay_compensated_cloud_ptr_in_input_frame(
new sensor_msgs::msg::PointCloud2());
transformPointCloud(

Check warning on line 362 in sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp#L361-L362

Added lines #L361 - L362 were not covered by tests
transformed_delay_compensated_cloud_ptr,
transformed_delay_compensated_cloud_ptr_in_input_frame, e.second->header.frame_id);

Check warning on line 364 in sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp#L364

Added line #L364 was not covered by tests
transformed_delay_compensated_cloud_ptr =
transformed_delay_compensated_cloud_ptr_in_input_frame;
}

Check warning on line 367 in sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PointCloudDataSynchronizerComponent::synchronizeClouds increases in cyclomatic complexity from 11 to 13, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
// gather transformed clouds
transformed_delay_compensated_cloud_ptr->header.stamp = oldest_stamp;
transformed_delay_compensated_cloud_ptr->header.frame_id = output_frame_;
Expand Down
Loading