发挥Fast DDS中间件的潜力 [社区贡献]

**目标:**本教程将展示如何在ROS 2中使用Fast DDS的扩展配置功能。

教程级别: 高级

**时间:**20分钟

背景

ROS 2栈与Fast DDS之间的接口由ROS 2中间件实现`rmw_fastrtps <https://github.com/ros2/rmw_fastrtps>`_提供。此实现在所有ROS 2发行版中都可用,包括二进制和源代码。

ROS 2 RMW 仅允许配置某些中间件的 QoS(参见 ROS 2 QoS 策略)。但是,rmw_fastrtps 提供了扩展的配置功能,以充分利用 Fast DDS 中的功能。本教程将通过一系列示例向您解释如何使用 XML 文件来解锁此扩展配置。

为了获取有关在ROS 2上使用*Fast DDS*的更多信息,请查看以下文档 <https://fast-dds.docs.eprosima.com/en/latest/fastdds/ros2/ros2.html>`__。

先决条件

本教程假设您知道如何 创建一个包。它还假设您知道如何编写一个 简单的发布者和订阅者 和一个 简单的服务和客户端。尽管示例是用C++实现的,但相同的概念也适用于Python包。

在同一节点中混合同步和异步发布

在这个第一个示例中,将创建一个具有两个发布者的节点,其中一个使用同步发布模式,另一个使用异步发布模式。

默认情况下,rmw_fastrtps 使用同步发布模式。

使用同步发布模式时,数据直接在用户线程的上下文中发送。这意味着在写操作期间发生的任何阻塞调用都会阻塞用户线程,从而阻止应用程序继续运行。然而,该模式通常在较低的延迟下产生更高的吞吐量,因为没有线程之间的通知或上下文切换。

另一方面,使用异步发布模式时,每次发布者调用写操作时,数据都会复制到队列中,然后会通知后台线程(异步线程)有数据添加到队列中,并在实际发送数据之前将线程的控制返回给用户。后台线程负责消耗队列并将数据发送给每个匹配的读者。

使用发布者创建节点

首先,在新的工作空间上创建一个名为``sync_async_node_example_cpp``的新软件包:

mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
ros2 pkg create --build-type ament_cmake --dependencies rclcpp std_msgs -- sync_async_node_example_cpp

然后,在包中添加一个名为``src/sync_async_writer.cpp``的文件,其内容如下。请注意,同步发布者将在主题``sync_topic``上发布,而异步发布者将在主题``async_topic``上发布。

#include <chrono>
#include <functional>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

class SyncAsyncPublisher : public rclcpp::Node
{
public:
    SyncAsyncPublisher()
        : Node("sync_async_publisher"), count_(0)
    {
        // Create the synchronous publisher on topic 'sync_topic'
        sync_publisher_ = this->create_publisher<std_msgs::msg::String>("sync_topic", 10);

        // Create the asynchronous publisher on topic 'async_topic'
        async_publisher_ = this->create_publisher<std_msgs::msg::String>("async_topic", 10);

        // This timer will trigger the publication of new data every half a second
        timer_ = this->create_wall_timer(
                500ms, std::bind(&SyncAsyncPublisher::timer_callback, this));
    }

private:
    /**
     * Actions to run every time the timer expires
     */
    void timer_callback()
    {
        // Create a new message to be sent
        auto sync_message = std_msgs::msg::String();
        sync_message.data = "SYNC: Hello, world! " + std::to_string(count_);

        // Log the message to the console to show progress
        RCLCPP_INFO(this->get_logger(), "Synchronously publishing: '%s'", sync_message.data.c_str());

        // Publish the message using the synchronous publisher
        sync_publisher_->publish(sync_message);

        // Create a new message to be sent
        auto async_message = std_msgs::msg::String();
        async_message.data = "ASYNC: Hello, world! " + std::to_string(count_);

        // Log the message to the console to show progress
        RCLCPP_INFO(this->get_logger(), "Asynchronously publishing: '%s'", async_message.data.c_str());

        // Publish the message using the asynchronous publisher
        async_publisher_->publish(async_message);

        // Prepare the count for the next message
        count_++;
    }

