In ROS communication, in addition to topic communication, there is also a type of service communication. Services include both client and server, where the client requests the service and the server provides the service. This section focuses on the client and explains how C++and Python can implement the client.
catkin_create_pkg learning_server std_msgs rospy roscpp geometry_msgs turtlesim
xxxxxxxxxx
catkin_make
a_new_turtle.cpp
x#include <ros/ros.h>
#include <turtlesim/Spawn.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "a_nes_turtle");// 初始化ROS节点
ros::NodeHandle node;
ros::service::waitForService("/spawn"); // 等待/spawn服务
ros::ServiceClient new_turtle = node.serviceClient<turtlesim::Spawn>("/spawn");//创建一个服务客户端,连接名为/spawn的服务
// 初始化turtlesim::Spawn的请求数据
turtlesim::Spawn new_turtle_srv;
new_turtle_srv.request.x = 6.0;
new_turtle_srv.request.y = 8.0;
new_turtle_srv.request.name = "turtle2";
// 请求服务传入xy位置参数以及名字参数
ROS_INFO("Call service to create a new turtle name is %s,at the x:%.1f,y:%.1f", new_turtle_srv.request.name.c_str(),
new_turtle_srv.request.x,
new_turtle_srv.request.y);
new_turtle.call(new_turtle_srv);
ROS_INFO("Spwan turtle successfully [name:%s]", new_turtle_srv.response.name.c_str());// 显示服务调用结果
return 0;
};
xxxxxxxxxx
add_executable(a_new_turtle src/a_new_turtle.cpp)
target_link_libraries(a_new_turtle ${catkin_LIBRARIES})
xxxxxxxxxx
cd ~/catkin_ws
catkin_make
source devel/setup.bash
xxxxxxxxxx
roscore
rosrun turtlesim turtlesim_node
rosrun learning_server a_new_turtle
After starting the node of Little Turtle, run a_ new_ The Turtle program will find that there will be another small turtle appearing in the screen, because the turtle's node provides a service/spa wn, which will generate another small turtle Turtle2. To view the services provided by the turtle, you can use the rossservice list command, as shown in the following figure
You can view the parameters required for this service through rossservice info/spa, as shown in the following figure
It can be seen that there are four parameters required: x, y, theta, and name, which are in a_ new_ There is initialization in turtle.cpp
xxxxxxxxxx
srv.request.x = 6.0;
srv.request.y = 8.0;
srv.request.name = "turtle2";
a_new_turtle.py
xxxxxxxxxx
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import sys
import rospy
from turtlesim.srv import Spawn
def turtle_spawn():
rospy.init_node('new_turtle')# ROS节点初始化
rospy.wait_for_service('/spawn')# 等待/spawn服务
try:
new_turtle = rospy.ServiceProxy('/spawn', Spawn)
response = new_turtle(2.0, 2.0, 0.0, "turtle2")# 输入请求数据
return response.name
except rospy.ServiceException, e:
print "failed to call service : %s"%e
if __name__ == "__main__":
#服务调用并显示调用结果
print "a new turtle named %s." %(turtle_spawn())
xxxxxxxxxx
roscore
rosrun turtlesim turtlesim_node
rosrun learning_server a_new_turtle.py
xxxxxxxxxx
response = add_turtle(2.0, 2.0, 0.0, "turtle2")
The corresponding parameters are x, y, theta, and name.