Skip to content

Commit ea7589a

Browse files
authored
Apply remappings to base topic before creating transport-specific topics (#326)
1 parent 6cec0b6 commit ea7589a

File tree

5 files changed

+17
-34
lines changed

5 files changed

+17
-34
lines changed

image_transport/src/camera_publisher.cpp

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@
3232
#include <string>
3333
#include <utility>
3434

35-
#include "rclcpp/expand_topic_or_service_name.hpp"
3635
#include "rclcpp/logging.hpp"
3736
#include "rclcpp/node.hpp"
3837

@@ -84,9 +83,7 @@ CameraPublisher::CameraPublisher(
8483
{
8584
// Explicitly resolve name here so we compute the correct CameraInfo topic when the
8685
// image topic is remapped (#4539).
87-
std::string image_topic = rclcpp::expand_topic_or_service_name(
88-
base_topic,
89-
node->get_name(), node->get_namespace());
86+
std::string image_topic = node->get_node_topics_interface()->resolve_topic_name(base_topic);
9087
std::string info_topic = getCameraInfoTopic(image_topic);
9188

9289
auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos);

image_transport/src/camera_subscriber.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -116,9 +116,7 @@ CameraSubscriber::CameraSubscriber(
116116
{
117117
// Must explicitly remap the image topic since we then do some string manipulation on it
118118
// to figure out the sibling camera_info topic.
119-
std::string image_topic = rclcpp::expand_topic_or_service_name(
120-
base_topic,
121-
node->get_name(), node->get_namespace());
119+
std::string image_topic = node->get_node_topics_interface()->resolve_topic_name(base_topic);
122120
std::string info_topic = getCameraInfoTopic(image_topic);
123121

124122
impl_->image_sub_.subscribe(node, image_topic, transport, custom_qos);

image_transport/src/publisher.cpp

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,6 @@
3535
#include <utility>
3636
#include <vector>
3737

38-
#include "rclcpp/expand_topic_or_service_name.hpp"
3938
#include "rclcpp/logging.hpp"
4039
#include "rclcpp/node.hpp"
4140

@@ -105,9 +104,7 @@ Publisher::Publisher(
105104
{
106105
// Resolve the name explicitly because otherwise the compressed topics don't remap
107106
// properly (#3652).
108-
std::string image_topic = rclcpp::expand_topic_or_service_name(
109-
base_topic,
110-
node->get_name(), node->get_namespace());
107+
std::string image_topic = node->get_node_topics_interface()->resolve_topic_name(base_topic);
111108
impl_->base_topic_ = image_topic;
112109
impl_->loader_ = loader;
113110

image_transport/src/republish.cpp

Lines changed: 6 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -61,13 +61,6 @@ Republisher::Republisher(const rclcpp::NodeOptions & options)
6161

6262
void Republisher::initialize()
6363
{
64-
std::string in_topic = rclcpp::expand_topic_or_service_name(
65-
"in",
66-
this->get_name(), this->get_namespace());
67-
std::string out_topic = rclcpp::expand_topic_or_service_name(
68-
"out",
69-
this->get_name(), this->get_namespace());
70-
7164
std::string in_transport = "raw";
7265
this->declare_parameter<std::string>("in_transport", in_transport);
7366
if (!this->get_parameter(
@@ -117,14 +110,14 @@ void Republisher::initialize()
117110
PublishMemFn pub_mem_fn = &image_transport::Publisher::publish;
118111

119112
pub_options.event_callbacks.matched_callback =
120-
[this, in_topic, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo &)
113+
[this, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo &)
121114
{
122115
std::scoped_lock<std::mutex> lock(this->pub_matched_mutex);
123116
if (this->pub.getNumSubscribers() == 0) {
124117
this->sub.shutdown();
125118
} else if (!this->sub) {
126119
this->sub = image_transport::create_subscription(
127-
this, in_topic,
120+
this, "in",
128121
std::bind(pub_mem_fn, &this->pub, std::placeholders::_1),
129122
in_transport,
130123
rmw_qos_profile_default,
@@ -133,7 +126,7 @@ void Republisher::initialize()
133126
};
134127

135128
this->pub = image_transport::create_publisher(
136-
this, out_topic,
129+
this, "out",
137130
rmw_qos_profile_default, pub_options);
138131
} else {
139132
// Use one specific transport for output
@@ -151,21 +144,21 @@ void Republisher::initialize()
151144
this->instance = loader->createUniqueInstance(lookup_name);
152145

153146
pub_options.event_callbacks.matched_callback =
154-
[this, in_topic, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo & matched_info)
147+
[this, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo & matched_info)
155148
{
156149
if (matched_info.current_count == 0) {
157150
this->sub.shutdown();
158151
} else if (!this->sub) {
159152
this->sub = image_transport::create_subscription(
160-
this, in_topic,
153+
this, "in",
161154
std::bind(
162155
pub_mem_fn,
163156
this->instance.get(), std::placeholders::_1), in_transport, rmw_qos_profile_default,
164157
sub_options);
165158
}
166159
};
167160

168-
this->instance->advertise(this, out_topic, rmw_qos_profile_default, pub_options);
161+
this->instance->advertise(this, "out", rmw_qos_profile_default, pub_options);
169162
}
170163
}
171164

image_transport/src/subscriber.cpp

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@
3232
#include <string>
3333
#include <vector>
3434

35-
#include "rclcpp/expand_topic_or_service_name.hpp"
3635
#include "rclcpp/logging.hpp"
3736

3837
#include "sensor_msgs/msg/image.hpp"
@@ -99,18 +98,17 @@ Subscriber::Subscriber(
9998
throw TransportLoadException(impl_->lookup_name_, e.what());
10099
}
101100

101+
std::string image_topic = node->get_node_topics_interface()->resolve_topic_name(base_topic);
102+
102103
// Try to catch if user passed in a transport-specific topic as base_topic.
103-
// TODO(ros2) use rclcpp to clean
104-
// std::string clean_topic = ros::names::clean(base_topic);
105-
std::string clean_topic = base_topic;
106104

107-
size_t found = clean_topic.rfind('/');
105+
size_t found = image_topic.rfind('/');
108106
if (found != std::string::npos) {
109-
std::string transport = clean_topic.substr(found + 1);
107+
std::string transport = image_topic.substr(found + 1);
110108
std::string plugin_name = SubscriberPlugin::getLookupName(transport);
111109
std::vector<std::string> plugins = loader->getDeclaredClasses();
112110
if (std::find(plugins.begin(), plugins.end(), plugin_name) != plugins.end()) {
113-
std::string real_base_topic = clean_topic.substr(0, found);
111+
std::string real_base_topic = image_topic.substr(0, found);
114112

115113
RCLCPP_WARN(
116114
impl_->logger_,
@@ -119,13 +117,13 @@ Subscriber::Subscriber(
119117
"error. Try subscribing to the base topic '%s' instead with parameter ~image_transport "
120118
"set to '%s' (on the command line, _image_transport:=%s). "
121119
"See http://ros.org/wiki/image_transport for details.",
122-
clean_topic.c_str(), real_base_topic.c_str(), transport.c_str(), transport.c_str());
120+
image_topic.c_str(), real_base_topic.c_str(), transport.c_str(), transport.c_str());
123121
}
124122
}
125123

126124
// Tell plugin to subscribe.
127-
RCLCPP_DEBUG(impl_->logger_, "Subscribing to: %s\n", base_topic.c_str());
128-
impl_->subscriber_->subscribe(node, base_topic, callback, custom_qos, options);
125+
RCLCPP_DEBUG(impl_->logger_, "Subscribing to: %s\n", image_topic.c_str());
126+
impl_->subscriber_->subscribe(node, image_topic, callback, custom_qos, options);
129127
}
130128

131129
std::string Subscriber::getTopic() const

0 commit comments

Comments
 (0)