要生成两个节点,一个节点名称叫server,一个叫client。server提供一个叫做mianji的服务,接受两个参数:长和宽,返回面积。
第一篇<主题>内容十分详细具体,包含了完整的步骤细节。但从这篇开始,不再记录完整的步骤细节。
=================生成study.service包======================
catkin_create_pkg study_service std_msgs rospy roscpp
========================生成.srv文件====================
mkdir srv
cd srv
该服务的.srv文件应该是这样的 :
float32 chang
float32 kuan
---
float32 mianji
我们创建文件/src/mianji.srv,并按上面的代码编辑
接下来,修改cmakelist,大概是这个样子:
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation)
add_service_files(
FILES
mianji.srv)
generate_messages(
DEPENDENCIES
std_msgs)
catkin_package()
然后编译,测试
rossrv show study_service/mianji
会显示
float32 chang
float32 kuan
---
float32 mianji
==========================生成server和client==============
cd ~/catkin_ws/src/study_service/src
vim server.cpp
并编辑,代码大概是
#include "ros/ros.h"
#include "study_service/mianji.h"
bool add_one(study_service::mianji::Request &req,
study_service::mianji::Response &res)
{
res.mianji = req.chang * req.kuan;
ROS_INFO("calculating!!!");
return true;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "server");
ros::NodeHandle n;
ros::ServiceServer service = n.advertiseService("mianji", add_one);
ROS_INFO("ready to calculate!");
ros::spin();
return 0;
}
编辑client.cpp
#include "ros/ros.h"
#include "study_service/mianji.h"
int main(int argc, char **argv)
{
if (argc!=3)
{
ROS_INFO("wrong input!");
return 1;
}
ros::init(argc, argv, "client");
ros::NodeHandle n;
ros::ServiceClient client = n.serviceClient<study_service::mianji>("mianji");
study_service::mianji srv;
srv.request.chang = atof(argv[1]);
srv.request.kuan = atof(argv[2]);
if (client.call(srv))
{
ROS_INFO("%f",srv.response.mianji);
}
else
{
ROS_INFO("failed!");
return 1;
}
return 0;
}
再次修改cmakelist
添加下面代码
add_executable(server src/server.cpp)
add_dependencies(server study_service_generate_message_cpp)
target_link_libraries(server ${catkin_LIBRARIES})
add_executable(client src/client.cpp)
add_dependencies(client study_service_generate_message_cpp)
target_link_libraries(client ${catkin_LIBRARIES})
编译并测试
打开三个终端,配置环境变量后运行
1,roscore
2, rosrun study_service server
3, rosrun study_service client 2. 25
客户端会显示[1499243433.917345177]: 50.000000
服务端会显示[1499243433.917147276]: calculating!!!