Note: This tutorial assumes that you have completed the previous tutorials: examining the simple publisher and subscriber.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Criando um Nó de Serviço-Cliente simples (C++)

Description: Neste tutorial é ensinado como escrever um Nó (node) de Serviço-Cliente em C++.

Tutorial Level: BEGINNER

Next Tutorial: Examining the simple service and client

Fazendo um Nó de Serviço (service)

Criaremos um Nó de serviço ("add_two_ints_server") que irá receber dois números inteiros (ints) e retornaremos a soma destes.

Change directory into the beginner_tutorials package, you created previously in the creating a rosbuild package tutorial:

roscd beginner_tutorials

Mude o seu diretório atual para o pacote beginner_tutorials que você criou dentro do seu catkin workspace nos tutoriais prévios:

roscd beginner_tutorials

Certifique-se que você seguiu as etapas corretas no tutorial anterior de como criar um serviço, creating the AddTwoInts.srv (tenha certeza de escolher a versão correta da ferramenta de construção (build) que você está usando, o mesmo pode ser consultado no link do topo da pagina wiki).

O Código

Crie o arquivo add_two_ints_server.cpp dentro da pasta /src dentro do pacote beginner_tutorials e cole o seguinte codigo dentro do arquivo .cpp:

   1 #include "ros/ros.h"
   2 #include "beginner_tutorials/AddTwoInts.h"
   3 
   4 bool add(beginner_tutorials::AddTwoInts::Request  &req,
   5          beginner_tutorials::AddTwoInts::Response &res)
   6 {
   7   res.sum = req.a + req.b;
   8   ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
   9   ROS_INFO("sending back response: [%ld]", (long int)res.sum);
  10   return true;
  11 }
  12 
  13 int main(int argc, char **argv)
  14 {
  15   ros::init(argc, argv, "add_two_ints_server");
  16   ros::NodeHandle n;
  17 
  18   ros::ServiceServer service = n.advertiseService("add_two_ints", add);
  19   ROS_INFO("Ready to add two ints.");
  20   ros::spin();
  21 
  22   return 0;
  23 }

O Código Explicado

Agora vamos entender o código!

   1 #include "ros/ros.h"
   2 #include "beginner_tutorials/AddTwoInts.h"
   3 

beginner_tutorials/AddTwoInts.h é o arquivo header gerado pelo arquivo .srv que haviamos criados anteriormente.

   4 bool add(beginner_tutorials::AddTwoInts::Request  &req,
   5          beginner_tutorials::AddTwoInts::Response &res)

Essa função provê o serviço para adicionar dois inteiros (ints), ele recebe uma requisição (do cliente) e responde (Response) com o tipo definido no arquivo .srv e retorna um booleano.

   6 {
   7   res.sum = req.a + req.b;
   8   ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
   9   ROS_INFO("sending back response: [%ld]", (long int)res.sum);
  10   return true;
  11 }

Aqui os dois inteiros são adicionados e guardados na resposta (Response). Então algumas informações sobre a requisição (request) são guardadas, por último o serviço retorna verdadeiro quando este é completado.

  18   ros::ServiceServer service = n.advertiseService("add_two_ints", add);

Aqui o serviço é criado e passado/avisado pelo ROS.

Escrevendo o Nó do Cliente

O Código

Crie o arquivo add_two_ints_client.cpp dentro da pasta /src dentro do pacote beginner_tutorials e cole o seguinte codigo dentro do arquivo .cpp:

   1 #include "ros/ros.h"
   2 #include "beginner_tutorials/AddTwoInts.h"
   3 #include <cstdlib>
   4 
   5 int main(int argc, char **argv)
   6 {
   7   ros::init(argc, argv, "add_two_ints_client");
   8   if (argc != 3)
   9   {
  10     ROS_INFO("usage: add_two_ints_client X Y");
  11     return 1;
  12   }
  13 
  14   ros::NodeHandle n;
  15   ros::ServiceClient client = n.serviceClient<beginner_tutorials::AddTwoInts>("add_two_ints");
  16   beginner_tutorials::AddTwoInts srv;
  17   srv.request.a = atoll(argv[1]);
  18   srv.request.b = atoll(argv[2]);
  19   if (client.call(srv))
  20   {
  21     ROS_INFO("Sum: %ld", (long int)srv.response.sum);
  22   }
  23   else
  24   {
  25     ROS_ERROR("Failed to call service add_two_ints");
  26     return 1;
  27   }
  28 
  29   return 0;
  30 }

O Código Explicado

Agora vamos entender o código!

  15   ros::ServiceClient client = n.serviceClient<beginner_tutorials::AddTwoInts>("add_two_ints");

Aqui criamos o cliente para o serviço add_two_ints. O objeto ros::ServiceClient é usado para chamar o serviço posteriormente.

  16   beginner_tutorials::AddTwoInts srv;
  17   srv.request.a = atoll(argv[1]);
  18   srv.request.b = atoll(argv[2]);

Aqui instanciamos uma classe de serviço autogerada e assinalamos valores para seu membro de requisição (request). Qualquer classe de serviço (service class) contém dois membros: request e response, também contém duas definições de classe: Response e Request.

  19   if (client.call(srv))

