RobotForge
Published·~18 min

Your first publisher and subscriber in Python (and C++)

A minimal node that publishes, and another that subscribes. Side-by-side Python and C++ so you can pick your language with full information.

by RobotForge
#ros2#python#cpp#tutorial

The mental model is free; the muscle memory costs one tutorial. Let's write a publisher that emits a counter every second and a subscriber that prints it. We'll do Python first, then the C++ version side-by-side. By the end, you'll know which language you want for your next node.

Setup

Create a workspace and a package:

mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
ros2 pkg create --build-type ament_python --dependencies rclpy std_msgs my_first_pkg
cd my_first_pkg/my_first_pkg

The publisher (Python)

Create talker.py:

import rclpy
from rclpy.node import Node
from std_msgs.msg import Int32

class Talker(Node):
    def __init__(self):
        super().__init__('talker')
        self.pub = self.create_publisher(Int32, 'counter', 10)
        self.timer = self.create_timer(1.0, self.tick)
        self.n = 0

    def tick(self):
        msg = Int32()
        msg.data = self.n
        self.pub.publish(msg)
        self.get_logger().info(f'published {self.n}')
        self.n += 1

def main():
    rclpy.init()
    rclpy.spin(Talker())

if __name__ == '__main__':
    main()

Three ideas to notice:

  • create_publisher(Int32, 'counter', 10) — type, topic name, queue depth. The 10 is your history buffer.
  • create_timer(1.0, self.tick) — call tick every 1.0 seconds. Timers are the cleanest way to do periodic work.
  • rclpy.spin(node) — run the executor. Nothing fires without this.

The subscriber (Python)

Create listener.py:

import rclpy
from rclpy.node import Node
from std_msgs.msg import Int32

class Listener(Node):
    def __init__(self):
        super().__init__('listener')
        self.sub = self.create_subscription(
            Int32, 'counter', self.on_msg, 10)

    def on_msg(self, msg: Int32):
        self.get_logger().info(f'got {msg.data}')

def main():
    rclpy.init()
    rclpy.spin(Listener())

if __name__ == '__main__':
    main()

Register and build

In my_first_pkg/setup.py, add both entry points:

entry_points={
    'console_scripts': [
        'talker = my_first_pkg.talker:main',
        'listener = my_first_pkg.listener:main',
    ],
},

Then from the workspace root:

cd ~/ros2_ws
colcon build --packages-select my_first_pkg
source install/setup.bash

Run it

Two terminals (both sourced):

# Terminal 1
ros2 run my_first_pkg talker

# Terminal 2
ros2 run my_first_pkg listener

The listener prints each counter value the talker emits. Congratulations — that's a complete ROS 2 system in 40 lines.

The C++ version, side by side

If Python feels slow or you want deterministic timing, switch to C++. The structure is identical.

#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/int32.hpp>

class Talker : public rclcpp::Node {
public:
  Talker() : Node("talker") {
    pub_ = create_publisher<std_msgs::msg::Int32>("counter", 10);
    timer_ = create_wall_timer(
        std::chrono::seconds(1),
        [this]() {
          auto msg = std_msgs::msg::Int32();
          msg.data = n_++;
          pub_->publish(msg);
          RCLCPP_INFO(get_logger(), "published %d", msg.data);
        });
  }
private:
  rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr pub_;
  rclcpp::TimerBase::SharedPtr timer_;
  int n_ = 0;
};

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

Same structure: node, publisher, timer, spin. The type annotations are noisier but the logic is the same.

When to choose which

  • Python: prototyping, perception pipelines calling PyTorch, ML research, anything with quick iteration. Limited to ~200–400 Hz before GIL contention bites.
  • C++: real-time control loops, high-rate sensor processing, embedded targets, anywhere determinism matters. The build setup is annoying but the runtime is bulletproof.

What will go wrong

  • Topic names don't match. /counter vs counter vs /my_first_pkg/counter are all different. Use ros2 topic list to see what's actually there.
  • Node names collide. Two nodes with the same name is undefined behavior — ROS will let you do it and misbehave silently. Unique names or use namespaces.
  • Subscriber misses messages. If the publisher ran before the subscriber started and you need the old data, use a TRANSIENT_LOCAL QoS profile to "latch" the last value.

Next

Services vs actions vs topics — the decision tree for picking the right primitive for a given task. Topics are fire-and-forget; sometimes you want request-response, sometimes you want a long-running goal with feedback.

Comments

    Sign in to post a comment.