ROS services with custom message type - Explained with example

ROS service with custom message

                 "A ROS service is noting but a simple client/server system💁"

ROS srv Definition 

In which client send request with input data and the server will do the calculation/any logical operations on the given input and provide the service/response/output .

“output /input can be one/many”

 

ROS srv with custom Message


                "service server can only exist once, but can have many clients"

 

-It is synchronous. The client sends a requests, and blocks until it receives a response.


Creating ROS service :

If your work space have multiple services, its recommended to create a single package dedicated to services for example service_hub👻.

So lets start with creating a package 

go to  /src folder inside your workspace --> $ cd ~/catkin_ws/src

create package -->

$ catkin_create_pkg service_hub std_msgs rospy roscpp.

💥our service hub is ready.!!

 

Next we have to define our .srv file.

"An srv file describes a service. It is composed of two parts: a request 

and a response"

-Create a folder named srv inside our package (inside service_hub ) .

-Create a file with name addition.srv inside srv folder

(creating a service to take 2 numbers as input and return the sum)

--catkin_ws 
             -- src 
                      --service_hub 
           --srv 
                                                --addition.srv                 
-Now copy paste the  below text into addition.srv file 
 
int32  input1
int32  input2
---
int32  sum
 
         "No.of hyphen used between input and response should be always 3"
 

Supported field type or  data types are :

  • int8, int16, int32, int64 (plus uint*)

  • float32, float64

  • string

  • time, duration

  • other msg files -->including user defined .msg files

  • variable-length array[] and fixed-length array[C]  

 

 Now we have to modify our CMakeLists.txt and package.xml

 
  <build_depend>message_generation</build_depend>
  <exec_depend>message_runtime</exec_depend> 
 

Add these 👆 lines in package.xml file (inside our package service_hub)

 

Modify CMakeLists.txt as:

👀Find-out--> find_package section in CMakeLists.txt and 

add "message_generation" on it. 


find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  message_generation
 
 

👀Find-out--> add_service_files in CMakeLists.txt and 

add " addition.srv" on it. 

 
add_service_files(
  FILES
   addition.srv
 

-Now run catkin_make to reflect the changes .

$ cd ~/catkin_ws/

$ catkin_make

💥 

To make sure our .srv file is visible to ros system

$ rossrv show addition --> name of .srv

It should print the content of addition.srv file

 (in-case of error --> source your workspace) 

 

 Create python script for service

 -->Inside service_hub/src

create file  addition_server.py 

 #!/usr/bin/env python3   #-->as i'm using python3
from service_hub.srv import addition,additionResponse 

#from package_name.srv import file_name,filename+Response 
import rospy

 
#fn to handle req.
def addition_callback(req):
    print("Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b)))
    return additionResponse(req.a + req.b)

rospy.init_node('addition_srv') 

#any_variable=rospy.Service(node name,service name,fn to call )  
service = rospy.Service('addition_srv', addition,addition_callback)
print("Ready to add two ints.")
rospy.spin()

-Make the python script exicutable 

$ chmod +x addition_server.py 

 

Now we can call our service from terminal and verify its working💫

 

$ rosservice call /addition 1 2

 

      "You can also use your custom message types in ros service"


example :

+++++++++++++++++++++++++++++++++++++++++++++++++

int32 Robot_id

int32 Robot_name

---

robot_messages/robot_data  my_robot_data

+++++++++++++++++++++++++++++++++++++++++++++++++++


In the above example robot_messages is the package name, which contain the message file named: robot_data

--Dont forget to add 

 

## Generate added messages and services with any dependencies listed here
 generate_messages(
   DEPENDENCIES
   std_msgs
   robot_messages  # Or other packages containing msgs
 )

 

These lines inside  CMakeLists.txt of service_hub(package which contain the service files )

 Ros-service is best suitable for applications like feedback like stuffs

                        Any dobut please feel free to comment!

Read:

Locomotion in mobile robotics. 

What is mavros?.

Introduction to robotics. 

Different types of robots?

ROS : 5 Major advantages of using ROS.

Important branches of robotics?