1
$\begingroup$

I am pretty new to ROS and would like to get some insight into if what I am creating is good and/or viable.

The system that I am making has a Publisher Node and a unknown number of Listener nodes (the number is finite (around 5-10), but the number of them that are active will depend on the hardware configuration of the system/robot). Each Listener subscribes to their respective topic ('/topic_1', '/topic_2', '/topic_3', ...) and their ID (1, 2, 3, ...). Note, each topic name and ID will be unique and the message format for the topics is the same (I am using a custom message that I've created).

The Publisher Node has an unordered_map that holds the Listener IDs and the Publishers to their topics.

unordered_map<uint8_t, rclcpp::Publisher<CustomMsgs::msg::CustomResponse>::SharedPtr> topic_table;

The Publisher Node also advertises a service ("/set_table") that is used to add new Publishers to the topic_table.


setTableService = this->create_service<CustomSrvs::srv::SetTable>(
    "/set_table",
    [this](const std::shared_ptr<CustomSrvs::srv::SetTable::Request> req,
           const std::shared_ptr<CustomSrvs::srv::SetTable::Response> res)
    {
        auto publisher = this->create_publisher<CustomMsgs::msg::CustomResponse>(req->value, 10);
        topic_table[req->id] = publisher;
        // Verify if the topic has been added to the table
        if(topic_table.find(req->id) == topic_table.end())
        {
            res->success = false;
            return;
        }
        res->success = true;
    }
);

The point of this is so that the Publisher Node need not have the knowledge of which Listener nodes even exist, what their topics are and only create the Publishers for the Listener nodes that are active (send the service request).

The Listener nodes only call the "/set_table" service once when they are started, meaning that adding new entries to the table will not be frequent.

Publishing to the topics will be in a separate thread of the Publisher node (The publisher node is basically used for UDP communication where the main execution thread of the node is used to send data over Ethernet and a new std::thread is created for the receiver part. I am using boost::asio for networking). When the receiver thread asynchronously receives data on the socket, the data is parsed and depending on the ID of the message, data is published on the respective topic:

topic_table[rsp_msg.id]->publish(rsp_msg);

I want to know if this type of dynamic creating of Publishers is advisable and/or safe to use and if there is maybe some better way to achieve what I intended to create. Is creating Publishers from a service callback bad practice?

Thanks in advance!

$\endgroup$

2 Answers 2

0
$\begingroup$

Depending on your platform's constraints and the content being published, you could consider just always creating a fixed number of publishers for all possible topics and setting the QoS appropriately to get the desired behavior as subscribers come and go (e.g. what history is kept, etc).

If nothing is subscribing to the topic, those messages won't actually make their way onto the network, so you don't need to worry about flooding the network with unread messages.

Perhaps this will introduce too much overhead on the publisher, but it sounds like in your case the publisher is always reading and sorting incoming packets anyways. But it would certainly be an easy and deterministic way to handle things.

$\endgroup$
0
$\begingroup$

In my personal opinion, you're using this service the way you should be using the parameter server. You may also be using multiple topics the way you could be using one topic. So I would consider this not best practices, but I'll elaborate.

It's pretty common to dynamically construct topics, services, and even callbacks: as you've observed, there are plenty of cases where you don't know what your node will need to connect to at compile-time. But, even though we can't know at compile time, we can know before run time: when you're about to turn on the robot, you know what the hardware configuration will be. So, rather than your current approach (which requires a service to be triggered and makes it difficult to understand what topics are being created), you can provide some kind of configuration file and construct your topics per that configuration.

This is where the parameter server comes into play. Parameters allow you to set a series of variables that your nodes can access. These can be set from within your launch file, or from a .yaml file that you call from your launch file. This approach to dynamically constructing topics is much more common. You can find an example of this being done in this widely-used robot localization package, and the documentation on parameters for ROS 2 can be found here.

That aside, you may be making this problem more complicated for yourself than necessary. You've mentioned that there is a series of topics here, and that they all have the same custom message type. Given that that's the case, do they really need to be different topics? If you need to know the unique origin of each message, that's information that could be held by the message. As a very widely-used example, consider the /tf topic: in a typical ROS robot configuration, you'll have several nodes publishing a wide array of different information to tf. But that's OK, because even though there is many active publishers to the one topic, the messages are designed with that in mind and providing one place to put the conceptually-linked information makes the overall system much easier to interface with.

$\endgroup$
2
  • $\begingroup$ "when you're about to turn on the robot, you know what the hardware configuration will be" That is not necessarily true. E.g. consider a pool of mobile robots driving around in a warehouse, each getting motion tasks from a central management node, and at runtime you want full flexibility to add or remove robots from the pool. For such a case, using a service to register each robot with the management node is imo. perfectly fine. Wrt. using one or multiple topics: it also depends, e.g for high frequency data it is not ideal that continuously callbacks are called for no reason... $\endgroup$
    – JRTG
    Commented Aug 10, 2023 at 14:30
  • $\begingroup$ I agree that there are cases where this is fine (you bring up a fair example). But, in this case, it sounds like rosparam is a perfectly acceptable approach: if that's the case, I would still argue that this is the preferred method. $\endgroup$
    – cst0
    Commented Aug 10, 2023 at 16:58

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.