Service communication is based on a request-resposne model, which is suitable for scenarios requiring occasional, real-time, and logical processed data transmission.
The service communication model involves three roles:
- Master (Manager)
- Server (Service Provider)
- Client (Service Requester)
The Master manages the registration of Servers and Clients, matching them by service name and helping to establish connections. Once connected, the Client can send requests, and the Server responds with the appropriate information.
The service communication process includes the following steps:
- advertise: The server registers with the Master, providing its RPC address and service name. The Master adds this information to the registry.
- Client Registrasion: The client registers with the Master, providing the service name. The Master adds this information to the registry.
- Master Matching: The Master matches the registered server and client and sends the server's TCP/UDP address to the client via RPC.
- Client Sends Request: The client establishes a network connection with the server using the provided TCP/UDP address and sends the request.
- Server Responds: The server processes the request and sends the response back to the client via TCP/UDP.
Note: 1. The first three steps use the RPC protocol, while the last two steps use TCP/UDP (default is TCP). 2. The client must ensure that the server is running before sending a request. 3. Multiple clients can share the same service name, but there can only be one server per service name. 4. Unlike topic communication, the ROS Master must be running for service communication to work.
Service Hello World Example
Let's start with a simple "Hello World" example to illustrate the basic usage of services in ROS.
When using services to transmit data, consider the following aspects:
- Service Name
- Message Format (srv)
- Server Implementation
- Client Implementation
We will create a simple service where the client requests to start or stop a robot, and the server starts or stops the robot's modules and returns the result.
2.1 Create and Initialize the Package
First, create the service\_hello\_world package with the following command:
catkin_create_pkg service_hello_world std_srvs roscpp rospy
2.2 Define the Service Name and Message Format
Service Name: /hello_world_service
Message Format: std_srvs::SetBool
Message File Path: /opt/ros/noetic/share/std_srvs/srv/SetBool.srv
Message File Content:
bool data # e.g. for hardware enabling / disabling
---
bool success # indicate successful run of triggered service
string message # informational, e.g. for error messages
2.3 Implement the Server and Client (C++ Version)
Create the service\_hello\_world\_server.cpp file in the src directory of the service\_hello\_world package with the following content:
#include <ros/ros.h>
#include <std_srvs/SetBool.h>
bool handleRobotSwitch(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &resp)
{
bool flag = req.data;
ROS_INFO("Server received [%s] command for the robot.", flag ? "start" : "stop");
if (flag)
{
ROS_INFO("Starting robot modules...");
ros::Duration(2).sleep();
if (ros::Time::now().toNSec() % 2 == 0)
{
resp.success = true;
resp.message = "Hello World.";
ROS_INFO("Robot modules started successfully.\n");
}
else
{
resp.success = false;
resp.message = "Sleeping more...";
ROS_INFO("Robot modules failed to start.\n");
}
}
else
{
ROS_INFO("Stopping robot modules...");
ros::Duration(2).sleep();
if (ros::Time::now().toNSec() % 2 == 0)
{
resp.success = true;
resp.message = "Good Night.";
ROS_INFO("Robot modules stopped successfully.\n");
}
else
{
resp.success = false;
resp.message = "Still rolling...";
ROS_INFO("Robot modules failed to stop.\n");
}
}
return true;
}
int main(int argc, char **argv)
{
setlocale(LC_ALL, "");
ros::init(argc, argv, "service_hello_world_server");
ros::NodeHandle nh;
ros::ServiceServer server = nh.advertiseService("/robotSwitch", handleRobotSwitch);
ROS_INFO("robotSwitch service is up...");
ros::spin();
return 0;
}
Create the service\_hello\_world\_client.cpp file in the src directory with the following content:
#include <ros/ros.h>
#include <std_srvs/SetBool.h>
int main(int argc, char **argv)
{
setlocale(LC_ALL, "");
ros::init(argc, argv, "service_hello_world_client");
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<std_srvs::SetBool>("/robotSwitch");
std_srvs::SetBool srv;
if (strcmp(argv[1], "on") == 0)
{
srv.request.data = true;
}
else if (strcmp(argv[1], "off") == 0)
{
srv.request.data = false;
}
else
{
ROS_WARN("Only 'on' and 'off' are supported.");
return 1;
}
if (client.call(srv))
{
if (srv.response.success)
{
ROS_INFO("Operation succeeded, %s", srv.response.message.c_str());
}
else
{
ROS_ERROR("Operation failed, %s", srv.response.message.c_str());
}
}
else
{
ROS_ERROR("Operation failed, unknown error!");
}
return 0;
}
Modify the CMakeLists.txt file to include the following:
add_executable(${PROJECT_NAME}_client src/service_hello_world_client.cpp)
add_executable(${PROJECT_NAME}_server src/service_hello_world_server.cpp)
target_link_libraries(${PROJECT_NAME}_client
${catkin_LIBRARIES}
)
target_link_libraries(${PROJECT_NAME}_server
${catkin_LIBRARIES}
)
Compile and Run
Compile the project with catkin\_make and then start the master, server, and client with the following commands:
1. Start the ROS master
roscore
2. Start the server
rosrun service_hello_world service_hello_world_server
3. Start the client
rosrun service_hello_world service_hello_world_client
2.4 Implement the Server and Client (Python Version)
Create the service\_hello\_world\_server.py file in the scripts directory with the following content:
import rospy
from std_srvs.srv import SetBool, SetBoolResponse
def handle_robot_switch(req):
flag = req.data
rospy.loginfo("Server received [%s] command for the robot.", "start" if flag else "stop")
if flag:
rospy.loginfo("Starting robot modules...")
if rospy.Time.now().to_nsec() % 2 == 0:
rospy.loginfo("Robot modules started successfully.\n")
return SetBoolResponse(True, "Hello World.")
else:
rospy.logerr("Robot modules failed to start.\n")
return SetBoolResponse(False, "Sleeping more...")
else:
rospy.loginfo("Stopping robot modules...")
if rospy.Time.now().to_nsec() % 2 == 0:
rospy.loginfo("Robot modules stopped successfully.\n")
return SetBoolResponse(True, "Good Night.")
else:
rospy.logerr("Robot modules failed to stop.\n")
return SetBoolResponse(False, "Still rolling...")
if __name__ == "__main__":
rospy.init_node("service_hello_world_server")
server = rospy.Service("/robotSwitch", SetBool, handle_robot_switch)
rospy.loginfo("robotSwitch service is up...")
rospy.spin()
Create the service\_hello\_world\_client.py file in the scripts directory with the following content:
import sys
import rospy
from std_srvs.srv import SetBool, SetBoolRequest
if __name__ == "__main__":
rospy.init_node("service_hello_world_client")
if len(sys.argv) != 2:
rospy.logerr("Incorrect number of arguments")
sys.exit(1)
flag = False
if sys.argv[1] == "on":
flag = True
elif sys.argv[1] == "off":
pass
else:
rospy.logwarn("Only 'on' and 'off' are supported.")
sys.exit(1)
rospy.loginfo("Client requesting [%s] the robot.", "start" if flag else "stop")
client = rospy.ServiceProxy("/robotSwitch", SetBool)
client.wait_for_service()
req = SetBoolRequest()
req.data = flag
res = client.call(req)
if res.success:
rospy.loginfo("Operation succeeded, %s", res.message)
else:
rospy.logerr("Operation failed, %s", res.message)
Modify the CMakeLists.txt file to include the following:
catkin_install_python(PROGRAMS
scripts/service_hello_world_server.py
scripts/service_hello_world_client.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
Compile and Run
Compile the project with catkin\_make and then start the master, server, and client with the following commands:
1. Start the ROS master (if not already running)
roscore
2. Start the server
rosrun service_hello_world service_hello_world_server.py
3. Start the client
rosrun service_hello_world service_hello_world_client.py