1.3.6. Change mutable QoS through get native API

1.3.6.1. Background

Fast DDS over Vulcanexus offers the possibility of not only configuring the QoS policy when creating ROS nodes, but also to modify the mutable ones after the node/publisher/subscription creation. The QoS that allow their modification after entity creation, are called mutable QoS. Please refer to Fast DDS QoS Policy documentation to get a list of all supported QoS and whether they are mutable.

Modifying Ownership and Ownership Strength QoS Policy explained the use of the Ownership and Ownership Strength QoS (see Ownership QoS Policy) and how to configure them within the ROS 2 talker/listener demo.

This tutorial will show how to change Ownership Strength QoS in runtime, after all nodes have been already deployed. This will be done through the interaction of three nodes (one subscriber and two publishers): After creation, the subscriber will only be receiving data from the publisher with the largest ownership strength (corresponding to exclusive ownership QoS).

../../../../../_images/publication_graph_before.png

After that, the ownership strength of the other publisher will be changed to become larger than that of the first one, thus making the subscriber to start showing the data of the latter publisher.

../../../../../_images/publication_graph_after.png

This will be done creating a custom package, following similar steps as in Monitoring for parameter changes (C++) to be able to change a node’s parameter, and respond to that change by changing the Partition QoS of the publisher.

The ROS 2 middleware layer (see Different ROS 2 DDS/RTPS vendors) provides APIs to get handles to the objects of the inner DDS implementation, which is needed to be able to change the mutable Qos. Thus, this tutorial will also show how to use that powerful tool. For another demo on how to access inner RMW entities, see demo_nodes_cpp_native.

1.3.6.2. Prerequisites

The first prerequisite is to have Vulcanexus Iron installed (see Linux binary installation or Linux installation from sources).

Also, before starting this tutorial, user should be familiar with creating a workspace and creating a package, as well as familiar with parameters and their function in a ROS 2 system. The recommendation is to first complete the following tutorials:

This tutorial focuses on the explanations regarding mutable QoS change in runtime and regarding access to inner objects of DDS middleware implementation, and for that reason, not all the code is going to be explained, as it is already explained in the aforementioned tutorials. Create a clean workspace and download the Vulcanexus - Change Mutable QoS Through get_native API project:

# Create directory structure
mkdir ~/vulcanexus_ws
mkdir ~/vulcanexus_ws/src
mkdir ~/vulcanexus_ws/src/vulcanexus_change_mutable_qos
mkdir ~/vulcanexus_ws/src/vulcanexus_change_mutable_qos/src

# Download project source code
cd ~/vulcanexus_ws/src/vulcanexus_change_mutable_qos
wget -O CMakeLists.txt https://raw.githubusercontent.com/eProsima/vulcanexus/iron/docs/resources/tutorials/core/qos/mutable/vulcanexus_change_mutable_qos/CMakeLists.txt
wget -O package.xml https://raw.githubusercontent.com/eProsima/vulcanexus/iron/docs/resources/tutorials/core/qos/mutable/vulcanexus_change_mutable_qos/package.xml

cd ~/vulcanexus_ws/src/vulcanexus_change_mutable_qos/src
wget -O change_mutable_qos_publisher.cpp https://raw.githubusercontent.com/eProsima/vulcanexus/iron/docs/resources/tutorials/core/qos/mutable/vulcanexus_change_mutable_qos/src/change_mutable_qos_publisher.cpp

# Download profile config files for Fast DDS participants
wget -O large_ownership_strength.xml https://raw.githubusercontent.com/eProsima/vulcanexus/iron/docs/resources/tutorials/core/qos/mutable/vulcanexus_change_mutable_qos/src/large_ownership_strength.xml
wget -O small_ownership_strength.xml https://raw.githubusercontent.com/eProsima/vulcanexus/iron/docs/resources/tutorials/core/qos/mutable/vulcanexus_change_mutable_qos/src/small_ownership_strength.xml
wget -O subscriber_exclusive_ownership.xml https://raw.githubusercontent.com/eProsima/vulcanexus/iron/docs/resources/tutorials/core/qos/mutable/vulcanexus_change_mutable_qos/src/subscriber_exclusive_ownership.xml

The resulting directory structure should be:

~/vulcanexus_ws/
└── src
    └── vulcanexus_change_mutable_qos
        ├── CMakeLists.txt
        ├── package.xml
        └── src
            ├── change_mutable_qos_publisher.cpp
            ├── large_ownership_strength.xml
            ├── small_ownership_strength.xml
            └── subscriber_exclusive_ownership.xml

1.3.6.3. Explaining the source code

In the case of the Subscriber, this tutorial only needs a minimal subscriber listening on the topic /chatter. For convenience, the listener node from demo_nodes_cpp package will be used, as it is just a minimal subscriber listening for the aforementioned topic. For more information on how to create a minimal subscriber, Writing a simple publisher and subscriber (C++) tutorial shows how to write one.

In the case of the Publishers, the package is using only one executable, which takes an argument to assign the name of the Node. Here not all the code is going to be explained, as the referred tutorials of the prerequisites section explain big part of it. For instance, the /chatter temporized publisher is explained in the Writing a simple publisher and subscriber (C++), and the mechanism to respond by means of a user callback to a change in a node’s parameter is explained in Monitoring for parameter changes (C++).

The demo_nodes_cpp_native shows how to access inner RMW and Fast DDS entities, although it is not actually explained. In this tutorial, that same mechanism is used. In the private section of the Node_ChangeMutableQoS_Publisher class, the pointers to the native handlers are declared:

