Trying ROS2: client/server within a single container


Welcome to the next pikoTutorial !

In the first article of Trying ROS2 series I showed how to implement and examine a basic publisher and subscriber within a single Docker container. Now it’s time for checking out how do you implement and set up a client/server connection within a single Docker container. In this pikoTutorial you’ll read about:

  • setting up a typical ROS server and client written in C++ using ROS 2
  • defining a custom service with .srv file
  • building everything as a Docker image
  • running both nodes within a single container using a launch file which now can be written in Python

Project structure

Let’s first define a project structure to understand what am I aiming at:

project
├── launch
    ├── run_server_client.py
├── src
    ├── cpp_client
        ├── CMakeLists.txt
        ├── main.cpp
        ├── package.xml
    ├── cpp_server
        ├── CMakeLists.txt
        ├── main.cpp
        ├── package.xml
    ├── interfaces
        ├── srv
            ├── GetDataSize.srv
        ├── CMakeLists.txt
        ├── package.xml
├── Dockerfile
├── ros_entrypoint.sh

Create packages

I will put server, client and the service definitions into separate ROS packages, so let’s first create them using the following commands:

Bash
ros2 pkg create --build-type ament_cmake cpp_client
ros2 pkg create --build-type ament_cmake cpp_server
ros2 pkg create --build-type ament_cmake interfaces

Defining a custom service type

To define a custom service type called GetDataSize, I create a GetDataSize.srv file in src/interfaces/srv folder. Remember that services definitions must be placed in srv folder and their names must be camel case. Otherwise, you’ll get the following build error:

rosidl_adapter.parser.InvalidResourceName: 'get_data_size_Request' is an
invalid message name.  It should have the pattern '^[A-Z][A-Za-z0-9]*$'

The src/interfaces/srv/GetDataSize.srv file looks like below:

C++
string dataset_name
---
int32 dataset_size

To generate a C++ code out of such service definition, we need to use rosidl_generate_interfaces function in src/interfaces/CMakeLists.txt file:

CMake
cmake_minimum_required(VERSION 3.8)
project(interfaces)

find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
  "srv/GetDataSize.msg"
)

ament_package()

And add proper entries to the src/interfaces/package.xml file:

XML
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>

Writing a C++ ROS2 client

Below you can find the implementation of the C++ client using ROS2. Below is the content of the src/cpp_client/main.cpp file.

C++
// ROS client library for C++ header
#include "rclcpp/rclcpp.hpp"
// GetDataSize service header
#include "interfaces/srv/get_data_size.hpp"
// aliases
using GetDataSizeService = interfaces::srv::GetDataSize;
using GetDataSizeRequest = GetDataSizeService::Request;
using GetDataSizeRequestPtr = std::shared_ptr<GetDataSizeService::Request>;
using GetDataSizeResponsePtr = std::shared_ptr<GetDataSizeService::Response>;
using namespace std::chrono_literals;
// constants
static constexpr const char* kNodeName {"cpp_client"};
static constexpr const char* kServiceName {"GetDataSize"};
// client class
class CppClient : public rclcpp::Node
{
public:
    CppClient()
    : Node(kNodeName),
      client_{create_client<GetDataSizeService>(kServiceName)}
    {
        // wait for the service in 1 second intervals
        while (!client_->wait_for_service(1s)) {
            std::cout << "[CLIENT] Waiting for service..." << std::endl;
        }

        std::cout << "[CLIENT] GetDataSizeService service found!" << std::endl;
    }
    // function responsible for sending request
    void SendRequest(const std::string dataset_name)
    {
        std::cout << "[CLIENT] Requesting size of dataset " << dataset_name << std::endl;
        // create a request
        GetDataSizeRequestPtr request = std::make_shared<GetDataSizeRequest>();
        request->dataset_name = dataset_name;
        // obtain the response
        auto response_future = client_->async_send_request(request);
        const auto result = rclcpp::spin_until_future_complete(this->get_node_base_interface(),
                                                               response_future);
        // check validity of the result
        if (result != rclcpp::FutureReturnCode::SUCCESS)
        {
            std::cout << "[CLIENT] Request sending failed!" << std::endl;
            client_->remove_pending_request(response_future);
            return;
        }
        // read the response from the future object
        const GetDataSizeResponsePtr response = response_future.get();
        // print the response payload
        std::cout << "[CLIENT] Response received: " << response->dataset_size << std::endl;
    }

private:
    rclcpp::Client<GetDataSizeService>::SharedPtr client_;
};
// main function
int main(int argc, char * argv[])
{
    rclcpp::init(argc, argv);
    std::shared_ptr<CppClient> node = std::make_shared<CppClient>();
    // send 3 different requests
    node->SendRequest("Lakes");
    node->SendRequest("Oceans");
    node->SendRequest("Rivers");

    rclcpp::shutdown();
}

