YARP
Yet Another Robot Platform
ROS Types in YARP: writing a portable

YARP built-in types can be sent through Ports.

Sometimes you need to send custom datatypes, in YARP objects that can be sent through ports are called portable objects. Port Power, Going Further with Ports shows how you can manually implement a portable object.

For ROS interoperability YARP supports ROS msg types. In this tutorial we see how you can automatically generate YARP portable objects using ROS syntax. The advantage in this case is that your type is compatible with ROS and can be directly read from a topic.

Introduction

Suppose we have two modules that wish to share a SharedData \m struct that contains a string and a vector. Normally you would define the data in a C++ header file and write serialization/deserialization methods to allow it to be sent and received to/from a port (this process is called marshalling/demarshalling). This process requires some YARP specific expertise, is error-prone and tedious. The idea here is that instead of manually writing the class you define the structure using the ROS syntax, then you ask a compiler (called yarpidl_rosmsg) to generate the class for you, including all the required code. Because you use the ROS syntax this type is also compatible with ROS and can be read from a topic.

Let's see how to do it.

ROS definition for SharedData

We start by defining our ShareData structure. Open a text editor and type the following:

string text
float64[] content

name this file SharedData.msg save and close it.

In ROS this specifies that SharedData is a struct that contains a text field of type string and a content field which type is a vector of double precision floating point numbers. ROS in fact supports much more options, see http://wiki.ros.org/msg.

Now you can convert the ROS type in a YARP compatible type.

Type:

yarpidl_rosmsg SharedData.msg

This is the output you shuld get:

[type] BEGIN SharedData.msg
[type] string text []
[type] float64[] content []
[type] END SharedData.msg
Generating SharedData.h

This will generate one file: yarp/rosidl/SharedData.h

In case you are interested you can inspect it to see that it defines a C++ class with some extra code. The good thing is that you don't actually need to bother about the details, but you can readily use the class in your code.

Now we can use these files in your YARP programs. We now write a sender and a receiver.

Code

This code is straightforward. We define a sender executable that opens a port and periodically writes a yarp::rosidl::SharedData object and a receiver that opens a port and receives the same message type.

As usual we start with the CMake code, write your CMakeLists.txt:

cmake_minimum_required(VERSION 3.12)
find_package(YARP COMPONENTS os REQUIRED)
add_executable(sender)
target_sources(sender PRIVATE sender.cpp)
target_include_directories(sender PRIVATE ${CMAKE_CURRENT_SOURCE_DIR})
target_link_libraries(sender PRIVATE YARP::YARP_os
YARP::YARP_init)

Now we write the code for the sender in sender.cpp:

#include <yarp/rosidl/SharedData.h>
#include <iostream>
#include <yarp/os/Time.h>
using namespace std;
int main()
{
if (!port.open("/sender"))
{
cerr<<"Error opening port, check your yarp network\n";
return -1;
}
cout<<"Starting sender\n";
double count=0.0;
while(true)
{
yarp::rosidl::SharedData d;
// d.text is a string
d.text="Hello from sender";
//d.content is a vector, let's push some data
d.content.push_back(count++);
d.content.push_back(count++);
port.write(d);
}
return 0;
}

Now compile the code

mkdir build
cd build
cmake ../
make
./sender

Now you can run yarp read on a separate console to inspect the content that is being transmitted on the port, the output should be something like this (you'll need a very recent version of YARP for this to work - if it doesn't just skip it):

~$ yarp read ... /sender
yarp: Port /tmp/port/1 active at tcp://127.0.0.1:10003
yarp: Receiving input from /sender to /tmp/port/1 using tcp
"Hello from sender" (276.0 277.0)
"Hello from sender" (278.0 279.0)

It is simple to write a receiver:

Append the following to the CMakeLists.txt

add_executable(receiver)
target_sources(receiver PRIVATE receiver.cpp)
target_link_libraries(receiver YARP::YARP_os
YARP::YARP_init)

Now we write the code for the receiver in receiver.cpp:

