rmw_fastrtps
is a ROS 2 middleware implementation, providing an interface between ROS 2 and eProsima's Fast DDS middleware.
This implementation is available in all ROS 2 distributions, both from binaries and from sources. You can specify Fast DDS as your ROS 2 middleware layer in two different ways:
- Exporting
RMW_IMPLEMENTATION
environment variable:export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
- When launching your ROS 2 application:
RMW_IMPLEMENTATION=rmw_fastrtps_cpp ros2 run <your_package> <your application>
rmw_fastrtps
actually provides not one but two different ROS 2 middleware implementations, both of them using Fast DDS as middleware layer: rmw_fastrtps_cpp
and rmw_fastrtps_dynamic_cpp
(note that directory rmw_fastrtps_shared_cpp
just contains the code that the two implementations share, and does not constitute a layer on its own).
The main difference between the two is that rmw_fastrtps_dynamic_cpp
uses introspection typesupport at run time to decide on the serialization/deserialization mechanism.
On the other hand, rmw_fastrtps_cpp
uses its own typesupport, which generates the mapping for each message type at build time.
Mind that the default ROS 2 RMW implementation is rmw_fastrtps_cpp
.
You can however set it to rmw_fastrtps_dynamic_cpp
using the environment variable RMW_IMPLEMENTATION
as described above.
ROS 2 only allows for the configuration of certain middleware QoS (see ROS 2 QoS policies).
In addition to ROS 2 QoS policies, rmw_fastrtps
sets two more Fast DDS configurable parameters:
- History memory policy:
PREALLOCATED_WITH_REALLOC_MEMORY_MODE
- Publication mode:
ASYNCHRONOUS_PUBLISH_MODE
However, rmw_fastrtps
offers the possibility to further configure Fast DDS:
Fast DDS features two different publication modes: synchronous and asynchronous. To learn more about the implications of choosing one mode over the other, please refer to DDS: Asynchronous vs Synchronous Publishing:
rmw_fastrtps
offers an easy way to change Fast DDS' publication mode without the need of defining a XML file. That is environment variable RMW_FASTRTPS_PUBLICATION_MODE
.
The admissible values are:
ASYNCHRONOUS
: asynchronous publication mode. Setting this mode implies that when the publisher invokes the write operation, the data is copied into a queue, a notification about the addition to the queue is performed, and control of the thread is returned to the user before the data is actually sent. A background thread (asynchronous thread) is in turn in charge of consuming the queue and sending the data to every matched reader.SYNCHRONOUS
: synchronous publication mode. Setting this mode implies that the data is sent directly within the context of the user thread. This entails that any blocking call occurring during the write operation would block the user thread, thus preventing the application with continuing its operation. It is important to note that this mode typically yields higher throughput rates at lower latencies, since the notification and context switching between threads is not present.AUTO
: let Fast DDS select the publication mode. This implies using the publication mode set in the XML file or, failing that, the default value set in Fast DDS (which currently is set toSYNCHRONOUS
).
If RMW_FASTRTPS_PUBLICATION_MODE
is not set, then both rmw_fastrtps_cpp
and rmw_fastrtps_dynamic_cpp
behave as if it were set to SYNCHRONOUS
.
Fast DDS QoS policies can be fully configured through a combination of the rmw QoS profile API, and the Fast DDS XML file's QoS elements. Configuration depends on the environment variable RMW_FASTRTPS_USE_QOS_FROM_XML
.
- ROS 2 QoS contained in
rmw_qos_profile_t
are always honored, unless set to*_SYSTEM_DEFAULT
. In that case, XML values, or Fast DDS default values in the absence of XML ones, are applied. Setting any QoS inrmw_qos_profile_t
to something other than*_SYSTEM_DEFAULT
entails that specifying it via XML files has no effect, since they do not override what was used to create the publisher, subscription, service, or client. - In order to modify the history memory policy or publication mode using XML files, environment variable
RMW_FASTRTPS_USE_QOS_FROM_XML
must be set to 1 (it is set to 0 by default). This tellsrmw_fastrtps
that it should override both the history memory policy and the publication mode using the XML. Bear in mind that setting this environment variable but not setting either of these policies in the XML results in Fast DDS' defaults configurations being used.
RMW_FASTRTPS_USE_QOS_FROM_XML | rmw QoS profile | Fast DDS XML QoS | Fast DDS XML history memory policy and publication mode |
---|---|---|---|
0 (default) | Use default values | Ignored - overridden by rmw_qos_profile_t |
Ignored - overrided by rmw_fastrtps |
0 (default) | Set to non system default | Ignored - overridden by rmw_qos_profile_t |
Ignored - overrided by rmw_fastrtps |
0 (default) | Set to system default | Used | Ignored - overrided by rmw_fastrtps |
1 | Use default values | Ignored - overridden by rmw_qos_profile_t |
Used |
1 | Set to non system default | Ignored - overridden by rmw_qos_profile_t |
Used |
1 | Set to system default | Used | Used |
Note: Setting RMW_FASTRTPS_USE_QOS_FROM_XML
to 1 effectively overrides whatever configuration was set with RMW_FASTRTPS_PUBLICATION_MODE
.
Furthermore, If RMW_FASTRTPS_USE_QOS_FROM_XML
is set to 1, and history memory policy or publication mode are not specified in the XML, then the Fast DDS' default configurations will be used:
- history memory policy :
PREALLOCATED_MEMORY_MODE
. - publication mode :
SYNCHRONOUS_PUBLISH_MODE
.
There are two ways of telling a ROS 2 application which XML to use:
- Placing your XML file in the running directory under the name
DEFAULT_FASTRTPS_PROFILES.xml
. - Setting environment variable
FASTRTPS_DEFAULT_PROFILES_FILE
to contain the path to your XML file (relative to the working directory).
To verify the actual QoS settings using rmw:
// Create a publisher within a node with specific topic, type support, options, and QoS
rmw_publisher_t* rmw_publisher = rmw_create_publisher(node, type_support, topic_name, qos_profile, publisher_options);
// Check the actual QoS set on the publisher
rmw_qos_profile_t qos;
rmw_publisher_get_actual_qos(rmw_publisher, &qos);
rmw_fastrtps
allows for the configuration of different entities with different QoS using the same XML file.
For doing so, rmw_fastrtps
locates profiles in the XML based on topic names abiding to the following rules:
To configure a publisher/subscription, define a <publisher>
/<subscriber>
profile with attribute profile_name=topic_name
, where topic name is the name of the topic prepended by the node namespace (which defaults to ""
if not specified), i.e. the node's namespace followed by topic name used to create the publisher/subscription.
Mind that topic names always start with /
(it is added when creating the topic if not present), and that namespace and topic name are always separated by one /
.
If such profile is not defined, rmw_fastrtps
attempts to load the <publisher>
/<subscriber>
profile with attribute is_default_profile="true"
.
The following table presents different combinations of node namespaces and user specified topic names, as well as the resulting topic names and the suitable profile names:
User specified topic name | Node namespace | Final topic name | Profile name |
---|---|---|---|
chatter |
DEFAULT ("" ) |
/chatter |
/chatter |
chatter |
test_namespace |
/test_namespace/chatter |
/test_namespace/chatter |
chatter |
/test_namespace |
/test_namespace/chatter |
/test_namespace/chatter |
/chatter |
test_namespace |
/chatter |
/chatter |
/chatter |
/test_namespace |
/chatter |
/chatter |
IMPORTANT: As shown in the table, node namespaces are NOT prepended to user specified topic names starting with /
, a.k.a Fully Qualified Names (FQN).
For a complete description of topic name remapping please refer to Remapping Names.
ROS 2 services contain a subscription for receiving requests, and a publisher to reply to them.
rmw_fastrtps
allows for configuring each of these endpoints separately in the following manner:
- To configure the request subscription, define a
<subscriber>
profile with attributeprofile_name=topic_name
, where topic name is the name of the service after mangling. For more information on name mangling, please refer to Topic and Service name mapping to DDS. If such profile is not defined,rmw_fastrtps
attempts to load a<subscriber>
profile with attributeprofile_name="service"
. If neither of the previous profiles exist,rmw_fastrtps
attempts to load the<subscriber>
profile with attributeis_default_profile="true"
. - To configure the reply publisher, define a
<publisher>
profile with attributeprofile_name=topic_name
, where topic name is the name of the service after mangling. If such profile is not defined,rmw_fastrtps
attempts to load a<publisher>
profile with attributeprofile_name="service"
. If neither of the previous profiles exist,rmw_fastrtps
attempts to load the<publisher>
profile with attributeis_default_profile="true"
.
ROS 2 clients contain a publisher to send requests, and a subscription to receive the service's replies.
rmw_fastrtps
allows for configuring each of these endpoints separately in the following manner:
- To configure the requests publisher, define a
<publisher>
profile with attributeprofile_name=topic_name
, where topic name is the name of the service after mangling. If such profile is not defined,rmw_fastrtps
attempts to load a<publisher>
profile with attributeprofile_name="client"
. If neither of the previous profiles exist,rmw_fastrtps
attempts to load the<publisher>
profile with attributeis_default_profile="true"
. - To configure the reply subscription, define a
<subscriber>
profile with attributeprofile_name=topic_name
, where topic name is the name of the service after mangling. If such profile is not defined,rmw_fastrtps
attempts to load a<subscriber>
profile with attributeprofile_name="client"
. If neither of the previous profiles exist,rmw_fastrtps
attempts to load the<subscriber>
profile with attributeis_default_profile="true"
.
The following example configures Fast DDS to publish synchronously, and to have a pre-allocated history that can be expanded whenever it gets filled.
-
Create a Fast DDS XML file with:
<?xml version="1.0" encoding="UTF-8"?> <dds xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles"> <profiles> <!-- Default publisher profile --> <publisher profile_name="default publisher profile" is_default_profile="true"> <qos> <publishMode> <kind>SYNCHRONOUS</kind> </publishMode> </qos> <historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy> </publisher> <!-- Publisher profile for topic helloworld --> <publisher profile_name="helloworld"> <qos> <publishMode> <kind>SYNCHRONOUS</kind> </publishMode> </qos> </publisher> <!-- Request subscriber profile for services --> <subscriber profile_name="service"> <historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy> </subscriber> <!-- Request publisher profile for clients --> <publisher profile_name="client"> <qos> <publishMode> <kind>ASYNCHRONOUS</kind> </publishMode> </qos> </publisher> <!-- Request subscriber profile for server of service "add_two_ints" --> <subscriber profile_name="rq/add_two_intsRequest"> <historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy> </subscriber> <!-- Reply subscriber profile for client of service "add_two_ints" --> <subscriber profile_name="rr/add_two_intsReply"> <historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy> </subscriber> </profiles> </dds>
-
Run the talker/listener ROS 2 demo:
-
In one terminal
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_file> RMW_FASTRTPS_USE_QOS_FROM_XML=1 RMW_IMPLEMENTATION=rmw_fastrtps_cpp ros2 run demo_nodes_cpp talker
-
In another terminal
FASTRTPS_DEFAULT_PROFILES_FILE=<path_to_xml_file> RMW_FASTRTPS_USE_QOS_FROM_XML=1 RMW_IMPLEMENTATION=rmw_fastrtps_cpp ros2 run demo_nodes_cpp listener
-
Quality Declarations for each package in this repository:
Quality Declarations for the external dependencies of these packages can be found in: