Write a Minimal ROS2 Cpp Node

In this tutorial you’ll learn how to create a ROS2 Cpp Node. The code will be simple to focus on the basics, and get a base structure for all your future ROS2 Cpp programs.

After a minimal running example I’ll show you what is the recommended way to write your node, using Object Oriented Programming (OOP).

(If you’re interested about writing a node in Python, check out the ROS2 Python node tutorial.)

Write a minimal ROS2 Cpp Node

Code structure for an rclcpp Node

#include "rclcpp/rclcpp.hpp"

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<rclcpp::Node>("my_node_name");
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

This code will start a ROS2 node, and wait until you kill the node.

Let’s break this code down line by line.

#include "rclcpp/rclcpp.hpp"

First we import the rclcpp library. From rclcpp we’ll be able to retrieve many of the ROS2 core functionalities: nodes, topics, services, etc.


You want to learn ROS2 efficiently?

Check out ROS2 For Beginners and learn ROS2 step by step, in 1 week.


int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);

In our main program, the first thing we do is to initiate ROS2 communications with rclcpp::init(). You have to pass 2 arguments, which are the parameters you get from the main() function.

This line is very important, you must call rclcpp::init() before you create any node.

    auto node = std::make_shared<rclcpp::Node>("my_node_name");

Now that ROS2 communications are initiated, we’re allowed to create an rclcpp::Node. You’ll specify the name of the node as an argument.

One good practice is to create a std::shared_ptr to handle the node object. With ROS2 you can use Cpp 14, so ditch the “new”/”delete” keywords, and use smart pointers instead.

Here we also used the keyword “auto” because the type is quite obvious – std::shared_ptr<rclcpp::Node>, this may be better to increase readability (but it’s really up to you).

    rclcpp::spin(node);

The node is created, however if we do nothing else the program will exit and our node will be destroyed.

rclcpp::spin() will do 2 things:

  • Pause the program here and keep the node alive. When you request to kill the node (for example CTRL+C), the spinning will stop and the program will resume.
  • Also it will allow all defined callback functions to be called. If you create a callback for a subscriber, a parameter, etc., then spin will monitor any input coming from other nodes, and will trigger some callbacks if needed.
    rclcpp::shutdown();
    return 0;
}

After you’ve killed the node, this is what gets executed. rclcpp::shutdown() will stop ROS2 communications, it is basically the opposite of rclcpp::init().

Because the node is stored in a smart pointer, you don’t need to worry about de-allocating its resources.

To resume, your minimal Cpp program will:

  • Initiate ROS2 communications.
  • Create a ROS2 node.
  • Make the node spin until you kill it.
  • Cleanup and shutdown ROS2 communications.

Install and run your ROS2 Cpp node

If you don’t already have a ROS2 Cpp package, create one and create a Cpp file in its src/ directory.

$ cd ~/ros2_ws/src/
$ ros2 pkg create my_robot_tutorials --build-type ament_cmake
$ cd my_robot_tutorials/src/
$ touch my_cpp_node.cpp

Write the previous code into “my_cpp_node.cpp”.

To compile the node, open the “CMakeLists.txt” of your package and add those lines just after find_package(ament_cmake REQUIRED):

...
find_package(rclcpp REQUIRED)

add_executable(minimal_cpp_node src/my_cpp_node.cpp)
ament_target_dependencies(minimal_cpp_node rclcpp)

install(TARGETS
  minimal_cpp_node
  DESTINATION lib/${PROJECT_NAME}
)
...

Also, don’t forget to add <depend>rclcpp</depend> after <buildtool_depend>ament_cmake</buildtool_depend> in “package.xml”.

Now you can compile your node.

$ cd ~/ros2_ws/
$ colcon build --packages-select my_robot_tutorials

To run your node, open a new terminal, source your ROS2 environment, and execute ros2 run:

$ ros2 run my_robot_tutorials minimal_cpp_node

This will do nothing, which is normal since we didn’t add any functionality to the node. Press CTRL+C to kill the node and exit the program.

Use OOP to write your ROS2 Cpp nodes

Code structure

Let’s rewrite the exact same minimal code but this time with OOP. We’ll add some functionalities just after that.

#include "rclcpp/rclcpp.hpp"

class MyNode : public rclcpp::Node
{
public:
    MyNode() : Node("my_node_name") {}

private:
};

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<MyNode>();
    rclcpp::spin(node);
    rclcpp::shutdown();
}

This is the recommended structure to write a node: create a class which inherits from rclcpp::Node. rclcpp::Node contains almost all ROS2 basic functionalities.

