Skip to content

Commit

Permalink
Add temporary fix if effective namespace returns a slash
Browse files Browse the repository at this point in the history
  • Loading branch information
devrite committed May 5, 2021
1 parent 4a405cc commit bddac70
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 2 deletions.
9 changes: 8 additions & 1 deletion image_transport/src/camera_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
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_effective_namespace());
node->get_name(), effective_namespace);
impl_->base_topic_ = image_topic;
impl_->loader_ = loader;

Expand Down

0 comments on commit bddac70

Please sign in to comment.