ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

Yes, you can use a template.

template<typename ServiceT>
typename ServiceT::Response::SharedPtr send_request(
  rclcpp::Node::SharedPtr node,
  rclcpp::Client<ServiceT>::SharedPtr client,
  typename ServiceT::Request::SharedPtr request)
{
  auto result = client->async_send_request(request);
  // Wait for the result.
  if (rclcpp::spin_until_future_complete(node, result) ==
    rclcpp::executor::FutureReturnCode::SUCCESS)
  {
    return result.get();
  } else {
    return NULL;
  }
}

Then you can call it like this

  using ServiceT1 = ....
  using ServiceT2 = ....

  auto node = rclcpp::Node::make_shared("client_node");
  auto client_1 = node->create_client<ServiceT1>("my_service_1_name");
  auto client_2 = node->create_client<ServiceT2>("my_service_2_name");

  auto request_1 = std::make_shared<ServiceT1::Request>();
  auto result_1 = send_request<ServiceT1>(node, client_1, request_1);

  auto request_2 = std::make_shared<ServiceT2::Request>();
  auto result_2 = send_request<ServiceT2>(node, client_2, request_2);

P.S. In ROS2 this is not the recommended style for creating nodes. You should create a class that extends rclcpp::Node and define the send_request function and the clients as members of this class.

Yes, you can use a template.

template<typename ServiceT>
typename ServiceT::Response::SharedPtr send_request(
  rclcpp::Node::SharedPtr node,
  typename rclcpp::Client<ServiceT>::SharedPtr client,
  typename ServiceT::Request::SharedPtr request)
{
  auto result = client->async_send_request(request);
  // Wait for the result.
  if (rclcpp::spin_until_future_complete(node, result) ==
    rclcpp::executor::FutureReturnCode::SUCCESS)
  {
    return result.get();
  } else {
    return NULL;
  }
}

Then you can call it like this

  using ServiceT1 = ....
  using ServiceT2 = ....

  auto node = rclcpp::Node::make_shared("client_node");
  auto client_1 = node->create_client<ServiceT1>("my_service_1_name");
  auto client_2 = node->create_client<ServiceT2>("my_service_2_name");

  auto request_1 = std::make_shared<ServiceT1::Request>();
  auto result_1 = send_request<ServiceT1>(node, client_1, request_1);

  auto request_2 = std::make_shared<ServiceT2::Request>();
  auto result_2 = send_request<ServiceT2>(node, client_2, request_2);

P.S. In ROS2 this is not the recommended style for creating nodes. You should create a class that extends rclcpp::Node and define the send_request function and the clients as members of this class.