切换至~/catkin_ws/src/learning_server功能包目录下,然后新建一个文件夹,命名为srv,用来存放自定义的服务消息。
切换至srv目录下,新建一个空白的srv文件,以srv为后缀表示代表是srv文件。这里我们以IntPlus.srv为例子说明下,把以下代码复制到刚刚创建好的srv文件里边。
xuint8 a
uint8 b
---
uint8 result
这里说明下srv文件的构成,由符号---分为上下两个部分,上边表示request下边是response。
xxxxxxxxxx
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
xxxxxxxxxx
在find_package里边加上message_generation
add_service_files(FILES IntPlus.srv)
generate_messages(DEPENDENCIES std_msgs)
xxxxxxxxxx
cd ~/catkin_ws
catkin_make
1)、切换至~/catkin_ws/src/learning_server/src下,新建两个cpp文件,命名为IntPlus_server.cpp和IntPlus_client.cpp,把以下代码分别复制到里边,
IntPlus_server.cpp
xxxxxxxxxx
/**
* 该例程将执行/Two_Int_Plus服务,服务数据类型learning_service::IntPlus
*/
// service回调函数,输入参数req,输出参数res
bool IntPlusCallback(learning_server::IntPlus::Request &req,
learning_server::IntPlus::Response &res)
{
ROS_INFO("number 1 is:%d ,number 2 is:%d ", req.a, req.b);// 显示请求数据
res.result = req.a + req.b ;// 反馈结果为两数之和
return res.result;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "IntPlus_server"); // ROS节点初始化
ros::NodeHandle n;// 创建节点句柄
// 创建一个server,注册回调函数IntPlusCallback
ros::ServiceServer Int_Plus_service = n.advertiseService("/Two_Int_Plus", IntPlusCallback);
// 循环等待回调函数
ROS_INFO("Ready to caculate.");
ros::spin();
return 0;
}
IntPlus_client.cpp
xxxxxxxxxx
/*
该例程将请求/Two_Int_Plus服务,服务数据类型learning_service::IntPlus
两个整型数相加求和
*/
using namespace std;
int main(int argc, char** argv)
{
int i,k;
cin>>i;
cin>>k;
ros::init(argc, argv, "IntPlus_client");// 初始化ROS节点
ros::NodeHandle node;// 创建节点句柄
// 发现/Two_Int_Plus服务后,创建一个服务客户端
ros::service::waitForService("/Two_Int_Plus");
ros::ServiceClient IntPlus_client = node.serviceClient<learning_server::IntPlus>("/Two_Int_Plus");
// 初始化learning_service::IntPlus的请求数据
learning_server::IntPlus srv;
srv.request.a = i;
srv.request.b = k;
ROS_INFO("Call service to plus %d and %d", srv.request.a, srv.request.b);// 请求服务调用
IntPlus_client.call(srv);
// 显示服务调用结果
ROS_INFO("Show the result : %d", srv.response.result);// 显示服务调用结果
return 0;
}
2)、修改CMakeLists.txt文件
xxxxxxxxxx
add_executable(IntPlus_server src/IntPlus_server.cpp)
target_link_libraries(IntPlus_server ${catkin_LIBRARIES})
add_dependencies(IntPlus_server ${PROJECT_NAME}_generate_messages_cpp)
add_executable(IntPlus_client src/IntPlus_client.cpp)
target_link_libraries(IntPlus_client ${catkin_LIBRARIES})
add_dependencies(IntPlus_client ${PROJECT_NAME}_generate_messages_cpp)
3)、核心部分
这里的实现流程和之前的一样,主要不一样的就是引入头文件和使用自定义服务文件:
引入头文件是
xxxxxxxxxx
前边learning_server是功能包名字,后边的IntPlus.h是刚才创建的srv文件产生的头文件名字
使用自定义服务文件是
xxxxxxxxxx
client:
learning_server::IntPlus srv;
srv.request.a = i;
srv.request.b = k;
ros::ServiceClient IntPlus_client = node.serviceClient<learning_server::IntPlus>("/Two_Int_Plus");
IntPlus_client.call(srv);
server:
ros::ServiceServer Int_Plus_service = n.advertiseService("/Two_Int_Plus", IntPlusCallback);
bool IntPlusCallback(learning_server::IntPlus::Request &req,
learning_server::IntPlus::Response &res)
4)、运行程序
xxxxxxxxxx
roscore
rosrun learning_server IntPlus_client
rosrun learning_server IntPlus_server
5)、运行截图
6)、程序说明
运行IntPlus_server后,会提示准备计算;运行IntPlus_client后,终端输入两个整型数字,接着IntPlus_server会计算出结果,并且返回回去给IntPlus_client,随后打印出结果。
1)、切换至~/catkin_ws/src/learning_server/script下,新建两个py文件,命名为IntPlus_server.py和IntPlus_client.py,把以下代码分别复制到里边,
IntPlus_server.py
xxxxxxxxxx
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
from learning_server.srv import IntPlus, IntPlusResponse
def IntPlusCallback(req):
rospy.loginfo("Ints: a:%d b:%d", req.a, req.b)# 显示请求数据
return IntPlusResponse(req.a+req.b)# 反馈数据
def IntPlus_server():
rospy.init_node('IntPlus_server')# ROS节点初始化
# 创建一个server,注册回调函数IntPlusCallback
s = rospy.Service('/Two_Int_Plus', IntPlus, IntPlusCallback)
print "Ready to caculate two ints."# 循环等待回调函数
rospy.spin()
if __name__ == "__main__":
IntPlus_server()
IntPlus_client.py
xxxxxxxxxx
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import sys
import rospy
from learning_server.srv import IntPlus, IntPlusRequest
def Plus_client():
# ROS节点初始化
rospy.init_node('IntPlus_client')
rospy.wait_for_service('/Two_Int_Plus')
try:
Plus_client = rospy.ServiceProxy('/Two_Int_Plus', IntPlus)
response = Plus_client(22, 20)# 请求服务调用,输入请求数据
return response.result
except rospy.ServiceException, e:
print "failed to call service : %s"%e
if __name__ == "__main__":
#服务调用并显示调用结果
print "Show two_int_plus result : %s" %(Plus_client())
2)、核心部分
这里主要是说明下如何导入自定义的服务消息模块和使用:
导入
xxxxxxxxxx
server:
from learning_server.srv import IntPlus, IntPlusResponse
client:
from learning_server.srv import IntPlus, IntPlusRequest
使用
xxxxxxxxxx
server:
s = rospy.Service('/Two_Int_Plus', IntPlus, IntPlusCallback)
return IntPlusResponse(req.a+req.b)# 反馈数据
client:
response = Plus_client(12, 20)# 请求服务调用,输入请求数据
return response.result
3)、运行程序
运行程序前,先给py文件增加可执行权限
xxxxxxxxxx
sudo chmod a+x IntPlus_server.py
sudo chmod a+x IntPlus_client.py
运行程序
xxxxxxxxxx
roscore
rosrun learning_server IntPlus_client.py
rosrun learning_server IntPlus_server.py
4)、程序运行说明
这里与C++版本不一致的是,这里的加数是程序里边设定(12和20)的,因此开启服务后,就立即能够返回结果。