实现自定义接口

**目标:**了解在ROS 2中实现自定义接口的更多方法。

教程级别: 初学者

时间: 15分钟

背景

在之前的教程中,你学习了如何创建自定义的msg和srv接口。

虽然最佳实践是在专用接口包中声明接口,但有时候在一个包中声明、创建和使用接口会更加方便。

请注意,目前只能在CMake包中定义接口。然而,可以在CMake包中使用Python库和节点(使用`ament_cmake_python <https://github.com/ament/ament_cmake/tree/humble/ament_cmake_python>`_),因此你可以在一个包中同时定义接口和Python节点。为了简单起见,我们在这里使用一个CMake包和C++节点。

本教程将重点介绍msg接口类型,但这里的步骤适用于所有接口类型。

先决条件

我们假设您在完成本教程之前已经阅读了 创建自定义的 msg 和 srv 文件。 教程的基础知识。

您应该已经安装了 ROS 2,创建了一个 工作空间,并且了解了 如何创建包

一如既往,请不要忘记在每个新打开的终端中 source ROS 2

任务

1 创建一个包

在您的工作空间 src 目录下,创建一个名为 more_interfaces 的包,并在其中创建一个用于存放消息文件的目录:

ros2 pkg create --build-type ament_cmake more_interfaces
mkdir more_interfaces/msg

2 创建一个消息文件

more_interfaces/msg 目录下,创建一个名为 AddressBook.msg 的新文件,并粘贴以下代码以创建一个用于携带个人信息的消息:

uint8 PHONE_TYPE_HOME=0
uint8 PHONE_TYPE_WORK=1
uint8 PHONE_TYPE_MOBILE=2

string first_name
string last_name
string phone_number
uint8 phone_type

该消息由以下字段组成:

  • first_name: 字符串类型

  • last_name: 字符串类型

  • phone_number: 字符串类型

  • phone_type: uint8 类型,具有多个已定义的命名常量值

请注意,可以在消息定义内部为字段设置默认值。有关更多自定义接口的方法,请参阅 接口

接下来,我们需要确保将 msg 文件转换为 C++、Python 和其他语言的源代码。

2.1 构建 msg 文件

打开 package.xml 并添加以下行:

<buildtool_depend>rosidl_default_generators</buildtool_depend>

<exec_depend>rosidl_default_runtime</exec_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

请注意,在构建时我们需要``rosidl_default_generators``,而在运行时,我们只需要``rosidl_default_runtime``。

打开``CMakeLists.txt``并添加以下行:

找到生成消息代码的软件包:

find_package(rosidl_default_generators REQUIRED)

声明您想要生成的消息列表:

set(msg_files
  "msg/AddressBook.msg"
)

通过手动添加.msg文件,我们确保CMake知道在添加其他.msg文件后何时重新配置项目。

生成消息:

rosidl_generate_interfaces(${PROJECT_NAME}
  ${msg_files}
)

还要确保导出消息的运行时依赖项:

ament_export_dependencies(rosidl_default_runtime)

现在您已经准备好从msg定义生成源文件。我们将在步骤4中一起完成,暂时跳过编译步骤。

2.2(额外)设置多个接口

注解

您可以在``CMakeLists.txt``中使用``set``来整洁地列出所有接口:

set(msg_files
  "msg/Message1.msg"
  "msg/Message2.msg"
  # etc
  )

set(srv_files
  "srv/Service1.srv"
  "srv/Service2.srv"
   # etc
  )

然后一次生成所有列表,如下所示:

rosidl_generate_interfaces(${PROJECT_NAME}
  ${msg_files}
  ${srv_files}
)

3 从同一软件包中使用接口

现在我们可以开始编写使用这个消息的代码。

在``more_interfaces/src``目录下创建一个名为``publish_address_book.cpp``的文件,并粘贴以下代码:

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "more_interfaces/msg/address_book.hpp"

using namespace std::chrono_literals;

class AddressBookPublisher : public rclcpp::Node
{
public:
  AddressBookPublisher()
  : Node("address_book_publisher")
  {
    address_book_publisher_ =
      this->create_publisher<more_interfaces::msg::AddressBook>("address_book", 10);

    auto publish_msg = [this]() -> void {
        auto message = more_interfaces::msg::AddressBook();

        message.first_name = "John";
        message.last_name = "Doe";
        message.phone_number = "1234567890";
        message.phone_type = message.PHONE_TYPE_MOBILE;

        std::cout << "Publishing Contact\nFirst:" << message.first_name <<
          "  Last:" << message.last_name << std::endl;

        this->address_book_publisher_->publish(message);
      };
    timer_ = this->create_wall_timer(1s, publish_msg);
  }

private:
  rclcpp::Publisher<more_interfaces::msg::AddressBook>::SharedPtr address_book_publisher_;
  rclcpp::TimerBase::SharedPtr timer_;
};


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

  return 0;
}

3.1 代码解释

包含我们新创建的``AddressBook.msg``的头文件。

