Skip to content

Commit

Permalink
Effective namespace is not necessary with node
Browse files Browse the repository at this point in the history
  • Loading branch information
devrite committed May 5, 2021
1 parent 6ba4560 commit 4a405cc
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 3 deletions.
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_effective_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
4 changes: 2 additions & 2 deletions image_transport/src/republish.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,9 @@ int main(int argc, char ** argv)
auto node = rclcpp::Node::make_shared("image_republisher");

std::string in_topic = rclcpp::expand_topic_or_service_name("in",
node->get_name(), node->get_effective_namespace());
node->get_name(), node->get_namespace());
std::string out_topic = rclcpp::expand_topic_or_service_name("out",
node->get_name(), node->get_effective_namespace());
node->get_name(), node->get_namespace());

std::string in_transport = vargv[1];

Expand Down

0 comments on commit 4a405cc

Please sign in to comment.