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): enable to change synchronized pointcloud topic name #6525

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_;
std::string synchronized_pointcloud_postfix_;

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

Expand Down Expand Up @@ -179,6 +180,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
void timer_callback();

void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat);
std::string replaceSyncTopicNamePostfix(
const std::string & original_topic_name, const std::string & postfix);

/** \brief processing time publisher. **/
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,8 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node
void timer_callback();

void checkSyncStatus(diagnostic_updater::DiagnosticStatusWrapper & stat);
std::string replaceSyncTopicNamePostfix(
const std::string & original_topic_name, const std::string & postfix);

/** \brief processing time publisher. **/
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
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 better: Overall Code Complexity

The mean cyclomatic complexity decreases from 6.18 to 5.92, 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 @@ -61,7 +61,8 @@
#include <utility>
#include <vector>

#define POSTFIX_NAME "_synchronized"
#define DEFAULT_SYNC_TOPIC_POSTFIX \
"_synchronized" // default postfix name for synchronized pointcloud

//////////////////////////////////////////////////////////////////////////////////////////////

Expand Down Expand Up @@ -112,6 +113,8 @@

// Check if publish synchronized pointcloud
publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", false);
synchronized_pointcloud_postfix_ =
declare_parameter("synchronized_pointcloud_postfix", "pointcloud");

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#L117

Added line #L117 was not covered by tests
}

// Initialize not_subscribed_topic_names_
Expand Down Expand Up @@ -185,10 +188,10 @@
}
}

// Transformed Raw PointCloud2 Publisher
{
// Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud
if (publish_synchronized_pointcloud_) {

Check warning on line 192 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#L192

Added line #L192 was not covered by tests
for (auto & topic : input_topics_) {
std::string new_topic = topic + POSTFIX_NAME;
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix_);

Check warning on line 194 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#L194

Added line #L194 was not covered by tests
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
transformed_raw_pc_publisher_map_.insert({topic, publisher});
Expand Down Expand Up @@ -231,6 +234,35 @@
}
}

std::string PointCloudConcatenateDataSynchronizerComponent::replaceSyncTopicNamePostfix(

Check warning on line 237 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#L237

Added line #L237 was not covered by tests
const std::string & original_topic_name, const std::string & postfix)
{
std::string replaced_topic_name;
// separate the topic name by '/' and replace the last element with the new postfix
size_t pos = original_topic_name.find_last_of("/");
if (pos == std::string::npos) {

Check warning on line 243 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#L243

Added line #L243 was not covered by tests
// not found '/': this is not a namespaced topic
RCLCPP_WARN_STREAM(

Check warning on line 245 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#L245

Added line #L245 was not covered by tests
get_logger(),
"The topic name is not namespaced. The postfix will be added to the end of the topic name.");
return original_topic_name + postfix;

Check warning on line 248 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#L248

Added line #L248 was not covered by tests
} else {
// replace the last element with the new postfix
replaced_topic_name = original_topic_name.substr(0, pos) + "/" + postfix;

Check warning on line 251 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#L251

Added line #L251 was not covered by tests
}

// if topic name is the same with original topic name, add postfix to the end of the topic name
if (replaced_topic_name == original_topic_name) {
RCLCPP_WARN_STREAM(

Check warning on line 256 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#L255-L256

Added lines #L255 - L256 were not covered by tests
get_logger(), "The topic name "
<< original_topic_name
<< " have the same postfix with synchronized pointcloud. We use the postfix "
"to the end of the topic name.");
replaced_topic_name = original_topic_name + DEFAULT_SYNC_TOPIC_POSTFIX;

Check warning on line 261 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#L261

Added line #L261 was not covered by tests
}
return replaced_topic_name;
}

