ROS2服务客户端(rclcpp::Client)是实现机器人「请求-响应」类交互的核心组件(如运动控制指令下发、传感器参数查询、设备状态获取等)。
一、服务客户端核心基础
1.1 服务通信模型定位
ROS2的通信模型分为三类,服务(Service)是一对一、双向、同步/异步的请求-响应模型,区别于话题(Topic,多对多、单向、异步)和动作(Action,多步、带反馈、异步):
- 客户端(Client):主动发起请求的节点(如机器人主控节点向视觉节点请求目标坐标);
- 服务端(Server):被动处理请求并返回响应的节点(如视觉节点处理图像后返回目标坐标);
- 接口定义:基于
.srv文件(如AddTwoInts.srv),编译后生成C++头文件,包含Request和Response两个结构体,是客户端与服务端的通信契约。
1.2 rclcpp::Client类核心结构
rclcpp::Client是模板类(模板参数ServiceT为.srv生成的服务类型),所有操作均基于共享指针(ROS2强制推荐,避免内存泄漏和线程安全问题),核心类型别名如下:
cpp
// 以AddTwoInts服务为例,工业场景可替换为自定义服务(如SetJointPos.srv)
using AddTwoInts = example_interfaces::srv::AddTwoInts;
using ClientPtr = rclcpp::Client<AddTwoInts>::SharedPtr; // 客户端共享指针
using RequestPtr = AddTwoInts::Request::SharedPtr; // 请求消息共享指针
using ResponsePtr = AddTwoInts::Response::SharedPtr; // 响应消息共享指针
using SharedFuture = rclcpp::Client<AddTwoInts>::SharedFuture; // 异步结果未来对象
二、核心成员函数
rclcpp::Client的成员函数是开发核心,以下按「使用频率+重要性」排序,覆盖所有关键接口:
2.1 客户端创建:create_client(Node成员函数)
rclcpp::Client无法直接构造,必须通过Node的create_client方法创建,是客户端初始化的唯一方式:
cpp
// 原型(简化版)
template<class ServiceT>
typename rclcpp::Client<ServiceT>::SharedPtr
Node::create_client(
const std::string &service_name, // 服务名称(与服务端一致,工业场景建议加命名空间,如"/arm/set_joint")
const rmw_qos_profile_t &qos_profile = rmw_qos_profile_services_default // QoS配置
);
// 工业级示例:创建带自定义QoS的客户端
rmw_qos_profile_t qos = rmw_qos_profile_services_default;
qos.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; // 可靠传输(机器人控制必选)
qos.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; // 易失性(无需持久化)
auto client = node->create_client<SetJointPos>("/arm/set_joint_position", qos);
关键说明:
- 服务名称是「通信唯一标识」,工业场景需按功能模块划分命名空间(如
/gripper/get_state、/base/set_velocity); - QoS配置直接影响通信可靠性:机器人控制类服务必须用
RELIABLE(可靠传输),非关键查询可用BEST_EFFORT(尽力而为)。
2.2 服务可用性检查:wait_for_service & is_service_available
(1)wait_for_service(阻塞式等待)
发送请求前必须确保服务端在线,该函数阻塞当前线程直到服务端上线或超时,是工业开发的「必用步骤」:
cpp
// 原型
template<class Rep, class Period>
bool wait_for_service(
const std::chrono::duration<Rep, Period> &timeout // 超时时间(如5s)
);
// 工业级示例:带重试逻辑的等待
int retry_count = 0;
const int MAX_RETRY = 3;
while (!client->wait_for_service(std::chrono::seconds(2)) && retry_count < MAX_RETRY) {
RCLCPP_WARN(node->get_logger(), "服务端未上线,重试第%d次...", retry_count + 1);
retry_count++;
}
if (retry_count >= MAX_RETRY) {
RCLCPP_ERROR(node->get_logger(), "服务端连接失败,退出!");
rclcpp::shutdown();
return -1;
}
(2)is_service_available(非阻塞式检查)
仅检查服务是否可用,不阻塞线程,适合「轮询式」场景(如机器人主控节点周期性检查外设服务):
cpp
// 原型
bool is_service_available() const;
// 示例:定时器回调中非阻塞检查
node->create_wall_timer(
std::chrono::seconds(1),
[client, node]() {
if (client->is_service_available()) {
RCLCPP_INFO(node->get_logger(), "服务端已在线");
} else {
RCLCPP_WARN(node->get_logger(), "服务端仍离线");
}
}
);
2.3 请求发送:async_send_request(核心)
ROS2推荐的异步发送请求 接口,非阻塞、不卡主线程,是工业级开发的首选,替代了旧版send_request(已标记为Deprecated):
cpp
// 原型(模板版,支持任意可调用对象作为回调)
template<class ServiceT, class CallbackT>
typename rclcpp::Client<ServiceT>::SharedFuture
async_send_request(
typename rclcpp::Client<ServiceT>::Request::SharedPtr request, // 请求数据(共享指针)
CallbackT &&callback = nullptr // 响应回调(可选)
);
// 工业级示例:带异常处理的异步请求
// 1. 构造请求(机器人关节控制指令)
auto request = std::make_shared<SetJointPos::Request>();
request->joint1 = 0.5; // 关节1角度(rad)
request->joint2 = 0.3; // 关节2角度(rad)
request->timeout = 5.0; // 执行超时(s)
// 2. 定义回调函数(工业场景需处理异常+线程安全)
std::mutex callback_mutex; // 线程安全锁(回调由ROS2线程池执行)
auto response_callback = [&](SharedFuture future) {
std::lock_guard<std::mutex> lock(callback_mutex); // 加锁
try {
ResponsePtr response = future.get(); // 获取响应(此时无阻塞,因回调触发时响应已返回)
if (response->success) {
RCLCPP_INFO(node->get_logger(), "关节控制成功,当前位置:%.2f, %.2f",
response->current_j1, response->current_j2);
} else {
RCLCPP_ERROR(node->get_logger(), "关节控制失败:%s", response->error_msg.c_str());
}
} catch (const std::future_error &e) {
RCLCPP_ERROR(node->get_logger(), "请求超时/取消:%s", e.what());
} catch (const rclcpp::exceptions::RCLError &e) {
RCLCPP_ERROR(node->get_logger(), "ROS2底层错误:%s", e.what());
}
};
// 3. 发送请求
client->async_send_request(request, response_callback);
关键说明:
- 回调函数的线程模型:ROS2默认使用「多线程回调组」,回调由线程池执行,操作共享数据(如机器人状态变量)必须加锁;
- Future对象:返回的
SharedFuture可手动调用get()获取响应,但get()会阻塞,仅适合简单场景(工业场景优先用回调)。
2.4 同步请求处理:spin_until_future_complete
若需「同步等待响应」(如机器人启动时的参数初始化),可结合async_send_request和spin_until_future_complete实现(替代旧版send_request):
cpp
// 示例:同步请求(工业场景慎用,易阻塞主线程)
auto future = client->async_send_request(request);
// 阻塞直到响应返回或超时
auto ret_code = rclcpp::spin_until_future_complete(node, future, std::chrono::seconds(5));
if (ret_code == rclcpp::FutureReturnCode::SUCCESS) {
ResponsePtr response = future.get();
RCLCPP_INFO(node->get_logger(), "同步请求成功:%s", response->error_msg.c_str());
} else if (ret_code == rclcpp::FutureReturnCode::TIMEOUT) {
RCLCPP_ERROR(node->get_logger(), "同步请求超时");
} else {
RCLCPP_ERROR(node->get_logger(), "同步请求失败");
}
2.5 辅助成员函数(全覆盖)
| 函数名 | 功能说明 | 工业场景使用场景 |
|---|---|---|
get_service_name() |
返回客户端绑定的服务名称(字符串) | 动态调试、多客户端管理时校验名称 |
get_qos_profile() |
返回客户端的QoS配置(rmw_qos_profile_t) |
运行时动态调整QoS、通信问题排查 |
get_node_base_interface() |
返回节点的基础接口指针(NodeBaseInterface::SharedPtr) |
自定义资源管理、底层API调用 |
is_valid() |
检查客户端是否有效(未被销毁、与节点绑定正常) | 动态创建/销毁客户端时的有效性校验 |
destroy() |
手动销毁客户端,释放底层资源(一般无需调用,节点销毁时自动释放) | 机器人动态切换服务端时手动清理资源 |
三、工业级开发完整流程
以「机器人关节控制服务客户端」为例,覆盖从工程配置到代码运行的全流程:
3.1 工程配置(package.xml + CMakeLists.txt)
(1)package.xml(依赖声明)
xml
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>arm_control_client</name>
<version>0.0.1</version>
<description>机器人关节控制服务客户端</description>
<maintainer email="dev@robot.com">Robot Dev Team</maintainer>
<license>Apache-2.0</license>
<!-- 核心依赖 -->
<depend>rclcpp</depend>
<depend>arm_interfaces</depend> <!-- 自定义服务包(包含SetJointPos.srv) -->
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
(2)CMakeLists.txt(编译配置)
cmake
cmake_minimum_required(VERSION 3.8)
project(arm_control_client)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic) # 工业级编译警告
endif()
# 查找依赖
find_package(rclcpp REQUIRED)
find_package(arm_interfaces REQUIRED) # 自定义服务包
# 编译可执行文件
add_executable(arm_client_node src/arm_client.cpp)
ament_target_dependencies(arm_client_node rclcpp arm_interfaces)
# 安装可执行文件(ROS2标准路径)
install(TARGETS
arm_client_node
DESTINATION lib/${PROJECT_NAME}
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
3.2 核心代码实现(工业级)
cpp
#include "rclcpp/rclcpp.hpp"
#include "arm_interfaces/srv/set_joint_pos.hpp" // 自定义关节控制服务
// 类型别名(简化代码,工业场景推荐)
using SetJointPos = arm_interfaces::srv::SetJointPos;
using ClientPtr = rclcpp::Client<SetJointPos>::SharedPtr;
using RequestPtr = SetJointPos::Request::SharedPtr;
using ResponsePtr = SetJointPos::Response::SharedPtr;
using SharedFuture = rclcpp::Client<SetJointPos>::SharedFuture;
class ArmControlClient : public rclcpp::Node {
public:
ArmControlClient() : Node("arm_control_client_node") {
// 1. 初始化QoS(工业级可靠传输)
rmw_qos_profile_t qos = rmw_qos_profile_services_default;
qos.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
qos.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
qos.depth = 1;
// 2. 创建客户端(绑定服务名称)
client_ = this->create_client<SetJointPos>("/arm/set_joint_position", qos);
// 3. 启动服务等待定时器(非阻塞)
wait_timer_ = this->create_wall_timer(
std::chrono::seconds(1),
std::bind(&ArmControlClient::check_service_status, this)
);
RCLCPP_INFO(this->get_logger(), "关节控制客户端已启动");
}
// 发送关节控制请求(对外接口)
void send_joint_request(double j1, double j2, double timeout) {
if (!client_->is_service_available()) {
RCLCPP_WARN(this->get_logger(), "服务端未在线,暂不发送请求");
return;
}
// 构造请求
auto request = std::make_shared<SetJointPos::Request>();
request->joint1 = j1;
request->joint2 = j2;
request->timeout = timeout;
// 异步发送请求+回调
client_->async_send_request(
request,
std::bind(&ArmControlClient::response_callback, this, std::placeholders::_1)
);
RCLCPP_INFO(this->get_logger(), "已发送关节控制请求:j1=%.2f, j2=%.2f", j1, j2);
}
private:
// 检查服务状态(定时器回调)
void check_service_status() {
static bool service_available = false;
if (client_->is_service_available() && !service_available) {
RCLCPP_INFO(this->get_logger(), "服务端已上线,可发送请求");
service_available = true;
wait_timer_->cancel(); // 停止检查
}
}
// 响应回调函数(工业级异常处理+线程安全)
void response_callback(SharedFuture future) {
std::lock_guard<std::mutex> lock(mutex_); // 线程安全锁
try {
ResponsePtr response = future.get();
if (response->success) {
RCLCPP_INFO(this->get_logger(),
"关节控制成功 | 当前位置:j1=%.2f, j2=%.2f | 执行耗时:%.2fs",
response->current_j1, response->current_j2, response->exec_time);
} else {
RCLCPP_ERROR(this->get_logger(),
"关节控制失败 | 错误信息:%s",
response->error_msg.c_str());
}
} catch (const std::exception &e) {
RCLCPP_FATAL(this->get_logger(), "请求异常:%s", e.what());
// 工业场景:异常时触发降级逻辑(如紧急停止)
emergency_stop();
}
}
// 紧急停止(工业级容错逻辑)
void emergency_stop() {
RCLCPP_WARN(this->get_logger(), "触发紧急停止,重置关节位置");
// 发送紧急停止请求(略)
}
// 成员变量
ClientPtr client_;
rclcpp::TimerBase::SharedPtr wait_timer_;
std::mutex mutex_; // 回调线程安全锁
};
int main(int argc, char *argv[]) {
// ROS2初始化
rclcpp::init(argc, argv);
auto client_node = std::make_shared<ArmControlClient>();
// 模拟发送关节控制请求(工业场景可从命令行/话题获取参数)
client_node->send_joint_request(0.5, 0.3, 5.0);
// 保持节点运行(异步回调依赖spin)
rclcpp::spin(client_node);
// 资源清理
rclcpp::shutdown();
return 0;
}
3.3 编译与运行
bash
# 编译(工业场景建议用colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release)
colcon build --packages-select arm_control_client
# 激活环境
source install/setup.bash
# 运行客户端(需先启动服务端)
ros2 run arm_control_client arm_client_node
四、高级特性(工业级扩展)
4.1 动态客户端(DynamicClient)
无需编译时知道服务类型,运行时解析.srv接口,适合通用机器人框架开发:
cpp
#include "rclcpp/dynamic_client/dynamic_client.hpp"
// 示例:动态调用任意服务
auto dynamic_client = rclcpp::dynamic_client::DynamicClient::make_shared(node);
dynamic_client->call_service(
"/arm/set_joint_position", // 服务名称
"arm_interfaces/srv/SetJointPos", // 服务类型
R"({"joint1":0.5, "joint2":0.3, "timeout":5.0})", // 请求数据(JSON)
[](const rclcpp::dynamic_client::DynamicResponse &response) {
RCLCPP_INFO(node->get_logger(), "动态请求响应:%s", response.get_json().c_str());
}
);
4.2 回调组(CallbackGroup)
控制回调执行的线程模型,工业场景避免回调阻塞:
cpp
// 创建可重入回调组(多线程执行回调)
auto callback_group = node->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
// 创建客户端时指定回调组
auto client = node->create_client<SetJointPos>(
"/arm/set_joint_position",
rmw_qos_profile_services_default,
callback_group // 绑定回调组
);
4.3 请求超时处理
工业场景避免请求无限等待,结合定时器实现超时取消:
cpp
// 发送请求时启动超时定时器
auto timeout_timer = node->create_wall_timer(
std::chrono::seconds(5),
[&]() {
RCLCPP_ERROR(node->get_logger(), "请求超时,取消操作");
timeout_timer->cancel();
// 工业场景:触发容错逻辑
}
);
// 回调中取消定时器(响应正常返回)
auto response_callback = [&](SharedFuture future) {
timeout_timer->cancel(); // 取消超时定时器
// 处理响应(略)
};
五、常见问题与工程实践
5.1 高频问题排查
- 请求发送失败:检查服务名称是否一致、服务端是否在线、QoS是否匹配;
- 回调不触发 :确保节点调用
rclcpp::spin()、回调组配置正确、未捕获异常导致回调退出; - 线程安全问题:回调中操作共享数据必须加锁,避免机器人状态变量被多线程篡改;
- 内存泄漏 :客户端必须用共享指针,避免手动
new/delete,节点销毁时自动释放资源。
5.2 工业级实践
- 命名规范 :服务名称按「模块/功能」划分(如
/gripper/get_state),避免冲突; - 异常处理 :回调中捕获所有异常(
std::exception、rclcpp::RCLError),触发降级/容错逻辑; - QoS适配 :控制类服务用
RELIABLE,查询类服务用BEST_EFFORT,根据场景调整历史深度; - 资源管理 :动态创建的客户端需手动
destroy(),避免节点退出时内存泄漏; - 日志规范 :按级别输出日志(
RCLCPP_INFO/WARN/ERROR/FATAL),便于工业场景调试。
总结
- ROS2 C++服务客户端核心是
rclcpp::Client模板类,通过create_client创建、async_send_request异步发送请求,是工业级机器人「请求-响应」交互的核心实现方式; - 核心流程:初始化节点→创建客户端(指定QoS)→等待服务端→构造请求→异步发送+回调处理→保持节点自旋;
- 工业级开发需重点关注:QoS配置(可靠传输)、线程安全(回调加锁)、异常处理(容错逻辑)、命名规范(模块划分),避免阻塞主线程、内存泄漏、通信失败等问题。