配置服务自省
目标:为服务客户端和服务器配置服务自检。
教程级别:高级
时间:15 分钟
概述
ROS 2 应用程序通常由在远程节点中执行特定程序的服务组成。
可以使用服务自省来自省服务数据通信。
在此演示中,我们将重点介绍如何为服务客户端和服务器配置服务自省状态,并使用“ros2 service echo”监视服务通信。
安装演示
有关安装 ROS 2 的详细信息,请参阅 安装说明。
如果您已安装 ROS 2 二进制包,请确保已安装“ros-rolling-demo-nodes-cpp”。
如果您下载了存档或从源代码构建了 ROS 2,它将已经成为安装的一部分。
自省配置状态
服务自省有 3 种配置状态。
RCL_SERVICE_INTROSPECTION_OFF |
Disabled |
RCL_SERVICE_INTROSPECTION_METADATA |
Only metadata without any user data contents |
RCL_SERVICE_INTROSPECTION_CONTENTS |
User data contents with metadata |
自省演示
此演示展示了如何使用“ros2 service echo”来管理服务自省并监控服务数据通信。
自省服务节点:
https://github.com/ros2/demos/blob/rolling/demo_nodes_cpp/src/services/introspection_service.cpp
namespace demo_nodes_cpp
{
class IntrospectionServiceNode : public rclcpp::Node
{
public:
DEMO_NODES_CPP_PUBLIC
explicit IntrospectionServiceNode(const rclcpp::NodeOptions & options)
: Node("introspection_service", options)
{
auto handle_add_two_ints =
[this](const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) -> void
{
(void)request_header;
RCLCPP_INFO(
this->get_logger(), "Incoming request\na: %" PRId64 " b: %" PRId64,
request->a, request->b);
response->sum = request->a + request->b;
};
// Create a service that will use the callback function to handle requests.
srv_ = create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", handle_add_two_ints);
auto on_set_parameter_callback =
[](std::vector<rclcpp::Parameter> parameters) {
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (const rclcpp::Parameter & param : parameters) {
if (param.get_name() != "service_configure_introspection") {
continue;
}
if (param.get_type() != rclcpp::ParameterType::PARAMETER_STRING) {
result.successful = false;
result.reason = "must be a string";
break;
}
if (param.as_string() != "disabled" && param.as_string() != "metadata" &&
param.as_string() != "contents")
{
result.successful = false;
result.reason = "must be one of 'disabled', 'metadata', or 'contents'";
break;
}
}
return result;
};
auto post_set_parameter_callback =
[this](const std::vector<rclcpp::Parameter> & parameters) {
for (const rclcpp::Parameter & param : parameters) {
if (param.get_name() != "service_configure_introspection") {
continue;
}
rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
if (param.as_string() == "disabled") {
introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
} else if (param.as_string() == "metadata") {
introspection_state = RCL_SERVICE_INTROSPECTION_METADATA;
} else if (param.as_string() == "contents") {
introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS;
}
this->srv_->configure_introspection(
this->get_clock(), rclcpp::SystemDefaultsQoS(), introspection_state);
break;
}
};
on_set_parameters_callback_handle_ = this->add_on_set_parameters_callback(
on_set_parameter_callback);
post_set_parameters_callback_handle_ = this->add_post_set_parameters_callback(
post_set_parameter_callback);
this->declare_parameter("service_configure_introspection", "disabled");
}
private:
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr srv_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
on_set_parameters_callback_handle_;
rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr
post_set_parameters_callback_handle_;
};
} // namespace demo_nodes_cpp
服务自省默认是禁用的,因此用户需要启用它以在服务服务器上调用“configure_introspection”。 在这个演示中,“IntrospectionServiceNode”使用名为“service_configure_introspection”的参数来配置服务自省状态。
首先我们需要启动“IntrospectionServiceNode”。
$ ros2 run demo_nodes_cpp introspection_service
要改变服务自省状态,我们需要设置“configure_introspection”参数,如下所示。
### User data contents with metadata
$ ros2 param set /introspection_service service_configure_introspection contents
### Or only metadata
$ ros2 param set /introspection_service service_configure_introspection metadata
### To disable
$ ros2 param set /introspection_service service_configure_introspection disabled
自省客户端节点:
https://github.com/ros2/demos/blob/rolling/demo_nodes_cpp/src/services/introspection_client.cpp
namespace demo_nodes_cpp
{
class IntrospectionClientNode : public rclcpp::Node
{
public:
DEMO_NODES_CPP_PUBLIC
explicit IntrospectionClientNode(const rclcpp::NodeOptions & options)
: Node("introspection_client", options)
{
client_ = create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");
auto on_set_parameter_callback =
[](std::vector<rclcpp::Parameter> parameters) {
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (const rclcpp::Parameter & param : parameters) {
if (param.get_name() != "client_configure_introspection") {
continue;
}
if (param.get_type() != rclcpp::ParameterType::PARAMETER_STRING) {
result.successful = false;
result.reason = "must be a string";
break;
}
if (param.as_string() != "disabled" && param.as_string() != "metadata" &&
param.as_string() != "contents")
{
result.successful = false;
result.reason = "must be one of 'disabled', 'metadata', or 'contents'";
break;
}
}
return result;
};
auto post_set_parameter_callback =
[this](const std::vector<rclcpp::Parameter> & parameters) {
for (const rclcpp::Parameter & param : parameters) {
if (param.get_name() != "client_configure_introspection") {
continue;
}
rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
if (param.as_string() == "disabled") {
introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
} else if (param.as_string() == "metadata") {
introspection_state = RCL_SERVICE_INTROSPECTION_METADATA;
} else if (param.as_string() == "contents") {
introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS;
}
this->client_->configure_introspection(
this->get_clock(), rclcpp::SystemDefaultsQoS(), introspection_state);
break;
}
};
on_set_parameters_callback_handle_ = this->add_on_set_parameters_callback(
on_set_parameter_callback);
post_set_parameters_callback_handle_ = this->add_post_set_parameters_callback(
post_set_parameter_callback);
this->declare_parameter("client_configure_introspection", "disabled");
timer_ = this->create_wall_timer(
std::chrono::milliseconds(500),
[this]() {
if (!client_->service_is_ready()) {
return;
}
if (!request_in_progress_) {
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = 2;
request->b = 3;
request_in_progress_ = true;
client_->async_send_request(
request,
[this](rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedFuture cb_f)
{
request_in_progress_ = false;
RCLCPP_INFO(get_logger(), "Result of add_two_ints: %ld", cb_f.get()->sum);
}
);
return;
}
});
}
private:
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
on_set_parameters_callback_handle_;
rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr
post_set_parameters_callback_handle_;
bool request_in_progress_{false};
};
} // namespace demo_nodes_cpp
然后,我们以同样的方式启动并配置“IntrospectionClientNode”。
$ ros2 run demo_nodes_cpp introspection_client
更改服务自省状态以设置“configure_introspection”参数,如下所示。
### User data contents with metadata
$ ros2 param set /introspection_client client_configure_introspection contents
### Or only metadata
$ ros2 param set /introspection_client client_configure_introspection metadata
### To disable
$ ros2 param set /introspection_client client_configure_introspection disabled
在本教程中,以下是“IntrospectionServiceNode”上的服务自省状态“CONTENTS”和“IntrospectionClientNode”上的服务自省状态“METADATA”的示例输出。 为了监视“IntrospectionClientNode”和“IntrospectionServiceNode”之间的服务通信,让我们运行它:
$ ros2 service echo --flow-style /add_two_ints
info:
event_type: REQUEST_SENT
stamp:
sec: 1709432402
nanosec: 680094264
client_gid: [1, 15, 0, 18, 86, 208, 115, 86, 0, 0, 0, 0, 0, 0, 21, 3]
sequence_number: 247
request: []
response: []
---
info:
event_type: REQUEST_RECEIVED
stamp:
sec: 1709432402
nanosec: 680459568
client_gid: [1, 15, 0, 18, 86, 208, 115, 86, 0, 0, 0, 0, 0, 0, 20, 4]
sequence_number: 247
request: [{a: 2, b: 3}]
response: []
---
info:
event_type: RESPONSE_SENT
stamp:
sec: 1709432402
nanosec: 680765280
client_gid: [1, 15, 0, 18, 86, 208, 115, 86, 0, 0, 0, 0, 0, 0, 20, 4]
sequence_number: 247
request: []
response: [{sum: 5}]
---
info:
event_type: RESPONSE_RECEIVED
stamp:
sec: 1709432402
nanosec: 681027998
client_gid: [1, 15, 0, 18, 86, 208, 115, 86, 0, 0, 0, 0, 0, 0, 21, 3]
sequence_number: 247
request: []
response: []
---
...
您可以看到 event_type: REQUEST_SENT
和 event_type: RESPONSE_RECEIVED
,这些自省服务事件发生在 IntrospectionClientNode
中。
并且这些事件不包含 request
和 response
字段中的任何内容,这是因为 IntrospectionClientNode
的服务自省状态设置为 METADATA
。
另一方面,来自 IntrospectionServiceNode
的 event_type: REQUEST_RECEIVED
和 event_type: RESPONSE_SENT
事件包含 request: [{a: 2, b: 3}]
和 response: [{sum: 5}]
,因为自省状态设置为 CONTENTS
。