文章目录
创建一个server
创建一个Client
编译功能包
运行Server和Client
ROS环境下上位机与Arduino通信
服务(Service)是节点之间同步通信的一种方式,允许客户端(Client)节点发布请求(Request),由服务端(Server)节点处理后反馈应答(Response)。

关于功能包我给大家整理好了,下载地址
大家把功能包放在工作空间的src目录下就可以了

创建一个server
首先创建Server节点,提供加法运算的功能,返回求和之后的结果。实现该节点的源码文件learning_communication/src/server.cpp内容如下:

#include "ros/ros.h"
//使用ROS中的服务,必须包含服务数据类型的头文件,这里使用的头文件是learning_communication/AddTwoInts.h,该头文件根据我们之前创建的服务数据类型的描述文件AddTwoInts.srv自动生成。
#include "learning_communication/AddTwoInts.h"
// service回调函数,输入参数req,输出参数res
bool add(learning_communication::AddTwoInts::Request &req,
learning_communication::AddTwoInts::Response &res)
{
// 将输入参数中的请求数据相加,结果放到应答变量中
res.sum = req.a + req.b;
ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
ROS_INFO("sending back response: [%ld]", (long int)res.sum);
return true;
}
int main(int argc, char **argv)
{
// ROS节点初始化
ros::init(argc, argv, "add_two_ints_server");
// 创建节点句柄
ros::NodeHandle n;
// 创建一个名为add_two_ints的server,注册回调函数add()
ros::ServiceServer service = n.advertiseService("add_two_ints", add);
// 循环等待回调函数
ROS_INFO("Ready to add two ints.");
ros::spin();
return 0;
}

这个代码可以分为下面几个部分:
1.头文件部分

#include "ros/ros.h"
#include "learning-communication/AddTwoInts.h"

使用ROS中的服务,必须包含服务数据类型的头文件,这里使用的头文件是learning_communication/AddTwoInts.h,该头文件根据我们之前创建的服务数据类型的描述文件AddTwoInts.srv自动生成。
2.主函数部分

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

主函数部分相对简单,先初始化节点,创建节点句柄,重点是要创建一个服务的Server,指定服务的名称以及接收到服务数据后的回调函数。然后开始循环等待服务请求;一旦有服务请求,Server就跳入回调函数进行处理。
3.回调函数部分

bool add(learning_communication::AddTwoInts::Request &req,learning_communication::AddTwoInts::Response &res)

回调函数是真正实现服务功能的部分,也是设计的重点。add()函数用于完成两个变量相加的功能,其传入参数便是我们在服务数据类型描述文件中声明的请求与应答的数据结构。

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

在完成加法运算后,求和结果会放到应答数据中,反馈到Client,回调函数返回true。

整个过程可总结为:
初始化ROS节点→创建Server实例→循环等待服务请求,进入回调函数→在回调函数中完成服务功能的处理并反馈应答数据

创建一个Client
创建Client节点,通过终端输入的两个加数发布服务请求,等待应答结果。该节点实现代码learning_communication/src/client.cpp的内容如下:

#include <cstdlib>
#include "ros/ros.h"
#include "learning_communication/AddTwoInts.h"
int main(int argc, char **argv)
{
// ROS节点初始化
ros::init(argc, argv, "add_two_ints_client");
// 从终端命令行获取两个加数
if (argc != 3)
{
ROS_INFO("usage: add_two_ints_client X Y");
return 1;
}
// 创建节点句柄
ros::NodeHandle n;
// 创建一个client,请求add_two_int service
// service消息类型是learning_communication::AddTwoInts
ros::ServiceClient client = n.serviceClient<learning_communication::AddTwoInts> ("add_two_ints");
// 创建learning_communication::AddTwoInts类型的service消息
learning_communication::AddTwoInts srv;
srv.request.a = atoll(argv[1]);
srv.request.b = atoll(argv[2]);
// 发布service请求,等待加法运算的应答结果
if (client.call(srv))
{
ROS_INFO("Sum: %ld", (long int)srv.response.sum);
}
else
{
ROS_ERROR("Failed to call service add_two_ints");
return 1;
}
return 0;
}

这个代码可以分为下面几个部分:
1.创建Client

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

首先需要创建一个add_two_ints的Client实例,指定服务类型为learning_communication:AddTwoInts。
2.发布服务请求