Aqui é onde de fato chamamos o serviço. Como as chamadas (calls) do serviço são bloqueadas, ele retornará uma única vez quando a chamada for feita . Se a chamada do serviço for sucedida, a função call() retornará verdadeiro e o valor em srv.response será válido. Se a chamada não for bem sucedida, call() retornará falso e o valor dentro da resposta (response) de srv.response será inválido.

Dando build nos seus Nós

Novamente edite o CMakeLists.txt do seu pacote beginner_tutorials:

$ rosed beginner_tutorials CMakeLists.txt 

e adicione o seguinte no final do arquivo:

rosbuild_add_executable(add_two_ints_server src/add_two_ints_server.cpp)
rosbuild_add_executable(add_two_ints_client src/add_two_ints_client.cpp)

Isso irá criar dois executáveis, "add_two_ints_server" e "add_two_ints_client", que irão por padrão para o diretório "bin".

Para mais informações de como usar CMake com ROS, veja CMakeLists Agora execute o comando make:

$ make

Compilando seus Nós

De novo, edite o arquivo CMakeLists.txt no seu pacote beginner_tutorials localizado em ~/catkin_ws/src/beginner_tutorials/CMakeLists.txt e adicione o seguinte pedaço de código ao final do arquivo:

https://raw.github.com/ros/catkin_tutorials/master/create_package_srvclient/catkin_ws/src/beginner_tutorials/CMakeLists.txt

  27 add_executable(add_two_ints_server src/add_two_ints_server.cpp)
  28 target_link_libraries(add_two_ints_server ${catkin_LIBRARIES})
  29 add_dependencies(add_two_ints_server beginner_tutorials_gencpp)
  30 
  31 add_executable(add_two_ints_client src/add_two_ints_client.cpp)
  32 target_link_libraries(add_two_ints_client ${catkin_LIBRARIES})
  33 add_dependencies(add_two_ints_client beginner_tutorials_gencpp)

Isto irá criar dois executáveis add_two_ints_server e add_two_ints_client, que irão por padrão no diretório do seu pacote do catkin workspace:devel space, localizado de forma padronizada em ~/catkin_ws/devel/lib/<nome do pacote>. Você pode inicializar executáveis diretamente no terminal indo até sua localização ou pode usar o comando rosrun para iniciá-los. Eles não são colocados no '<prefix>/bin' pois isto poluiria o PATH quando você fosse instalar o seu pacote no sistema. Se você quiser que seu executável esteja no PATH na hora da instalação, você pode determinar um alvo (target) na configuração de instalação, veja: catkin/CMakeLists.txt

Para uma descrição mais detalhada do arquivo CMakeLists.txt veja: catkin/CMakeLists.txt

Agora rode catkin_make:

# In your catkin workspace
cd ~/catkin_ws
catkin_make

Se o seu build falhar por alguma razão:

  • type rosls beginner_tutorials/srv_gen/cpp/include/beginner_tutorials/ and check that the .h file matches the include in the client and server .cpp files.

Rodando os Nós

Para rodar os Nós necessita-se que você tenha o ROS core inicializado. Abra um novo terminal e digite:

roscore

Se tudo ocorrer bem, você deve ter uma saída resultante do comando como essa abaixo:

... logging to /u/takayama/.ros/logs/83871c9c-934b-11de-a451-
001d927076eb/roslaunch-ads-31831.log
... loading XML file 
[/wg/stor1a/rosbuild/shared_installation/ros/tools/roslaunch/roscore.xml]
Added core node of type [rosout/rosout] in namespace [/]
started roslaunch server http://ads:54367/

SUMMARY
======

NODES

changing ROS_MASTER_URI to [http://ads:11311/] for starting master locally
starting new master (master configured for auto start)
process[master]: started with pid [31874]
ROS_MASTER_URI=http://ads:11311/
setting /run_id to 83871c9c-934b-11de-a451-001d927076eb
+PARAM [/run_id] by /roslaunch
+PARAM [/roslaunch/uris/ads:54367] by /roslaunch
process[rosout-1]: started with pid [31889]
started core service [/rosout]
+SUB [/time] /rosout http://ads:33744/
+SERVICE [/rosout/get_loggers] /rosout http://ads:33744/
+SERVICE [/rosout/set_logger_level] /rosout http://ads:33744/
+PUB [/rosout_agg] /rosout http://ads:33744/
+SUB [/rosout] /rosout http://ads:33744/

Agora está tudo pronto para rodarmos o servidor e o cliente.

Rodando o Servidor

Começe rodando o servidor, abra um novo terminal e digite:

rosrun beginner_tutorials add_two_ints_server

Você deve ver algo similar como:

Ready to add two ints.

Rodando o Cliente

Agora vamos rodar o cliente com os argumentos necessários, em outro terminal (shell)

$ rosrun beginner_tutorials add_two_ints_client 1 3

No shell do cliente você deve ver algo como:

Sum: 4

Já no shell do servidor você deve ver algo como:

request: x=1, y=3
sending back response: [4]

Agora que você escreveu um Serviço-Cliente simples, vamos para examine the simple service and client.

Wiki: pt_BR/ROS/Tutorials/WritingServiceClient(c++) (last edited 2020-04-19 01:10:05 by henriquePoleselo)