Skip to content

Commit 6de7344

Browse files
committed
chore: move topic rename function to class member
Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 3c59e1c commit 6de7344

File tree

4 files changed

+67
-55
lines changed

4 files changed

+67
-55
lines changed

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp

+2-18
Original file line numberDiff line numberDiff line change
@@ -85,24 +85,6 @@
8585
#include <tf2_ros/buffer.h>
8686
#include <tf2_ros/transform_listener.h>
8787

88-
// replace topic name postfix
89-
inline std::string replace_topic_name_postfix(
90-
const std::string & original_topic_name, const std::string & postfix)
91-
{
92-
// separate the topic name by '/' and replace the last element with the new postfix
93-
size_t pos = original_topic_name.find_last_of("/");
94-
if (pos == std::string::npos) {
95-
// not found '/': this is not a namespaced topic
96-
std::cerr
97-
<< "The topic name is not namespaced. The postfix will be added to the end of the topic name."
98-
<< std::endl;
99-
return original_topic_name + postfix;
100-
} else {
101-
// replace the last element with the new postfix
102-
return original_topic_name.substr(0, pos) + "/" + postfix;
103-
}
104-
}
105-
10688
namespace pointcloud_preprocessor
10789
{
10890
using autoware_point_types::PointXYZI;
@@ -198,6 +180,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
198180
void timer_callback();
199181

200182
void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat);
183+
std::string replaceSyncTopicNamePostfix(
184+
const std::string & original_topic_name, const std::string & postfix);
201185

202186
/** \brief processing time publisher. **/
203187
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp

+2-17
Original file line numberDiff line numberDiff line change
@@ -85,23 +85,6 @@
8585
#include <tf2_ros/buffer.h>
8686
#include <tf2_ros/transform_listener.h>
8787

