YARP
Yet Another Robot Platform
Writing code to talk to ROS topics

While you can configure conventional YARP ports to talk to ROS topics (see Use ROS with existing YARP programs), YARP provides specialized classes that simplify this task:

An important thing to keep in mind is that YARP needs to be aware of ROS types. If you are writing new code it is easy to generate ROS compatible YARP data types starting.

For example the following code shows how to write a program that listen to the /chatter topic. In this case we use the ROS type std_msgs/String.

The first thing to do is to generate a YARP compatible type for std_msgs/String:

$ yarpidl_rosmsg String

This will produce the file yarp/rosmsg/String.h which can be used directly in our YARP program.

Type the following code in a file, e.g. listener.cpp:

/*
* SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <yarp/os/Node.h>
namespace {
YARP_LOG_COMPONENT(LISTENER, "yarp.example.ros.listener")
}
int main(int argc, char* argv[])
{
YARP_UNUSED(argc);
YARP_UNUSED(argv);
Network yarp;
/* creates a node called /yarp/listener */
Node node("/yarp/listener");
/* subscribe to topic chatter */
if (!subscriber.topic("/chatter")) {
yCError(LISTENER) << "Failed to subscriber to /chatter";
return -1;
}
/* read data from the topic */
while (true) {
subscriber.read(data);
yCInfo(LISTENER) << "Received:" << data.data;
}
return 0;
}
Utilities for manipulating the YARP network, including initialization and shutdown.
Definition: Network.h:783
The Node class.
Definition: Node.h:24
A port specialized for reading data of a constant type published on a topic.
Definition: Subscriber.h:23
T * read(bool shouldWait=true)
Read a message from the port.
Definition: Subscriber.h:114
bool topic(const std::string &name)
Set topic to subscribe to.
Definition: Subscriber.h:63
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
The main, catch-all namespace for YARP.
Definition: dirs.h:16
#define YARP_UNUSED(var)
Definition: api.h:162
int main(int argc, char *argv[])
Definition: yarpros.cpp:263

An example CMakeLists.txt file to compile this code would be:

cmake_minimum_required(VERSION 3.12)
find_package(YARP COMPONENTS os REQUIRED)
add_executable(listener)
target_sources(listener PRIVATE listener.cpp)
target_link_libraries(listener PRIVATE YARP::YARP_os
YARP::YARP_init)

You can now publish the string "Hello World" to the topic /chatter using ROS:

rostopic pub /chatter std_msgs/String "hello yarp" --r 10

and listen to it using the YARP program above:

./listener
yarp: Port /yarp/listener active at tcp://192.168.152.130:10002
yarp: Port /chatter-@/yarp/listener active at tcp://192.168.152.130:10003
yarp: Receiving input from /rostopic_36275_1464212662655 to /chatter-@/yarp/listener using tcpros+role.pub+topic./chatter
Received:hello yarp
Received:hello yarp
Received:hello yarp
...

You can verify the existence of a node called /yarp/listener by running:

rosnode list
/rosout
/yarp/listener

We can now write our own publisher using YARP. The code is quite simple, type it in a file, e.g. talker.cpp:

/*
* SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
* SPDX-License-Identifier: BSD-3-Clause
*/
#include <yarp/os/Node.h>
#include <yarp/os/Time.h>
namespace {
YARP_LOG_COMPONENT(TALKER, "yarp.example.ros.talker")
constexpr double loop_delay = 0.1;
}
int main(int argc, char* argv[])
{
YARP_UNUSED(argc);
YARP_UNUSED(argv);
Network yarp;
/* creates a node called /yarp/talker */
Node node("/yarp/talker");
/* subscribe to topic chatter */
if (!publisher.topic("/chatter")) {
yCError(TALKER) << "Failed to create publisher to /chatter";
return -1;
}
while (true) {
/* prepare some data */
data.data = "Hello from YARP";
/* publish it to the topic */
publisher.write(data);
/* wait some time to avoid flooding with messages */
yarp::os::Time::delay(loop_delay);
}
return 0;
}
A port specialized for publishing data of a constant type on a topic.
Definition: Publisher.h:23
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:64
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:149
void delay(double seconds)
Wait for a certain number of seconds.
Definition: Time.cpp:111

an example CMakeLists.txt file to compile this code would be:

cmake_minimum_required(VERSION 3.12)
find_package(YARP COMPONENTS os REQUIRED)
add_executable(talker)
target_sources(talker PRIVATE talker.cpp)
target_link_libraries(talker PRIVATE YARP::YARP_os
YARP::YARP_init)

We can run this code on a terminal:

./talker
yarp: Port /yarp/talker active at tcp://192.168.152.130:10004
yarp: Port /chatter+@/yarp/talker active at tcp://192.168.152.130:10006
yarp: Sending output from /chatter+@/yarp/talker to /listener using tcpros
yarp: Removing output from /chatter+@/yarp/talker to /listener

You can verify the existence of a node called /yarp/talker and topic /chatter by running:

rosnode list
/rosout
/yarp/talker
rostopic list
/chatter
/rosout
/rosout_agg

And see the output using the listener from ros tutorials:

rosrun roscpp_tutorials listener
[ INFO] [1464213813.965287858]: I heard: [Hello from YARP]
[ INFO] [1464213814.066799996]: I heard: [Hello from YARP]
[ INFO] [1464213814.169264100]: I heard: [Hello from YARP]
[ INFO] [1464213814.271588965]: I heard: [Hello from YARP]
[ INFO] [1464213814.373758392]: I heard: [Hello from YARP]
...

The following tutorials show how to write your own data type using ROS syntax: