Skip to content

Commit 44e4be7

Browse files
authored
feat(pointcloud_preprocessor): enable to change synchronized pointcloud topic name (autowarefoundation#6525)
* feat: enable to change synchronized pointcloud message Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * fix: bug fix in topic name replace function Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * revert: revert changes do not related with this PR Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> * chore: move topic rename function to class member Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com> --------- Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 92c478e commit 44e4be7

File tree

5 files changed

+76
-12
lines changed

5 files changed

+76
-12
lines changed

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

+3
Original file line numberDiff line numberDiff line change
@@ -126,6 +126,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
126126
double timeout_sec_ = 0.1;
127127

128128
bool publish_synchronized_pointcloud_;
129+
std::string synchronized_pointcloud_postfix_;
129130

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

@@ -179,6 +180,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
179180
void timer_callback();
180181

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

183186
/** \brief processing time publisher. **/
184187
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
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,8 @@ class PointCloudDataSynchronizerComponent : public rclcpp::Node
177177
void timer_callback();
178178

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

181183
/** \brief processing time publisher. **/
182184
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

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

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

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

@@ -112,6 +113,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
112113

113114
// Check if publish synchronized pointcloud
114115
publish_synchronized_pointcloud_ = declare_parameter("publish_synchronized_pointcloud", false);
116+
synchronized_pointcloud_postfix_ =
117+
declare_parameter("synchronized_pointcloud_postfix", "pointcloud");
115118
}
116119

117120
// Initialize not_subscribed_topic_names_
@@ -185,10 +188,10 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
185188
}
186189
}
187190

188-
// Transformed Raw PointCloud2 Publisher
189-
{
191+
// Transformed Raw PointCloud2 Publisher to publish the transformed pointcloud
192+
if (publish_synchronized_pointcloud_) {
190193
for (auto & topic : input_topics_) {
191-
std::string new_topic = topic + POSTFIX_NAME;
194+
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix_);
192195
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
193196
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
194197
transformed_raw_pc_publisher_map_.insert({topic, publisher});
@@ -231,6 +234,35 @@ void PointCloudConcatenateDataSynchronizerComponent::transformPointCloud(
231234
}
232235
}
233236

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+
234266
/**
235267
* @brief compute transform to adjust for old timestamp
236268
*

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp

-6
Original file line numberDiff line numberDiff line change
@@ -74,12 +74,6 @@ PointCloudConcatenationComponent::PointCloudConcatenationComponent(
7474
return;
7575
}
7676
}
77-
// add postfix to topic names
78-
{
79-
for (auto & topic : input_topics_) {
80-
topic = topic + POSTFIX_NAME;
81-
}
82-
}
8377

8478
// Initialize not_subscribed_topic_names_
8579
{

sensing/pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_nodelet.cpp

+35-2
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
@@ -55,6 +55,7 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
5555
}
5656

5757
// Set parameters
58+
std::string synchronized_pointcloud_postfix;
5859
{
5960
output_frame_ = static_cast<std::string>(declare_parameter("output_frame", ""));
6061
if (output_frame_.empty()) {
@@ -71,6 +72,9 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
7172
RCLCPP_ERROR(get_logger(), "Only one topic given. Need at least two topics to continue.");
7273
return;
7374
}
75+
// output topic name postfix
76+
synchronized_pointcloud_postfix =
77+
declare_parameter("synchronized_pointcloud_postfix", "pointcloud");
7478

7579
// Optional parameters
7680
maximum_queue_size_ = static_cast<int>(declare_parameter("max_queue_size", 5));
@@ -150,7 +154,7 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
150154
// Transformed Raw PointCloud2 Publisher
151155
{
152156
for (auto & topic : input_topics_) {
153-
std::string new_topic = topic + POSTFIX_NAME;
157+
std::string new_topic = replaceSyncTopicNamePostfix(topic, synchronized_pointcloud_postfix);
154158
auto publisher = this->create_publisher<sensor_msgs::msg::PointCloud2>(
155159
new_topic, rclcpp::SensorDataQoS().keep_last(maximum_queue_size_));
156160
transformed_raw_pc_publisher_map_.insert({topic, publisher});
@@ -173,6 +177,35 @@ PointCloudDataSynchronizerComponent::PointCloudDataSynchronizerComponent(
173177
}
174178
}
175179

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+
176209
//////////////////////////////////////////////////////////////////////////////////////////////
177210
// overloaded functions
178211
void PointCloudDataSynchronizerComponent::transformPointCloud(

0 commit comments

Comments
 (0)