    // This timer will trigger the publication of new data every half a second
    rclcpp::TimerBase::SharedPtr timer_;

    // A publisher that publishes asynchronously
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr async_publisher_;

    // A publisher that publishes synchronously
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr sync_publisher_;

    // Number of messages sent so far
    size_t count_;
};

int main(int argc, char * argv[])
{
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<SyncAsyncPublisher>());
    rclcpp::shutdown();
    return 0;
}

现在打开``CMakeLists.txt``文件,添加一个新的可执行文件并命名为``SyncAsyncWriter``,这样你就可以使用``ros2 run``运行你的节点:

add_executable(SyncAsyncWriter src/sync_async_writer.cpp)
ament_target_dependencies(SyncAsyncWriter rclcpp std_msgs)

最后,添加``install(TARGETS...)``部分,以便``ros2 run``可以找到你的可执行文件:

install(TARGETS
    SyncAsyncWriter
    DESTINATION lib/${PROJECT_NAME})

你可以通过删除一些不必要的部分和注释来简化你的``CMakeLists.txt``,使其看起来像这样:

cmake_minimum_required(VERSION 3.8)
project(sync_async_node_example_cpp)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

add_executable(SyncAsyncWriter src/sync_async_writer.cpp)
ament_target_dependencies(SyncAsyncWriter rclcpp std_msgs)

install(TARGETS
    SyncAsyncWriter
    DESTINATION lib/${PROJECT_NAME})

ament_package()

如果此节点现在构建并运行,两个发布者将表现相同,在两个主题中都进行异步发布,因为这是默认的发布模式。默认的发布模式配置可以在节点启动期间通过使用 XML 文件进行更改。

创建具有配置文件的 XML 文件。

创建名为“SyncAsync.xml”的文件,并包含以下内容:

<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">

    <!-- default publisher profile -->
    <publisher profile_name="default_publisher" is_default_profile="true">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
    </publisher>

    <!-- default subscriber profile -->
    <subscriber profile_name="default_subscriber" is_default_profile="true">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
    </subscriber>

    <!-- publisher profile for topic sync_topic -->
    <publisher profile_name="/sync_topic">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
        <qos>
            <publishMode>
                <kind>SYNCHRONOUS</kind>
            </publishMode>
        </qos>
    </publisher>

    <!-- publisher profile for topic async_topic -->
    <publisher profile_name="/async_topic">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
        <qos>
            <publishMode>
                <kind>ASYNCHRONOUS</kind>
            </publishMode>
        </qos>
    </publisher>

 </profiles>

请注意,定义了多个发布者和订阅者的配置文件。有两个默认配置文件,将“is_default_profile”设置为“true”,还有两个与先前定义的主题名称相匹配的配置文件:“sync_topic”和“async_topic”。这两个配置文件将发布模式分别设置为“同步”或“异步”。还请注意,所有配置文件都指定了“historyMemoryPolicy”值,这对于示例的运行是必需的,稍后在本教程中将进行解释。

执行发布者节点

您需要导出以下环境变量以加载XML文件:

export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
export FASTRTPS_DEFAULT_PROFILES_FILE=path/to/SyncAsync.xml

最后,确保您已经加载了设置文件并运行了节点:

source install/setup.bash
ros2 run sync_async_node_example_cpp SyncAsyncWriter

您应该看到发布者从发布节点发送数据,如下所示:

[INFO] [1612972049.994630332] [sync_async_publisher]: Synchronously publishing: 'SYNC: Hello, world! 0'
[INFO] [1612972049.995097767] [sync_async_publisher]: Asynchronously publishing: 'ASYNC: Hello, world! 0'
[INFO] [1612972050.494478706] [sync_async_publisher]: Synchronously publishing: 'SYNC: Hello, world! 1'
[INFO] [1612972050.494664334] [sync_async_publisher]: Asynchronously publishing: 'ASYNC: Hello, world! 1'
[INFO] [1612972050.994368474] [sync_async_publisher]: Synchronously publishing: 'SYNC: Hello, world! 2'
[INFO] [1612972050.994549851] [sync_async_publisher]: Asynchronously publishing: 'ASYNC: Hello, world! 2'

