You're reading the documentation for an older, but still supported, version of ROS 2. For information on the latest version, please have a look at Jazzy.

Configure service introspection

Goal: Configure service introspection for a service client and a server.

Tutorial level: Advanced

Time: 15 minutes

Overview

ROS 2 applications usually consist of services to execute specific procedures in remote nodes. It is possible to introspect service data communication with service introspection.

In this demo, we’ll be highlighting how to configure service introspection state for a service client and a server and monitor service communication with ros2 service echo.

Installing the demo

See the installation instructions for details on installing ROS 2.

If you’ve installed ROS 2 binary packages, ensure that you have ros-iron-demo-nodes-cpp installed. If you downloaded the archive or built ROS 2 from source, it will already be part of the installation.

Introspection Configuration State

There are 3 configuration states for service introspection.

Service Introspection Configuration State

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

Introspection demo

This demo shows how to manage service introspection and monitor the service data communication with using ros2 service echo.

IntrospectionServiceNode:

https://github.com/ros2/demos/blob/iron/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

Service introspection is disable in default, so users need to enable it to call configure_introspection on service server. In this demo, IntrospectionServiceNode uses a parameter named `service_configure_introspection to configure the service introspection state.

1st we need to start IntrospectionServiceNode.

$ ros2 run demo_nodes_cpp introspection_service

To change service introspection state, we need to set the configure_introspection parameter as following.

### 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

IntrospectionClientNode:

https://github.com/ros2/demos/blob/iron/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

And then, we start and configure IntrospectionClientNode in the same way.

$ ros2 run demo_nodes_cpp introspection_client

Change service introspection state to set configure_introspection parameter as following.

### 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

In this tutorial the following is example output with service introspection state CONTENTS on IntrospectionServiceNode and METADATA on IntrospectionClientNode. To monitor service communication between IntrospectionClientNode and IntrospectionServiceNode, let’s run it:

$ 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: []
---
...

You can see the event_type: REQUEST_SENT and event_type: RESPONSE_RECEIVED, those introspection service event take place in IntrospectionClientNode. And those events does not include any contents in request and response field, this is because IntrospectionClientNode’s service introspection state is set to METADATA. On the other hand, event_type: REQUEST_RECEIVED and event_type: RESPONSE_SENT event from IntrospectionServiceNode includes request: [{a: 2, b: 3}] and response: [{sum: 5}] as introspection state is set to CONTENTS.