【 声明:版权所有,欢迎转载,请勿用于商业用途。 联系信箱:feixiaoxing @163.com】
前面我们谈到了消息通信,但是这种通信是单向的。也就是一个人发送消息,一个人接收消息,仅此而已。在ros当中,还有一种通信,称之为服务通信。它和单项通信最大的区别就是,我们把数据发送给对方,还能得到对方的反馈结果。这在很多场合下都是非常适合的。

1、创建srv文件
和消息传递一样,服务通信也需要创建脚本文件。首先在package目录下面创建一个srv文件加,里面添加PassWord.srv文件,内容如下,
int64 password
---
bool result
内容是比较简单的。这个时候cd到workspace顶层,输入catkin_make,就可以生成对应的头文件,当然CMakeLists.txt也是需要修改的。
2、修改CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(beginner_tutorials)
## Find catkin and any catkin packages
find_package(catkin REQUIRED COMPONENTS message_generation roscpp rospy std_msgs genmsg)
add_message_files(FILES Student.msg)
add_service_files(FILES PassWord.srv)
## Generate added messages and services
generate_messages(DEPENDENCIES std_msgs)
## Declare a catkin package
catkin_package()
## Build talker and listener
include_directories(include ${catkin_INCLUDE_DIRS})
add_executable(talker src/talker.cpp)
target_link_libraries(talker ${catkin_LIBRARIES})
add_dependencies(talker beginner_tutorials_generate_messages_cpp)
add_executable(listener src/listener.cpp)
target_link_libraries(listener ${catkin_LIBRARIES})
add_dependencies(listener beginner_tutorials_generate_messages_cpp)
通过make编译以及查找,我们发现生成的.h文件都被放到了devel目录下了,
feixiaoxing@feixiaoxing-VirtualBox:~/Desktop/catkin_ws$ find . -name "*.h"
./devel/include/beginner_tutorials/PassWordResponse.h
./devel/include/beginner_tutorials/PassWordRequest.h
./devel/include/beginner_tutorials/Student.h
./devel/include/beginner_tutorials/PassWord.h
3、重写talker.cpp文件
#include "ros/ros.h"
#include "beginner_tutorials/PassWord.h"
#include <cstdlib>
using namespace std;
int main(int argc, char** argv)
{
ros::init(argc, argv, "node_client");
if(argc < 2)
{
cout << "Error param, please run eg: rosrun beginner_tutorials talker 123456" << endl;
return 1;
}
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<beginner_tutorials::PassWord>("pswserver", 100);
beginner_tutorials::PassWord srv;
srv.request.password = atoi(argv[1]);
if(client.call(srv))
{
ROS_INFO("client connect success!");
if(srv.response.result)
{
ROS_INFO("Welcom, correct password!");
}
else
{
ROS_INFO("Sorry, password error");
}
}
else
{
ROS_INFO("client connect fail");
}
return 0;
}
代码中唯一需要注意的就是client.call这个用法。
4、重写listener.cpp文件
#include "ros/ros.h"
#include "beginner_tutorials/PassWord.h"
bool serverCallback(beginner_tutorials::PassWord::Request& req,
beginner_tutorials::PassWord::Response& res)
{
res.result = (req.password == 123456) ? true :false;
return true;
}
int main(int argc, char* argv[])
{
ros::init(argc, argv, "server_node");
ros::NodeHandle nh;
ros::ServiceServer serv = nh.advertiseService("pswserver", &serverCallback);
ros::spin();
return 0;
}
这里的回调函数注意一下,也就是serverCallback的用法。
5、启动和测试
准备了节点之后就可以开始编译。编译的方法也比较简单,就是输入catkin_make。确认没有问题之后,就是启动roscore和source ~/devel/setup.sh。依次打开listener和talker,
rosrun beginner_tutorials listener
不出意外,打开talker之后,就可以看到这样的打印信息,
feixiaoxing@feixiaoxing-VirtualBox:~/Desktop/catkin_ws$ rosrun beginner_tutorials talker 123456
[ INFO] [1695354474.608237290]: client connect success!
[ INFO] [1695354474.608742554]: Welcom, correct password!