-
Notifications
You must be signed in to change notification settings - Fork 316
/
Copy pathmain.cpp
50 lines (47 loc) · 1.79 KB
/
main.cpp
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
// Copyright 2016 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 <chrono>
#include <cinttypes>
#include <memory>
#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"
using AddTwoInts = example_interfaces::srv::AddTwoInts;
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("minimal_client");
auto client = node->create_client<AddTwoInts>("add_two_ints");
while (!client->wait_for_service(std::chrono::seconds(1))) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(node->get_logger(), "client interrupted while waiting for service to appear.");
return 1;
}
RCLCPP_INFO(node->get_logger(), "waiting for service to appear...");
}
auto request = std::make_shared<AddTwoInts::Request>();
request->a = 41;
request->b = 1;
auto result_future = client->async_send_request(request);
if (rclcpp::spin_until_future_complete(node, result_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "service call failed :(");
return 1;
}
auto result = result_future.get();
RCLCPP_INFO(node->get_logger(), "result of %" PRId64 " + %" PRId64 " = %" PRId64,
request->a, request->b, result->sum);
rclcpp::shutdown();
return 0;
}