diff --git a/image_transport/src/camera_subscriber.cpp b/image_transport/src/camera_subscriber.cpp index 94cd5929..78fdf071 100644 --- a/image_transport/src/camera_subscriber.cpp +++ b/image_transport/src/camera_subscriber.cpp @@ -120,8 +120,15 @@ 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: when is resolved: https://github.com/ros2/rclcpp/issues/1656 + + //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_effective_namespace()); + node->get_name(), effective_namespace); std::string info_topic = getCameraInfoTopic(image_topic); impl_->image_sub_.subscribe(node, image_topic, transport, custom_qos); diff --git a/image_transport/src/publisher.cpp b/image_transport/src/publisher.cpp index 38a59175..7d61cb98 100644 --- a/image_transport/src/publisher.cpp +++ b/image_transport/src/publisher.cpp @@ -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_effective_namespace()); + node->get_name(), effective_namespace); impl_->base_topic_ = image_topic; impl_->loader_ = loader;