Writing ROS code
This page covers writing ROS nodes, which are programs that connect (often with TCP) to a central server program, called the ROS core. After connecting with the core, ROS nodes can communicate with each other. Three ways ROS nodes communicate are topics, services, and parameters. We mostly use topics. This page has Python and C++ (Arduino) examples for communicating between two nodes using topics.
Topics are like mailing lists. Each topic has a name and a data type. Names usually start with a forward slash, such as /bike_state
. Data types are defined by ROS (or you). Here's a list of the standard ones. We mostly use Float32 and Float32MultiArray. Nodes publish to and subscribe from topics. Multiple nodes can publish to and subscribe from the same topic. There are also command-line and graphical tools for publishing to a topic and showing messages published to a topic.4
Note that there is no single Topic class. There is a Publisher class and a Subscriber class, both of which together do all the stuff you want to do with a topic.
Key reminder! On the Arduino, the NodeHandle constructor takes the number of publishers and the number of subscribers. If you're adding a new one of either, increment the number!
Writing a node
Python (Pi) | Arduino/C++ (Due) | Description |
---|---|---|
import rospy
from std_msgs.msg import Float32
|
#include <ros.h>
#include <std_msgs/Float32.h>
|
Imports the main ROS "client library" (code needed to interact with ROS) and the Float32 message type. |
rospy.init_node("asdf")
The node name is "asdf". Also takes an optional argument |
typedef ros::NodeHandle_<ArduinoHardware, 1, 3, 500, 500> RosNodeHandle;
RosNodeHandle nh;
// in a function:
nh.initNode();
Note: |
Initializes a node handle. A node handle is an object used to interact with ROS. |
pub = rospy.Publisher("hjkl", Float32, queue_size=10)
|
std_msgs::Float32 hjkl_data;
ros::Publisher hjkl_pub("hjkl", &hjkl_data);
// In a function:
nh.advertise(hjkl_pub);
|
Sets up a publisher who will publish to the topic hjkl .
|
pub.publish(42)
|
hjkl_data.data = 42;
hjkl_pub.publish(&hjkl_data);
|
Publishes the number 42. |
def foo_callback(data):
print(data.data)
rospy.Subscriber("foo", Float32, foo_callback)
|
void foo_callback(const std_msgs::Float32& data) {
Serial.println(data.data);
}
ros::Subscriber<std_msgs::Float32> foo_sub("foo", &foo_callback);
// In a function:
nh.subscribe(foo_sub);
|
Subscribes to the topic foo , which publishes Float32 values.
|
Working with a Float32MultiArray
Background knowledge. The Float32MultiArray is used to store an array of Float32s in any dimension. So it could be a regular array, or a 2-D array, or a 3-D one, and so on. There's a MultiArrayLayout field that tells you what the layout is. That's a bit wasteful, so really we should be defining custom message types.
Arduino/C++
Assuming you have a NodeHandle nh
(see above) and want to publish to and then subscribe from a topic "/foo". We're using a 3-element Float32MultiArray with a single unnamed dimension. To publish, first declare these two objects (probably as globals):
std_msgs::Float32MultiArray foo_data;
ros::Publisher foo_pub("foo", &foo_data);
Then run this setup code once:
// Helper variable to make the code read a bit easier
int foo_data_size = 3;
// Set the data_length field. Even though this field isn't mentioned in the documentation, it's mandatory! If you don't set this field to a nonzero length, everything will compile and run, but data won't actually be published.
foo_data.data_length = foo_data_size;
// Set the data_offset field, which contains the number of padding elements (i.e. elements we don't care about) at the front of the array. It'll usually be zero.
foo_data.layout.data_offset = 0;
// Create the dim array, which has an array of MultiArrayDimension objects. We use malloc to make a heap-allocated array because we expect this array to be alive for the entire lifetime of the program. The cast and the sizeof are the standard C/C++ way to create an array.
foo_data.layout.dim = (std_msgs::MultiArrayDimension *)
malloc(sizeof(std_msgs::MultiArrayDimension) * foo_data_size);
// Create the data array, which will hold the actual data. We will write to this array later when we're about to publish to the topic. Note that we create an array of floats, because this is a Float32MultiArray. If it were a different sort of multi array we might use a different data type. Note the "double data" (i.e. we have a variable called data and we write to its <code>data</code> field).
foo_data.data = (float *)malloc(sizeof(float) * foo_data_size);
// Tell ROS about the new publisher so that we're able to publish using it.
nh.advertise(foo_pub);
Then, every time you want to publish (in this example, we publish the array {1.1, 2.2, 3.3}
):
foo_data.data[0] = 1.1;
foo_data.data[1] = 2.2;
foo_data.data[2] = 3.3;
foo_pub.publish(&foo_data);
Todo: C++ subscribing, Python publishing and subscribing
Launch files
See the page on launch files