Skip to content

Commit

Permalink
Fix resolving sub-namespaces incorrectly
Browse files Browse the repository at this point in the history
Signed-off-by: Markus Hofstaetter <[email protected]>
  • Loading branch information
HPaper authored and devrite committed May 5, 2021
1 parent 872a6de commit d2275bc
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 5 deletions.
4 changes: 2 additions & 2 deletions image_transport/include/image_transport/camera_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
#ifndef IMAGE_TRANSPORT__CAMERA_PUBLISHER_H_
#define IMAGE_TRANSPORT__CAMERA_PUBLISHER_H_

#pragma message ("Warning: This header is deprecated. Use 'cammera_publisher.hpp' instead")
#pragma message ("Warning: This header is deprecated. Use 'camera_publisher.hpp' instead")

#include "cammera_publisher.hpp"
#include "camera_publisher.hpp"

#endif // IMAGE_TRANSPORT__CAMERA_PUBLISHER_H_
8 changes: 7 additions & 1 deletion image_transport/src/camera_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,14 @@ CameraPublisher::CameraPublisher(
{
// Explicitly resolve name here so we compute the correct CameraInfo topic when the
// image topic is remapped (#4539).

// FIXME: once https://github.com/ros2/rclcpp/issues/1656 is resolved, see #187
std::string effective_namespace = node->get_effective_namespace();
if (effective_namespace.length() > 1 && effective_namespace.back() == '/')
effective_namespace.pop_back();

std::string image_topic = rclcpp::expand_topic_or_service_name(base_topic,
node->get_name(), node->get_namespace());
node->get_name(), effective_namespace);
std::string info_topic = getCameraInfoTopic(image_topic);

auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos);
Expand Down
8 changes: 7 additions & 1 deletion image_transport/src/camera_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,8 +120,14 @@ 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.

// FIXME: once https://github.com/ros2/rclcpp/issues/1656 is resolved, see #187
std::string effective_namespace = node->get_effective_namespace();
if (effective_namespace.length() > 1 && effective_namespace.back() == '/')
effective_namespace.pop_back();

std::string image_topic = rclcpp::expand_topic_or_service_name(base_topic,
node->get_name(), node->get_namespace());
node->get_name(), effective_namespace);
std::string info_topic = getCameraInfoTopic(image_topic);

impl_->image_sub_.subscribe(node, image_topic, transport, custom_qos);
Expand Down
8 changes: 7 additions & 1 deletion image_transport/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,8 +105,14 @@ Publisher::Publisher(
{
// Resolve the name explicitly because otherwise the compressed topics don't remap
// properly (#3652).

// FIXME: once https://github.com/ros2/rclcpp/issues/1656 is resolved, see #187
std::string effective_namespace = node->get_effective_namespace();
if (effective_namespace.length() > 1 && effective_namespace.back() == '/')
effective_namespace.pop_back();

std::string image_topic = rclcpp::expand_topic_or_service_name(base_topic,
node->get_name(), node->get_namespace());
node->get_name(), effective_namespace);
impl_->base_topic_ = image_topic;
impl_->loader_ = loader;

Expand Down

0 comments on commit d2275bc

Please sign in to comment.