创建自定义的 msg 和 srv 文件。

**目标:**定义自定义接口文件(.msg.srv),并在 Python 和 C++ 节点中使用它们。

教程级别: 初学者

**时间:**20分钟

背景

在之前的教程中,你使用消息和服务接口了解了 topicsservices 以及简单的发布者/订阅者 (C++/Python) 和服务/客户端 (C++/Python) 节点。你使用的接口在这些情况下是预定义的。

虽然使用预定义的接口定义是一个好习惯,但有时你可能需要自定义自己的消息和服务。本教程将介绍创建自定义接口定义的最简单方法。

先决条件

你应该有一个 ROS 2 工作空间

本教程还使用了发布者/订阅者 (C++Python) 以及服务/客户端 (C++Python) 教程中创建的软件包,以尝试新的自定义消息。

任务

1 创建一个新的包

在本教程中,您将创建自己的``.msg``和``.srv``文件,并将它们放在一个单独的包中,然后在另一个包中使用它们。这两个包应该在同一个工作空间中。

由于我们将使用之前教程中创建的发布/订阅和服务/客户端包,请确保您处于与这些包相同的工作空间中(ros2_ws/src),然后运行以下命令来创建一个新的包:

ros2 pkg create --build-type ament_cmake tutorial_interfaces

tutorial_interfaces 是新包的名称。请注意,它只能是 CMake 包,但这并不限制您可以在哪种类型的包中使用消息和服务。您可以在 CMake 包中创建自定义接口,然后在 C++ 或 Python 节点中使用它,这将在最后一节中介绍。

要求将``.msg``和``.srv``文件分别放置在名为``msg``和``srv``的目录中。请在``ros2_ws/src/tutorial_interfaces``中创建这些目录:

mkdir msg srv

2 创建自定义定义

2.1 msg定义

在刚刚创建的``tutorial_interfaces/msg``目录中,创建一个名为``Num.msg``的新文件,并添加一行代码声明其数据结构:

int64 num

这是一个自定义消息,传递一个名为``num``的64位整数。

在刚刚创建的``tutorial_interfaces/msg``目录中,还需创建一个名为``Sphere.msg``的新文件,并按照以下内容进行编写:

geometry_msgs/Point center
float64 radius

这个自定义消息使用了另一个消息包中的消息(在这种情况下为``geometry_msgs/Point``)。

2.2 服务定义

在刚刚创建的 tutorial_interfaces/srv 目录中,创建一个名为 AddThreeInts.srv 的新文件,其请求和响应结构如下所示:

int64 a
int64 b
int64 c
---
int64 sum

这是您自定义的服务,它请求三个名为 abc 的整数,并以名为 sum 的整数作为响应。

3. CMakeLists.txt

要将您定义的接口转换为特定语言的代码(如C++和Python),以便在这些语言中使用它们,请将以下行添加到 CMakeLists.txt 中:

find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
  "msg/Num.msg"
  "msg/Sphere.msg"
  "srv/AddThreeInts.srv"
  DEPENDENCIES geometry_msgs # Add packages that above messages depend on, in this case geometry_msgs for Sphere.msg
)

注解

在rosidl_generate_interfaces中,第一个参数(库名称)必须与${PROJECT_NAME}匹配(参见https://github.com/ros2/rosidl/issues/441#issuecomment-591025515)。

4 package.xml

因为接口依赖于rosidl_default_generators来生成特定语言的代码,所以您需要在其上声明构建工具依赖项。rosidl_default_runtime是一个运行时或执行阶段的依赖项,以便稍后能够使用这些接口。rosidl_interface_packages是您的软件包“tutorial_interfaces”应关联的依赖组的名称,使用`<member_of_group>`标签声明。

将以下行添加到`package.xml`的`<package>`元素中:

<depend>geometry_msgs</depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>

5 构建``tutorial_interfaces``包

现在你的自定义接口包的所有部分都已经就位,你可以构建这个包。在你的工作空间的根目录(~/ros2_ws)中运行以下命令:

colcon build --packages-select tutorial_interfaces

现在其他ROS 2包可以发现这些接口。

6 确认消息和服务的创建

在新的终端中,从你的工作空间(ros2_ws)内运行以下命令以加载它:

source install/setup.bash

现在,你可以通过使用 ros2 interface show 命令确认接口创建是否成功:

ros2 interface show tutorial_interfaces/msg/Num

应该返回:

int64 num

而且

ros2 interface show tutorial_interfaces/msg/Sphere

应该返回:

geometry_msgs/Point center
        float64 x
        float64 y
        float64 z
float64 radius

而且

ros2 interface show tutorial_interfaces/srv/AddThreeInts

应该返回:

int64 a
int64 b
int64 c
---
int64 sum

7 测试新接口

在这一步中,您可以使用之前教程中创建的软件包。对节点、``CMakeLists.txt``和``package.xml``文件进行一些简单的修改,即可使用您的新接口。

7.1 使用发布/订阅测

在之前的教程(C++)中创建的发布者/订阅者包稍作修改,你就可以看到 Num.msg 的作用。由于你将把标准字符串消息更改为数值消息,输出结果将稍有不同。

发布者

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/num.hpp"                                            // CHANGE

using namespace std::chrono_literals;

class MinimalPublisher : public rclcpp::Node
{
public:
  MinimalPublisher()
  : Node("minimal_publisher"), count_(0)
  {
    publisher_ = this->create_publisher<tutorial_interfaces::msg::Num>("topic", 10);  // CHANGE
    timer_ = this->create_wall_timer(
      500ms, std::bind(&MinimalPublisher::timer_callback, this));
  }

private:
  void timer_callback()
  {
    auto message = tutorial_interfaces::msg::Num();                                   // CHANGE
    message.num = this->count_++;                                                     // CHANGE
    RCLCPP_INFO_STREAM(this->get_logger(), "Publishing: '" << message.num << "'");    // CHANGE
    publisher_->publish(message);
  }
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<tutorial_interfaces::msg::Num>::SharedPtr publisher_;             // CHANGE
  size_t count_;
};

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

订阅者

#include <functional>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/num.hpp"                                       // CHANGE

using std::placeholders::_1;

class MinimalSubscriber : public rclcpp::Node
{
public:
  MinimalSubscriber()
  : Node("minimal_subscriber")
  {
    subscription_ = this->create_subscription<tutorial_interfaces::msg::Num>(    // CHANGE
      "topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
  }

private:
  void topic_callback(const tutorial_interfaces::msg::Num & msg) const  // CHANGE
  {
    RCLCPP_INFO_STREAM(this->get_logger(), "I heard: '" << msg.num << "'");     // CHANGE
  }
  rclcpp::Subscription<tutorial_interfaces::msg::Num>::SharedPtr subscription_;  // CHANGE
};

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

CMakeLists.txt

添加以下行(仅限C++):

#...

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED)                      # CHANGE

add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp tutorial_interfaces)    # CHANGE

