Skip to content

Commit

Permalink
apply same treatment to image_view
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Jan 18, 2024
1 parent e350e74 commit 914baf2
Showing 1 changed file with 5 additions and 3 deletions.
8 changes: 5 additions & 3 deletions image_view/src/image_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,8 +107,10 @@ ImageViewNode::ImageViewNode(const rclcpp::NodeOptions & options)
auto transport = this->declare_parameter("image_transport", "raw");
RCLCPP_INFO(this->get_logger(), "Using transport \"%s\"", transport.c_str());

std::string topic = rclcpp::expand_topic_or_service_name(
"image", this->get_name(), this->get_namespace());
// For compressed topics to remap appropriately, we need to pass a
// fully expanded and remapped topic name to image_transport
auto node_base = this->get_node_base_interface();
std::string topic = node_base->resolve_topic_or_service_name("image", false);

image_transport::TransportHints hints(this, transport);
pub_ = this->create_publisher<sensor_msgs::msg::Image>("output", 1);
Expand All @@ -118,7 +120,7 @@ ImageViewNode::ImageViewNode(const rclcpp::NodeOptions & options)

auto topics = this->get_topic_names_and_types();

if (topics.find(topic) != topics.end()) {
if (topics.find(topic) == topics.end()) {
RCLCPP_WARN(
this->get_logger(), "Topic 'image' has not been remapped! "
"Typical command-line usage:\n"
Expand Down

0 comments on commit 914baf2

Please sign in to comment.