/**
* @brief compute transform to adjust for old timestamp
*
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/concatenate_data/concatenate_pointclouds.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 6.00 to 5.91, 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 @@ -73,13 +73,7 @@
RCLCPP_ERROR(get_logger(), "The number of topics does not match the number of offsets.");
return;
}
}

Check notice on line 76 in sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

PointCloudConcatenationComponent::PointCloudConcatenationComponent decreases in cyclomatic complexity from 11 to 10, 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.
// add postfix to topic names
{
for (auto & topic : input_topics_) {
topic = topic + POSTFIX_NAME;
}
}

// Initialize not_subscribed_topic_names_
{
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 better: Overall Code Complexity

The mean cyclomatic complexity decreases from 5.25 to 5.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 @@ -34,7 +34,7 @@
#include <vector>

// postfix for output topics
#define POSTFIX_NAME "_synchronized"
#define DEFAULT_SYNC_TOPIC_POSTFIX "_synchronized"
//////////////////////////////////////////////////////////////////////////////////////////////

namespace pointcloud_preprocessor
Expand All @@ -55,6 +55,7 @@
}

// Set parameters
std::string synchronized_pointcloud_postfix;
{
output_frame_ = static_cast<std::string>(declare_parameter("output_frame", ""));
if (output_frame_.empty()) {
Expand All @@ -71,6 +72,9 @@
RCLCPP_ERROR(get_logger(), "Only one topic given. Need at least two topics to continue.");
return;
}
// output topic name postfix
synchronized_pointcloud_postfix =
declare_parameter("synchronized_pointcloud_postfix", "pointcloud");

Check warning on line 77 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#L77

Added line #L77 was not covered by tests

// Optional parameters
maximum_queue_size_ = static_cast<int>(declare_parameter("max_queue_size", 5));
Expand Down Expand Up @@ -150,7 +154,7 @@
// Transformed Raw PointCloud2 Publisher
{
for (auto & topic : input_topics_) {
std::string new_topic = topic + POSTFIX_NAME;
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix);

Check warning on line 157 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#L157

Added line #L157 was not covered by tests
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
transformed_raw_pc_publisher_map_.insert({topic, publisher});
Expand All @@ -173,6 +177,35 @@
}
}

std::string PointCloudDataSynchronizerComponent::replaceSyncTopicNamePostfix(

Check warning on line 180 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#L180

Added line #L180 was not covered by tests
const std::string & original_topic_name, const std::string & postfix)
{
std::string replaced_topic_name;
// separate the topic name by '/' and replace the last element with the new postfix
size_t pos = original_topic_name.find_last_of("/");
if (pos == std::string::npos) {

Check warning on line 186 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#L186

Added line #L186 was not covered by tests
// not found '/': this is not a namespaced topic
RCLCPP_WARN_STREAM(

Check warning on line 188 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#L188

Added line #L188 was not covered by tests
get_logger(),
"The topic name is not namespaced. The postfix will be added to the end of the topic name.");
return original_topic_name + postfix;

Check warning on line 191 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#L191

Added line #L191 was not covered by tests
} else {
// replace the last element with the new postfix
replaced_topic_name = original_topic_name.substr(0, pos) + "/" + postfix;

Check warning on line 194 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#L194

Added line #L194 was not covered by tests
}

// if topic name is the same with original topic name, add postfix to the end of the topic name
if (replaced_topic_name == original_topic_name) {
RCLCPP_WARN_STREAM(

Check warning on line 199 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#L198-L199

Added lines #L198 - L199 were not covered by tests
get_logger(), "The topic name "
<< original_topic_name
<< " have the same postfix with synchronized pointcloud. We use the postfix "
"to the end of the topic name.");
replaced_topic_name = original_topic_name + DEFAULT_SYNC_TOPIC_POSTFIX;

Check warning on line 204 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#L204

Added line #L204 was not covered by tests
}
return replaced_topic_name;
}

//////////////////////////////////////////////////////////////////////////////////////////////
// overloaded functions
void PointCloudDataSynchronizerComponent::transformPointCloud(
Expand Down
Loading