88-
// replace topic name postfix
89-
inline std::string replace_topic_name_postfix(
90-
const std::string & original_topic_name, const std::string & postfix)
91-
{
92-
// separate the topic name by '/' and replace the last element with the new postfix
93-
size_t pos = original_topic_name.find_last_of("/");
94-
if (pos == std::string::npos) {
95-
// not found '/': this is not a namespaced topic
96-
std::cerr
97-
<< "The topic name is not namespaced. The postfix will be added to the end of the topic name."
98-
<< std::endl;
99-
return original_topic_name + postfix;
100-
} else {
101-
// replace the last element with the new postfix
102-
return original_topic_name.substr(0, pos) + '/' + postfix;
103-
}
104-
}
10588
namespace pointcloud_preprocessor
10689
{
10790
using autoware_point_types::PointXYZI;
@@ -194,6 +177,8 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node
194177
void timer_callback();
195178

196179
void checkSyncStatus(diagnostic_updater::DiagnosticStatusWrapper & stat);
180+
std::string replaceSyncTopicNamePostfix(
181+
const std::string & original_topic_name, const std::string & postfix);
197182

198183
/** \brief processing time publisher. **/
199184
std::unique_ptr<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

+32-10
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,8 @@
6161
#include <utility>
6262
#include <vector>
6363

64-
#define POSTFIX_NAME "_synchronized" // default postfix name for synchronized pointcloud
64+
#define DEFAULT_SYNC_TOPIC_POSTFIX \
65+
"_synchronized" // default postfix name for synchronized pointcloud
6566

6667
//////////////////////////////////////////////////////////////////////////////////////////////
6768

@@ -190,15 +191,7 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
190191
// Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud
191192
if (publish_synchronized_pointcloud_) {
192193
for (auto & topic : input_topics_) {
193-
std::string new_topic = replace_topic_name_postfix(topic, synchronized_pointcloud_postfix_);
194-
if (new_topic == topic) {
195-
RCLCPP_WARN_STREAM(
196-
get_logger(),
197-
"The topic name "
198-
<< topic
199-
<< " does not have a postfix. The postfix will be added to the end of the topic name.");
200-
new_topic = topic + POSTFIX_NAME;
201-
}
194+
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix_);
202195
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
203196
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
204197
transformed_raw_pc_publisher_map_.insert({topic, publisher});
@@ -241,6 +234,35 @@ void PointCloudConcatenateDataSynchronizerComponent::transformPointCloud(
241234
}
242235
}
243236

237+
std::string PointCloudConcatenateDataSynchronizerComponent::replaceSyncTopicNamePostfix(
238+
const std::string & original_topic_name, const std::string & postfix)
239+
{
240+
std::string replaced_topic_name;
241+
// separate the topic name by '/' and replace the last element with the new postfix
242+
size_t pos = original_topic_name.find_last_of("/");
243+
if (pos == std::string::npos) {
244+
// not found '/': this is not a namespaced topic
245+
RCLCPP_WARN_STREAM(
246+
get_logger(),
247+
"The topic name is not namespaced. The postfix will be added to the end of the topic name.");
248+
return original_topic_name + postfix;
249+
} else {
250+
// replace the last element with the new postfix
251+
replaced_topic_name = original_topic_name.substr(0, pos) + "/" + postfix;
252+
}
253+
254+
// if topic name is the same with original topic name, add postfix to the end of the topic name
255+
if (replaced_topic_name == original_topic_name) {
256+
RCLCPP_WARN_STREAM(
257+
get_logger(), "The topic name "
258+
<< original_topic_name
259+
<< " have the same postfix with synchronized pointcloud. We use the postfix "
260+
"to the end of the topic name.");
261+
replaced_topic_name = original_topic_name + DEFAULT_SYNC_TOPIC_POSTFIX;
262+
}
263+
return replaced_topic_name;
264+
}
265+
244266
/**
245267
* @brief compute transform to adjust for old timestamp
246268
*

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

+31-10
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
#include <vector>
3535

3636
// postfix for output topics
37-
#define POSTFIX_NAME "_synchronized"
37+
#define DEFAULT_SYNC_TOPIC_POSTFIX "_synchronized"
3838
//////////////////////////////////////////////////////////////////////////////////////////////
3939

4040
namespace pointcloud_preprocessor
@@ -154,15 +154,7 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
154154
// Transformed Raw PointCloud2 Publisher
155155
{
156156
for (auto & topic : input_topics_) {
157-
std::string new_topic = replace_topic_name_postfix(topic, synchronized_pointcloud_postfix);
158-
if (new_topic == topic) {
159-
RCLCPP_WARN_STREAM(
160-
get_logger(),
161-
"The topic name "
162-
<< topic
163-
<< " does not have a postfix. The postfix will be added to the end of the topic name.");
164-
new_topic = topic + POSTFIX_NAME;
165-
}
157+
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix);
166158
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
167159
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
168160
transformed_raw_pc_publisher_map_.insert({topic, publisher});
@@ -185,6 +177,35 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
185177
}
186178
}
187179

180+
std::string PointCloudDataSynchronizerComponent::replaceSyncTopicNamePostfix(
181+
const std::string & original_topic_name, const std::string & postfix)
182+
{
183+
std::string replaced_topic_name;
184+
// separate the topic name by '/' and replace the last element with the new postfix
185+
size_t pos = original_topic_name.find_last_of("/");
186+
if (pos == std::string::npos) {
187+
// not found '/': this is not a namespaced topic
188+
RCLCPP_WARN_STREAM(
189+
get_logger(),
190+
"The topic name is not namespaced. The postfix will be added to the end of the topic name.");
191+
return original_topic_name + postfix;
192+
} else {
193+
// replace the last element with the new postfix
194+
replaced_topic_name = original_topic_name.substr(0, pos) + "/" + postfix;
195+
}
196+
197+
// if topic name is the same with original topic name, add postfix to the end of the topic name
198+
if (replaced_topic_name == original_topic_name) {
199+
RCLCPP_WARN_STREAM(
200+
get_logger(), "The topic name "
201+
<< original_topic_name
202+
<< " have the same postfix with synchronized pointcloud. We use the postfix "
203+
"to the end of the topic name.");
204+
replaced_topic_name = original_topic_name + DEFAULT_SYNC_TOPIC_POSTFIX;
205+
}
206+
return replaced_topic_name;
207+
}
208+
188209
//////////////////////////////////////////////////////////////////////////////////////////////
189210
// overloaded functions
190211
void PointCloudDataSynchronizerComponent::transformPointCloud(

0 commit comments

Comments
 (0)