现在你有一个同步发布者和一个异步发布者在同一个节点中运行。

创建一个带有订阅者的节点。

接下来,将创建一个新的节点,并添加订阅者,这些订阅者将监听 sync_topicasync_topic 的发布。在一个名为 src/sync_async_reader.cpp 的新源文件中写入以下内容:

#include <functional>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using std::placeholders::_1;

class SyncAsyncSubscriber : public rclcpp::Node
{
public:

    SyncAsyncSubscriber()
        : Node("sync_async_subscriber")
    {
        // Create the synchronous subscriber on topic 'sync_topic'
        // and tie it to the topic_callback
        sync_subscription_ = this->create_subscription<std_msgs::msg::String>(
            "sync_topic", 10, std::bind(&SyncAsyncSubscriber::topic_callback, this, _1));

        // Create the asynchronous subscriber on topic 'async_topic'
        // and tie it to the topic_callback
        async_subscription_ = this->create_subscription<std_msgs::msg::String>(
            "async_topic", 10, std::bind(&SyncAsyncSubscriber::topic_callback, this, _1));
    }

private:

    /**
     * Actions to run every time a new message is received
     */
    void topic_callback(const std_msgs::msg::String & msg) const
    {
        RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
    }

    // A subscriber that listens to topic 'sync_topic'
    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sync_subscription_;

    // A subscriber that listens to topic 'async_topic'
    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr async_subscription_;
};

int main(int argc, char * argv[])
{
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<SyncAsyncSubscriber>());
    rclcpp::shutdown();
    return 0;
}

打开 CMakeLists.txt 文件,并添加一个新的可执行文件,命名为 SyncAsyncReader,位于之前的 SyncAsyncWriter 下面:

add_executable(SyncAsyncReader src/sync_async_reader.cpp)
ament_target_dependencies(SyncAsyncReader rclcpp std_msgs)

install(TARGETS
    SyncAsyncReader
    DESTINATION lib/${PROJECT_NAME})

执行订阅者节点

在一个终端中运行发布者节点后,打开另一个终端并导出所需的环境变量以加载XML文件:

export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
export FASTRTPS_DEFAULT_PROFILES_FILE=path/to/SyncAsync.xml

最后,确保您已经加载了设置文件并运行了节点:

source install/setup.bash
ros2 run sync_async_node_example_cpp SyncAsyncReader

您应该看到订阅者节点接收来自发布者节点的数据,如下所示:

[INFO] [1612972054.495429090] [sync_async_subscriber]: I heard: 'SYNC: Hello, world! 10'
[INFO] [1612972054.995410057] [sync_async_subscriber]: I heard: 'ASYNC: Hello, world! 10'
[INFO] [1612972055.495453494] [sync_async_subscriber]: I heard: 'SYNC: Hello, world! 11'
[INFO] [1612972055.995396561] [sync_async_subscriber]: I heard: 'ASYNC: Hello, world! 11'
[INFO] [1612972056.495534818] [sync_async_subscriber]: I heard: 'SYNC: Hello, world! 12'
[INFO] [1612972056.995473953] [sync_async_subscriber]: I heard: 'ASYNC: Hello, world! 12'

示例的分析

配置文件XML

XML文件定义了发布者和订阅者的多个配置。您可以有一个默认的发布者配置文件和多个特定主题的发布者配置文件。唯一的要求是所有的发布者配置文件必须具有不同的名称,并且只能有一个默认配置文件。订阅者也是如此。

为了为特定的主题定义配置,只需将配置文件命名为ROS 2主题名称(例如示例中的``/sync_topic``和``/async_topic``),``rmw_fastrtps``将为该主题的所有发布者和订阅者应用该配置文件。默认配置文件由属性``is_default_profile``设置为``true``来标识,并且在没有其他与主题名称匹配的配置文件时充当回退配置文件。

