一、服务模型
客户端向服务端发送开关型指令(Request),控制海龟是否运动。即客户端执行一次命令行就可以向服务端发送指令让小海龟运动,再次执行一次此命令行的话小海龟就停止运动。
服务端给客户端发送等速度信息Topic消息(Response)。
二、创建服务器代码
把turtle_command_server.cpp或turtle_command_server.py拷贝到catkin_ws/src/learning_service/src路径中。
2.2cpp编程
/**
* 该例程将执行/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;
}
三、配置服务器代码编译规则
配置CMakeLists.txt中的编译规则
add_executable(turtle_command_server src/turtle_command_server.cpp)
target_link_libraries(turtle_command_server ${catkin_LIBRARIES})
四、编译并运行服务器
注:每执行一次$ rosservice call /turtle_command “{}”,就会改变一次小海龟的状态,即是运动还是停止状态。
$ cd ~/catkin_ws
$ catkin_make
$ source devel/setup.bash
$ roscore
$ rosrun turtlesim turtlesim_node
$ rosrun learning_service turtle_command_server
$ rosservice call /turtle_command "{}"