I kept src/cpp_client/CMakeLists.txt file in its most minimalistic form, so it contains the executable depending on our previously defined interfaces package:

CMake
cmake_minimum_required(VERSION 3.5)
project(cpp_client)

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(interfaces REQUIRED)

add_executable(${PROJECT_NAME} main.cpp)
ament_target_dependencies(${PROJECT_NAME}
    rclcpp
    interfaces
)

install(TARGETS ${PROJECT_NAME}
        DESTINATION lib/${PROJECT_NAME})

ament_package()

We must also remember about adding interfaces dependency to the src/cpp_client/package.xml file. Otherwise, the dependency build order will not be preserved and colcon may try to build e.g. cpp_client package before interfaces package (on which cpp_client depends) has been built.

XML
<depend>interfaces</depend>

Writing a C++ ROS2 server

Now it’s time to create src/cpp_server/main.cpp file:

C++
// ROS client library for C++ header
#include "rclcpp/rclcpp.hpp"
#include <iomanip>
// GetDataSize service header
#include "interfaces/srv/get_data_size.hpp"
// aliases
using GetDataSizeService = interfaces::srv::GetDataSize;
using RequestHeaderPtr = std::shared_ptr<rmw_request_id_t>;
using GetDataSizeRequestPtr = std::shared_ptr<GetDataSizeService::Request>;
using GetDataSizeResponsePtr = std::shared_ptr<GetDataSizeService::Response>;
// constants
static constexpr const char* kNodeName {"cpp_server"};
static constexpr const char* kServiceName {"GetDataSize"};
// overloaded stream operator for easy request header printing
std::ostream& operator<<(std::ostream& os, const RequestHeaderPtr& request_header)
{
    os << "Request number "
       << request_header->sequence_number
       << " from ";
    std::copy(std::begin(request_header->writer_guid),
              std::end(request_header->writer_guid),
              std::ostream_iterator<int>(os, " "));

    return os;
}
// mock data
static const std::unordered_map<std::string, std::vector<int>> kData = {
    {"Lakes", {1, 2, 3}},
    {"Oceans", {1, 2, 3, 4, 5}},
    {"Rivers", {1, 2, 3, 4, 5, 6, 7}},
};
// server class
class CppServer : public rclcpp::Node
{
public:
    CppServer()
    : Node(kNodeName)
    {
        // create a service and provide a callback which will be called upon
        // receiving a request
        service_ = create_service<GetDataSizeService>(kServiceName,
                                                      [this](RequestHeaderPtr request_header,
                                                             GetDataSizeRequestPtr request,
                                                             GetDataSizeResponsePtr response){
            HandleGetDataSizeRequest(request_header, request, response);
        });

        std::cout << "[SERVER] Server up and running" << std::endl;
    }

private:
    void HandleGetDataSizeRequest(RequestHeaderPtr request_header,
                                  GetDataSizeRequestPtr request,
                                  GetDataSizeResponsePtr response)
    {
        std::cout << "[SERVER] Received: " << request_header << std::endl;
        // populate the response with the proper data size
        response->dataset_size = kData.at(request->dataset_name).size();
    }

    rclcpp::Service<GetDataSizeService>::SharedPtr service_;
};
// main function
int main(int argc, char * argv[])
{
    rclcpp::init(argc, argv);
    std::shared_ptr<CppServer> node = std::make_shared<CppServer>();
    rclcpp::spin(node);
    rclcpp::shutdown();
}