环境变量``FASTRTPS_DEFAULT_PROFILES_FILE``用于通知*Fast DDS*加载配置文件的XML文件路径。

RMW_FASTRTPS_USE_QOS_FROM_XML

在所有可配置属性中,rmw_fastrtps 对待 publishModehistoryMemoryPolicy 有所不同。默认情况下,这些值在 rmw_fastrtps 实现中被设置为 ASYNCHRONOUSPREALLOCATED_WITH_REALLOC,并且忽略了 XML 文件中设置的值。要使用 XML 文件中的值,必须将环境变量 RMW_FASTRTPS_USE_QOS_FROM_XML 设置为 1

然而,这带来了**另一个注意事项**:如果设置了 RMW_FASTRTPS_USE_QOS_FROM_XML,但 XML 文件没有定义 publishModehistoryMemoryPolicy,这些属性会取代 rmw_fastrtps 的默认值而使用 Fast DDS 的默认值。这一点非常重要,特别是对于 historyMemoryPolicy,因为 Fast DDS 的默认值是 PREALLOCATED,而这与 ROS2 主题数据类型不兼容。因此,在示例中,明确设置了此策略的有效值(DYNAMIC)。

rmw_qos_profile_t 的优先级排序

除非设置为``*_SYSTEM_DEFAULT``,否则始终会遵守包含在`rmw_qos_profile_t <http://docs.ros2.org/latest/api/rmw/structrmw__qos__profile__t.html>`_中的ROS 2 QoS。在这种情况下,将应用XML值(或在没有XML值的情况下使用*Fast DDS*的默认值)。这意味着如果``rmw_qos_profile_t``中的任何QoS设置为与``*_SYSTEM_DEFAULT``不同的其他值,则会忽略XML中的相应值。

使用XML配置其他FastDDS功能

尽管我们已经创建了一个具有不同配置的节点的两个发布者,但很难检查它们是否表现不同。现在已经介绍了XML配置文件的基础知识,让我们使用它们来配置对节点具有一些可视效果的内容。具体来说,将设置一个发布者的最大匹配订阅者数量,并在另一个发布者上设置一个分区定义。请注意,这些只是在``rmw_fastrtps``上可以通过XML文件调整的所有配置属性中的非常简单的示例。请参考`*Fast DDS*文档<https://fast-dds.docs.eprosima.com/en/latest/fastdds/xml_configuration/xml_configuration.html#xml-profiles>`__以查看可以通过XML文件配置的属性的完整列表。

限制匹配订阅者的数量

在``/async_topic``发布者配置文件中添加最大匹配订阅者数。它应该是这样的:

<!-- publisher profile for topic async_topic -->
<publisher profile_name="/async_topic">
    <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
    <qos>
        <publishMode>
            <kind>ASYNCHRONOUS</kind>
        </publishMode>
    </qos>
    <matchedSubscribersAllocation>
        <initial>0</initial>
        <maximum>1</maximum>
        <increment>1</increment>
    </matchedSubscribersAllocation>
</publisher>

匹配的订阅者数量被限制为一个。

现在打开三个终端,并且不要忘记加载设置文件和设置所需的环境变量。在第一个终端中运行发布者节点,在其他两个终端中运行订阅者节点。你会发现只有第一个订阅者节点从两个主题接收到消息。第二个订阅者节点无法在``/async_topic``中完成匹配过程,因为发布者已经阻止了它,由于已经达到了最大匹配订阅者数。因此,这第三个终端只会接收到``/sync_topic``的消息:

[INFO] [1613127657.088860890] [sync_async_subscriber]: I heard: 'SYNC: Hello, world! 18'
[INFO] [1613127657.588896594] [sync_async_subscriber]: I heard: 'SYNC: Hello, world! 19'
[INFO] [1613127658.088849401] [sync_async_subscriber]: I heard: 'SYNC: Hello, world! 20'

在主题中使用分区

分区功能可以用于控制在同一主题下发布者和订阅者之间的信息交换。

