|
| 1 | +// Copyright 2016 Open Source Robotics Foundation, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include <chrono> |
| 16 | +#include <cinttypes> |
| 17 | +#include <memory> |
| 18 | + |
| 19 | +#include "example_interfaces/srv/add_two_ints.hpp" |
| 20 | +#include "rclcpp/rclcpp.hpp" |
| 21 | + |
| 22 | +using namespace std::chrono_literals; |
| 23 | +using example_interfaces::srv::AddTwoInts; |
| 24 | + |
| 25 | +/* This example creates a subclass of Node and uses std::bind() to register a |
| 26 | + * member function as a callback from the client. */ |
| 27 | + |
| 28 | +class MinimalClient : public rclcpp::Node |
| 29 | +{ |
| 30 | +public: |
| 31 | + MinimalClient() |
| 32 | + : Node("minimal_client") |
| 33 | + { |
| 34 | + client_ = this->create_client<AddTwoInts>("add_two_ints"); |
| 35 | + while (!client_->wait_for_service(1s)) { |
| 36 | + if (!rclcpp::ok()) { |
| 37 | + RCLCPP_ERROR(this->get_logger(), "client interrupted while waiting for service to appear."); |
| 38 | + } |
| 39 | + RCLCPP_INFO(this->get_logger(), "waiting for service to appear..."); |
| 40 | + } |
| 41 | + auto request = std::make_shared<AddTwoInts::Request>(); |
| 42 | + request->a = 41; |
| 43 | + request->b = 1; |
| 44 | + auto result_future = client_->async_send_request( |
| 45 | + request, |
| 46 | + [this](rclcpp::Client<AddTwoInts>::SharedFutureWithRequest result_future) { |
| 47 | + auto result = result_future.get(); |
| 48 | + auto request = result.first; |
| 49 | + auto response = result.second; |
| 50 | + RCLCPP_INFO( |
| 51 | + this->get_logger(), "result of %" PRId64 " + %" PRId64 " = %" PRId64, |
| 52 | + request->a, request->b, response->sum); |
| 53 | + rclcpp::shutdown(); |
| 54 | + }); |
| 55 | + } |
| 56 | + |
| 57 | +private: |
| 58 | + rclcpp::Client<AddTwoInts>::SharedPtr client_; |
| 59 | +}; |
| 60 | + |
| 61 | +int main(int argc, char * argv[]) |
| 62 | +{ |
| 63 | + rclcpp::init(argc, argv); |
| 64 | + rclcpp::spin(std::make_shared<MinimalClient>()); |
| 65 | + rclcpp::shutdown(); |
| 66 | + return 0; |
| 67 | +} |
0 commit comments