-
Notifications
You must be signed in to change notification settings - Fork 357
Expand file tree
/
Copy pathmain.cpp
More file actions
90 lines (77 loc) · 3.29 KB
/
main.cpp
File metadata and controls
90 lines (77 loc) · 3.29 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
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;
}