#include <yarp/rosidl/SharedData.h>
#include <iostream>
using namespace std;
int main()
{
cout<<"Starting receiver\n";
if (!port.open("/receiver"))
{
cerr<<"Error opening port, check your yarp network\n";
return -1;
}
network.connect("/sender", "/receiver");
int count=0;
while(true)
{
yarp::rosidl::SharedData d;
port.read(d);
//access d
cout << count << " Received SharedData:\n";
cout << d.text << "\n";
for (int i=0; i<d.content.size(); i++)
{
cout<<d.content[i]<<" ";
}
cout<<"\n";
count++;
}
return 0;
}

Compile, and start the receiver, with the sender running:

$ ./receiver
Starting receiver
yarp: Port /receiver active at tcp://192.168.59.129:10003
yarp: Receiving input from /sender to /receiver using tcp
0 Received SharedData:
Hello from sender
396 397
1 Received SharedData:
Hello from sender
398 399
2 Received SharedData:
Hello from sender
400 401
3 Received SharedData:
Hello from sender
402 403
...

Using CMake

YARP provides CMake supports to automate the invocation of yarpidl_rosmsg. This is convenient in large projects when we generate several files and we do not want to keep track of all of them individually.

Edit the file CMakeLists.txt:

cmake_minimum_required(VERSION 3.12)
#find YARP
find_package(YARP REQUIRED)

We now tell CMake to parse SharedData.msg with the rosmsg compiler. All generated files will be placed in separate include and src directories.

#compile definition file to generate source code into the desired directory
set(generated_libs_dir "${CMAKE_CURRENT_SOURCE_DIR}")
yarp_idl_to_dir(SharedData.msg ${generated_libs_dir})

The first time you run CMake it will produce a file SharedData_msg.cmake that contains all generated files. This file can be used to compile our executables, i.e.:

#include files generated previously
include(SharedData_msg.cmake)
include_directories(${generated_libs_dir}/include)
# create the sender
add_executable(sender)
target_sources(sender PRIVATE sender.cpp
${headers}
${sources})
target_link_libraries(sender PRIVATE YARP::YARP_os
YARP::YARP_init)
# create the receiver
add_executable(receiver)
target_sources(receiver PRIVATE receiver.cpp
${headers}
${sources})
target_link_libraries(receiver PRIVATE YARP::YARP_os
YARP::YARP_init)

Now you just have to execute CMake. The variable ALLOW_IDL_GENERATION controls if the rosmsg compiler is executed to generate SharedData.h or not. Notice that the first time you run cmake you have to enable this flag otherwise compilation will fail because SharedData.h will be missing.

cd build
cmake ../ -DALLOW_IDL_GENERATION=TRUE

The code generation step is required only when SharedData.msg is modified.

Related Tutorials

This tutorial continues with:

More information on interoperatiblity with ROS can be found here: Using YARP with ROS

The Thrift IDL allows defining portable objects and modules interfaces with YARP native types:

Code for this tutorial can be found here: example/idl/rosportable

Network.h
yarp::sig::file::read
bool read(ImageOf< PixelRgb > &dest, const std::string &src, image_fileformat format=FORMAT_ANY)
Definition: ImageFile.cpp:827
main
int main(int argc, char *argv[])
Definition: yarpros.cpp:261
yarp::os::Port::open
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:82
yarp::os::Port
A mini-server for network communication.
Definition: Port.h:50
yarp::os::NetworkBase::connect
static bool connect(const std::string &src, const std::string &dest, const std::string &carrier="", bool quiet=true)
Request that an output port connect to an input port.
Definition: Network.cpp:685
BufferedPort.h
yarp::os::Port::read
bool read(PortReader &reader, bool willReply=false) override
Read an object from the port.
Definition: Port.cpp:475
yarp::os::mkdir
int mkdir(const char *p)
Portable wrapper for the mkdir() function.
Definition: Os.cpp:40
yarp::os::Port::write
bool write(const PortWriter &writer, const PortWriter *callback=nullptr) const override
Write an object to the port.
Definition: Port.cpp:430
yarp::os::Network
Utilities for manipulating the YARP network, including initialization and shutdown.
Definition: Network.h:786
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
Time.h
yarp::os::Time::delay
void delay(double seconds)
Wait for a certain number of seconds.
Definition: Time.cpp:114