|
| 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 <cinttypes> |
| 16 | +#include <functional> |
| 17 | +#include <memory> |
| 18 | + |
| 19 | +#include "example_interfaces/srv/add_two_ints.hpp" |
| 20 | +#include "rclcpp/rclcpp.hpp" |
| 21 | + |
| 22 | +using example_interfaces::srv::AddTwoInts; |
| 23 | + |
| 24 | +/* This example creates a subclass of Node and uses a fancy C++11 lambda |
| 25 | + * function to shorten the callback syntax, at the expense of making the |
| 26 | + * code somewhat more difficult to understand at first glance. */ |
| 27 | + |
| 28 | +class MinimalService : public rclcpp::Node |
| 29 | +{ |
| 30 | +public: |
| 31 | + MinimalService() |
| 32 | + : Node("minimal_service") |
| 33 | + { |
| 34 | + server_ = this->create_service<AddTwoInts>( |
| 35 | + "add_two_ints", |
| 36 | + [this](const AddTwoInts::Request::SharedPtr request, |
| 37 | + AddTwoInts::Response::SharedPtr response) { |
| 38 | + RCLCPP_INFO( |
| 39 | + this->get_logger(), |
| 40 | + "request: %" PRId64 " + %" PRId64, request->a, request->b); |
| 41 | + response->sum = request->a + request->b; |
| 42 | + }); |
| 43 | + } |
| 44 | + |
| 45 | +private: |
| 46 | + rclcpp::Service<AddTwoInts>::SharedPtr server_; |
| 47 | +}; |
| 48 | + |
| 49 | +int main(int argc, char * argv[]) |
| 50 | +{ |
| 51 | + rclcpp::init(argc, argv); |
| 52 | + rclcpp::spin(std::make_shared<MinimalService>()); |
| 53 | + rclcpp::shutdown(); |
| 54 | + return 0; |
| 55 | +} |
0 commit comments