The constructor is a good place to initiate your node with a name and options (not present here). You will also define your publishers/subscribers/services here.

What changed in the main function? Well now instead of creating a rclcpp::Node object, we create an object of the custom class we wrote. The node’s name is now set in the constructor, but nothing prevents you from passing the name from the main if you want, and then use it.

From now on, any addition/change you’ll make to your node will be inside the MyNode class. The main function will stay the same.

Add some functionalities to your node

Let’s make our node print “Hello from ROS2” at 5Hz. We’ll use the code structure from above and add what’s needed.

#include "rclcpp/rclcpp.hpp"

class MyNode : public rclcpp::Node
{
public:
    MyNode() : Node("my_node_name")
    {
        timer_ = this->create_wall_timer(
            std::chrono::milliseconds(200),
            std::bind(&MyNode::timerCallback, this));
    }

private:
    void timerCallback()
    {
        RCLCPP_INFO(this->get_logger(), "Hello from ROS2");
    }

    rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<MyNode>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

Let’s break the new stuff down line by line.

    rclcpp::TimerBase::SharedPtr timer_;

We declare a ROS2 Timer object as a private attribute of the class. Note that ROS2 brings you some useful types: you can use SharedPtr, which means that the object will in fact be contained inside a std::shared_ptr.

private:
    void timerCallback()
    {
        RCLCPP_INFO(this->get_logger(), "Hello from ROS2");
    }

We add a callback for this timer. We make this method private since it will only be called from within the node class.

Inside this method we simply print something on the screen, with RCLCPP_INFO(). We use the inherited method get_logger() to get the node’s logger and all the settings that go with it.

    MyNode() : Node("my_node_name")
    {
        timer_ = this->create_wall_timer(
            std::chrono::milliseconds(200),
            std::bind(&MyNode::timerCallback, this));
    }

Inside the constructor we initialize the timer with another inherited method: create_wall_timer(). We need to give 2 arguments: the duration between 2 callbacks, and the function to call. Here to pass the class method we have to use std::bind(). The callback will start being triggered when the node starts spinning.

And as you can see, no need to change anything in the main function of the program. Using a class inherited from rclcpp::Node makes the approach quite modular.

If you run this node you should see the message printed every 0.2 second:

$ ros2 run my_robot_tutorials minimal_cpp_node 
[INFO] [my_node_name]: Hello from ROS2
[INFO] [my_node_name]: Hello from ROS2
[INFO] [my_node_name]: Hello from ROS2
[INFO] [my_node_name]: Hello from ROS2

As long as your node is alive and spinning, the timer created in the constructor will continue to trigger callbacks at 5Hz. When you request to kill the node with CTRL+C, the spinning will end and no callback will be called anymore. Then, it’s time for cleanup and shutdown, and the program exits.

For reference: ROS2 Cpp node without OOP (not recommended)

#include "rclcpp/rclcpp.hpp"

std::shared_ptr<rclcpp::Node> node = nullptr;

void timerCallback()
{
    RCLCPP_INFO(node->get_logger(), "Hello from ROS2");
}

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    node = std::make_shared<rclcpp::Node>("my_node_name");
    auto timer = node->create_wall_timer(
        std::chrono::milliseconds(200), timerCallback);
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

This will work, but is much less modular and scalable than using OOP. Using global variables is not a good practice (you could try to pass the node as a parameter for each callback function, but it would cause other problems too), and we had to write functionality code inside the main function.

Not using the OOP way also prevents you from using ROS2 components and lifecycle node, which can be quite useful for more complex applications.

Writing ROS2 code like this may be fine for small projects that you don’t intend to share with the ROS2 community. But if you intend to work with other ROS developers, or simply to read the code from some robots using ROS2, well OOP is the convention used by (almost) everybody. It will save you – and others who work with your code – time and potential headaches.

Going further with ROS2 Cpp nodes

In this tutorial you have seen how to write a basic ROS2 Cpp node with rclcpp.

There is much more you can do: components, lifecycled nodes, running multiple nodes in the same executable with intra-process communication, etc.

But the most important thing is that you first clearly understand how to write the code foundation that you’ll need for your nodes. Once you’re clear with that, start to work with ROS2 publishers, subscribers, parameters, services. Those are the most important functionalities you have to learn. And you’ll see, if you already have a good code structure for your nodes, adding more ROS2 functionalities will be quite straightforward.

Want to learn how to program with ROS2?

Don't miss this opportunity:

ROS2 For Beginners - Step by Step Course


[NEW] ROS 2 Book


Or, learn with a video course