#include "more_interfaces/msg/address_book.hpp"

创建一个节点和一个 AddressBook 发布者。

using namespace std::chrono_literals;

class AddressBookPublisher : public rclcpp::Node
{
public:
  AddressBookPublisher()
  : Node("address_book_publisher")
  {
    address_book_publisher_ =
      this->create_publisher<more_interfaces::msg::AddressBook>("address_book");

创建一个定期发布消息的回调函数。

auto publish_msg = [this]() -> void {

创建一个 AddressBook 消息实例,稍后我们将发布它。

auto message = more_interfaces::msg::AddressBook();

填充 AddressBook 字段。

message.first_name = "John";
message.last_name = "Doe";
message.phone_number = "1234567890";
message.phone_type = message.PHONE_TYPE_MOBILE;

最后定期发送消息。

std::cout << "Publishing Contact\nFirst:" << message.first_name <<
  "  Last:" << message.last_name << std::endl;

this->address_book_publisher_->publish(message);

创建一个每秒调用``publish_msg``函数的1秒定时器。

timer_ = this->create_wall_timer(1s, publish_msg);

3.2 构建发布者。

我们需要在``CMakeLists.txt``中为该节点创建一个新的目标:

find_package(rclcpp REQUIRED)

add_executable(publish_address_book src/publish_address_book.cpp)
ament_target_dependencies(publish_address_book rclcpp)

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

4 尝试一下

返回到工作空间的根目录以构建包:

cd ~/ros2_ws
colcon build --packages-up-to more_interfaces

然后运行以下命令激活工作空间并运行发布者:

source install/local_setup.bash
ros2 run more_interfaces publish_address_book

你应该看到发布者正在转发你定义的消息,包括你在 publish_address_book.cpp 中设置的值。

为了确认消息正在 address_book 主题上发布,打开另一个终端,加载工作空间,并调用 topic echo

source install/setup.bash
ros2 topic echo /address_book

在本教程中,我们不会创建一个订阅者,但你可以尝试自己编写一个进行练习(使用 编写一个简单的发布者和订阅者(C++) 来帮助你)。

5(额外)使用现有接口定义

注解

您可以在新的接口定义中使用现有的接口定义。例如,假设有一个名为``Contact.msg``的消息,它属于一个名为``rosidl_tutorials_msgs``的现有ROS 2包。假设它的定义与我们之前自定义的``AddressBook.msg``接口相同。

在这种情况下,您可以将``AddressBook.msg``(与您的节点在同一包中的接口)定义为类型``Contact``(在一个*单独的*包中的接口)。您甚至可以将``AddressBook.msg``定义为类型``Contact``的*数组*,如下所示:

rosidl_tutorials_msgs/Contact[] address_book

要生成此消息,您需要在``package.xml``中声明对``Contact.msg``所在的包``rosidl_tutorials_msgs``的依赖项:

<build_depend>rosidl_tutorials_msgs</build_depend>

<exec_depend>rosidl_tutorials_msgs</exec_depend>

还需要在``CMakeLists.txt``中进行如下设置:

find_package(rosidl_tutorials_msgs REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
  ${msg_files}
  DEPENDENCIES rosidl_tutorials_msgs
)

你还需要在发布者节点中包含``Contact.msg``的头文件,以便能够将``contacts``添加到你的``address_book``。

#include "rosidl_tutorials_msgs/msg/contact.hpp"

你可以将回调函数改为以下内容:

auto publish_msg = [this]() -> void {
   auto msg = std::make_shared<more_interfaces::msg::AddressBook>();
   {
     rosidl_tutorials_msgs::msg::Contact contact;
     contact.first_name = "John";
     contact.last_name = "Doe";
     contact.phone_number = "1234567890";
     contact.phone_type = message.PHONE_TYPE_MOBILE;
     msg->address_book.push_back(contact);
   }
   {
     rosidl_tutorials_msgs::msg::Contact contact;
     contact.first_name = "Jane";
     contact.last_name = "Doe";
     contact.phone_number = "4254242424";
     contact.phone_type = message.PHONE_TYPE_HOME;
     msg->address_book.push_back(contact);
   }

   std::cout << "Publishing address book:" << std::endl;
   for (auto contact : msg->address_book) {
     std::cout << "First:" << contact.first_name << "  Last:" << contact.last_name <<
       std::endl;
   }

   address_book_publisher_->publish(*msg);
 };

构建并运行这些更改会显示预期的消息定义,以及上面定义的消息数组。

总结

在本教程中,你尝试了不同的字段类型来定义接口,然后在使用接口的同一软件包中构建了一个接口。

您还学习了如何将另一个接口用作字段类型,以及使用``package.xml``、``CMakeLists.txt``和``#include``语句来利用该功能所必需的内容。

下一步

接下来,您将创建一个简单的ROS 2软件包,其中包含一个自定义参数,您将学习如何从启动文件中设置该参数。同样,您可以选择使用 C++Python 来编写它。