在 ROS2 开发过程中,标准的接口类型(如 std_msgs 或 geometry_msgs)已能满足大部分通信需求。但在特定应用场景下,用户需要根据实际需求定义自己的接口类型,如自定义消息、自定义服务甚至自定义动作(Action)。本章将系统介绍如何在 ROS2 中创建并使用自定义的消息与服务接口,帮助读者掌握这一核心技能。
创建流程
在 ROS2 中,接口类型通过 .msg、.srv 和 .action 文件进行定义,并由接口定义语言(IDL)自动生成相应编程语言的调用代码。在实际开发中,当标准接口无法满足需求时,开发者通常需要定义自己的 .msg 或 .srv 文件,以支持特定数据结构的通信,主要流程如下:
-
在功能包中创建
msg/或srv/文件夹; -
定义
.msg或.srv文件内容; -
修改
CMakeLists.txt和package.xml以集成接口生成; -
编写发布/订阅或服务端/客户端程序;
-
编译并验证。
以下将逐步展开。本教程将在自己的功能包中创建自定义的.msg和.srv文件,然后在另一个功能包中使用它们,两个功能包在同一个工作空间(ros2_ws)中。
在之前教程中创建的pub/sub和service/client功能包相同的工作空间中(ros2_ws/src)中创建一个新的功能包:
ros2 pkg create --build-type ament_cmake --license Apache-2.0 tutorial_interfaces
tutorial_interfaces是新功能包的名称,它只能是CMake类型的功能包,但这并不影响我们在不同的功能包中使用。在CMake功能包中创建自己的自定义接口,并在C++或Python节点中使用它。
.msg 和 .srv 文件必须分别放置在称为 msg 和 srv 的目录中。这两个目录需要在ros2_ws/src/tutorial_interfaces 中创建:
cd tutorial_interfaces
mkdir msg srv
创建自定义接口
消息定义
在刚刚创建的 tutorial_interfaces/msg 目录中,新建一个名为 Num.msg 的文件,包含一个声明其数据结构的代码行:
int64 num
这是一个自定义消息,传递一个名为 num 的64位整数。
在同一 tutorial_interfaces/msg 目录中,新建一个名为 Sphere.msg 的文件,包含以下内容:
geometry_msgs/Point center
float64 radius
这个自定义消息使用了另一个功能包中的消息(此例中为geometry_msgs/Point,其中geometry_msgs 功能包的名称,Point 为消息类型)。
服务定义
回到刚刚创建的 tutorial_interfaces/srv 目录,新建一个名为 AddThreeInts.srv 的文件,具有以下请求和响应结构:
int64 a
int64 b
int64 c
---
int64 sum
这是自定义的服务,a、b和c的整数请求,sum为整数响应。
配置 CMakeLists.txt
在 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 # 添加上述消息依赖的功能包,Sphere.msg依赖功能包geometry_msgs
)
配置 package.xml
在 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>
<depend>geometry_msgs</depend> 功能包在构建和运行时都依赖于 geometry_msgs 功能包. <buildtool_depend>rosidl_default_generators</buildtool_depend> 表示在构建过程中需要 rosidl_default_generators 工具。 <exec_depend>rosidl_default_runtime</exec_depend>
表示在执行或运行节点时,需要 rosidl_default_runtime 功能包<member_of_group>rosidl_interface_packages</member_of_group> 将功能包归类到rosidl_interface_packages 组。这样做的目的是为了在 ROS 生态系统中对功能包进行分类,使用特定类型接口(如.msg和.srv文件)的功能包可以被轻松地识别和管理。
构建功能包
现在,可以构建功能包了。在工作空间根目录(~/ros2_ws)中,运行以下命令:
colcon build --packages-select tutorial_interfaces
如果编译成功,接口就可以被其他ROS 2功能包发现并使用了。 下面的步骤可以确定接口是否创建成功。打开新终端,运行以下加载命令:
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
测试新接口
在这里,我们使用先前教程中创建的功能包验证自定义消息和服务类型。通过对节点、CMakeLists.txt 和 package.xml 文件进行一些简单的修改,你就可以使用新接口。
使用pub/sub测试Num.msg
通过对先前教程(C++或Python)中创建的发布者/订阅者包进行一些修改,验证Num.msg 接口。
这里我们修改 C++ 编写的发布者节点和用 python 编写的订阅者节点。从而实现不同语言不同功能之间话题的通信。
发布者代码
首先修改C++编写发布者节点:
#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); // 修改
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
void timer_callback()
{
auto message = tutorial_interfaces::msg::Num(); // 修改
message.num = this->count_++; // 修改
RCLCPP_INFO_STREAM(this->get_logger(), "Publishing: '" << message.num << "'"); // 修改
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<tutorial_interfaces::msg::Num>::SharedPtr publisher_; // 修改
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
配置CMakeLists.txt
在CMakeLists.txt中添加以下行(C++):
#...
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED) # 修改
add_executable(talker src/publisher_member_function.cpp)
ament_target_dependencies(talker rclcpp tutorial_interfaces) # 修改
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME})
ament_package()
配置package.xml
在package.xml添加以下依赖:
<depend>tutorial_interfaces</depend>
在完成上述编辑并保存所有更改后,构建功能包:
colcon build --packages-select cpp_pubsub
订阅者代码
在之前的教程中我们已经编写了使用 python 编写订阅者节点功能包 py_pubsub,现在对该功能包进行修改:
import rclpy
from rclpy.node import Node
from tutorial_interfaces.msg import Num # 修改
class MinimalSubscriber(Node):
def __init__(self):
super().__init__('minimal_subscriber')
self.subscription = self.create_subscription(
Num, # 修改
'topic',
self.listener_callback,
10)
self.subscription
def listener_callback(self, msg):
self.get_logger().info('I heard: "%d"' % msg.num) # 修改
def main(args=None):
rclpy.init(args=args)
minimal_subscriber = MinimalSubscriber()
rclpy.spin(minimal_subscriber)
minimal_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
配置package.xml
在package.xml中添加以下依赖:
<depend>tutorial_interfaces</depend>
添加订阅者入口点
在功能包下的setup.py文件中修改订阅者的节点入口:
entry_points={
'console_scripts': [
'listener = py_pubsub.subscriber_member_function:main',
],
},
listener:命令行中用于启动订阅者节点的名称。py_pubsub.subscriber_member_function:main:指定运行订阅者节点的入口函数。 完成修改后保存文件。
测试
在工作空间的根目录(ros2_ws)下打开两个新的终端,并在每个终端上都执行:
source install/setup.bash
然后在两个终端上运行修改后的发布者节点和订阅者节点:
ros2 run cpp_pubsub talker
ros2 run py_pubsub listener
如果一切顺利就可以观察到发布者和订阅者之间在通讯。
使用service/client 测试 AddThreeInts.srv
先前教程使用了 Python 创建服务功能包,完成了客户端发送两个整数,服务端完成相加并传回客户端的目标。这里在功能包 py_srvcli 基础上进行一些修改,将原始的请求两个整数相加更改为三个整数相加。
服务端代码
from tutorial_interfaces.srv import AddThreeInts # 修改
import rclpy
from rclpy.node import Node
class MinimalService(Node):
def __init__(self):
super().__init__('minimal_service')
self.srv = self.create_service(AddThreeInts, 'add_three_ints', self.add_three_ints_callback) # 修改
def add_three_ints_callback(self, request, response):
response.sum = request.a + request.b + request.c # 修改
self.get_logger().info('Incoming request\na: %d b: %d c: %d' % (request.a, request.b, request.c)) # 修改
return response
def main(args=None):
rclpy.init(args=args)
minimal_service = MinimalService()
rclpy.spin(minimal_service)
rclpy.shutdown()
if __name__ == '__main__':
main()
客户端代码
from tutorial_interfaces.srv import AddThreeInts # 修改
import sys
import rclpy
from rclpy.node import Node
class MinimalClientAsync(Node):
def __init__(self):
super().__init__('minimal_client_async')
self.cli = self.create_client(AddThreeInts, 'add_three_ints') # 修改
while not self.cli.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.req = AddThreeInts.Request() # 修改
def send_request(self):
self.req.a = int(sys.argv[1])
self.req.b = int(sys.argv[2])
self.req.c = int(sys.argv[3]) # 修改
self.future = self.cli.call_async(self.req)
def main(args=None):
rclpy.init(args=args)
minimal_client = MinimalClientAsync()
minimal_client.send_request()
while rclpy.ok():
rclpy.spin_once(minimal_client)
if minimal_client.future.done():
try:
response = minimal_client.future.result()
except Exception as e:
minimal_client.get_logger().info(
'Service call failed %r' % (e,))
else:
minimal_client.get_logger().info(
'Result of add_three_ints: for %d + %d + %d = %d' % # 修改
(minimal_client.req.a, minimal_client.req.b, minimal_client.req.c, response.sum)) # 修改
break
minimal_client.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
配置package.xml
添加以下行:
<depend>tutorial_interfaces</depend>
setup.py文件不需要配置。
测试
在完成上述编辑并保存所有更改后,构建功能包:
colcon build --packages-select py_srvcli
在工作空间的根目录(ros2_ws)下打开两个新的终端,并在每个终端上都执行:
source install/setup.bash
然后在两个终端上运行修改后的服务端节点和客户端节点,如果一切顺利就可以观察到服务端和客户端之间的通信。
ros2 run py_srvcli server
ros2 run py_srvcli client 2 3 1
总结
本教程中展示了如何在自己的功能包中创建自定义接口,并在其他功能包中使用这些接口。