使用ROS Service(二) 代码演示

程序演示

下面是我写的一个服务程序,服务文件ctrl.srv的构成为:

1
2
3
int8 cmd
---
bool ret

客户端发出命令,如果cmd!=0,服务端会打开摄像头程序;如果cmd=0,服务端会关闭摄像头程序。

注意:最好是将所有自定义的服务和消息文件放到一个单独的package里面,否则会出现一个package的修改会影响到另一个用到它的消息/服务的package的编译.

新建srv文件后,容易忘记在CMakeLists里添加这个文件,导致编译失败

服务端

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
#include <ros/ros.h>
#include <riki_msgs/ctrl.h>

bool control(riki_msgs::ctrl::Request &req, riki_msgs::ctrl::Response &res)
{
if(req.cmd==0)
{
ROS_INFO("shutting down camera");
system("rosnode kill /usb_cam");
ROS_INFO("close camera done");
res.ret = 0;
}
else
{
ROS_INFO("starting camera");
system("roslaunch usb_cam usb_cam.launch & ");
ROS_INFO("camera is up");
res.ret = 1;
}
}

int main(int argc, char** argv)
{
ros::init(argc,argv,"camServer");
ros::NodeHandle nh;
ros::ServiceServer server = nh.advertiseService("control_cam",control);
ROS_INFO("------ waiting for client's request ------");
ros::spin();
return 0;
}

可以看出服务端的程序与话题中的订阅者程序高度相似,control函数就是个回调函数。

system函数调用roslaunch时,由于是在fork出的子进程里执行,launch的节点会一直阻塞不返回,在命令最后加&,让子进程返回

service回调函数里只能return truefalse,若return整数会导致客户端的call结果为false,但实际成功,这样会影响判断。

service客户端发命令后,出现报错 ERROR: service [/service_name] responded with an error: b’’ ,原因在于service服务端的回调函数必须 return true


advertiseService的部分源码

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
bool ServiceManager::advertiseService(const AdvertiseServiceOptions& ops)
{
boost::recursive_mutex::scoped_lock shutdown_lock(shutting_down_mutex_);
if (shutting_down_)
{
return false;
}
{
boost::mutex::scoped_lock lock(service_publications_mutex_);
// 如果service已经发布,就报错,然后返回,其实这里改成报警比较合适
if (isServiceAdvertised(ops.service))
{
ROS_ERROR("Tried to advertise a service that is already advertised in this node [%s]", ops.service.c_str());
return false;
}

如果涉及到耗时的工作,回调函数应该这样写

1
2
3
4
5
6
bool serviceCB(mow_msgs::task::Request &req, mow_msgs::task::Response &res)
{
// ......
res.ret = "to charge";
// 耗时的工作
}

如果把耗时的工作放在res之前,那么客户端提前退出时(比如ctrl+C),会报错没有收到返回值,虽然不影响,但是不优雅。

客户端

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
#include <ros/ros.h>
#include <riki_msgs/ctrl.h>

int main(int argc, char** argv)
{
ros::init(argc, argv, "controlCam");
if(argc!=2)
{
ROS_INFO("client need command");
return 1;
}
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<riki_msgs::ctrl>("control_cam");
riki_msgs::ctrl srv;
srv.request.cmd = atoi(argv[1]);
if(client.exists())
{
ROS_INFO("service control_cam is up");
ROS_INFO("service name:%s",client.getService().c_str());
}
else
{
ROS_ERROR("service control_cam is not available");
return 1;
}
if(client.call(srv))
{
ROS_INFO("client calling srv !");
if(srv.request.cmd>0)
ROS_INFO("Sending command start!");
else
ROS_INFO("Sending command stop!");
}
else
{
ROS_ERROR("client calls srv failed !");
return 1;
}
// 调用成功以后才能获取response
cout<<"服务端的返回值: "<<srv.response.ret<<endl;
return 0;
}

构建client的时候后面的路径要写绝对路径,有时候需要加个 /

客户端的程序与话题发布者的程序高度相似,exists()检查服务端的服务是否启动,若未启动则返回。call调用了服务,成功会返回true而且调用完成后,可以在客户端程序里获得服务端的返回值

最后,先运行服务端,然后运行客户端,如果是rosrun control_cam controlCam 1则在服务端所在终端启动摄像头程序,若是0则关闭。

另一种使用方式

1
2
3
4
5
6
7
8
9
std_srvs::Empty srv;
ros::service::call("/move_base_node/clear_costmaps", srv);

while(!ros::service::call("static_map", req, resp))
{
ROS_WARN("Request for map failed; trying again...");
ros::Duration d(0.5);
d.sleep();
}

常用函数

ros::ServiceClient常用函数:

1
2
3
4
5
6
7
8
9
bool call (Service &service)  //调用service,client发起通信。成功返回true

bool exists () //检查相应名称的服务是否可用

std::string getService () //返回客户端通信的服务名称
// 单例模式
static const ServiceManagerPtr & instance ()

bool unadvertiseService (const std::string &serv_name)

如果要解除service,用法是ros::ServiceManager::instance()::unadvertiseService,也就是使用单例模式进行全局访问。 API说isServiceAdvertised可以判断某service是否发布,但可惜是private

问题


切换算法时,会有个报警 Tried to advertise a service that is already advertised in this node。这个其实无任何影响,报警在ROS底层的源码,原因在于GlobalPlanner::initialize函数有一句:

1
make_plan_srv_ = private_nh.advertiseService("make_plan", &GlobalPlanner::makePlanService, this);

这里是已经注册了service,如果想要去掉这个报警,可以这样改:
1
2
3
4
std::string makePlanServiceName = "/move_base/"+name+"/make_plan";

ros::ServiceManager::instance()->unadvertiseService(makePlanServiceName);
make_plan_srv_ = private_nh.advertiseService("make_plan", &GlobalPlanner::makePlanService, this);

其中的bool ros::ServiceManager::unadvertiseService(const std::string& serv_name)作用是 Unadvertise a service. This call unadvertises a service, which must have been previously advertised, using advertiseService().

md5不匹配

调用service时报错md5不匹配,其实是调用失败了,call的返回值是false,首先应检查客户端定义是否正确和服务是否存在:

客户端一直阻塞

我在move_base.cpp里写了一个函数 func,是rosservice的客户端,调用service clear_costmaps。在MoveBase的其他函数里,调用这个函数,结果发现会一直阻塞。后来注意到服务端程序就是MoveBase::clearCostmapsService,也就是在同一个类里

客户端call service阻塞的原因只有两个:

  1. 多个客户端call 同一个service,而服务端一次只能处理一个请求
  2. 服务端程序没有return值

服务端程序是MoveBase的,而且有了返回值,那么只可能是第一个原因了。

参考:blocking service callbacks