Skip to content

Commit

Permalink
feat: make concatenate node to publish pointclouds in sensor frame
Browse files Browse the repository at this point in the history
Signed-off-by: yoshiri <[email protected]>
  • Loading branch information
YoshiRi committed Mar 11, 2024
1 parent 7081a61 commit 855d440
Show file tree
Hide file tree
Showing 4 changed files with 47 additions and 20 deletions.
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
Expand Up @@ -112,7 +112,9 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
}

// 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,22 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds(
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
if (keep_input_frame_in_synchronized_pointcloud_) {

Check warning on line 403 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

Added line #L403 was 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 407 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#L405-L407

Added lines #L405 - L407 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;

Check warning on line 411 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#L409-L411

Added lines #L409 - L411 were not covered by tests
} 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 415 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#L413-L415

Added lines #L413 - L415 were not covered by tests
}

Check warning on line 417 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 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.
} else {
not_subscribed_topic_names_.insert(e.first);
}
Expand All @@ -418,20 +432,6 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
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 +469,19 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
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 474 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#L472-L474

Added lines #L472 - L474 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 481 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#L478-L481

Added lines #L478 - L481 were not covered by tests
}
}
}
}

///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,9 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
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 @@ -352,6 +354,16 @@ PointCloudDataSynchronizerComponent::synchronizeClouds()
adjust_to_old_data_transform, *transformed_cloud_ptr,
*transformed_delay_compensated_cloud_ptr);

if (keep_input_frame_in_synchronized_pointcloud_) {

Check warning on line 357 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

Added line #L357 was 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 361 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#L360-L361

Added lines #L360 - L361 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 363 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#L363

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

Check warning on line 366 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 12, 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

0 comments on commit 855d440

Please sign in to comment.