Skip to content

Commit

Permalink
Apply remappings to base topic before creating transport-specific top…
Browse files Browse the repository at this point in the history
…ics (#326)
  • Loading branch information
bjsowa authored Oct 2, 2024
1 parent 6cec0b6 commit ea7589a
Show file tree
Hide file tree
Showing 5 changed files with 17 additions and 34 deletions.
5 changes: 1 addition & 4 deletions image_transport/src/camera_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
#include <string>
#include <utility>

#include "rclcpp/expand_topic_or_service_name.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/node.hpp"

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

auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos);
Expand Down
4 changes: 1 addition & 3 deletions image_transport/src/camera_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,9 +116,7 @@ CameraSubscriber::CameraSubscriber(
{
// Must explicitly remap the image topic since we then do some string manipulation on it
// to figure out the sibling camera_info topic.
std::string image_topic = rclcpp::expand_topic_or_service_name(
base_topic,
node->get_name(), node->get_namespace());
std::string image_topic = node->get_node_topics_interface()->resolve_topic_name(base_topic);
std::string info_topic = getCameraInfoTopic(image_topic);

impl_->image_sub_.subscribe(node, image_topic, transport, custom_qos);
Expand Down
5 changes: 1 addition & 4 deletions image_transport/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@
#include <utility>
#include <vector>

#include "rclcpp/expand_topic_or_service_name.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/node.hpp"

Expand Down Expand Up @@ -105,9 +104,7 @@ Publisher::Publisher(
{
// Resolve the name explicitly because otherwise the compressed topics don't remap
// properly (#3652).
std::string image_topic = rclcpp::expand_topic_or_service_name(
base_topic,
node->get_name(), node->get_namespace());
std::string image_topic = node->get_node_topics_interface()->resolve_topic_name(base_topic);
impl_->base_topic_ = image_topic;
impl_->loader_ = loader;

Expand Down
19 changes: 6 additions & 13 deletions image_transport/src/republish.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,13 +61,6 @@ Republisher::Republisher(const rclcpp::NodeOptions & options)

void Republisher::initialize()
{
std::string in_topic = rclcpp::expand_topic_or_service_name(
"in",
this->get_name(), this->get_namespace());
std::string out_topic = rclcpp::expand_topic_or_service_name(
"out",
this->get_name(), this->get_namespace());

std::string in_transport = "raw";
this->declare_parameter<std::string>("in_transport", in_transport);
if (!this->get_parameter(
Expand Down Expand Up @@ -117,14 +110,14 @@ void Republisher::initialize()
PublishMemFn pub_mem_fn = &image_transport::Publisher::publish;

pub_options.event_callbacks.matched_callback =
[this, in_topic, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo &)
[this, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo &)
{
std::scoped_lock<std::mutex> lock(this->pub_matched_mutex);
if (this->pub.getNumSubscribers() == 0) {
this->sub.shutdown();
} else if (!this->sub) {
this->sub = image_transport::create_subscription(
this, in_topic,
this, "in",
std::bind(pub_mem_fn, &this->pub, std::placeholders::_1),
in_transport,
rmw_qos_profile_default,
Expand All @@ -133,7 +126,7 @@ void Republisher::initialize()
};

this->pub = image_transport::create_publisher(
this, out_topic,
this, "out",
rmw_qos_profile_default, pub_options);
} else {
// Use one specific transport for output
Expand All @@ -151,21 +144,21 @@ void Republisher::initialize()
this->instance = loader->createUniqueInstance(lookup_name);

pub_options.event_callbacks.matched_callback =
[this, in_topic, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo & matched_info)
[this, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo & matched_info)
{
if (matched_info.current_count == 0) {
this->sub.shutdown();
} else if (!this->sub) {
this->sub = image_transport::create_subscription(
this, in_topic,
this, "in",
std::bind(
pub_mem_fn,
this->instance.get(), std::placeholders::_1), in_transport, rmw_qos_profile_default,
sub_options);
}
};

this->instance->advertise(this, out_topic, rmw_qos_profile_default, pub_options);
this->instance->advertise(this, "out", rmw_qos_profile_default, pub_options);
}
}

Expand Down
18 changes: 8 additions & 10 deletions image_transport/src/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
#include <string>
#include <vector>

#include "rclcpp/expand_topic_or_service_name.hpp"
#include "rclcpp/logging.hpp"

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

std::string image_topic = node->get_node_topics_interface()->resolve_topic_name(base_topic);

// Try to catch if user passed in a transport-specific topic as base_topic.
// TODO(ros2) use rclcpp to clean
// std::string clean_topic = ros::names::clean(base_topic);
std::string clean_topic = base_topic;

size_t found = clean_topic.rfind('/');
size_t found = image_topic.rfind('/');
if (found != std::string::npos) {
std::string transport = clean_topic.substr(found + 1);
std::string transport = image_topic.substr(found + 1);
std::string plugin_name = SubscriberPlugin::getLookupName(transport);
std::vector<std::string> plugins = loader->getDeclaredClasses();
if (std::find(plugins.begin(), plugins.end(), plugin_name) != plugins.end()) {
std::string real_base_topic = clean_topic.substr(0, found);
std::string real_base_topic = image_topic.substr(0, found);

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

// Tell plugin to subscribe.
RCLCPP_DEBUG(impl_->logger_, "Subscribing to: %s\n", base_topic.c_str());
impl_->subscriber_->subscribe(node, base_topic, callback, custom_qos, options);
RCLCPP_DEBUG(impl_->logger_, "Subscribing to: %s\n", image_topic.c_str());
impl_->subscriber_->subscribe(node, image_topic, callback, custom_qos, options);
}

std::string Subscriber::getTopic() const
Expand Down

0 comments on commit ea7589a

Please sign in to comment.