ROS2 入门应用 引用自定义服务(C++)
-
1. 查看自定义服务
2. 修改服务应答
3. 修改服务请求
4. 修改依赖关系
5. 修改编译信息
6. 编译和运行
1. 查看自定义服务
引用在《ROS2 入门应用 创建自定义接口》中自定义的服务AddThreeInts.srv
ros2 interface show tutorial_interfaces/srv/AddThreeInts
# int64 a
# int64 b
# int64 c
# ---
# int64 sum
需要对《ROS2 入门应用 请求和应答(C++)》中创建的服务端/客户端功能包稍作修改
cd ~/ros2_ws/src/cpp_srvcli/src
将把两个整数求和更改为三个整数求和
2. 修改服务应答
修改add_two_ints_server.cpp
服务端源文件,涉及服务类型变更和应用变化
#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", 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)
{
/* 初始化ROS2 */
rclcpp::init(argc, argv);
/* 定义服务端节点add_three_ints_server */
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_three_ints_server"); // CHANGE
/* 创建服务名为add_three_ints,服务函数为add的service服务端 */
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);
/* 退出ROS2 */
rclcpp::shutdown();
}
3. 修改服务请求
修改add_two_ints_client.cpp
客户端源文件,涉及服务类型变更和应用变化
#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)
{
/* 初始化ROS2 */
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;
}
/* 定义客户端节点add_three_ints_client*/
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_three_ints_client"); // CHANGE
/* 创建服务名为add_three_ints的client客户端 */
rclcpp::Client<tutorial_interfaces::srv::AddThreeInts>::SharedPtr client = // CHANGE
node->create_client<tutorial_interfaces::srv::AddThreeInts>("add_three_ints"); // CHANGE
/* 创建请求request */
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
/* 搜索服务节点,间隔1s */
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
}
/* 退出ROS2 */
rclcpp::shutdown();
return 0;
}
4. 修改依赖关系
在package.xml
清单文件中,添加对自定义服务的依赖项的声明
<depend>tutorial_interfaces</depend>
5. 修改编译信息
在CMakeLists.txt
编译文件中
- 更换搜索库
tutorial_interfaces
- 更换可执行文件目标依赖关系
tutorial_interfaces
#... 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()
6. 编译和运行
进入工作空间根目录
cd ~/ros2_ws
编译:
colcon build --packages-select cpp_srvcli
打开一个新终端,运行服务端节点:
ros2 run cpp_srvcli server
# [INFO] [rclcpp]: Ready to add three ints.
打开一个新终端,运行客户端节点:
ros2 run cpp_srvcli client 1 2 3
# [INFO] [rclcpp]: Sum: 6
谢谢
评论(0)
您还未登录,请登录后发表或查看评论