分区引入了一个逻辑实体隔离级别的概念,它在由域ID引起的物理隔离内部。要使发布者与订阅者进行通信,它们必须至少属于一个公共分区。分区代表了在域和主题之外进一步分离发布者和订阅者的另一级别。与域和主题不同,一个端点可以同时属于多个分区。为了将某些数据共享到不同的域或主题,每个域或主题必须有一个不同的发布者,共享其自己的更改历史。然而,一个单独的发布者可以使用单个主题数据更改将相同的数据样本共享到不同的分区,从而减少网络负载。

让我们将``/sync_topic``发布者更改为分区``part1``,并创建一个使用分区``part2``的新``/sync_topic``订阅者。它们的配置文件现在应该如下所示:

<!-- publisher profile for topic sync_topic -->
<publisher profile_name="/sync_topic">
    <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
    <qos>
        <publishMode>
            <kind>SYNCHRONOUS</kind>
        </publishMode>
        <partition>
            <names>
                <name>part1</name>
            </names>
        </partition>
    </qos>
</publisher>

<!-- subscriber profile for topic sync_topic -->
<subscriber profile_name="/sync_topic">
    <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
    <qos>
        <partition>
            <names>
                <name>part2</name>
            </names>
        </partition>
    </qos>
</subscriber>

打开两个终端。不要忘记源化设置文件并设置所需的环境变量。在第一个终端上运行发布者节点,在另一个终端上运行订阅者节点。您应该注意到只有``/async_topic``的消息到达订阅者。由于``/sync_topic``的发布者与其所在的分区不同,因此``/sync_topic``订阅者无法接收到数据。

[INFO] [1612972054.995410057] [sync_async_subscriber]: I heard: 'ASYNC: Hello, world! 10'
[INFO] [1612972055.995396561] [sync_async_subscriber]: I heard: 'ASYNC: Hello, world! 11'
[INFO] [1612972056.995473953] [sync_async_subscriber]: I heard: 'ASYNC: Hello, world! 12'

配置服务和客户端

服务和客户端各自具有一个发布者和一个订阅者,它们通过两个不同的主题进行通信。例如,对于一个名为``ping``的服务,有以下情况:

  • 一个服务的订阅者监听来自``/rq/ping``的请求。

  • 一个服务的发布者在``/rr/ping``上发送响应。

  • 一个客户端发布者在``/rq/ping``上发送请求。

  • 一个客户端订阅者监听``/rr/ping``上的响应。

虽然您可以使用这些主题名称在XML上设置配置文件,但有时您可能希望将同一配置文件应用于节点上的所有服务或客户端。您可以只创建一个名为``service``的发布者和订阅者配置文件对,而不是为所有服务生成所有主题名称的相同配置文件。对于客户端,也可以创建一个名为``client``的配对。

使用服务和客户端创建节点。

开始创建带有服务的节点。在您的软件包中添加一个名为``src/ping_service.cpp``的新源文件,并使用以下内容:

#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/trigger.hpp"

/**
 * Service action: responds with success=true and prints the request on the console
 */
void ping(const std::shared_ptr<example_interfaces::srv::Trigger::Request> request,
        std::shared_ptr<example_interfaces::srv::Trigger::Response> response)
{
    // The request data is unused
    (void) request;

    // Build the response
    response->success = true;

    // Log to the console
    RCLCPP_INFO(rclcpp::get_logger("ping_server"), "Incoming request");
    RCLCPP_INFO(rclcpp::get_logger("ping_server"), "Sending back response");
}

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);

    // Create the node and the service
    std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("ping_server");
    rclcpp::Service<example_interfaces::srv::Trigger>::SharedPtr service =
        node->create_service<example_interfaces::srv::Trigger>("ping", &ping);

    // Log that the service is ready
    RCLCPP_INFO(rclcpp::get_logger("ping_server"), "Ready to serve.");

    // run the node
    rclcpp::spin(node);
    rclcpp::shutdown();
}

创建一个名为``src/ping_client.cpp``的文件,其中包含以下内容:

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/trigger.hpp"

