创建自定义 msg 和 srv 文件
目标: 定义自定义接口文件(“.msg”和“.srv”)并将它们与 Python 和 C++ 节点一起使用。
教程几倍: 初学者
时间: 20 分钟
背景
在之前的教程中,您利用消息和服务接口了解了 topics、services 以及简单的发布者/订阅者 (C++/Python) 和服务/客户端 (C++/Python) 节点。 在这些情况下,您使用的接口是预定义的。
虽然使用预定义的接口定义是一种很好的做法,但有时您可能也需要定义自己的消息和服务。 本教程将向您介绍创建自定义接口定义的最简单方法。
先决条件
您应该有一个 ROS 2 工作区。
本教程还使用发布者/订阅者 (C++ 和 Python) 和服务/客户端 (C++ 和 Python) 教程中创建的包来尝试新的自定义消息。
任务
1 创建新包
在本教程中,您将在自己的包中创建自定义 .msg
和 .srv
文件,然后在单独的包中使用它们。
两个包都应位于同一个工作区中。
由于我们将使用在之前的教程中创建的 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
中创建目录:
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 srv 定义
返回刚刚创建的“tutorial_interfaces/srv”目录,创建一个名为“AddThreeInts.srv”的新文件,其中包含以下请求和响应结构:
int64 a
int64 b
int64 c
---
int64 sum
这是您的自定义服务,它请求三个名为“a”、“b”和“c”的整数,并以一个名为“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
)
Note
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
colcon build --packages-select tutorial_interfaces
colcon build --merge-install --packages-select tutorial_interfaces
现在,其他 ROS 2 软件包将可以发现这些接口。
6 确认 msg 和 srv 创建
在新的终端中,从您的工作区(“ros2_ws”)内运行以下命令来获取它:
source install/setup.bash
. install/setup.bash
call install/setup.bat
现在,您可以使用“ros2 interface show”命令确认您的接口创建是否有效:
ros2 interface show tutorial_interfaces/msg/Num
should return:
int64 num
And
ros2 interface show tutorial_interfaces/msg/Sphere
should return:
geometry_msgs/Point center
float64 x
float64 y
float64 z
float64 radius
And
ros2 interface show tutorial_interfaces/srv/AddThreeInts
should return:
int64 a
int64 b
int64 c
---
int64 sum
7 测试新接口
对于此步骤,您可以使用在之前的教程中创建的包。
对节点、CMakeLists.txt
和 package.xml
文件进行一些简单的修改,您就可以使用新的接口。
7.1 使用 pub/sub 测试 Num.msg
对之前教程中创建的发布者/订阅者包进行一些修改(C++ 或 Python),您可以看到 Num.msg
的实际效果。
由于您要将标准字符串消息更改为数字消息,因此输出会略有不同。
Publisher
#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;
}
import rclpy
from rclpy.node import Node
from tutorial_interfaces.msg import Num # CHANGE
class MinimalPublisher(Node):
def __init__(self):
super().__init__('minimal_publisher')
self.publisher_ = self.create_publisher(Num, 'topic', 10) # CHANGE
timer_period = 0.5
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
def timer_callback(self):
msg = Num() # CHANGE
msg.num = self.i # CHANGE
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%d"' % msg.num) # CHANGE
self.i += 1
def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalPublisher()
rclpy.spin(minimal_publisher)
minimal_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Subscriber
#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;
}
import rclpy
from rclpy.node import Node
from tutorial_interfaces.msg import Num # CHANGE
class MinimalSubscriber(Node):
def __init__(self):
super().__init__('minimal_subscriber')
self.subscription = self.create_subscription(
Num, # CHANGE
'topic',
self.listener_callback,
10)
self.subscription
def listener_callback(self, msg):
self.get_logger().info('I heard: "%d"' % msg.num) # CHANGE
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()
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>
<exec_depend>tutorial_interfaces</exec_depend>
完成上述编辑并保存所有更改后,构建包:
On Linux/macOS:
colcon build --packages-select cpp_pubsub
On Windows:
colcon build --merge-install --packages-select cpp_pubsub
On Linux/macOS:
colcon build --packages-select py_pubsub
On Windows:
colcon build --merge-install --packages-select py_pubsub
然后打开两个新终端,在每个终端中输入“ros2_ws”,然后运行:
ros2 run cpp_pubsub talker
ros2 run cpp_pubsub listener
ros2 run py_pubsub talker
ros2 run py_pubsub listener
由于“Num.msg”仅传递一个整数,因此发送者应该仅发布整数值,而不是之前发布的字符串:
[INFO] [minimal_publisher]: Publishing: '0'
[INFO] [minimal_publisher]: Publishing: '1'
[INFO] [minimal_publisher]: Publishing: '2'
7.2 使用服务/客户端测试 AddThreeInts.srv
对上一个教程中创建的服务/客户端包(C++ 或 Python)进行一些修改后,您可以看到 AddThreeInts.srv
的实际效果。
由于您将把原始的两个整数请求 srv 更改为三个整数请求 srv,因此输出会略有不同。
Service
#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();
}
from tutorial_interfaces.srv import AddThreeInts # CHANGE
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) # CHANGE
def add_three_ints_callback(self, request, response):
response.sum = request.a + request.b + request.c # CHANGE
self.get_logger().info('Incoming request\na: %d b: %d c: %d' % (request.a, request.b, request.c)) # CHANGE
return response
def main(args=None):
rclpy.init(args=args)
minimal_service = MinimalService()
rclpy.spin(minimal_service)
rclpy.shutdown()
if __name__ == '__main__':
main()
Client
#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;
}
from tutorial_interfaces.srv import AddThreeInts # CHANGE
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') # CHANGE
while not self.cli.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.req = AddThreeInts.Request() # CHANGE
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]) # CHANGE
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' % # CHANGE
(minimal_client.req.a, minimal_client.req.b, minimal_client.req.c, response.sum)) # CHANGE
break
minimal_client.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
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>
<exec_depend>tutorial_interfaces</exec_depend>
完成上述编辑并保存所有更改后,构建包:
On Linux/macOS:
colcon build --packages-select cpp_srvcli
On Windows:
colcon build --merge-install --packages-select cpp_srvcli
On Linux/macOS:
colcon build --packages-select py_srvcli
On Windows:
colcon build --merge-install --packages-select py_srvcli
然后打开两个新终端,在每个终端中输入“ros2_ws”,然后运行:
ros2 run cpp_srvcli server
ros2 run cpp_srvcli client 2 3 1
ros2 run py_srvcli service
ros2 run py_srvcli client 2 3 1
摘要
在本教程中,您学习了如何在自己的包中创建自定义接口以及如何在其他包中使用这些接口。
本教程仅涉及定义自定义接口的皮毛。 您可以在以下位置了解更多信息 About ROS 2 interfaces.
后续步骤
The next tutorial 涵盖了在 ROS 2 中使用接口的更多方法。