Skip to content

Commit

Permalink
chore: move topic rename function to class member
Browse files Browse the repository at this point in the history
Signed-off-by: yoshiri <[email protected]>
  • Loading branch information
YoshiRi committed Mar 1, 2024
1 parent 3c59e1c commit 6de7344
Show file tree
Hide file tree
Showing 4 changed files with 67 additions and 55 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -85,24 +85,6 @@
#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 Expand Up @@ -198,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 @@ -85,23 +85,6 @@
#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 Expand Up @@ -194,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
Expand Up @@ -61,7 +61,8 @@
#include <utility>
#include <vector>

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

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

Expand Down Expand Up @@ -190,15 +191,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
// 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 = 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;
}
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 @@ -241,6 +234,35 @@ void PointCloudConcatenateDataSynchronizerComponent::transformPointCloud(
}
}

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
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 Down Expand Up @@ -154,15 +154,7 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
// Transformed Raw PointCloud2 Publisher
{
for (auto & topic : input_topics_) {
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;
}
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 @@ -185,6 +177,35 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
}
}

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

0 comments on commit 6de7344

Please sign in to comment.