using namespace std::chrono_literals;

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);

    // Create the node and the client
    std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("ping_client");
    rclcpp::Client<example_interfaces::srv::Trigger>::SharedPtr client =
        node->create_client<example_interfaces::srv::Trigger>("ping");

    // Create a request
    auto request = std::make_shared<example_interfaces::srv::Trigger::Request>();

    // Wait for the service to be available
    while (!client->wait_for_service(1s)) {
        if (!rclcpp::ok()) {
            RCLCPP_ERROR(rclcpp::get_logger("ping_client"), "Interrupted while waiting for the service. Exiting.");
            return 0;
        }
        RCLCPP_INFO(rclcpp::get_logger("ping_client"), "Service not available, waiting again...");
    }

    // Now that the service is available, send the request
    RCLCPP_INFO(rclcpp::get_logger("ping_client"), "Sending request");
    auto result = client->async_send_request(request);

    // Wait for the result and log it to the console
    if (rclcpp::spin_until_future_complete(node, result) ==
        rclcpp::FutureReturnCode::SUCCESS)
    {
        RCLCPP_INFO(rclcpp::get_logger("ping_client"), "Response received");
    } else {
        RCLCPP_ERROR(rclcpp::get_logger("ping_client"), "Failed to call service ping");
    }

    rclcpp::shutdown();
    return 0;
}

打开``CMakeLists.txt``文件,并添加两个新的可执行文件``ping_service``和``ping_client``:

find_package(example_interfaces REQUIRED)

add_executable(ping_service src/ping_service.cpp)
ament_target_dependencies(ping_service example_interfaces rclcpp)

add_executable(ping_client src/ping_client.cpp)
ament_target_dependencies(ping_client example_interfaces rclcpp)

install(TARGETS
    ping_service
    DESTINATION lib/${PROJECT_NAME})

install(TARGETS
    ping_client
    DESTINATION lib/${PROJECT_NAME})

最后,构建软件包。

为服务和客户端创建XML配置文件

创建一个名为 ping.xml 的文件,并使用以下内容填充:

<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">

    <!-- default publisher profile -->
    <publisher profile_name="default_publisher" is_default_profile="true">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
    </publisher>

    <!-- default subscriber profile -->
    <subscriber profile_name="default_subscriber" is_default_profile="true">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
    </subscriber>

    <!-- service publisher is SYNC -->
    <publisher profile_name="service">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
        <qos>
            <publishMode>
                <kind>SYNCHRONOUS</kind>
            </publishMode>
        </qos>
    </publisher>

    <!-- client publisher is ASYNC -->
    <publisher profile_name="client">
        <historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
        <qos>
            <publishMode>
                <kind>ASYNCHRONOUS</kind>
            </publishMode>
        </qos>
    </publisher>

</profiles>

此配置文件将服务端的发布模式设置为 SYNCHRONOUS,客户端的发布模式设置为 ASYNCHRONOUS。请注意,我们仅定义了服务和客户端的发布者配置文件,但也可以提供订阅者配置文件。

执行节点操作

打开两个终端并在每个终端上加载设置文件。然后设置所需的环境变量以加载 XML:

export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
export FASTRTPS_DEFAULT_PROFILES_FILE=path/to/ping.xml

在第一个终端上运行服务节点。

ros2 run sync_async_node_example_cpp ping_service

您应该看到服务正在等待请求:

[INFO] [1612977403.805799037] [ping_server]: Ready to serve

在第二个终端上运行客户端节点。

ros2 run sync_async_node_example_cpp ping_client

您应该看到客户端发送请求并接收响应:

[INFO] [1612977404.805799037] [ping_client]: Sending request
[INFO] [1612977404.825473835] [ping_client]: Response received

同时,服务器控制台中的输出已被更新:

[INFO] [1612977403.805799037] [ping_server]: Ready to serve
[INFO] [1612977404.807314904] [ping_server]: Incoming request
[INFO] [1612977404.836405125] [ping_server]: Sending back response