Skip to content

Commit d2275bc

Browse files
HPaperdevrite
authored andcommitted
Fix resolving sub-namespaces incorrectly
Signed-off-by: Markus Hofstaetter <[email protected]>
1 parent 872a6de commit d2275bc

File tree

4 files changed

+23
-5
lines changed

4 files changed

+23
-5
lines changed

image_transport/include/image_transport/camera_publisher.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,8 @@
3838
#ifndef IMAGE_TRANSPORT__CAMERA_PUBLISHER_H_
3939
#define IMAGE_TRANSPORT__CAMERA_PUBLISHER_H_
4040

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

43-
#include "cammera_publisher.hpp"
43+
#include "camera_publisher.hpp"
4444

4545
#endif // IMAGE_TRANSPORT__CAMERA_PUBLISHER_H_

image_transport/src/camera_publisher.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -87,8 +87,14 @@ CameraPublisher::CameraPublisher(
8787
{
8888
// Explicitly resolve name here so we compute the correct CameraInfo topic when the
8989
// image topic is remapped (#4539).
90+
91+
// FIXME: once https://github.com/ros2/rclcpp/issues/1656 is resolved, see #187
92+
std::string effective_namespace = node->get_effective_namespace();
93+
if (effective_namespace.length() > 1 && effective_namespace.back() == '/')
94+
effective_namespace.pop_back();
95+
9096
std::string image_topic = rclcpp::expand_topic_or_service_name(base_topic,
91-
node->get_name(), node->get_namespace());
97+
node->get_name(), effective_namespace);
9298
std::string info_topic = getCameraInfoTopic(image_topic);
9399

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

image_transport/src/camera_subscriber.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,8 +120,14 @@ CameraSubscriber::CameraSubscriber(
120120
{
121121
// Must explicitly remap the image topic since we then do some string manipulation on it
122122
// to figure out the sibling camera_info topic.
123+
124+
// FIXME: once https://github.com/ros2/rclcpp/issues/1656 is resolved, see #187
125+
std::string effective_namespace = node->get_effective_namespace();
126+
if (effective_namespace.length() > 1 && effective_namespace.back() == '/')
127+
effective_namespace.pop_back();
128+
123129
std::string image_topic = rclcpp::expand_topic_or_service_name(base_topic,
124-
node->get_name(), node->get_namespace());
130+
node->get_name(), effective_namespace);
125131
std::string info_topic = getCameraInfoTopic(image_topic);
126132

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

image_transport/src/publisher.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -105,8 +105,14 @@ Publisher::Publisher(
105105
{
106106
// Resolve the name explicitly because otherwise the compressed topics don't remap
107107
// properly (#3652).
108+
109+
// FIXME: once https://github.com/ros2/rclcpp/issues/1656 is resolved, see #187
110+
std::string effective_namespace = node->get_effective_namespace();
111+
if (effective_namespace.length() > 1 && effective_namespace.back() == '/')
112+
effective_namespace.pop_back();
113+
108114
std::string image_topic = rclcpp::expand_topic_or_service_name(base_topic,
109-
node->get_name(), node->get_namespace());
115+
node->get_name(), effective_namespace);
110116
impl_->base_topic_ = image_topic;
111117
impl_->loader_ = loader;
112118

0 commit comments

Comments
 (0)