ros服务通信的原理类似于RPC,其实现原理如下图所示
实验目标
- 创建一个客户端和一个服务端
- 客户端向服务端发送两个参数num1和num2
- 服务端接收到客户端的两个参数num1和num2,并计算出num1+num2的求和结果,最后返回给客户端
- 客户端接收服务端的计算结果
前期准备
创建相关文件
创建功能包ros_server_client
在根工作空间目录下执行
catkin_create_pkg ros_server_client roscpp rospy std_msgs
在功能包ros_server_client下创建消息结构文件目录和文件
其中AddInts.srv文件的内容为
int32 num1
int32 num2
---
int32 sum
修改配置文件
修改package.xml的内容为
<buildtool_depend>catkin</buildtool_depend><build_depend>roscpp</build_depend><build_depend>rospy</build_depend><build_depend>std_msgs</build_depend><build_depend>message_generation</build_depend><build_export_depend>roscpp</build_export_depend><build_export_depend>rospy</build_export_depend><build_export_depend>std_msgs</build_export_depend><exec_depend>roscpp</exec_depend><exec_depend>rospy</exec_depend><exec_depend>std_msgs</exec_depend><exec_depend>message_runtime</exec_depend>
修改CMakeLists.txt文件的内容为
find_package(catkin REQUIRED COMPONENTSroscpprospystd_msgsmessage_generation
)
add_service_files(FILESAddInts.srv
)
generate_messages(DEPENDENCIESstd_msgs
)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES ros_server_clientCATKIN_DEPENDS roscpp rospy std_msgs message_runtime
# DEPENDS system_lib
)
编译生成中间文件
catkin_make
服务端实现
服务端代码实现
在工作空间下创建服务端代码文件ros_server.cc
#include"ros/ros.h"
#include"ros_server_client/AddInts.h"// 服务通信对象回调
bool responseHander(ros_server_client::AddInts::Request& request,ros_server_client::AddInts::Response& response){int num1=request.num1;int num2=request.num2;ROS_INFO("receive parameters: %d , %d",num1,num2);int sum=num1+num2;response.sum=sum;ROS_INFO("num1+num2=%d",sum);return true;
}int main(int argc,char* argv[]){// 防止中文乱码setlocale(LC_ALL,"");// 初始化ros节点ros::init(argc,argv,"ros_server_node");// 创建ros节点handlerros::NodeHandle ros_server_node_handler;// 创建服务通信对象ros::ServiceServer ros_server=ros_server_node_handler.advertiseService("addInts",responseHander);ROS_INFO("server start!");ros::spin();
}
修改CMakeLists.txt文件
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(ros_server_node src/ros_server.cc)## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")## Add cmake target dependencies of the executable
## same as for the library above
add_dependencies(ros_server_node ${PROJECT_NAME}_gencpp)## Specify libraries to link a library or executable target against
target_link_libraries(ros_server_node${catkin_LIBRARIES}
)
编译生成代码
服务端测试
启动ros
roscore
启动服务端和客户端
客户端实现
创建客户端代码文件ros_client.cc
客户端代码实现
#include"ros/ros.h"
#include"ros_server_client/AddInts.h"int main(int argc,char* argv[]){ros::init(argc,argv,"ros_client_node");ros::NodeHandle ros_client_node_handler;ros::ServiceClient ros_client=ros_client_node_handler.serviceClient<ros_server_client::AddInts>("addInts");ros_server_client::AddInts parms;parms.request.num1=10;parms.request.num2=20;bool response=ros_client.call(parms);if(response){ROS_INFO("response successfully!");ROS_INFO("response result is %d ",parms.response.sum);}else{ROS_INFO("response error!");}return 0;
}
修改CMakeLists.txt文件
add_executable(ros_server_node src/ros_server.cc)
add_executable(ros_client_node src/ros_client.cc)## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")## Add cmake target dependencies of the executable
## same as for the library above
add_dependencies(ros_server_node ${PROJECT_NAME}_gencpp)
add_dependencies(ros_client_node ${PROJECT_NAME}_gencpp)## Specify libraries to link a library or executable target against
target_link_libraries(ros_server_node${catkin_LIBRARIES}
)
target_link_libraries(ros_client_node${catkin_LIBRARIES}
)
编译代码测试
代码优化,使用动态参数提交
#include"ros/ros.h"
#include"ros_server_client/AddInts.h"int main(int argc,char* argv[]){if(argc!=3){ROS_INFO("parms numbers error!");return 1;}ros::init(argc,argv,"ros_client_node");ros::NodeHandle ros_client_node_handler;ros::ServiceClient ros_client=ros_client_node_handler.serviceClient<ros_server_client::AddInts>("addInts");ros_server_client::AddInts parms;// 获取命令行参数parms.request.num1=atoi(argv[1]);parms.request.num2=atoi(argv[2]);// 这行代码的作用是,如果服务端尚未启动,那么客户端将会被挂起,直到服务端启动后才请求响应结果ros_client.waitForExistence();bool response=ros_client.call(parms);if(response){ROS_INFO("response successfully!");ROS_INFO("response result is %d ",parms.response.sum);}else{ROS_INFO("response error!");}return 0;
}
重新编译执行
测试1:先启动服务端,再启动客户端
测试2:先启动客户端,再启动服务端
参考:
063服务通信_理论模型_Chapter2-ROS通信机制_哔哩哔哩_bilibili