Skip to content

Client for remotely streaming ROS messages through websockets using rosboard as server

License

Notifications You must be signed in to change notification settings

kiwicampus/rosboard_client

Repository files navigation

Rosboard Client

The main objective of this library is to selectively stream ROS topics using websockets from a remote robot to a local machine, allowing to use visualization tools like rviz, rqt, mapviz, etc on live data transmitted over the internet. The library implements a client to use with a rosboard server running in the remote robot.

Dependencies

This package requires the following dependencies:

Existing alternatives

There are already some alternatives that allow to transmit ros data over the internet, however they have some drawbacks

  • Connecting a local ROS2 system to a remote one using a VPN like Husarnet. This removes the possibility of selecting only some topics for transmission, and does not perform any compression of the data, which makes it unsuitable for robots running high data rate sensors like cameras and LIDAR and relying on a cellular connection to stream the data.

  • Using rosbridge_suite. Though this does allow to stream topics selectively through websockets, its compression proved inefficient for large messages like images and occupancy grids, which lead to a very high bandwidth usage, lag "accumulation" and a severe drop in the rate of messages arriving to the desktop client.

Rosboard showed to overcome this drawbacks, keeping a comparatively lower bandwidth usage when streaming data intensive messages and having lower non-accumulating lag.

Brief functionality description

This library provides a desktop client that connects to a remote rosboard server and allows to create subscriptions to topics on that server. When a message is received binary data is decoded and passed to a user specified callback.

The library also provides a set of republishers meant to convert json data from rosboard back to ROS messages and republish them on the local machine. They account for the special subsampling and compression made by rosboard on Images, LaserScans, PointCloud2s and OccupancyGrids, and can convert virtually any other type of messages by relying on the rclpy_message_converter library, added as a submodule in this package.

The networking module is decoupled from the ROS dependent republishers, so it can be used as a standalone package providing custom callbacks for subscriptions that handle the json payloads. The socket client decompresses and decodes all the data before passing it to the callback.

An easy way of running this over the internet is using ngrok. After setting your authtoken you can tunnel the rosboard server, usually in the 8888 port using the tcp protocol:

ngrok tcp 8888

The url that ngrok provides can be used as host for creating the rosboard client.

How to use it

Note: Running the rosboard client requires the usage of our own rosboard fork running in the server side. This fork provides the required functionalities for the client to work as intended. Some of the functionalities that are available in our fork are:

  • Streaming topics from the client to the server.
  • Streaming of occupancy grids.
  • Checking that QoS profiles are kept when streaming topics.

To use the client, please follow the next steps:

  • Configure a workspace in which you will use the tool e.g. (~/rosboard_client_ws/).
  • Clone the repo in your workspace source folder:
    $ cd ~/rosboard_client_ws/src/
    $ git clone git@github.com:kiwicampus/rosboard_client.git # if using SSH
    # or
    $ git clone https://github.com/kiwicampus/rosboard_client.git # if using HTTPS
  • Navigate to the rosboard package and initialize submodules and install requirements:
    $ cd ~/rosboard_client_ws/src/rosboard_client/
    $ git submodule update --init --recursive
    $ pip install -r requirements.txt
  • Build the package:
    $ cd ~/rosboard_client_ws/
    $ colcon build --symlink-install --packages-up-to rosboard_client
  • Source the workspace:
    $ source ~/rosboard_client_ws/install/setup.bash

By this point you can either run the standalone or the GUI rosboard client nodes:

# To run the standalone node. Remember to configure `topics_to_subscribe.yaml`
$ ros2 run rosboard_client rosboard_client
# To run the GUI node.
$ ros2 run rosboard_client rosboard_client_gui

Note: this instructions do not take into account any additional interfaces packages that you require when running the client. Remember to download, build and source those interfaces packages. Not sourced interfaces might prevent topics from streaming.

Rosboard GUI

This package includes a graphical user interface (GUI) that can be used to connect the local computer (client) to the server. The GUI allows an user to define which topics will be streamed from the server to the client and viceversa. In addition to such capability, the interface presents information related to the rate in which the topic messages are received and the latency of them i.e. the time difference between the message header stamp and the current system time. Finally, some general metrics are presented regarding the CPU usage, average roundtrip time (RTT), and current download speed. This application is intended to ease the streaming process while being capable of dynamically selecting which topics are streamed.

rosboard-gui

Comparison with Rosbridge

We think of rosbridge as the main alternative to rosboard. In this context, we want to prove that rosboard presents an improved approach to streaming data from a remote device within the context of ROS. To do so, we propose a benchmark of metrics relevant to the streaming process. We must note that we will provide any third party with the capability of executing their own tests. We will benchmark two (2) metrics: latency and download speed.

  • Latency: we define latency as the time difference between the timestamp of the received message and the current computer time. We must note that there might be difference in the server and client clock that might affect this measurement.
  • Bandwidth Usage: is the measurement of received bytes per second while using rosboard. Keep in mind that this measurement is a system-wide metric. In this context, any additional process using the network interface might contaminate the test.

