|
| 1 | +#include "agnocast_sample_interfaces/srv/sum_int_array.hpp" |
| 2 | +#include "rclcpp/rclcpp.hpp" |
| 3 | + |
| 4 | +#include <thread> |
| 5 | + |
| 6 | +using namespace std::chrono_literals; |
| 7 | + |
| 8 | +constexpr size_t ARRAY_SIZE = 100; |
| 9 | + |
| 10 | +int main(int argc, char * argv[]) |
| 11 | +{ |
| 12 | + rclcpp::init(argc, argv); |
| 13 | + |
| 14 | + auto node = rclcpp::Node::make_shared("ros_client"); |
| 15 | + std::thread spin_thread([node]() mutable { |
| 16 | + rclcpp::executors::SingleThreadedExecutor executor; |
| 17 | + executor.add_node(node); |
| 18 | + executor.spin(); |
| 19 | + }); |
| 20 | + |
| 21 | + auto client = node->create_client<agnocast_sample_interfaces::srv::SumIntArray>("sum_int_array"); |
| 22 | + |
| 23 | + while (!client->wait_for_service(1s)) { |
| 24 | + if (!rclcpp::ok()) { |
| 25 | + RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting."); |
| 26 | + return 0; |
| 27 | + } |
| 28 | + RCLCPP_INFO(node->get_logger(), "Service not available, waiting again..."); |
| 29 | + } |
| 30 | + |
| 31 | + auto request1 = |
| 32 | + std::make_shared<typename agnocast_sample_interfaces::srv::SumIntArray::Request>(); |
| 33 | + for (size_t i = 1; i <= ARRAY_SIZE; ++i) { |
| 34 | + request1->data.push_back(i); |
| 35 | + } |
| 36 | + client->async_send_request( |
| 37 | + std::move(request1), |
| 38 | + [node = node.get()]( |
| 39 | + rclcpp::Client<agnocast_sample_interfaces::srv::SumIntArray>::SharedFuture future) { |
| 40 | + RCLCPP_INFO(node->get_logger(), "Result1: %ld", future.get()->sum); |
| 41 | + }); |
| 42 | + |
| 43 | + auto request2 = |
| 44 | + std::make_shared<typename agnocast_sample_interfaces::srv::SumIntArray::Request>(); |
| 45 | + for (size_t i = 0; i < ARRAY_SIZE; ++i) { |
| 46 | + request2->data.push_back(i); |
| 47 | + } |
| 48 | + auto future = client->async_send_request(std::move(request2)); |
| 49 | + RCLCPP_INFO(node->get_logger(), "Result2: %ld", future.get()->sum); |
| 50 | + |
| 51 | + spin_thread.join(); |
| 52 | + rclcpp::shutdown(); |
| 53 | + return 0; |
| 54 | +} |
0 commit comments