ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ROS2 get publisher node name from subscriber

asked 2022-05-31 09:58:37 -0500

muttidrhummer gravatar image

Hi all, is there a way in ros2 to get the name of the node who is publishing a topic ? in ROS1 it could be done using ros::MessageEvent , while in ros2 there is no such way. Thanks

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2022-05-31 11:23:36 -0500

highmax1234 gravatar image

updated 2022-05-31 11:51:18 -0500

Following the trace of the command line ros2 topic infoleads us here: https://github.com/ros2/ros2cli/blob/... From there we can see that the rclcpp Graph API contains the methods. I quickly tried something out:

launch this in a terminal: ros2 run demo_nodes_cpp talker

And run the following code:

#include <chrono>
#include <functional>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"


class MinimalPublisher : public rclcpp::Node
{
  public:
    MinimalPublisher()
    : Node("minimal_publisher"), count_(0)
    {
      timer_ = this->create_wall_timer(
      500ms, std::bind(&MinimalPublisher::timer_callback, this));
    }

  private:
    void timer_callback()
    {
      auto result = this->get_publishers_info_by_topic("/chatter");
      for(const auto& node : result)
      {
        std::cout << node.node_name() << " topic type: " << node.topic_type() << " qos history: " << node.qos_profile().get_rmw_qos_profile().history <<  std::endl;
      }
    }
    rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());
  rclcpp::shutdown();
  return 0;
}

This outputs:

ros2 run graph_node graph_node 
talker topic type: std_msgs/msg/String qos history: 3
talker topic type: std_msgs/msg/String qos history: 3
talker topic type: std_msgs/msg/String qos history: 3
edit flag offensive delete link more

Comments

Thanks for the quick reply, i will try it soon. Thanks

muttidrhummer gravatar image muttidrhummer  ( 2022-05-31 11:30:24 -0500 )edit
1

This seems to get you all publishers for a specific topic, not the publisher who published the message that was just received -- which is what ros::MessageEvent allowed.

gvdhoorn gravatar image gvdhoorn  ( 2022-06-01 01:56:24 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-05-31 09:58:37 -0500

Seen: 600 times

Last updated: May 31 '22