1.4.5. Static Discovery¶
1.4.5.1. Background¶
OMG DDS Interoperability specification defines the basic discovery mechanism that allows distributed systems to automatically find and match Endpoints sharing the same Topic. This mechanism is performed in two phases as explained in Fast DDS documentation:
Participant Discovery Phase (PDP): DDS DomainParticipants discover and acknowledge the existence of remote DomainParticipants. Usually done sending periodic announcements to well-known multicast addresses and ports defined in the specification.
Endpoint Discovery Phase (EDP): each DDS DomainParticipant send information about its own endpoints (DataWriters and DataReaders) through the communication channels established in the previous phase.
Standard discovery has its caveats, like the required multicast traffic being sent periodically, that can saturate the network bandwidth in constraint network architectures with a large number of DDS DomainParticipants. Vulcanexus leverages latest eProsima Fast DDS release to improve ROS 2 middleware layer. Being aware of the standard discovery mechanism caveats, eProsima Fast DDS provides alternative discovery mechanisms:
Fast DDS Discovery Server reduces the discovery metatraffic using a centralized client-server discovery mechanism instead of a distributed one. More information can be found in Using Fast DDS Discovery Server as discovery protocol tutorial. This schema reduces discovery metatraffic from both PDP and EDP phases because the information is sent exclusively to the DomainParticipants in a need-to-know basis.
Setting an initial peers list and disabling multicast also decreases the discovery traffic for the PDP phase, sending each DomainParticipant the announcement to the locators where the announcement is expected.
Fast DDS Static Discovery removes completely any EDP discovery metatraffic by configuring the endpoints, topics and data types beforehand. This tutorial deals on how to use this discovery mechanism within Vulcanexus. More information about Static EDP discovery can be found in Fast DDS documentation.
1.4.5.2. Prerequisites¶
This tutorial uses ROS 2 demo_nodes_cpp
package which is provided with Vulcanexus Desktop distribution.
If another Vulcanexus distribution is used, please ensure that this package and its dependencies are installed.
Wireshark is also used to capture and analyze the network traffic.
Please, remember to source the environment in every terminal used during this tutorial.
source /opt/vulcanexus/jazzy/setup.bash
1.4.5.3. Overview¶
This tutorial will use ROS 2 demo_nodes_cpp
talker
and listener
applications to showcase the different configurations:
Talker-listener communication using Standard discovery. Shared memory transport is explicitly disabled to ensure EDP discovery traffic can be captured.
Talker-listener communication using Static EDP discovery.
Talker-listener full-fledged communication.
1.4.5.4. Standard discovery¶
eProsima Fast DDS enables by default a Shared Memory (SHM) transport and a UDP transport.
With this configuration, PDP discovery metatraffic will always be performed through the UDP transport.
However, if the SHM transport requirements are met, EDP discovery metatraffic and user data traffic will be sent through this transport.
In order to capture the traffic and analyze it, the SHM transport is going to be disabled.
Save the following XML configuration file at the desired location, which will be referred as <path_to_xml_config_file>
from here onwards, with vulcanexus_disable_shm.xml
name.
<?xml version="1.0" encoding="UTF-8" ?>
<dds>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<transport_descriptors>
<transport_descriptor>
<transport_id>udp_transport</transport_id>
<type>UDPv4</type>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="default_participant_profile" is_default_profile="true">
<rtps>
<userTransports>
<transport_id>udp_transport</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
</rtps>
</participant>
</profiles>
</dds>
This configuration disables the builtin transports and registers a user-defined UDPv4 transport.
After launching Wireshark (with administrative privileges to be able to capture network traffic), start capturing the traffic going through any
interface.
The traffic shown can be filtered using as parameter rtps
to see only traffic of interest.
Next, run the talker and the listener:
source /opt/vulcanexus/jazzy/setup.bash
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_config_file>/vulcanexus_disable_shm.xml ros2 run demo_nodes_cpp listener
source /opt/vulcanexus/jazzy/setup.bash
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_config_file>/vulcanexus_disable_shm.xml ros2 run demo_nodes_cpp talker
The traffic captured will show several DATA(p)
messages which are the periodic DomainParticipant announcements sent to multicast (PDP) and to any DomainParticipant already matched (Liveliness).
In this case, the EDP discovery traffic will also be captured as DATA(w)
, DataWriter discovery metatraffic, and DATA(r)
, DataReader discovery metatraffic.
The screenshot below has been taken running this tutorial.
1.4.5.5. Static EDP discovery¶
Now, Static EDP discovery is going to be enabled in order to remove any EDP discovery metatraffic. Within Vulcanexus ecosystem, Static EDP can only be enabled through XML configuration. Whereas different Endpoint profiles can be defined within the same XML file using the Topic name, it is not possible to have different DomainParticipant profiles within the same file when using Vulcanexus. Consequently, a different configuration file is required for each DomainParticipant, because the Static EDP settings include the path to the static XML configuration file which defines the Endpoints, Topics, and Data types.
Save the following XML configuration files in the path_to_xml_config_file
under the names talker_profile.xml
and listener_profile.xml
respectively:
<?xml version="1.0" encoding="UTF-8" ?>
<dds>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<transport_descriptors>
<transport_descriptor>
<transport_id>udp_transport</transport_id>
<type>UDPv4</type>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="talker_participant_profile" is_default_profile="true">
<rtps>
<name>talker</name>
<userTransports>
<transport_id>udp_transport</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
<builtin>
<discovery_config>
<EDP>STATIC</EDP>
<static_edp_xml_config>file://static_edp_info.xml</static_edp_xml_config>
</discovery_config>
</builtin>
</rtps>
</participant>
<data_writer profile_name="/chatter">
<userDefinedID>101</userDefinedID>
</data_writer>
</profiles>
</dds>
<?xml version="1.0" encoding="UTF-8" ?>
<dds>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<transport_descriptors>
<transport_descriptor>
<transport_id>udp_transport</transport_id>
<type>UDPv4</type>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="listener_participant_profile" is_default_profile="true">
<rtps>
<name>listener</name>
<userTransports>
<transport_id>udp_transport</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
<builtin>
<discovery_config>
<EDP>STATIC</EDP>
<static_edp_xml_config>file://static_edp_info.xml</static_edp_xml_config>
</discovery_config>
</builtin>
</rtps>
</participant>
<data_reader profile_name="/chatter">
<userDefinedID>102</userDefinedID>
</data_reader>
</profiles>
</dds>
Besides setting the EDP discovery to STATIC
and defining the path to the Static configuration XML file, the Endpoint userDefinedID
must be set so the Endpoints can be identified in this Static configuration file.
Every remote Endpoint must be defined within this configuration file, with the Topic and Data type name so matching can be performed by the local DomainParticipant statically without the need for the remote participant to send the Endpoint discovery information.
The specific endpoint QoS has also to be defined or the default QoS will be assumed.
Save the static configuration XML file to the same location under the name static_edp_info.xml
:
<staticdiscovery>
<participant>
<name>talker</name>
<writer>
<userId>101</userId>
<topicName>rt/chatter</topicName>
<topicDataType>std_msgs::msg::dds_::String_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
</participant>
<participant>
<name>listener</name>
<reader>
<userId>102</userId>
<topicName>rt/chatter</topicName>
<topicDataType>std_msgs::msg::dds_::String_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
</participant>
</staticdiscovery>
It is important to be aware of ROS 2 Topic mangling rules. Whereas the endpoint profile has to be set using the ROS 2 Topic name, the static discovery configuration must used the DDS Topic name.
Run again the talker-listener demo loading the corresponding XML configuration file using FASTRTPS_DEFAULT_PROFILES_FILE
environment variable:
source /opt/vulcanexus/jazzy/setup.bash
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_config_file>/listener_profile.xml ros2 run demo_nodes_cpp listener
source /opt/vulcanexus/jazzy/setup.bash
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_config_file>/talker_profile.xml ros2 run demo_nodes_cpp talker
If the traffic is captured again using Wireshark, this time no DATA(w)
or DATA(r)
is exchanged, but communication is established.
1.4.5.6. Full-fledged Static EDP discovery¶
ROS 2 provides several introspection tools like ros2 topic list
or ros2 node list
.
Running these commands with the previous example will show only the default ROS 2 topics (/parameter_events
and /rosout
) and no node.
The /chatter
topic and the /talker
and /listener
nodes would not appear even though they are up and running and communicating.
The issue is related to the internal endpoints that ROS 2 ecosystem, and by extension Vulcanexus, launch within each node to ensure these tools work as expected.
Also, the vast majority of these tools depend on another DomainParticipant known as the ROS 2 Daemon.
This section will complete the previous XML files so a full-fledged communication within Vulcanexus ecosystem is achieved, with working introspection tools.
Information about every internal ROS 2 endpoint has been included.
These endpoints are related to topic and node discovery, ROS 2 logging module, and parameters services and events.
Below, the complete XML files are shown. Please, replaced the previous XML configuration files with these ones and the new one required to configure the ROS 2 daemon DomainParticipant.
<?xml version="1.0" encoding="UTF-8" ?>
<dds>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<transport_descriptors>
<transport_descriptor>
<transport_id>udp_transport</transport_id>
<type>UDPv4</type>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="talker_participant_profile" is_default_profile="true">
<rtps>
<name>talker</name>
<userTransports>
<transport_id>udp_transport</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
<builtin>
<discovery_config>
<EDP>STATIC</EDP>
<static_edp_xml_config>file://static_edp_info.xml</static_edp_xml_config>
</discovery_config>
</builtin>
</rtps>
</participant>
<data_writer profile_name="/chatter">
<userDefinedID>101</userDefinedID>
</data_writer>
<!-->ROS 2 Internal Endpoints<-->
<data_writer profile_name="/parameter_events">
<userDefinedID>201</userDefinedID>
</data_writer>
<data_writer profile_name="ros_discovery_info">
<userDefinedID>202</userDefinedID>
</data_writer>
<data_writer profile_name="/rosout">
<userDefinedID>203</userDefinedID>
</data_writer>
<data_writer profile_name="rr/talker/describe_parametersReply">
<userDefinedID>204</userDefinedID>
</data_writer>
<data_writer profile_name="rr/talker/list_parametersReply">
<userDefinedID>205</userDefinedID>
</data_writer>
<data_writer profile_name="rr/talker/get_parametersReply">
<userDefinedID>206</userDefinedID>
</data_writer>
<data_writer profile_name="rr/talker/get_parameter_typesReply">
<userDefinedID>207</userDefinedID>
</data_writer>
<data_writer profile_name="rr/talker/set_parametersReply">
<userDefinedID>208</userDefinedID>
</data_writer>
<data_writer profile_name="rr/talker/set_parameters_atomicallyReply">
<userDefinedID>209</userDefinedID>
</data_writer>
<data_reader profile_name="/parameter_events">
<userDefinedID>210</userDefinedID>
</data_reader>
<data_reader profile_name="ros_discovery_info">
<userDefinedID>211</userDefinedID>
</data_reader>
<data_reader profile_name="rq/talker/set_parametersRequest">
<userDefinedID>212</userDefinedID>
</data_reader>
<data_reader profile_name="rq/talker/get_parametersRequest">
<userDefinedID>213</userDefinedID>
</data_reader>
<data_reader profile_name="rq/talker/get_parameter_typesRequest">
<userDefinedID>214</userDefinedID>
</data_reader>
<data_reader profile_name="rq/talker/set_parameters_atomicallyRequest">
<userDefinedID>215</userDefinedID>
</data_reader>
<data_reader profile_name="rq/talker/describe_parametersRequest">
<userDefinedID>216</userDefinedID>
</data_reader>
<data_reader profile_name="rq/talker/list_parametersRequest">
<userDefinedID>217</userDefinedID>
</data_reader>
</profiles>
</dds>
<?xml version="1.0" encoding="UTF-8" ?>
<dds>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<transport_descriptors>
<transport_descriptor>
<transport_id>udp_transport</transport_id>
<type>UDPv4</type>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="listener_participant_profile" is_default_profile="true">
<rtps>
<name>listener</name>
<userTransports>
<transport_id>udp_transport</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
<builtin>
<discovery_config>
<EDP>STATIC</EDP>
<static_edp_xml_config>file://static_edp_info.xml</static_edp_xml_config>
</discovery_config>
</builtin>
</rtps>
</participant>
<data_reader profile_name="/chatter">
<userDefinedID>102</userDefinedID>
</data_reader>
<!-->ROS 2 Internal Endpoints<-->
<data_reader profile_name="/parameter_events">
<userDefinedID>1</userDefinedID>
</data_reader>
<data_reader profile_name="ros_discovery_info">
<userDefinedID>2</userDefinedID>
</data_reader>
<data_reader profile_name="rq/listener/get_parametersRequest">
<userDefinedID>3</userDefinedID>
</data_reader>
<data_reader profile_name="rq/listener/get_parameter_typesRequest">
<userDefinedID>4</userDefinedID>
</data_reader>
<data_reader profile_name="rq/listener/set_parametersRequest">
<userDefinedID>5</userDefinedID>
</data_reader>
<data_reader profile_name="rq/listener/set_parameters_atomicallyRequest">
<userDefinedID>6</userDefinedID>
</data_reader>
<data_reader profile_name="rq/listener/describe_parametersRequest">
<userDefinedID>7</userDefinedID>
</data_reader>
<data_reader profile_name="rq/listener/list_parametersRequest">
<userDefinedID>8</userDefinedID>
</data_reader>
<data_writer profile_name="/parameter_events">
<userDefinedID>9</userDefinedID>
</data_writer>
<data_writer profile_name="ros_discovery_info">
<userDefinedID>10</userDefinedID>
</data_writer>
<data_writer profile_name="/rosout">
<userDefinedID>11</userDefinedID>
</data_writer>
<data_writer profile_name="rr/listener/describe_parametersReply">
<userDefinedID>12</userDefinedID>
</data_writer>
<data_writer profile_name="rr/listener/get_parametersReply">
<userDefinedID>13</userDefinedID>
</data_writer>
<data_writer profile_name="rr/listener/get_parameter_typesReply">
<userDefinedID>14</userDefinedID>
</data_writer>
<data_writer profile_name="rr/listener/set_parametersReply">
<userDefinedID>15</userDefinedID>
</data_writer>
<data_writer profile_name="rr/listener/set_parameters_atomicallyReply">
<userDefinedID>16</userDefinedID>
</data_writer>
<data_writer profile_name="rr/listener/list_parametersReply">
<userDefinedID>17</userDefinedID>
</data_writer>
</profiles>
</dds>
<?xml version="1.0" encoding="UTF-8" ?>
<dds>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
<transport_descriptors>
<transport_descriptor>
<transport_id>udp_transport</transport_id>
<type>UDPv4</type>
</transport_descriptor>
</transport_descriptors>
<participant profile_name="ros2_daemon_participant_profile" is_default_profile="true">
<rtps>
<name>ros2_daemon</name>
<userTransports>
<transport_id>udp_transport</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
<builtin>
<discovery_config>
<EDP>STATIC</EDP>
<static_edp_xml_config>file://static_edp_info.xml</static_edp_xml_config>
</discovery_config>
</builtin>
</rtps>
</participant>
<!-->ROS 2 Internal Endpoints<-->
<data_writer profile_name="/rosout">
<userDefinedID>51</userDefinedID>
</data_writer>
<data_writer profile_name="ros_discovery_info">
<userDefinedID>52</userDefinedID>
</data_writer>
<data_writer profile_name="/parameter_events">
<userDefinedID>53</userDefinedID>
</data_writer>
<data_reader profile_name="ros_discovery_info">
<userDefinedID>54</userDefinedID>
</data_reader>
</profiles>
</dds>
<staticdiscovery>
<participant>
<name>talker</name>
<writer>
<userId>101</userId>
<topicName>rt/chatter</topicName>
<topicDataType>std_msgs::msg::dds_::String_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>201</userId>
<topicName>rt/parameter_events</topicName>
<topicDataType>rcl_interfaces::msg::dds_::ParameterEvent_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>202</userId>
<topicName>ros_discovery_info</topicName>
<topicDataType>rmw_dds_common::msg::dds_::ParticipantEntitiesInfo_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>203</userId>
<topicName>rt/rosout</topicName>
<topicDataType>rcl_interfaces::msg::dds_::Log_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>204</userId>
<topicName>rr/talker/describe_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::DescribeParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>205</userId>
<topicName>rr/talker/list_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::ListParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>206</userId>
<topicName>rr/talker/get_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>207</userId>
<topicName>rr/talker/get_parameter_typesReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParametersTypes_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>208</userId>
<topicName>rr/talker/set_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>209</userId>
<topicName>rr/talker/set_parameters_atomicallyReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParametersAtomically_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<reader>
<userId>210</userId>
<topicName>rt/parameter_events</topicName>
<topicDataType>rcl_interfaces::msg::dds_::ParameterEvent_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>211</userId>
<topicName>ros_discovery_info</topicName>
<topicDataType>rmw_dds_common::msg::dds_::ParticipantEntitiesInfo_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>212</userId>
<topicName>rq/talker/set_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>213</userId>
<topicName>rq/talker/get_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>214</userId>
<topicName>rq/talker/get_parameter_typesRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParameterTypes_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>215</userId>
<topicName>rq/talker/set_parameters_atomicallyRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParametersAtomically_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>216</userId>
<topicName>rq/talker/describe_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::DescribeParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>217</userId>
<topicName>rq/talker/list_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::ListParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
</participant>
<participant>
<name>listener</name>
<reader>
<userId>102</userId>
<topicName>rt/chatter</topicName>
<topicDataType>std_msgs::msg::dds_::String_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>1</userId>
<topicName>rt/parameter_events</topicName>
<topicDataType>rcl_interfaces::msg::dds_::ParameterEvent_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>2</userId>
<topicName>ros_discovery_info</topicName>
<topicDataType>rmw_dds_common::msg::dds_::ParticipantEntitiesInfo_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>3</userId>
<topicName>rq/listener/get_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>4</userId>
<topicName>rq/listener/get_parameter_typesRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParameterTypes_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>5</userId>
<topicName>rq/listener/set_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>6</userId>
<topicName>rq/listener/set_parameters_atomicallyRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParametersAtomically_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>7</userId>
<topicName>rq/listener/describe_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::DescribeParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<reader>
<userId>8</userId>
<topicName>rq/listener/list_parametersRequest</topicName>
<topicDataType>rcl_interfaces::srv::dds_::ListParameters_Request_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</reader>
<writer>
<userId>9</userId>
<topicName>rt/parameter_events</topicName>
<topicDataType>rcl_interfaces::msg::dds_::ParameterEvent_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>10</userId>
<topicName>ros_discovery_info</topicName>
<topicDataType>rmw_dds_common::msg::dds_::ParticipantEntitiesInfo_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>11</userId>
<topicName>rt/rosout</topicName>
<topicDataType>rcl_interfaces::msg::dds_::Log_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>12</userId>
<topicName>rr/listener/describe_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::DescribeParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>13</userId>
<topicName>rr/listener/get_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>14</userId>
<topicName>rr/listener/get_parameter_typesReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::GetParametersTypes_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>15</userId>
<topicName>rr/listener/set_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>16</userId>
<topicName>rr/listener/set_parameters_atomicallyReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::SetParametersAtomically_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>17</userId>
<topicName>rr/listener/list_parametersReply</topicName>
<topicDataType>rcl_interfaces::srv::dds_::ListParameters_Response_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
</participant>
<participant>
<name>ros2_daemon</name>
<writer>
<userId>51</userId>
<topicName>rt/rosout</topicName>
<topicDataType>rcl_interfaces::msg::dds_::Log_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>52</userId>
<topicName>ros_discovery_info</topicName>
<topicDataType>rmw_dds_common::msg::dds_::ParticipantEntitiesInfo_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</writer>
<writer>
<userId>53</userId>
<topicName>rt/parameter_events</topicName>
<topicDataType>rcl_interfaces::msg::dds_::ParameterEvent_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>VOLATILE_DURABILITY_QOS</durabilityQos>
</writer>
<reader>
<userId>54</userId>
<topicName>ros_discovery_info</topicName>
<topicDataType>rmw_dds_common::msg::dds_::ParticipantEntitiesInfo_</topicDataType>
<reliabilityQos>RELIABLE_RELIABILITY_QOS</reliabilityQos>
<durabilityQos>TRANSIENT_LOCAL_DURABILITY_QOS</durabilityQos>
</reader>
</participant>
</staticdiscovery>
Run again the talker-listener demo loading the corresponding XML configuration file using FASTRTPS_DEFAULT_PROFILES_FILE
environment variable.
This time a third terminal is required to run the ROS 2 daemon.
source /opt/vulcanexus/jazzy/setup.bash
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_config_file>/listener_profile.xml ros2 run demo_nodes_cpp listener
source /opt/vulcanexus/jazzy/setup.bash
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_config_file>/talker_profile.xml ros2 run demo_nodes_cpp talker
source /opt/vulcanexus/jazzy/setup.bash
ros2 daemon stop
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_config_file>/ros2_daemon_profile.xml ros2 daemon start
ros2 topic list
ros2 node list
Now, besides the internal ROS 2 Topics, the /chatter
topic will be listed as well as the ROS 2 nodes /talker
and /listener
.