Two laptops were configured in a Local Area Network (LAN) using a network switch. The network switch was not connected to the internet in order to prevent contaminating the test. The used switch had a bandwidth limit of 100 Mibps. We did the benchmark with a data-intensive topics: a RGB camera streaming. The next table presents the used specifications for the streamed topic:

Topic Resolution FPS
RGB Camera 640 x 360 15

We did our tests streaming the camera feed from a computer connected to a LAN.

Streaming Tool Avg. Latency [ms] Avg. Bandwidth Usage [KiB/s]
Rosboard (JPEG compression) 96.38 11010.14
Rosbridge (no compression) 22330.06 12420.32
Rosbridge (CBOR compression) 6035.99 8215.36
Rosbridge (PNG compression) 19096.12 12054.46

A visual representation on the difference between rosboard and rosbridge can be seen in the following GIFs. These GIFs were recorded in the client side while streaming the color image. The streaming visualized using Rviz and captured by recording the screen. This visualization and recording took place in the client ROS network. You may notice how rosboard (left) has less latency than rosbridge (right, no compression).

rosboard-chrono

rosbridge-chrono

Running your own benchmarks

To run the rosboard benchmarking, you need to follow the next steps in the server side:

  1. Run the rosboard node by running ros2 run rosboard rosboard_node. You may use the server IP address to connect from the client or forward the port using a third-party tool such as Ngrok.

Run the next steps in the client side:

  1. Configure the rosboard_config.yaml file with the URL of the server and the topics you want to stream:
    • To configure the URL, set the url value in the file.
    • To configure the topics you want to stream from the server, configure the topics in the topics value in the file.
    • If you want to stream topics to the server, configure the topics_to_stream value in the file.
  2. Run the rosboard benchmark script by executing ros2 run rosboard_client rosboard_benchmark. Let the script run for at least a minute and for it to print the test results in console. You may now exit the script.

To run the rosbridge benchmarking, you need to follow the next steps in the server side:

  1. Run the ros2 launch rosbridge_server rosbridge_websocket.py.

Run the next steps in the client side:

  1. Configure the rosbridge_config.yaml file with the topics you want to stream:
    • Configure the URL in the corresponding field in the YAML file.
    • Add a topic by setting it as a key in the YAML file for the topics_to_subscribe entry.
    • Set the message type in the type field.
    • Set the compression algorithm in the compression field.
  2. Run the rosbridge benchmark script by executing ros2 run rosboard_client rosboard_benchmark. Let the script run for at least a minute and for it to print the test results in console. You may now exit the script.

Note: to run these tests, we used our own rosboard, rosbridge and roslibpy forks. In the case of rosboard, our forks allow us to fix an issue regarding ROS2 QoS (PR) and adding the feature of streaming topics from the client to the server. With regard of rosbridge, these forks correct some issues that are present in the main rosbridge repository such as allowing the CBOR and PNG compression for images when using ROS2. We strongly recommend using such forks to run the test. The links to our forks are:

  • rosboard: our own rosboard fork.
  • rosbridge_suite: use the cbor_fix branch when compiling the package.
  • roslibpy: use the cbor branch for CBOR compression and cbor_png for PNG compression.

ROS independent usage

from rosboard_client.client import RosboardClient

def cb(rosboard_data):
    print(f"got data: {rosboard_data}")

# this will create a client that is independent from ROS
client = RosboardClient(host='localhost:8888', connection_timeout=5)

topic = "/fix"

# Upon being created, the client stores the available topics in the remote server
# This raises an exception if the topic is not available
topic_type = client.get_topic_type(topic)

# Creates a subscription and runs the callback each time data is received
client.create_socket_subscription(msg_type=topic_type, topic=topic, callback=cb)

# The rest of your code. The client runs on a separate thread

Minimal ROS republisher node

import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor

from rosboard_client.ros import PublisherManager
from rosboard_client.client import RosboardClient


class RosboardClientNode(Node):
    def __init__(self):
        Node.__init__(self, node_name="rosboard_client")

        topics = ["/scan", "/tf", "/fix"]

        client = RosboardClient(host="localhost:8888", connection_timeout=5)

        for topic in topics:
            # Check if topic is available
            if not client.is_topic_available(topic):
                continue

            topic_type = client.get_topic_type(topic)

            # Get the republisher class for a given topic type
            republisher_class = PublisherManager.getDefaultPublisherForType(topic_type)

            # create the republisher object
            republisher = republisher_class(
                parent_node=self, topic_name=topic, topic_class_name=topic_type
            )

            # create the subscriptions with the republisher callback
            # each time a message arrives on a topic through rosboard
            # it will be published under the same topic name on the ros local system
            client.create_socket_subscription(
                topic_type, topic, republisher.parse_and_publish
            )


def main(args=None):
    # The usual ROS2 stuff
    rclpy.init(args=args)

    rosboard_client = RosboardClientNode()
    executor = MultiThreadedExecutor()
    rclpy.spin(rosboard_client, executor)

    rosboard_client.destroy_node()
    rclpy.shutdown()


if __name__ == "__main__":
    main()

About

Client for remotely streaming ROS messages through websockets using rosboard as server

Topics

Resources

License

Stars

Watchers

Forks

Packages

No packages published

Contributors 4

  •  
  •  
  •  
  •  

Languages