目录
准备工作
首先启动前的写的launch文件
roslaunch wugui_ttest wugui_start.launch
列出所有的ROS服务
rosservice list
rosmelodic@rosmelodic-virtual-machine:~/catkin_ws$ rosservice list
/clear
/key/get_loggers
/key/set_logger_level
/kill
/reset
/rosout/get_loggers
/rosout/set_logger_level
/spawn
/turtle1/get_loggers
/turtle1/set_logger_level
/turtle1/set_pen
/turtle1/teleport_absolute
/turtle1/teleport_relative
/wugui_pose/get_loggers
/wugui_pose/set_logger_level
找到对应的服务,服务名必须找到,因为服务通信中服务端和客户端必须相同服务名才能进行通信,并列出该服务的详细信息
rosservice info
rosmelodic@rosmelodic-virtual-machine:~/catkin_ws$ rosservice info /spawn
Node: /turtle1
URI: rosrpc://rosmelodic-virtual-machine:54625
Type: turtlesim/Spawn
Args: x y theta name
Node节点名,Type服务数据类型名,Args服务接收的请求参数名。
查询特定的服务数据类型,还记得在查询自定义服务数据类型时,必须进入其所在的工作空间才能查询。
rossrv info
rosmelodic@rosmelodic-virtual-machine:~/catkin_ws$ rossrv info turtlesim/Spawn
float32 x
float32 y
float32 theta
string name
---
string name
请求和应答数据通过---分开,同时发现rosservice info查看的服务详细信息,只显示了请求的数据类型。
尝试在控制台终端通过命令生成新的乌龟
rosservice call
rosservice call /spawn "x: 2.0
y: 2.0
theta: 3.14
name: 'turtle2'"
因为在实际应用中有逻辑关系,故不满足于在终端通过命令实现生成乌龟。
c++通过服务通信生成乌龟
因为程序的c++头文件和python的库要用到turtlesim包,故要确定turtlesim包是否导进来了。
检查package.xml文件
<build_depend>turtlesim</build_depend>
<exec_depend>turtlesim</exec_depend>
检查CMakeList.txt
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
rospy
std_msgs
turtlesim
)
创建文件wugui_service_client.cpp
wugui_service_client.cpp
#include "ros/ros.h"
#include "turtlesim/Spawn.h"
/*
乌龟生成的服务端已经有了,需要客户端给其发布消息
服务名称:/spawn 通过rosservice list查询到的
服务通信的消息数据类型:turtlesim/Spawn 通过rosservice info查询到的
1.头文件
2.初始化ROS节点
3.初始化节点句柄
4.创建客户端
5.组织与发布数据
6.处理响应
*/
int main(int argc, char *argv[])
{
// 防止控制台中文乱码
setlocale(LC_ALL,"");
// 初始化ROS节点
ros::init(argc,argv,"wugui_service_call");
// 初始化节点句柄
ros::NodeHandle n;
// 创建客户端
ros::ServiceClient client = n.serviceClient<turtlesim::Spawn>("/spawn");
// 组织数据
turtlesim::Spawn wugui_xiaoxi;
wugui_xiaoxi.request.x = 3.0;
wugui_xiaoxi.request.y = 3.0;
wugui_xiaoxi.request.theta = 3.14;
wugui_xiaoxi.request.name = "turtle2";
// 等待服务端启动,客户端挂起
client.waitForExistence();
// 发布数据,并返回一个发布成功与否的布尔类型值
bool tiaojian = client.call(wugui_xiaoxi);
// 根据返回的布尔值,按照条件输出字符串
if(tiaojian)
{
ROS_INFO("乌龟已经生成,名字是:%s",wugui_xiaoxi.response.name.c_str());
}
else
{
ROS_INFO("乌龟消息接收失败,乌龟生成失败!!!");
}
return 0;
}
注意的点是控制台输出的字符串必须是c的字符串,要不会报错数据类型有误!
ROS_INFO("乌龟已经生成,名字是:%s",wugui_xiaoxi.response.name.c_str());
另一个注意的点是利用创建客户端后,调用客户端下的waitForExistence函数,加入客户端挂起功能,防止客户端先启动服务端后启动发生报错。
client.waitForExistence();
配置CMakeList.txt文件
add_executable(wugui_service_client src/wugui_service_client.cpp)
add_dependencies(wugui_service_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(wugui_service_client
${catkin_LIBRARIES}
)
编译
catkin_make
启动上一篇博文的launch文件
roslaunch wugui_ttest wugui_start.launch
启动客户端
注意无须roscore了,因为roslaunch默认启动roscore(ROS Master)
rosrun wugui_ttest wugui_service_client
结果
把客户端节点放入launch文件中
<!-- 启动乌龟GUI和键盘控制节点 -->
<launch>
<!-- 乌龟GUI -->
<node pkg="turtlesim" type="turtlesim_node" name="turtle1" output="screen"/>
<!-- 键盘控制 -->
<node pkg="turtlesim" type="turtle_teleop_key" name="key" output="screen"/>
<!-- 乌龟位姿订阅 -->
<node pkg="wugui_ttest" type="test01_sub_pose_p.py" name="wugui_pose" output="screen"/>
<!-- 加一个乌龟 -->
<node pkg="wugui_ttest" type="wugui_service_client" name="wugui_spawn" output="screen"/>
</launch>
再次启动launch文件
rosrun wugui_ttest wugui_service_client
python通过服务通信生成乌龟
创建wugui_service_client_p.py
wugui_service_client_p.py
#! /usr/bin/env python
# -*- coding: UTF-8 -*-
"""
乌龟生成的服务端已经有了,需要客户端给其发布消息
服务名称:/spawn 通过rosservice list查询到的
服务通信的消息数据类型:turtlesim/Spawn 通过rosservice info查询到的
1.导入包
2.初始化ROS节点
3.创建客户端
4.组织与发布请求数据
5.处理响应
"""
import rospy
from turtlesim.srv import Spawn,SpawnRequest,SpawnResponse
import logging
logging.basicConfig()
if __name__ == "__main__":
rospy.init_node("wugui_service_call_p")
client = rospy.ServiceProxy(name="/spawn", service_class=Spawn)
request = SpawnRequest()
request.x = 4.0
request.y = 4.0
request.theta = 3.14
request.name = "turtle3"
client.wait_for_service()
try:
response = client.call(request)
rospy.loginfo("生成乌龟的名字:%s",response.name)
except Exception as e:
rospy.logerr("请求失败")
# response = client.call(request)
# rospy.loginfo("生成乌龟的名字:%s",response.name)
注意的点1: 在client.call前加入client.wait_for_service(),使得在服务端没开启前客户端挂起。
注意的点2:
import logging
logging.basicConfig()防止rospy.logerr报错。
添加可执行权限
chmod +x *.py
CMakeList.txt配置(melodic版本非必要)
catkin_install_python(PROGRAMS
scripts/wugui_service_client_p.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
编译(melodic版本非必要)
catkin_make
启动之前的launch文件
roslaunch wugui_ttest wugui_start.launch
启动客户端
rosrun wugui_ttest wugui_service_client_p.py
结果
将此客户端节点加入launch文件
<!-- 启动乌龟GUI和键盘控制节点 -->
<launch>
<!-- 乌龟GUI -->
<node pkg="turtlesim" type="turtlesim_node" name="turtle1" output="screen"/>
<!-- 键盘控制 -->
<node pkg="turtlesim" type="turtle_teleop_key" name="key" output="screen"/>
<!-- 乌龟位姿订阅 -->
<node pkg="wugui_ttest" type="test01_sub_pose_p.py" name="wugui_pose" output="screen"/>
<!-- 加一个乌龟 -->
<node pkg="wugui_ttest" type="wugui_service_client" name="wugui_spawn" output="screen"/>
<!-- 加另一个乌龟 -->
<node pkg="wugui_ttest" type="wugui_service_client_p.py" name="wugui_spawn_p" output="screen"/>
</launch>
注意的点,节点启动并不是按照launch文件依次启动,节点乌龟名必须不同,否则服务请求失败,这是这个服务端的特性。