ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
For the gory details of the ports used by DDS, you can look at section 9.6 of the RTPS specification. RTPS (Real Time Publish Subscribe) is the wire protocol used by DDS.
Discovery traffic is traffic sent between DDS domain participants (in the case of ROS 2, a node) to find each other. It is sent out by one participant when it starts and potentially periodically after that to announce their existence and to find other participants. The ideal way to do this is by doing a UDP multicast, which sends the message to everyone on the same subnet. DDS participants listen on the discovery multicast port for broadcasts by other participants so they know where each other lives. However, because UDP multicast is not always available, unicast is also possible. In unicast the originating host sends the packet directly to the target IP.
User traffic is traffic that is not discovery. In other words, it is the data being sent on your topics, the service calls being made, etc., as well as internal DDS traffic such as looking for topics to connect. It can be sent by multicast because this is quite efficient when sending to multiple destinations (things like switches can handle the packet duplication instead of the originating host having to send out multiple packets itself). Like discovery traffic, it can also be sent via unicast.
All this stuff is happening on UDP, which is why you don't see explicit connections. You will not see these ports sending data because they are for listening on. Which ports are used to send are chosen by the OS, hence you seeing ephemeral ports sending data to them.
On to some specific questions:
I have no idea what the user multicast port does, because it doesn't show up when I use lsof -iUDP or ss -uap. Apparently 7401 is the port number reserved for this function but no process is using this port on my machine.
It won't necessarily be port 7401. As the page you linked to shows, it will be a port number calculated by the formula 7400 + (250 * Domain) + 1
. The actual port number may change if your domain ID changes. See what ROS_DOMAIN_ID
is set to to get an idea of what it will be.
I feel that if the discovery multicast node is for discovering new nodes and keeping track of existing ones, they should be sending messages like ACKNACK or HEARTBEAT, according to the legend here.
Discovery traffic won't include ACKNACK
or HEARTBEAT
messages. Those belong to user traffic.