add_executable(listener src/subscriber_member_function.cpp)
ament_target_dependencies(listener rclcpp tutorial_interfaces)  # CHANGE

install(TARGETS
  talker
  listener
  DESTINATION lib/${PROJECT_NAME})

ament_package()

package.xml

添加以下行:

<depend>tutorial_interfaces</depend>

在进行上述编辑并保存所有更改后,构建包:

在Linux/macOS上:

colcon build --packages-select cpp_pubsub

在Windows上:

colcon build --merge-install --packages-select cpp_pubsub

然后在两个新终端中分别打开,每个终端中执行以下命令:

ros2 run cpp_pubsub talker
ros2 run cpp_pubsub listener

由于``Num.msg``只传递整数,因此talker只应该发布整数值,而不是之前发布的字符串:

[INFO] [minimal_publisher]: Publishing: '0'
[INFO] [minimal_publisher]: Publishing: '1'
[INFO] [minimal_publisher]: Publishing: '2'

7.2 使用服务/客户端测试``AddThreeInts.srv``

在之前的教程(C++)创建的服务/客户端包上做一些修改,你就可以看到``AddThreeInts.srv``的效果。由于你将原来的两个整数请求 srv 更改为三个整数请求 srv,输出结果会有些不同。

服务端

#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp"                                        // CHANGE

#include <memory>

void add(const std::shared_ptr<tutorial_interfaces::srv::AddThreeInts::Request> request,     // CHANGE
          std::shared_ptr<tutorial_interfaces::srv::AddThreeInts::Response>       response)  // CHANGE
{
  response->sum = request->a + request->b + request->c;                                      // CHANGE
  RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Incoming request\na: %ld" " b: %ld" " c: %ld",  // CHANGE
                request->a, request->b, request->c);                                         // CHANGE
  RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]", (long int)response->sum);
}

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

  std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_three_ints_server");   // CHANGE

  rclcpp::Service<tutorial_interfaces::srv::AddThreeInts>::SharedPtr service =               // CHANGE
    node->create_service<tutorial_interfaces::srv::AddThreeInts>("add_three_ints",  &add);   // CHANGE

  RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add three ints.");                     // CHANGE

  rclcpp::spin(node);
  rclcpp::shutdown();
}

客户端

#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp"                                       // CHANGE

#include <chrono>
#include <cstdlib>
#include <memory>

using namespace std::chrono_literals;

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

  if (argc != 4) { // CHANGE
      RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "usage: add_three_ints_client X Y Z");      // CHANGE
      return 1;
  }

  std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_three_ints_client");  // CHANGE
  rclcpp::Client<tutorial_interfaces::srv::AddThreeInts>::SharedPtr client =                // CHANGE
    node->create_client<tutorial_interfaces::srv::AddThreeInts>("add_three_ints");          // CHANGE

  auto request = std::make_shared<tutorial_interfaces::srv::AddThreeInts::Request>();       // CHANGE
  request->a = atoll(argv[1]);
  request->b = atoll(argv[2]);
  request->c = atoll(argv[3]);                                                              // CHANGE

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

  auto result = client->async_send_request(request);
  // Wait for the result.
  if (rclcpp::spin_until_future_complete(node, result) ==
    rclcpp::FutureReturnCode::SUCCESS)
  {
    RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Sum: %ld", result.get()->sum);
  } else {
    RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_three_ints");    // CHANGE
  }

  rclcpp::shutdown();
  return 0;
}

CMakeLists.txt

添加以下行(仅限C++):

#...

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED)         # CHANGE

add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
  rclcpp tutorial_interfaces)                      # CHANGE

add_executable(client src/add_two_ints_client.cpp)
ament_target_dependencies(client
  rclcpp tutorial_interfaces)                      # CHANGE

install(TARGETS
  server
  client
  DESTINATION lib/${PROJECT_NAME})

ament_package()

package.xml

添加以下行:

<depend>tutorial_interfaces</depend>

在进行上述编辑并保存所有更改后,构建包:

在Linux/macOS上:

colcon build --packages-select cpp_srvcli

在Windows上:

colcon build --merge-install --packages-select cpp_srvcli

然后在两个新终端中分别打开,每个终端中执行以下命令:

ros2 run cpp_srvcli server
ros2 run cpp_srvcli client 2 3 1

总结

在本教程中,您学习了如何在自己的软件包中创建自定义接口,并如何在其他软件包中利用这些接口。

这个教程只是关于定义自定义接口的入门。您可以在 ROS 2 接口文档 中了解更多信息。

下一步

下一个教程 中,将介绍在ROS 2中使用接口的更多方法。