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

Generic Subscriber in ROS2

asked 2020-08-17 05:38:26 -0500

nyxaria gravatar image

I am looking to replicate ROS1 behaviour where I could use ShapeShifter to subscribe to any topic, and not have to specify the message type. This code would run in C++.

I have found this Pull Request but it seems nothing has yet come of this.

Does anyone know if this is possible in ROS2 using C++? If not C++, then Python?

Many thanks

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
2

answered 2020-08-17 08:16:31 -0500

lukicdarkoo gravatar image

updated 2020-08-17 08:24:15 -0500

Not completely what are looking for, but here is one way to do in Python. In Python, you can use get_msg_class from ros2topic.api to get the message type and then subscribe to the topic. Here is an example:

import rclpy
from rclpy.node import Node
from ros2topic.api import get_msg_class


class TestSubscriber(Node):
    def __init__(self):
        super().__init__('test_subscriber')
        message_type = get_msg_class(self, '/topic_name', include_hidden_topics=True)
        print('Message type:', message_type)
        self.create_subscription(message_type, '/topic_name', self.on_message_received, 1)

    def on_message_received(self, message):
        print(message)


def main(args=None):
    rclpy.init(args=args)
    test_subscriber = TestSubscriber()
    rclpy.spin(test_subscriber)
    test_subscriber.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

Test it by running e.g.:

ros2 topic pub /topic_name std_msgs/String '{ data: test_value }'
edit flag offensive delete link more

Comments

This is awesome, thanks! Such as a shame the C++ api is not there yet.

nyxaria gravatar image nyxaria  ( 2020-08-17 08:22:39 -0500 )edit
1

answered 2020-08-17 07:25:57 -0500

dawonn_haval gravatar image

Take a look at rosbag2, it subscribes to serialized topics regardless of message type.

https://github.com/ros2/rosbag2/blob/...

edit flag offensive delete link more

Comments

Thank you!

nyxaria gravatar image nyxaria  ( 2020-08-17 08:22:47 -0500 )edit
0

answered 2023-01-12 08:24:00 -0500

ros_geek gravatar image

For anyone looking for a cpp solution:

#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/generic_subscription.hpp"
#include "std_msgs/msg/string.hpp"
using std::placeholders::_1;

class MinimalSubscriber : public rclcpp::Node
{
  public:
    MinimalSubscriber()
    : Node("minimal_subscriber")
    {
      auto data = rclcpp::Node::get_topic_names_and_types();
      auto msg_type = data["/topic_name"];

      for(auto type : msg_type){
      std::cout << type  << std::endl;
      rclcpp::QoS qos = rclcpp::QoS(10);
      std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> call = std::bind(&MinimalSubscriber::topic_callback, this, _1);
      subscription_ = this->create_generic_subscription("/topic_name",type ,qos, call );
    }
     }

  private:
    void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg)
    {
      RCLCPP_INFO(this->get_logger(), "I heard:");
    }
    std::shared_ptr<rclcpp::GenericSubscription> subscription_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalSubscriber>());
  rclcpp::shutdown();
  return 0;
}
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-08-17 05:38:26 -0500

Seen: 2,010 times

Last updated: Jan 12 '23