ROS Publisher#

What you will need

  • A Duckietown robot powered on and discoverable via dts fleet discover

What you will get

  • Learn to create a ROS Publisher node using the ROS publish–subscribe pattern

Create Publisher ROS Node#

The publish–subscribe pattern is fundamental in robotics. ROS implements this pattern via ROS Publishers and ROS Subscribers. A publisher sends messages into the ROS network for subscribers to receive.

In Create a new Catkin package, a new Catkin package was created. Now, add a ROS node containing a publisher:

  1. From the DTProject root, create the source directory:

mkdir -p ./packages/my_package/src
  1. Create my_publisher_node.py in packages/my_package/src/ with the following content:

#!/usr/bin/env python3


import os
import rospy
from std_msgs.msg import String
from duckietown.dtros import DTROS, NodeType


class MyPublisherNode(DTROS):
   def __init__(self, node_name):
       super(MyPublisherNode, self).__init__(node_name=node_name, node_type=NodeType.GENERIC)
       self._vehicle_name = os.environ['VEHICLE_NAME']
       self._publisher = rospy.Publisher('chatter', String, queue_size=10)


   def run(self):
       rate = rospy.Rate(1)  # 1 Hz
       message = f"Hello from {self._vehicle_name}!"
       while not rospy.is_shutdown():
           rospy.loginfo(f"Publishing message: '{message}'")
           self._publisher.publish(message)
           rate.sleep()


if __name__ == '__main__':
   node = MyPublisherNode(node_name='my_publisher_node')
   node.run()
   rospy.spin()
  1. Make the script executable:

chmod +x ./packages/my_package/src/my_publisher_node.py

Note

Using the DTROS superclass from duckietown.dtros is recommended for enhanced features beyond standard ROS.

Define Launcher#

To run the node inside the Docker container, create a launcher script:

  1. Create launchers/my-publisher.sh with:

#!/bin/bash
source /environment.sh
dt-launchfile-init
rosrun my_package my_publisher_node.py
dt-launchfile-join
  1. Make it executable:

chmod +x ./launchers/my-publisher.sh

Launch the Publisher Node#

  1. Ensure the Duckiebot is reachable:

ping ROBOT_NAME.local
  1. Rebuild the project on the robot:

dts devel build -H ROBOT_NAME -f
  1. Run using the new launcher:

dts devel run -H ROBOT_NAME -L my-publisher

The output will include logs such as:

[INFO] Publishing message: 'Hello from ROBOT_NAME!'
...

Congratulations 🎉

A ROS Publisher node has been built and executed successfully on Duckiebot.