The implementations of src/cpp_server/CMakeLists.txt and src/cpp_server/package.xml files are analogous to cpp_client, so I’ll skip writing about them here.

Writing a ROS2 launch file

After we have client and server ready to run, it’s time to define a Python launch file launch/run_server_client.py :

Python
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package='cpp_server',
            executable='cpp_server',
            output='screen',
        ),
        Node(
            package='cpp_client',
            executable='cpp_client',
            output='screen',
        ),
    ])

This file can be provided to ros2 launch command, but because we will run it inside the docker container environment which will require sourcing the ROS underlay and the workspace overlay anyway, let’s put all of these commands to a ros_entrypoint.sh file:

Bash
#!/bin/bash
set -e

source /opt/ros/rolling/setup.bash
source /app/src/install/setup.bash

ros2 launch launch/run_server_client.py

If you want to learn more about the ROS underlays and overlays, you can read more about them in this pikoTutorial.

Alternatively, if you don’t want to use ros2 launch, this script could look like this:

Bash
#!/bin/bash
set -e

source /opt/ros/rolling/setup.bash
source /app/src/install/setup.bash

ros2 run cpp_server cpp_server &
ros2 run cpp_client cpp_client

Writing a Dockerfile

To create a Docker image, I’ll use osrf/ros:rolling-desktop as a base image. It’s because on my Ubuntu 24.04 I use Rolling Ridley ROS 2 distro, so I want my container environment to be the same as my local one.

Dockerfile
# use ROS Rolling Ridley image as the base
FROM osrf/ros:rolling-desktop
# specify bash as shell to use source command
SHELL ["/bin/bash", "-c"]
# change working directory to /app
WORKDIR /app
# copy all the ROS workspace files
COPY src src/
COPY launch launch/
COPY ros_entrypoint.sh /app
# build workspace
RUN cd src && \
    source /opt/ros/rolling/setup.bash && \
    colcon build
# assign permission to the entrypoint script
RUN chmod +x /app/ros_entrypoint.sh
# run entrypoint script
ENTRYPOINT ["/app/ros_entrypoint.sh"]

Putting all together

At this point we have all the parts, but before we start working with the container, let’s check locally if the workspace build at all with the following command:

Bash
source /opt/ros/rolling/setup.bash
colcon build

If everything succeeded, you should see the output similar to:

Starting >>> interfaces
Finished <<< interfaces [6.45s]                     
Starting >>> cpp_client
Starting >>> cpp_server
Finished <<< cpp_server [15.2s]                                       
Finished <<< cpp_client [15.4s]                    
Summary: 3 packages finished [22.2s]

Now as we know that ROS workspace can be successfully built, it’s time to build a docker image:

Bash
docker build -t ros_server_client .

Note for beginners: if you’re struggling with missing Docker permissions, check this pikoTutorial out.

To run the container basing on this image, run:

Bash
docker run --rm --name server_client ros_server_client

Examining nodes’ behavior inside the container

After running the container, you will see the following logs:

[SERVER] Server up and running
[CLIENT] GetDataSizeService service found!
[CLIENT] Requesting size of dataset Lakes
[SERVER] Received: Request number 1 from 1 15 235 125 64 0 173 57 0 0 0 0 0 0 20 4 
[CLIENT] Response received: 3
[CLIENT] Requesting size of dataset Oceans
[SERVER] Received: Request number 2 from 1 15 235 125 64 0 173 57 0 0 0 0 0 0 20 4 
[CLIENT] Response received: 5
[CLIENT] Requesting size of dataset Rivers
[SERVER] Received: Request number 3 from 1 15 235 125 64 0 173 57 0 0 0 0 0 0 20 4 
[CLIENT] Response received: 7

You may want to examine further what’s going on in the container, so let’s go inside our container using:

Bash
docker container exec -it server_client /bin/bash

The first thing to check is whether our service GetDataSize is on the list of active services:

Bash
ros2 service list

This should give the output in which one of the entries represents our service:

/GetDataSize

Let’s then check the properties of that service:

Bash
ros2 service info /GetDataSize

As expected, we see that there is 1 server and 0 clients because after sending 3 requests, the client implemented above exits:

Type: interfaces/srv/GetDataSize
Clients count: 0
Services count: 1