目录
1. 定义srv文件
服务通信中,数据分成两部分,请求与响应,在 srv 文件中请求和响应使用---
分割。
在功能包下创建srv目录,添加ServiceMsg.srv文件,具体实现如下:
string name
---
bool on_the_list
bool good_guy
int32 age
string nickname
2.编辑配置文件
package.xml中添加编译依赖与执行依赖
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
<!--
exce_depend 以前对应的是 run_depend 现在非法
-->
CMakeLists.txt编辑 srv 相关配置
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
# 需要加入 message_generation,必须有 std_msgs
add_service_files(
FILES
ServiceMsg.srv
)
generate_messages(
DEPENDENCIES
std_msgs
)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES example_ros_service
CATKIN_DEPENDS roscpp std_msgs
# DEPENDS system_lib
)
3.编译
编译后的中间文件查看:
C++ 需要调用的中间文件(…/工作空间/devel/include/包名/xxx.h)
4.使用
(1) 服务端代码 example_ros_service.cpp
#include "ros/ros.h"
#include "example_ros_service/ServiceMsg.h"
#include "iostream"
#include "string.h"
bool callBack( example_ros_service::ServiceMsg::Request &req, example_ros_service::ServiceMsg::Response &res){
ROS_INFO("callBack activated");
std::string in_name(req.name);
res.on_the_list = false;
if (in_name.compare("hao"))
{
ROS_INFO("ask about hao");
res.age = 24;
res.good_guy = true;
res.nickname = "shahao";
res.on_the_list = true;
}
if (in_name.compare("kai"))
{
ROS_INFO("ask about kai");
res.age = 24;
res.good_guy = false;
res.nickname = "peizhu";
res.on_the_list = true;
}
return true;
}
int main(int argc, char *argv[])
{
ros::init(argc, argv, "example_ros_service");
ros::NodeHandle nh;
ros::ServiceServer service = nh.advertiseService("lookup_by_name",callBack);
ROS_INFO("ready to look up names.");
ros::spin();
/* code */
return 0;
}
(2) CMakeists.txt配置文件并编译执行
add_executable(example_ros_service src/example_ros_service.cpp)
add_dependencies(example_ros_service ${PROJECT_NAME}_gencpp)
target_link_libraries(example_ros_service
${catkin_LIBRARIES}
)
roscore #启动核心
###
source ./devel/setup.bash
rosrun example_ros_service example_ros_service #启动节点
(3) 客户端的指令
rosservice call /look_by_name 'hao'
(4) 客户端响应结果
或编写客户端代码
example_ros_client.cpp 的代码如下:
#include "ros/ros.h"
#include "string.h"
#include "example_ros_service/ServiceMsg.h"
int main(int argc, char *argv[])
{
ros::init(argc, argv, "example_ros_client");
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<example_ros_service::ServiceMsg>("lookup_by_name");
example_ros_service::ServiceMsg srv;
std::string in_name;
//循环发起请求
while (ros::ok())
{
std::cout << std::endl << "enter a name(x to quit)" << std::endl;
std::cin >> in_name;
if(in_name.compare("x") == 0){
return 0;
}
srv.request.name = in_name;
if (client.call(srv)){
if (srv.response.on_the_list){
std::cout << srv.request.name << "is known as " << srv.response.nickname << std::endl;
std::cout << "he is " << srv.response.age << "years old" << std::endl;
if (srv.response.good_guy){
std::cout << "he is reported to be a good guy" << std::endl;
}else{
std::cout << "avoid him : he is not a good guy" << std::endl;
}
}else{
std::cout << srv.request.name << "is not in my database" << std::endl;
}
}else{
ROS_INFO("failed to call service lookup_bu_name");
return 1;
}
}
return 0;
}