Subscribe to camera#

What you will need

  • A Duckietown robot turned ON and visible on dts fleet discover

What you will get

  • Learn how to receive camera images from your robot using a ROS Subscriber

Topic and message type of interest#

ROS enables processes to exchange messages over named topics. To communicate, two ROS nodes must agree on:

  • A topic name (e.g., camera images)

  • A message type (e.g., JPEG frames)

For the Duckiebot camera sensor:

  • Topic: /ROBOT_NAME/camera_node/image/compressed

  • Message type: sensor_msgs/CompressedImage

    std_msgs/Header header
    string format
    uint8[] data
    

    where:

    • header: standard ROS header

    • format: image format (e.g., png, jpeg)

    • data: byte array containing the encoded image

Create Subscriber ROS Node#

Assuming a Catkin package exists at packages/my_package/, create a new file in its src/ directory:

mkdir -p ./packages/my_package/src

Then add camera_reader_node.py:

#!/usr/bin/env python3

import os
import rospy
from duckietown.dtros import DTROS, NodeType
from sensor_msgs.msg import CompressedImage
import cv2
from cv_bridge import CvBridge

class CameraReaderNode(DTROS):

   def __init__(self, node_name):
       super(CameraReaderNode, self).__init__(
           node_name=node_name,
           node_type=NodeType.VISUALIZATION
       )
       self._vehicle_name = os.environ['VEHICLE_NAME']
       self._camera_topic = f"/{self._vehicle_name}/camera_node/image/compressed"
       self._bridge = CvBridge()
       self._window = "camera-reader"
       cv2.namedWindow(self._window, cv2.WINDOW_AUTOSIZE)
       self.sub = rospy.Subscriber(self._camera_topic, CompressedImage, self.callback)

   def callback(self, msg):
       image = self._bridge.compressed_imgmsg_to_cv2(msg)
       cv2.imshow(self._window, image)
       cv2.waitKey(1)

if __name__ == '__main__':
   node = CameraReaderNode(node_name='camera_reader_node')
   rospy.spin()

Make the script executable:

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

Define launcher#

Create launchers/camera-reader.sh:

#!/bin/bash

source /environment.sh

dt-launchfile-init
rosrun my_package camera_reader_node.py
dt-launchfile-join

Rebuild the image:

dts devel build -f

Launch the node#

Run the subscriber locally with display access:

dts devel run -R ROBOT_NAME -L camera-reader -X

A window will open showing the camera feed:

Live camera feed window displaying frames

Fig. 10 Camera feed window.#

To stop, press Ctrl+C.

Note

The -X flag allows the container to create windows on the local display.

Attention

The trick we learned in Run locally to speed up our development workflow becomes mandatory here. In fact, this particular node needs access to a screen to be able to open the window showing the camera feed, hence the need to run it locally as the Duckiebot is not connected to a monitor. You can put this to the test by attempting to build and run this node on the Duckiebot (using the -H ROBOT_NAME) flag, you will be presented the error cannot open display.

Congratulations 🎉

You just built and ran your first ROS node that displays the Duckiebot camera feed on your screen.