ROS2 学习记录(二)——ROS2 自定义消息与服务,编写 ROS2 中的 launch 文件
文章目录
自定义 ROS2 消息类型与服务类型
单独创建一个 ROS2 包,专门用于存储自定义的消息与服务。由于这个包中不需要存放节点,因此在创建包时,包的类型可以任选,包的依赖可以为空。
1ros2 pkg create --build-type ament_cmake custom_interfaces
在 custom_interfaces
中,创建 msg
和 srv
目录,分别用于存放初始消息文件和服务文件。ROS2 中的消息文件与服务文件均与 ROS1 中相同。
1mkdir -p custom_interfaces/msg
2mkdir -p custom_interfaces/srv
3touch custom_interfaces/msg/Coordinate.msg
4touch custom_interfaces/srv/CoordinteTransformation.srv
在 Coordinate.msg
中,我希望该类型消息能够传递一组平面直角坐标参数,包括横纵坐标两个值,因此在文件中输入如下内容:
1float64 x
2float64 y
而在 CoordinateTransformation.srv
中,我希望该服务的请求为一组平面直角坐标系的坐标,响应为该点在平面极坐标系中的坐标,在文件中输入如下内容:
1float64 x
2float64 y
3---
4float64 radius
5float64 theta
现在需要编译消息与服务,生成对应的 C++ 头文件和 Python 库文件。首先编辑 package.xml
文件,添加编译消息与服务的依赖:
1<build_depend>rosidl_default_generators</build_depend>
2<exec_depend>rosidl_default_runtime</exec_depend>
3<member_of_group>rosidl_interface_packages</member_of_group>
随后编辑 CMakeLists.txt
,将自定义消息与服务设置为编译目标:
1find_package(rosidl_default_generators REQUIRED)
2rosidl_generate_interfaces(${PROJECT_NAME}
3 "msg/Coordinate.msg"
4 "srv/CoordinateTransformation.srv"
5)
6ament_export_dependencies(rosidl_default_runtime)
随后,编译自定义消息与服务:
1colcon build --packages-select custom_interfaces
编译成功后,在 install/custom_interfaces
目录下能够找到生成的 C++ 头文件和 Python 库文件。此时需要手动将头文件和库文件的路径添加到 IntelliSense 的读取路径中,确保后续编写代码时,IntelliSense 能够正确识别。
使用 launch 文件启动多个节点
现在以自定义服务通信为例,使用 C++ 编写服务端节点和客户端节点。首先创建一个包,存放两个 C++ 节点:
1ros2 pkg create --build-type ament_cmake cpp_custom --dependencies rclcpp custom_interfaces
在 cpp_custom/src
目录下创建两个 C++ 文件 server.cpp
与 client.cpp
,分别表示服务端节点和客户端节点。
服务端:
1#include "custom_interfaces/srv/coordinate_transformation.hpp"
2#include "rclcpp/rclcpp.hpp"
3
4#include <cmath>
5
6using custom_interfaces::srv::CoordinateTransformation;
7using std::placeholders::_1;
8using std::placeholders::_2;
9
10class TransformationServer : public rclcpp::Node {
11 public:
12 TransformationServer() : Node("transformation_server") {
13 service_ =
14 create_service<CoordinateTransformation>("transformation", std::bind(&TransformationServer::handle, this, _1, _2));
15 }
16
17 private:
18 rclcpp::Service<CoordinateTransformation>::SharedPtr service_;
19
20 void handle(const CoordinateTransformation::Request::SharedPtr request,
21 const CoordinateTransformation::Response::SharedPtr response) {
22 double x = request->x, y = request->y;
23 RCLCPP_INFO(this->get_logger(), "Received request: x=%f y=%f", x, y);
24 response->radius = std::sqrt(x * x + y * y);
25 response->theta = std::atan2(y, x);
26 }
27};
28
29int main(int argc, char **argv) {
30 rclcpp::init(argc, argv);
31 rclcpp::spin(std::make_shared<TransformationServer>());
32 rclcpp::shutdown();
33 return 0;
34}
客户端:
1#include "custom_interfaces/srv/coordinate_transformation.hpp"
2#include "rclcpp/rclcpp.hpp"
3
4#include <ctime>
5#include <random>
6
7using custom_interfaces::srv::CoordinateTransformation;
8using namespace std::chrono_literals;
9
10class TransformationClient : public rclcpp::Node {
11 public:
12 TransformationClient() : Node("transformation_client") {
13 client_ = create_client<CoordinateTransformation>("transformation");
14 timer_ = create_wall_timer(2s, std::bind(&TransformationClient::send_request, this));
15 }
16
17 private:
18 rclcpp::Client<CoordinateTransformation>::SharedPtr client_;
19 rclcpp::TimerBase::SharedPtr timer_;
20
21 void send_request() {
22 auto request = std::make_shared<CoordinateTransformation::Request>();
23 auto random_pair = generate_random();
24 request->x = random_pair.first;
25 request->y = random_pair.second;
26 client_->async_send_request(request, std::bind(&TransformationClient::response_callback, this, std::placeholders::_1));
27 }
28
29 std::pair<double, double> generate_random() {
30 std::default_random_engine generator;
31 std::uniform_real_distribution<double> distribution(-180.0, 180.0);
32 generator.seed(time(0));
33 double x = distribution(generator);
34 generator.seed(time(0) + 1);
35 double y = distribution(generator);
36 return std::make_pair(x, y);
37 }
38
39 void response_callback(const rclcpp::Client<CoordinateTransformation>::SharedFuture future) {
40 RCLCPP_INFO(this->get_logger(), "Received response: radius=%f theta=%f", future.get()->radius, future.get()->theta);
41 }
42};
43
44int main(int argc, char **argv) {
45 rclcpp::init(argc, argv);
46 rclcpp::spin(std::make_shared<TransformationClient>());
47 rclcpp::shutdown();
48 return 0;
49}
编辑 CMakeLists.txt
,添加编译目标:
1add_executable(transformation_server src/server.cpp)
2ament_target_dependencies(transformation_server rclcpp custom_interfaces)
3add_executable(transformation_client src/client.cpp)
4ament_target_dependencies(transformation_client rclcpp custom_interfaces)
5
6install(TARGETS
7 transformation_server
8 transformation_client
9 DESTINATION lib/${PROJECT_NAME}
10)
运行命令编译该包中的两个节点:
1colcon build --packages-select cpp_custom
编译成功后,在包目录下创建 luanch
目录,用于存放 launch 文件。ROS1 中的 launch 文件为 XML 格式,而 ROS2 中的 launch 文件为 Python 脚本。在 launch
目录下创建 transformation.launch.py
文件,内容如下:
1from launch import LaunchDescription
2from launch_ros.actions import Node
3
4
5def generate_launch_description():
6 return LaunchDescription(
7 [
8 Node(
9 package="cpp_custom",
10 executable="transformation_server",
11 name="transformation_server",
12 ),
13 Node(
14 package="cpp_custom",
15 executable="transformation_client",
16 name="transformation_client",
17 ),
18 ]
19 )
虽然 ROS2 中的 launch 文件格式与 ROS1 中不同,但是其文件结构与 ROS1 一致。运行如下命令使用 launch 文件启动这两个节点:
1ros2 launch cpp_custom/launch/transformation.launch.py
随后即可看到两个节点运行。