learning_communication::AddTwoInts srv;
srv.request.a = atoll(argv[1]);
srv.request.b = atoll(argv[2]);

然后实例化一个服务数据类型的变量,该变量包含两个成员:request和response。将节点运行时输入的两个参数作为需要相加的两个整型数存储到变量中。

if (client.call(srv))

接着进行服务调用。该调用过程会发生阻塞,调用成功后返回true,访问srv.reponse即可获取服务请求的结果。如果调用失败会返回false,srv.reponse则不可使用。
服务中的Client类似于话题中的Publisher,整个过程可总结为:
初始化ROS节点→创建一个Client实例→发布服务请求数据→等待Server处理之后的应答结果

编译功能包
代码已经编写完成,接下来编辑CMakeLists.txt文件,加入如下编译规则,与编译Publisher和Subscriber时的配置类似:

add_executable(server src/server.cpp)
target_link_libraries(server ${catkin_LIBRARIES})
add_dependencies(server ${PROJECT_NAME}_gencpp)
add_executable(client src/client.cpp)
target_link_libraries(client ${catkin_LIBRARIES})
add_dependencies(client ${PROJECT_NAME}_gencpp)

现在就可以使用catkin_make命令编译功能包了。

运行Server和Client
再强调一下,别忘了环境变量的设置

1.启动roscore
在运行节点之前,首先需要确保ROS Master已经成功启动:

$ roscore
2.运行Server节点
打开终端,使用如下命令运行Server节点:

$ rosrun learning_communication server
如果运行正常,终端中应该会显示如图所示的信息。

3.运行Client节点
打开一个新的终端,运行Client节点,同时需要输入加法运算的两个加数值:

$ rosrun learning_communication client 3 5
Client发布服务请求,Server完成服务功能后反馈结果给Client。在Server和Client的终端中分别可以看到如图所示的日志信息。

功能包里还放置了一个洗盘子的例程,有兴趣可以看一下

ROS环境下上位机与Arduino通信

环境配置清点
准备工作和话题的订阅发布

Arduino服务端的搭建
下面给大家看一下示例程序,解读类似

/*
 * rosserial Service Server
 */

#include <ros.h>
#include <std_msgs/String.h>
#include <rosserial_arduino/Test.h>

ros::NodeHandle  nh;
using rosserial_arduino::Test;

int i;
void callback(const Test::Request & req, Test::Response & res){
  if((i++)%2)
    res.output = "hello";
  else
    res.output = "world";
}//回调函数,返回值为“hello world”

ros::ServiceServer<Test::Request, Test::Response> server("test_srv",&callback);//服务器对象声明,后面两个参数,一个是服务器名称,另一个是收到客户端内容后所调用的函数。对应的类型分别是Test::Request和TestResponse

std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);

char hello[13] = "hello world!";

void setup()
{
  nh.initNode();
  nh.advertiseService(server);//在setup函数中需要对服务器进行绑定。
  nh.advertise(chatter);
}

void loop()
{
  str_msg.data = hello;
  chatter.publish( &str_msg );
  nh.spinOnce();
  delay(10);
}

测试:
此程序完成的操作是服务器接受到指令后实现返回给客户段hello与word交替返回。
新终端分别打开运行

roscore
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
rosservice call test_srv ""

Arduino客户端的搭建
下面给大家看一下示例程序,解读类似

/*
 * rosserial Service Client
 */

#include <ros.h>
#include <std_msgs/String.h>
#include <rosserial_arduino/Test.h>

ros::NodeHandle  nh;
using rosserial_arduino::Test;

ros::ServiceClient<Test::Request, Test::Response> client("test_srv");//客户端对象声明    client是客户端的名称,“test_srv”是它所链接的服务器名称
std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);

char hello[13] = "hello world!";

void setup()
{
  nh.initNode();
  nh.serviceClient(client);//节点句柄绑定客户端。
  nh.advertise(chatter);
  while(!nh.connected()) nh.spinOnce();
  nh.loginfo("Startup complete");
}

void loop()
{
  Test::Request req;
  Test::Response res;
  req.input = hello;
  client.call(req, res);
  str_msg.data = res.output;
  chatter.publish( &str_msg );
  nh.spinOnce();
  delay(100);
}

测试:
新终端分别打开运行:

roscore
    rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
      rosservice call test_srv ""