Skip to main content

Creating Nodes - Services

Chapter description

In this chapter, we continued the previous project about services, so make sure you understand all the topics from the previous chapter. Services are one-time requests that should perform a one-time action, and the result of that action is returned as a response. To be able to better understand the interactions between packages, we will use a node called image_saver, which will save the image in the computer's memory after receiving a request. In addition, you will also learn how to perform recurring actions using timers.

You can run this tutorial on:

Repository containing the final effect after doing all the ROS Tutorials you can find here.

Install ROS package

First, we need to install the image_view package, which contains the image_save node. To install the additional ROS package, we use apt. The syntax of ROS packages is standardized and looks like this:

husarion@husarion:~$
sudo apt-get install ros-$ROS_DISTRO-NAME-OF-PACKAGE

For image_view package use:

husarion@husarion:~$
sudo apt-get install ros-$ROS_DISTRO-image-view

How service works?

The image_view package includes the image_saver node that allows you to save the image. In order for the node to work properly, we need to tell it what topic with the image it should subscribe to. Also we should remap the topic related to the camera info /camera_info. This topic contains information about camera parameters such as resolution or data for image calibration. We also set parameter save_all_image to false. With all this information, the command to run should look like this.

husarion@husarion:~$
rosrun image_view image_saver _save_all_image:=false /image:=/camera/color/image_raw /camera_info:=/camera/color/camera_info __name:=image_saver

/camera/color/image_raw and /camera/color/camera_info parameter depends on the type of camera you are using. Use rostopic list to find camera topics.

At this point, the node is already running and waiting for the /save service to be called. We can call this service from the terminal. Usage of rosservice is similar to rostopic.

husarion@husarion:~$
rosservice call /image_saver/save "{}"

As a result, you should see new photo in your current directory.

Create timer

Very often in robotics you have to perform an activity cyclically, every certain amount of time. In this case, we can use a timer. In this example, we create a basic timer action that will print a message in the terminal.

~/ros_ws/src/tutorial_pkg/src/my_first_node.cpp
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <std_msgs/UInt8.h>

ros::Publisher brightness_pub;

void imageCallback(const sensor_msgs::ImageConstPtr &image)
{
long long sum = 0;
for (int value : image->data)
{
sum += value;
}
int avg = sum / image->data.size();

std_msgs::UInt8 brightness_value;
brightness_value.data = avg;
brightness_pub.publish(brightness_value);
}

void timerCallback(const ros::TimerEvent&)
{
ROS_INFO("Timer activate");
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "my_first_node");
ros::NodeHandle n("~");
ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
brightness_pub = n.advertise<std_msgs::UInt8>("brightness", 1);
ros::Timer timer = n.createTimer(ros::Duration(5.0), timerCallback);

ROS_INFO("Node started!");
ros::spin();
}
The code explained
  1. Create a timer, which will call the timer_callback function after counting down 5 seconds.
ros::Timer timer = n.createTimer(ros::Duration(5.0), timerCallback);
  1. Creating a callback function, which prints a info.
void timerCallback(const ros::TimerEvent&)
{
ROS_INFO("Timer activate");
}

Task 1

Please build and test above code as in the previous chapter. Now your node should print Timer activate every 5 seconds.

Adding parameters

Our timer works beautifully, however, what if we wanted the action to be performed once every 5s, and another time every 1s. This would require changing the code every time and rebuilding it. However, there is a much better way instead of changing the code, we can add a parameter specifying how often the timer should be executed. In the following, we will modify the node so that it is possible to change the action frequency.

~/ros_ws/src/tutorial_pkg/src/my_first_node.cpp
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <std_msgs/UInt8.h>

ros::Publisher brightness_pub;

void imageCallback(const sensor_msgs::ImageConstPtr &image)
{
long long sum = 0;
for (int value : image->data)
{
sum += value;
}
int avg = sum / image->data.size();

std_msgs::UInt8 brightness_value;
brightness_value.data = avg;
brightness_pub.publish(brightness_value);
}

void timerCallback(const ros::TimerEvent&)
{
ROS_INFO("Timer activate");

std_srvs::Empty srv;
client.call(srv);
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "my_first_node");
ros::NodeHandle n("~");

double timer_period_s;
n.param("timer_period_s", timer_period_s, 5.0);

ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
brightness_pub = n.advertise<std_msgs::UInt8>("brightness", 1);
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);

ROS_INFO("Node started!");
ros::spin();
}

