This page is part of the documentation of auKsys/4

In this tutorial, we are going to present how to transfer a large dataset of sensory data between two agents. Using either ROS topics or a MQTT broker.

Setting up

For this tutorial, we will use two agents, with namespaces agent0, agent1. In two different terminals, the ROS kDB server for each of those agents can be started with:

ros2 run ros_kdb kdb_server --ros-args -r __ns:=/agent0 -p db_port:=10142
ros2 run ros_kdb kdb_server --ros-args -r __ns:=/agent1 -p db_port:=10143

We will use the dataset of lidar data acquired near the buildings of the Gränsö castle. It can be downloaded and uncompressed with the following command:

curl -o lidar_buildings.kdb_dataset.xz "https://gitlab.liu.se/lks/tutorials_data/-/raw/main/lidar_buildings.kdb_dataset.xz?ref_type=heads&inline=false"
xz -d lidar_buildings.kdb_dataset.xz

It can be loaded in agent0 with:

ros2 service call /agent0/kdb_server/dataset/import ros_kdb_interfaces/srv/ImportDataset "filename: `pwd`/lidar_buildings.kdb_dataset"

You can check it was loaded properly with:

ros2 run ros_kdb datasets_info --ros-args -r __ns:=/agent0

It should show something like:

(There are 1 datasets)
uri: http://askco.re/examples#lidar_granso
 - type : http://askco.re/sensing#lidar3d_scan
 - geometry : POLYGON ((16.683033999999999 57.760852999999997, 16.682670000000002 57.760638000000000, 16.683056000000001 57.760435000000001, 16.683501000000000 57.760635000000001, 16.683033999999999 57.760852999999997))
 - agents: 
 - status: Completed
 - statistics: 63 data points

Dataset metadata synchronisation

Before starting the data synchronisation, the metadata needs to be synchronised between the agents, using the following for ROS topics:

ros2 service call /agent0/kdb_server/krql_query ros_kdb_interfaces/srv/QueryDatabase 'queries: [ { query: "start graph sync: { uri: http://askco.re/graphs#private_datasets }"} ]'
ros2 service call /agent1/kdb_server/krql_query ros_kdb_interfaces/srv/QueryDatabase 'queries: [ { query: "start graph sync: { uri: http://askco.re/graphs#private_datasets }"} ]'

Or when using MQTT broker (with a localhost broker):

ros2 service call /agent0/kdb_server/krql_query ros_kdb_interfaces/srv/QueryDatabase 'queries: [ { query: "start graph sync: { uri: http://askco.re/examples#map, transport: mqtt, mqtt_broker: tcp://localhost:1883 }"} ]'
ros2 service call /agent1/kdb_server/krql_query ros_kdb_interfaces/srv/QueryDatabase 'queries: [ { query: "start graph sync: { uri: http://askco.re/examples#map, transport: mqtt, mqtt_broker: tcp://localhost:1883 }"} ]'

For more details, refer to the RDF Graph Synchronisation tutorial.

Data transfer using ROS topics

The following service calls will start data transfer using ROS2 topic. The first call is executed in the kDB server which send the data, in our example, agent0. In the call, we specify the URI for the dataset to transefer (in this case http://askco.re/examples#lidar_granso), a communication namespace (this should be a unique absolute name, we recommend to generate it from a UUID) and a list of agents that will receive the data (in this case only agent1):

ros2 service call /agent0/setup_sending_data ros_kdb_interfaces/srv/SetupSendingData "{ dataset_uri: http://askco.re/examples#lidar_granso, communication_namespace: /t9fc38331_7080_4132_b39f_155ff7c156f8, receivers: [ agent1 ] }"

For the receiving agent, we need to specify the dataset URI, the communication namespace, and the name of the agent sending the data (in this case agent0):

ros2 service call /agent1/setup_receiving_data ros_kdb_interfaces/srv/SetupReceivingData "{ dataset_uri: http://askco.re/examples#lidar_granso, communication_namespace: /t9fc38331_7080_4132_b39f_155ff7c156f8, sender: agent0 }"

The transfer can take some time. And once it is completed, a message is sent to the topic /kdb/data_synchronisation_finished.

Data transfer using MQTT

The following service calls will start data transfer using ROS2 topic. The first call is executed in the kDB server which send the data, in our example, agent0. In the call, we specify the URI for the dataset to transefer (in this case http://askco.re/examples#lidar_granso), a communication namespace (this should be a unique absolute name, we recommend to generate it from a UUID) and a list of agents that will receive the data (in this case only agent1):

ros2 service call /agent0/setup_sending_data ros_kdb_interfaces/srv/SetupSendingData "{ dataset_uri: http://askco.re/examples#lidar_granso, communication_namespace: mqtt://localhost:1883/t9fc38331_7080_4132_b39f_155ff7c156f8, receivers: [ agent1 ] }"

For the receiving agent, we need to specify the dataset URI, the communication namespace, and the name of the agent sending the data (in this case agent0):

ros2 service call /agent1/setup_receiving_data ros_kdb_interfaces/srv/SetupReceivingData "{ dataset_uri: http://askco.re/examples#lidar_granso, communication_namespace: mqtt://localhost:1883/t9fc38331_7080_4132_b39f_155ff7c156f8, sender: agent0 }"

The transfer can take some time. And once it is completed, a message is sent to the topic /kdb/data_synchronisation_finished.