Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add two example packages of service client and service server to understand asynchronism #398

Open
wants to merge 2 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 30 additions & 0 deletions rclcpp/services/async_recv_cb_client/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
cmake_minimum_required(VERSION 3.5)
project(examples_rclcpp_async_recv_cb_client)

# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

add_executable(client_main main.cpp)
ament_target_dependencies(client_main rclcpp std_msgs example_interfaces)

install(TARGETS client_main
DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
53 changes: 53 additions & 0 deletions rclcpp/services/async_recv_cb_client/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
# Async Receive Callback Client

## Summary

This package contains an example that includes a node that
is a client to the *add_two_ints* service. It shows how
to receive the response in a callback, thus avoiding any
waiting mechanism that might impact in the spinning of
the node.

Please, note that the former example in package:
*examples_rclcpp_async_client* has a very specific way for
spinning that are avoid in this example.

The goal of this package is helping programmers to understand
how asyncronous services work.

## Usage

Launch:

```bash
ros2 run examples_rclcpp_delayed_service service_main
```

```bash
ros2 run examples_rclcpp_async_recv_cb_client client_main
```

And trigger the call to the service by:

```bash
ros2 topic pub --once /input_topic std_msgs/msg/Int32 "data: 5"
```

Try to issue more than one call by publishing inmediately another
value to /input_topic.

You might listen to the topic that publishs the result:

```bash
ros2 topic echo /output_topic
```

## TODO

* Resolve the following questions:

> 1. What is the callback group for the response callback?
> 2. Is it possible to set another callback group?

Actually, answer to 1 should be the default node callback group.
Answer to 2 should be at api documentation (or sources?).
90 changes: 90 additions & 0 deletions rclcpp/services/async_recv_cb_client/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <rclcpp/rclcpp.hpp>
#include <example_interfaces/srv/add_two_ints.hpp>
#include <std_msgs/msg/int32.hpp>

class AsyncReceiveCallbackClient : public rclcpp::Node
{
public:
AsyncReceiveCallbackClient()
: Node("examples_rclcpp_async_recv_cb_client")
{
// Create AddTwoInts client
client_ = this->create_client<example_interfaces::srv::AddTwoInts>("add_two_ints");

// Wait until service is avaible
while (!client_->wait_for_service(std::chrono::seconds(1))) {
RCLCPP_ERROR(this->get_logger(), "Service is not available, trying again after 1 second");
}

// Create a subcription to an input topic
subscription_ = this->create_subscription<std_msgs::msg::Int32>(
"input_topic", 10,
std::bind(&AsyncReceiveCallbackClient::topic_callback, this, std::placeholders::_1));

// Create a publisher for broadcasting the result
publisher_ = this->create_publisher<std_msgs::msg::Int32>("output_topic", 10);

RCLCPP_INFO(this->get_logger(), "DelayedSumClient Initialized.");
}

private:
void topic_callback(const std::shared_ptr<std_msgs::msg::Int32> msg)
{
RCLCPP_INFO(this->get_logger(), "Received %d at topic.", msg->data);
if (msg->data >= 0) {
RCLCPP_INFO(this->get_logger(), " Input topic is %d >= 0. Requesting sum...", msg->data);

// Create request to sum msg->data + 100
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = msg->data;
request->b = 100;

// Calls the service and bind the callback to receive response (not blocking!)
auto future_result = client_->async_send_request(
request,
std::bind(
&AsyncReceiveCallbackClient::handle_service_response, this, std::placeholders::_1));
} else {
RCLCPP_INFO(this->get_logger(), " Input topic is %d < 0. No request is sent", msg->data);
}
}

// Callback to receive response (call inside the spinning method like any other callback)
void handle_service_response(
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedFuture future)
{
auto response = future.get();
RCLCPP_INFO(this->get_logger(), "Response: %ld", response->sum);

// Publish response at output topic
auto result_msg = std_msgs::msg::Int32();
result_msg.data = response->sum;
publisher_->publish(result_msg);
}

rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr subscription_;
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr publisher_;
};

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<AsyncReceiveCallbackClient>());
rclcpp::shutdown();
return 0;
}
31 changes: 31 additions & 0 deletions rclcpp/services/async_recv_cb_client/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>examples_rclcpp_async_recv_cb_client</name>
<version>0.20.2</version>
<description>Example of an async service client that uses
a callback to receive the response from the server.</description>

<maintainer email="[email protected]">Santiago Tapia-Fernández</maintainer>

<license>Apache License 2.0</license>

<author email="[email protected]">Santiago Tapia-Fernández</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>rclcpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>example_interfaces</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>example_interfaces</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
29 changes: 29 additions & 0 deletions rclcpp/services/delayed_service/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
cmake_minimum_required(VERSION 3.5)
project(examples_rclcpp_delayed_service)

# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclcpp REQUIRED)

add_executable(service_main main.cpp)
ament_target_dependencies(service_main rclcpp example_interfaces)

install(TARGETS service_main
DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
9 changes: 9 additions & 0 deletions rclcpp/services/delayed_service/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# Delayed service

This package contains an example that includes a node that
implements *add_two_ints* service and has a parameter to
hold the response for a given time.

The goal of this service is helping programmers to understand
how asyncronous services work.

67 changes: 67 additions & 0 deletions rclcpp/services/delayed_service/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <memory>
#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"

class DelayedSumService : public rclcpp::Node
{
public:
DelayedSumService()
: Node("delayed_service")
{
// Declares a parameter for delaying (default to 2.0 seconds)
this->declare_parameter("response_delay", 2.0);

service_ = this->create_service<example_interfaces::srv::AddTwoInts>(
"add_two_ints", std::bind(
&DelayedSumService::add_two_ints_callback, this, std::placeholders::_1,
std::placeholders::_2));

RCLCPP_INFO(this->get_logger(), "DelayedSumService is ready.");
}

private:
void add_two_ints_callback(
const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response)
{
// Gets parameter value
double delay;
this->get_parameter("response_delay", delay);

auto result = request->a + request->b;
RCLCPP_INFO_STREAM(
this->get_logger(),
"Request:" << request->a << " + " << request->b << " delayed " << delay << " seconds");

// Simulates the delay
std::this_thread::sleep_for(std::chrono::duration<double>(delay));

response->sum = result;
RCLCPP_INFO_STREAM(this->get_logger(), "Response: " << result);
}

rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service_;
};

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<DelayedSumService>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
30 changes: 30 additions & 0 deletions rclcpp/services/delayed_service/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>examples_rclcpp_delayed_service</name>
<version>0.20.2</version>
<description>A service server which adds two numbers but imposes a delay
in the response for showing the effect of delayed responses at time scale
that can be observed by the user/programmer.</description>

<maintainer email="[email protected]">Santiago Tapia-Fernández</maintainer>

<license>Apache License 2.0</license>

<author email="[email protected]">Santiago Tapia-Fernández</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>rclcpp</build_depend>
<build_depend>example_interfaces</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>example_interfaces</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>