一、创建功能包
-
$ cd ~/catkin_ws/src
要进入src文件夹才能创建功能包 -
$ catkin_create_pkg learning_service roscpp rospy std_msgs geometry_msgs turtlesim
创建learning_service功能包
二、创建服务端代码
如何实现一个服务端
- 初始化ROS节点
- 创建一个Sever实例
- 循环等待服务请求,进入回调函数
- 在回调函数中完成服务功能的处理,并反馈应答数据
-
$ cd ~/catkin_ws/src/learning_service/src
-
$ touch turtle_command_server.cpp
创建cpp文件 -
$ gedit turtle_command_server.cpp
编辑cpp文件,输入以下代码
/***********************************************************************
Copyright 2020 GuYueHome (www.guyuehome.com).
***********************************************************************/
/**
* 该例程将执行/turtle_command服务,服务数据类型std_srvs/Trigger
*/
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <std_srvs/Trigger.h>
ros::Publisher turtle_vel_pub;
bool pubCommand = false;
// service回调函数,输入参数req,输出参数res
bool commandCallback(std_srvs::Trigger::Request &req,
std_srvs::Trigger::Response &res)
{
pubCommand = !pubCommand;
// 显示请求数据
ROS_INFO("Publish turtle velocity command [%s]", pubCommand==true?"Yes":"No");
// 设置反馈数据
res.success = true;
res.message = "Change turtle command state!"
return true;
}
int main(int argc, char **argv)
{
// ROS节点初始化
ros::init(argc, argv, "turtle_command_server");
// 创建节点句柄
ros::NodeHandle n;
// 创建一个名为/turtle_command的server,注册回调函数commandCallback
ros::ServiceServer command_service = n.advertiseService("/turtle_command", commandCallback);
// 创建一个Publisher,发布名为/turtle1/cmd_vel的topic,消息类型为geometry_msgs::Twist,队列长度10
turtle_vel_pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 10);
// 循环等待回调函数
ROS_INFO("Ready to receive turtle command.");
// 设置循环的频率
ros::Rate loop_rate(10);
while(ros::ok())
{
// 查看一次回调函数队列
ros::spinOnce();
// 如果标志为true,则发布速度指令
if(pubCommand)
{
geometry_msgs::Twist vel_msg;
vel_msg.linear.x = 0.5;
vel_msg.angular.z = 0.2;
turtle_vel_pub.publish(vel_msg);
}
//按照循环频率延时
loop_rate.sleep();
}
return 0;
}
三、配置服务端代码编译规则
-
$ cd ~/catkin_ws/src/learning_service
-
$ gedit CMakeLists.txt
在
#############
## Install ##
#############
之前输入
add_executable(turtle_command_server src/turtle_command_server.cpp)
target_link_libraries(turtle_command_server ${catkin_LIBRARIES})
四、编译并运行服务端
-
$ cd ~/catkin_ws
进入工作空间根目录 -
$ catkin_make
编译工作空间 -
$ source devel/setup.bash
设置环境变量 -
$ roscore
启动ROS Master -
$ rosrun turtlesim turtlesim_node
启动小海龟仿真器 -
$ rosrun learning_service turtle_command_server
运行可执行文件turtle_command_server -
$ rosservice call/turtle_command"{}"
通过终端发送发送Client请求
回车,另一个终端提示
[ INFO] [1621258407.932670382]: Publish turtle velocity command [Yes]
屏幕上的海龟开始运动起来(pubCommand被改为true)
-
$ rosservice call/turtle_command"{}"
再次发送Client请求
回车,终端提示
[ INFO] [1621258572.732759710]: Publish turtle velocity command [No]
屏幕上的海龟停止运动(pubCommand取反被改为false)