ros / ros_comm

ROS communications-related packages, including core client libraries (roscpp, rospy, roslisp) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
http://wiki.ros.org/ros_comm
747 stars 914 forks source link

[topic_tools/mux] add wait_publisher_initialization option in mux #2305

Closed knorth55 closed 1 year ago

knorth55 commented 1 year ago

mux node does not have sleep between advertise and publish. this causes dropping first message publication. this does not matter when the topic's frequency is high. but when the topic's frequency is low, dropping the first message causes huge time loss.

This PR add option to add 0.1ms sleep between advertise and publish. This change avoids dropping the first message.

How to test

Sample launch

Publish topic in 10 second. without this PR, the first message of /node_mux will drop, so we need to wait 20 seconds to get /node_mux topic.

<launch>
  <arg name="wait_publisher_initialization" default="false" />

  <node name="node1" pkg="rostopic" type="rostopic"
        args="pub -r 0.1 /node1 std_msgs/String node1" 
        output="screen" />
  <node name="node2" pkg="rostopic" type="rostopic"
        args="pub -r 0.1 /node2 std_msgs/String node2"
        output="screen" />
  <node name="mux" pkg="topic_tools" type="mux"
        args="/node_mux /node1 /node2"
        output="screen">
    <rosparam subst_value="true">
      wait_publisher_initialization: $(arg wait_publisher_initialization) 
    </rosparam>
  </node>
</launch>

wait_publisher_initialization: true (this PR)

After 10 seconds, /node1, /node2 and /node_mux arrived!

$ rostopic echo /node1
data: "node1"
---
$ rostopic echo /node2
data: "node2"
---
$ rostopic echo /node_mux
data: "node1"
---

wait_publisher_initialization: false (current behavior)

After 10 seconds, /node1 and /node2 arrive, but /node_mux did not arrived.

$ rostopic echo /node1
data: "node1"
---
$ rostopic echo /node2
data: "node2"
---
$ rostopic echo /node_mux
knorth55 commented 1 year ago

@mjcarroll can you review this PR? this first topic drop causes unintended robot behavior.

Our case: In our lab, we use mux for speech-to-text result, because there are several running speech-to-text engines to select. When a person talk to the robot, the robot always ignore the person at first, which is caused by this first topic drop. Therefore, we need to speak the same thing twice when mux start publishing the topic.

In order to avoid this behavior, we make this wait_publisher_initialization option for mux. This PR does not change the default behavior.

knorth55 commented 1 year ago

@peci1 Thank you for your advice! I add wait_publisher_second param