The code explained
  1. In ROS param member function is used to declare a parameter named timer_period_s with a default value (if parameter doesn't exist) and assign it to double timer_period_s variable.
double timer_period_s;
n.param("timer_period_s", timer_period_s, 5.0);
  1. We use a timer_period_s variable to specify the frequency of the timer.
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);

Create launch file

As before, we can use the rosrun command, this time with the additional argument _timer_period_s:=2.0. So the entire command looks like this:

husarion@husarion:~$
rosrun my_ros_package my_node_executable _timer_period_s:=2.0

However, we can see that slowly writing the command to run the script becomes more and more tedious. So let's do it differently and use the roslaunch command discussed in the first chapter. Select your favorite language and create new new file inside launch directory.

husarion@husarion:~$
mkdir -p ~/ros_ws/src/tutorial_pkg/launch/
touch ~/ros_ws/src/tutorial_pkg/launch/my_launch_file.launch

Open this file and paste following code:

~/ros_ws/src/tutorial_pkg/launch/my_launch_file.launch
<launch>
<node pkg="tutorial_pkg" type="my_first_node" name="my_first_node" output="screen"/>
<param name="timer_period_s" value="2"/>
</node>
</launch>

Launch your node

Now we can again build our package and use roslaunch command to run our node.

husarion@husarion:~$
catkin make
roslaunch tutorial_pkg my_launch_file.launch

Task 2

Change timer_period_s parameter value in launch file and test it. Properly created program should work in an intuitive way without rebuilding your code (launch files doesn't require building after changing content).

Create client

As you can see, creating a timer with parameters is relatively simple. In addition, we already know how services work, let's create a node that will save us one camera frame every certain number of seconds. So let's use the created timer to start the service and save the photo from the camera.

~/ros_ws/src/tutorial_pkg/src/my_first_node.cpp
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <std_msgs/UInt8.h>
#include <std_srvs/Empty.h>

ros::Publisher brightness_pub;
ros::ServiceClient client;

void imageCallback(const sensor_msgs::ImageConstPtr &image)
{
long long sum = 0;
for (int value : image->data)
{
sum += value;
}
int avg = sum / image->data.size();

std_msgs::UInt8 brightness_value;
brightness_value.data = avg;
brightness_pub.publish(brightness_value);
}

void timerCallback(const ros::TimerEvent&)
{
ROS_INFO("Timer activate");

std_srvs::Empty srv;
client.call(srv);
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "my_first_node");
ros::NodeHandle n("~");

double timer_period_s;
n.param("timer_period_s", timer_period_s, 5.0);

ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
brightness_pub = n.advertise<std_msgs::UInt8>("brightness", 1);
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);
client = n.serviceClient<std_srvs::Empty>("/image_saver/save");

ROS_INFO("Node started!");
ros::spin();
}
The code explained
  1. Begin with importing required header for std_srvs/Empty message type. This type of message has no field and can not carry any data, it can be used only for invoking action in another node and getting reply when its done.
#include <std_srvs/Empty.h>
  1. Declare publisher object.
ros::ServiceClient client;
  1. Next, define a client on your system to call a std_srvs::srv::Empty service named /save.
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);
  1. Send std_srvs::Empty service.
std_srvs::Empty srv;
client.call(srv);

Building configuration

To build project you need to add the new std_srvs dependency to the CMakeList.txt.

~/ros_ws/src/tutorial_pkg/CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(tutorial_pkg)

add_compile_options(-std=c++11)

find_package(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
std_msg
std_srvs
)

catkin_package(
CATKIN_DEPENDS
)

include_directories(${catkin_INCLUDE_DIRS})

add_executable(my_first_node src/my_first_node.cpp)

