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 3 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 @@ -85,6 +85,24 @@
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

// replace topic name postfix
inline std::string replace_topic_name_postfix(
const std::string & original_topic_name, const std::string & postfix)
{
// 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) {
// not found '/': this is not a namespaced topic
std::cerr
kyoichi-sugahara marked this conversation as resolved.
Show resolved Hide resolved
<< "The topic name is not namespaced. The postfix will be added to the end of the topic name."
<< std::endl;
return original_topic_name + postfix;
} else {
// replace the last element with the new postfix
return original_topic_name.substr(0, pos) + "/" + postfix;
}
}

namespace pointcloud_preprocessor
{
using autoware_point_types::PointXYZI;
Expand Down Expand Up @@ -126,6 +144,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
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,23 @@
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

// replace topic name postfix
inline std::string replace_topic_name_postfix(
const std::string & original_topic_name, const std::string & postfix)
{
// 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) {
// not found '/': this is not a namespaced topic
std::cerr
<< "The topic name is not namespaced. The postfix will be added to the end of the topic name."
<< std::endl;
return original_topic_name + postfix;
} else {
// replace the last element with the new postfix
return original_topic_name.substr(0, pos) + '/' + postfix;
}
}
namespace pointcloud_preprocessor
{
using autoware_point_types::PointXYZI;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@
#include <utility>
#include <vector>

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

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

Expand Down Expand Up @@ -112,6 +112,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro

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

// Initialize not_subscribed_topic_names_
Expand Down Expand Up @@ -185,10 +187,18 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
}
}

// Transformed Raw PointCloud2 Publisher
{
// Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud
if (publish_synchronized_pointcloud_) {
for (auto & topic : input_topics_) {
std::string new_topic = topic + POSTFIX_NAME;
std::string new_topic = replace_topic_name_postfix(topic, synchronized_pointcloud_postfix_);
if (new_topic == topic) {
RCLCPP_WARN_STREAM(
get_logger(),
"The topic name "
<< topic
<< " does not have a postfix. The postfix will be added to the end of the topic name.");
new_topic = topic + POSTFIX_NAME;
}
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
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
Expand Up @@ -55,6 +55,7 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
}

// 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 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
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");

// Optional parameters
maximum_queue_size_ = static_cast<int>(declare_parameter("max_queue_size", 5));
Expand Down Expand Up @@ -150,7 +154,15 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
// Transformed Raw PointCloud2 Publisher
{
for (auto & topic : input_topics_) {
std::string new_topic = topic + POSTFIX_NAME;
std::string new_topic = replace_topic_name_postfix(topic, synchronized_pointcloud_postfix);
if (new_topic == topic) {
RCLCPP_WARN_STREAM(
get_logger(),
"The topic name "
<< topic
<< " does not have a postfix. The postfix will be added to the end of the topic name.");
new_topic = topic + POSTFIX_NAME;
}
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
Loading