Session 4: Playing with Images in ROS2 Using OpenCV
In this session, we’re going to learn how to use OpenCV with ROS2 by doing something really simple but cool—we’ll convert an image to black and white.
Why Are We Doing This?
Understanding how to process images is super important for making things like self-driving cars. So, let’s start with something basic and easy to understand.
What We’ll Do
Understand OpenCV library and how to use it with ROS2
Capture an image from ROS2.
Convert the image to black and white using OpenCV.
Display the original and the black-and-white images.
OpenCV Overview
OpenCV (Open Source Computer Vision Library) is a free and open library that helps computers understand images and videos. With OpenCV, you can do things like:
Change Images: Make images clearer, find edges, and switch colors.
Find Features: Spot important parts in pictures.
Detect Objects: Identify things like faces or eyes in photos.
Analyze Videos: Watch videos and track moving objects.
Learn from Data: Use smart algorithms to make predictions.
OpenCV works with languages like Python and C++, and it’s used by many people around the world.
To learn more, check out the official OpenCV website.
Let’s Get Started
First, we need to capture an image from ROS2. Don’t worry if this sounds complicated; the code will make it easy.
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
import cv2
from cv_bridge import CvBridge
class ImageConverter(Node):
def __init__(self):
super().__init__("image_converter")
self.bridge = CvBridge()
self.subscription = self.create_subscription(
Image,
"/stk_image",
self.image_callback,
1
)
def image_callback(self, msg):
# Convert the ROS2 image message to an OpenCV image
cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
# Convert the image to grayscale (black and white)
gray_image = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
# Display the original and the grayscale images
cv2.imshow("Original Image", cv_image)
cv2.imshow("Black and White Image", gray_image)
# Wait for a key press and close the image windows
cv2.waitKey(1)
def main():
rclpy.init()
image_converter = ImageConverter()
rclpy.spin(image_converter)
rclpy.shutdown()
if __name__ == "__main__":
main()
Code Explanation:
Load Libraries
We start by importing the necessary libraries:
import rclpy from rclpy.node import Node from sensor_msgs.msg import Image import cv2 from cv_bridge import CvBridge
rclpy: ROS2 Python client library.
Node: Base class for creating ROS2 nodes.
Image: Message type for images.
cv2: OpenCV library for image processing.
CvBridge: Helper class to convert between ROS2 images and OpenCV images.
Initialize ROS2
We create a ROS2 node named
image_converter:class ImageConverter(Node): def __init__(self): super().__init__("image_converter")
Capture and Convert
We subscribe to an image topic and convert the received images to grayscale:
self.subscription = self.create_subscription( Image, "/stk_image", self.image_callback, 1 )
The callback function,
image_callback, handles the image conversion:def image_callback(self, msg): cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8") gray_image = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
In this, BGR stands for Blue, Green, and Red, which are the color channels in the image. We convert the image to grayscale using the cv2.cvtColor function.
Display Images
The original and black-and-white images are displayed using OpenCV:
cv2.imshow("Original Image", cv_image) cv2.imshow("Black and White Image", gray_image)
Wait and Close
The images will keep updating as new images are received. You can close the image windows by pressing any key:
cv2.waitKey(1)
Running the Node
Finally, we initialize and run the node:
def main(): rclpy.init() image_converter = ImageConverter() rclpy.spin(image_converter) rclpy.shutdown()
This keeps the node running and continuously processing incoming images.
Now you have a basic ROS2 node that converts images to black and white using OpenCV!
What’s Next?
Try modifying the code to save the black-and-white image to your computer. You can also experiment with other color transformations. This is a great way to learn how to process images, which is a key skill in robotics and self-driving cars!