target_link_libraries(my_first_node
${catkin_LIBRARIES}

Create launch file

To test the node, we can use the rosrun command again. However, it would require that in addition to my_first_node, you also run the image_saver node. Instead, we can add an additional node to our launch file.

Open this file and paste following code:

~/ros_ws/src/tutorial_pkg/launch/my_launch_file.launch
<launch>

<node pkg="tutorial_pkg" type="my_first_node" name="my_first_node" output="screen"/>
<param name="timer_period_s" value="2"/>
</node>

<node pkg="image_view" type="image_saver" name="image_saver" output="screen">
<remap from="/image" to="/camera/color/image_raw"/>
<remap from="/camera_info" to="/camera/color/camera_info"/>
<param name="save_all_image" value="false" />
</node>

</launch>

Build your code and run it. After running this file, you may notice that a new save_images folder has been created in your current directory. On the side of this folder you can see how frames are written to it.

Create service

The final modification in the node will be the provision of service. Service will return information regarding how many images were saved.

~/ros_ws/src/tutorial_pkg/src/my_first_node.cpp
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <std_msgs/UInt8.h>
#include <std_srvs/Empty.h>
#include <std_srvs/Trigger.h>

uint saved_imgs = 0;

ros::Publisher brightness_pub;
ros::ServiceClient client;

void imageCallback(const sensor_msgs::ImageConstPtr &image)
{
long long sum = 0;
for (int value : image->data)
{
sum += value;
}
int avg = sum / image->data.size();

std_msgs::UInt8 brightness_value;
brightness_value.data = avg;
brightness_pub.publish(brightness_value);
}

void timerCallback(const ros::TimerEvent&)
{
ROS_INFO("Timer activate");

std_srvs::Empty srv;
client.call(srv);
saved_imgs++;
}

bool saved_img(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
{
res.success = 1;
res.message = "Saved images: " + std::to_string(saved_imgs);
return true;
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "my_first_node");
ros::NodeHandle n("~");

double timer_period_s;
n.param("timer_period_s", timer_period_s, 5.0);

ros::Subscriber sub = n.subscribe("/camera/color/image_raw", 10, imageCallback);
brightness_pub = n.advertise<std_msgs::UInt8>("brightness", 1);
ros::Timer timer = n.createTimer(ros::Duration(timer_period_s), timerCallback);
client = n.serviceClient<std_srvs::Empty>("/image_saver/save");
ros::ServiceServer service = n.advertiseService("image_counter", saved_img);

ROS_INFO("Node started!");
ros::spin();
}
The code explained
  1. Begin with including required header for std_srvs/Trigger message type. It has no field for request and two fields for response: bool success and string message
#include <std_srvs/Trigger.h>
  1. Define variable for storing number of saved images.
uint saved_imgs = 0;
  1. Next, define a server on your system to providing the std_srvs::srv::Trigger service named /image_counter. Function std::bind like in subscriber points to callback.
ros::ServiceServer service = n.advertiseService("image_counter", saved_img);
  1. Increment image counter after saving frame.
saved_imgs++;
  1. Callback function to execute when service is called. Inside the function, we set up the response fields according to the std_srvs/Trigger service.
bool saved_img(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
{
res.success = 1;
res.message = "Saved images: " + std::to_string(saved_imgs);
return true;
}

Create launch file

The last thing which we can add to launch is running astra camera or Gazebo simulator depend on the launch argument use_sim. Let's change launch file for the last one.

Open this file and paste following code:

~/ros_ws/src/tutorial_pkg/launch/my_launch_file.launch
<launch>

<arg name="use_gazebo" default="false"/>

<include unless="$(arg use_gazebo)" file="$(find astra_camera)/launch/astra.launch"/>
<include if="$(arg use_gazebo)" file="$(find rosbot_bringup)/launch/rosbot_tutorial.launch"/>

<node pkg="tutorial_pkg" type="my_first_node" name="my_first_node" output="screen"/>
<param name="timer_period_s" value="2"/>
</node>

<node pkg="image_view" type="image_saver" name="image_saver" output="screen">
<remap from="/image" to="/camera/color/image_raw"/>
<remap from="/camera_info" to="/camera/color/camera_info"/>
<param name="save_all_image" value="false" />
</node>

</launch>

Running your code

Build your node and execute launch file.

husarion@husarion:~$
docker compose up -d rosbot ros-master
roslaunch tutorial_pkg my_launch_file.launch

Then call service using rosservice call command.

husarion@husarion:~$
rosservice call /my_first_node/image_counter

As a response you should get something like this:

image

Summary

Congratulations! You understand the basics of using the basic communication interfaces in ROS. From now on you should have no problems writing your own node code, adding parameters, build it and run it with either rosrun or roslaunch. By now, you should be familiar with the following concepts in ROS (Robot Operating System):

  • running ROSbot/Gazebo simulator
  • subscription to published topics
  • publish new topic
  • create timer
  • provide service
  • call to provided service

by Łukasz Mitka & Rafał Górecki, Husarion s Do you need any support with completing this tutorial or have any difficulties with software or hardware? Feel free to describe your thoughts on our community forum: https://community.husarion.com or to contact our support: support@husarion.com