// Pointers to RMW and Fast DDS inner object handles
rcl_publisher_t * rcl_publisher_;
rmw_publisher_t * rmw_publisher_;
eprosima::fastdds::dds::DataWriter * data_writer_;

In the constructor, the pointers are populated by calling the APIs provided by the rmw and rmw_fastrtps_cpp, until obtaining the eprosima::fastdds::dds::DataWriter handle:

// Access RMW and Fast DDS inner object handles
rcl_publisher_ = publisher_->get_publisher_handle().get();
rmw_publisher_ = rcl_publisher_get_rmw_handle(rcl_publisher_);
data_writer_ = rmw_fastrtps_cpp::get_datawriter(rmw_publisher_);

When the Publisher_X_ownership_strength is updated (for instance, via command line using ros2 param set command), the parameter callback is raised, and the eprosima::fastdds::dds::DataWriter handle is used to update its ownership strength. Below, a snippet of code from the constructor of the node, where the parameter is declared, the subscription to its changes is registered, and the callback to be run on the parameter change event is defined.

// Declare parameter
std::string parameter_name = node_name_prefix + "_ownership_strength";
this->declare_parameter(parameter_name, 100); // This is the parameter initialization. 100 is only to state it is int type

// Create a parameter subscriber that can be used to monitor parameter changes
param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);

// Set a callback for this node's integer parameter, "Publisher_X_ownership_strength"
auto callback = [this](const rclcpp::Parameter & p) {
    RCLCPP_INFO(
      this->get_logger(), "Callback: Received an update to parameter \"%s\" of type %s: \"%ld\"",
      p.get_name().c_str(),
      p.get_type_name().c_str(),
      p.as_int());

    eprosima::fastdds::dds::DataWriterQos dw_qos;
    data_writer_->get_qos(dw_qos);

    dw_qos.ownership_strength().value = p.as_int();
    data_writer_->set_qos(dw_qos);
  };
callback_handle_ = param_subscriber_->add_parameter_callback(parameter_name, callback);

In this case, as in the current version of Fast DDS the builtin statistics are enabled by default (see DomainParticipantQos), it is needed to retrieve the internal QoS by means of ::get_qos(), then perform the modifications and update the QoS by means of ::set_qos(): The value of the ownership strength is set from the value of the updated parameter.

1.3.6.4. Configuration of initial QoS

Ownership Strength Policy is mutable, but Ownership Policy is not, so configuring EXCLUSIVE_OWNERSHIP_POLICY to all participants before running the ROS nodes is needed. To do that, inside the package, there are three xml files. Each one of them defines a profile for a publisher with a “large” ownership strength, another with a “small” ownership strength and a subscriber (that does not need an ownership strength definition). For the three of them, exclusive ownership is defined.

<?xml version="1.0" encoding="UTF-8" ?>
<dds>
    <profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
        <data_writer profile_name="/chatter">
            <qos>
                <ownership>
                    <kind>EXCLUSIVE</kind>
                </ownership>
                <ownershipStrength>
                    <value>10</value>
                </ownershipStrength>
            </qos>
        </data_writer>
    </profiles>
</dds>

1.3.6.5. Build

Now the package is ready to be built. Change the directory to the workspace folder and build using colcon:

source /opt/vulcanexus/iron/setup.bash
cd ~/vulcanexus_ws
colcon build

1.3.6.6. Run

Open three terminals in the workspace folder. On each of them, Vulcanexus installation, as well as the package installation is needed. Then, export the FASTRTPS_DEFAULT_PROFILES_FILE environment variable to point out to the corresponding profiles file and run the node.

  • In the first terminal, run the listener node from the demo_nodes_cpp, configured with the subscriber_exclusive_ownership.xml file.

  • Then, in another terminal, run the first publisher, configured also with the large_ownership_strength.xml file. This Publisher will then be configured with ownership strength value of 10. At this point both nodes should be communicating, and the messages from Publisher 1 should be shown in the Subscriber.

  • In the third terminal, run the second publisher, configured with the small_ownership_strength.xml file. This Publisher will then be configured with ownership strength value of 2. This Publisher 2 starts sending messages (it can be seen that the number of the message starts from 1 while the messages from Publisher 1 are already in a higher number), and the Subscriber is still receiving messages from Publisher 1 and not from Publisher 2. This is because of the exclusive ownership.

The code to execute in each terminal can be found in the tabs below:

source /opt/vulcanexus/iron/setup.bash
cd ~/vulcanexus_ws
`# Using profile to set exclusive ownership`
export FASTRTPS_DEFAULT_PROFILES_FILE=./install/vulcanexus_change_mutable_qos/profiles/subscriber_exclusive_ownership.xml
ros2 run demo_nodes_cpp listener  `# Run minimal subscriber`

Publisher 1 has higher ownership strength than Publisher 2.

1.3.6.7. Change mutable QoS via command line

In this last section, the param set command will be used to change the value of the node’s parameter created earlier. The parameter change will cause the parameter-changed callback to be called, which then results in a change in the ownership strength. In another terminal, try the following code:

source /opt/vulcanexus/iron/setup.bash
cd ~/vulcanexus_ws
source install/setup.bash
ros2 param set /Publisher_2_change_mutable_qos Publisher_2_ownership_strength 50

With that execution, the ownership strength of the Publisher 2 has changed to become larger than that of the Publisher 1. Now the Subscriber should be receiving the messages from the Publisher 2 and not from the Publisher 1.