ROS2 Face Detection Project
It is now time for us to go a bit more further.
We will modify and upgrade the camera stream publisher node from our camera stream project to capture a video stream from a camera, detect the faces inside the stream, overlay a rectangle over each detected faces and publish the overlayed image to the video stream topic.
We will also reuse the camera stream subscriber node to subscribe to the camera topic and display it in an OpenCV window.
Create a new package with dependencies.
$ cd ~/ros2_ws/src
$ ros2 pkg create --build-type ament_python face_detector --dependencies rclpy image_transport cv_bridge sensor_msgs std_msgs opencv-python
Create the face_detector_publisher.py file and populate it with the following code:
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import os
class FaceDetectorPub(Node):
"""
Create a FaceDetectorPub class, which is a subclass of the Node class.
"""
def __init__(self):
"""
Class constructor to set up the node.
"""
# Initiate the Node class's constructor and give it a name.
super().__init__('face_detector_pub')
# Create the publisher. This publisher will publish an Image
# to the video_frame_data topic. The queue size is 10 messages.
self.publisher_ = self.create_publisher(Image, 'video_frame_data', 10)
# We will publish a message every 0.1 seconds.
timer_period = 0.1 # seconds
# Create the timer.
self.timer = self.create_timer(timer_period, self.timer_callback)
# Create a VideoCapture object.
# The argument '0' gets the default webcam.
self.cap = cv2.VideoCapture(0)
# Used to convert between ROS and OpenCV images.
self.br = CvBridge()
# Load the haar cascade classifier.
self.haar_path = os.path.expanduser('~') + '/ros2_ws/src/face_detector/resource/haar_classifier.xml'
self.face_cascade = cv2.CascadeClassifier(self.haar_path)
def timer_callback(self):
"""
Callback function.
This function gets called every 0.1 seconds.
"""
# Capture frame-by-frame.
# This method returns True/False as well
# as the video frame.
ret, frame = self.cap.read()
# Convert to gray scale image.
frame_gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
## Detect faces & returns positions of faces as Rect(x,y,w,h).
face_rects = self.face_cascade.detectMultiScale(frame_gray, 1.3, 5)
# Draw rectangles representing the detected faces.
for (x, y, w, h) in face_rects:
cv2.rectangle(frame, (x, y), (x + w, y + h), (255, 0, 0), 2)
if ret == True:
# Publish the image.
# The 'cv2_to_imgmsg' method converts an OpenCV
# image to a ROS 2 image message.
self.publisher_.publish(self.br.cv2_to_imgmsg(frame))
def release_camera(self):
"""
Release the camera when done.
"""
self.cap.release()
def main(args=None):
"""
Main function to initialize the node and start the face detector publisher.
"""
# Initialize the rclpy library.
rclpy.init(args=args)
# Create the node.
face_detector_publisher_node = FaceDetectorPub()
# Spin the node so the callback function is called.
try:
rclpy.spin(face_detector_publisher_node)
finally:
# Release the camera.
face_detector_publisher_node.release_camera()
# Destroy the node explicitly.
face_detector_publisher_node.destroy_node()
# Shutdown the ROS client library for Python.
rclpy.shutdown()
if __name__ == '__main__':
main()
For the face detection, we will use a machine learning based approach called haar cascade.
Even though it is particularly popular for detecting faces, it can be trained to detect other objects as well.
This approach has the ability to rapidly evaluate features at multiple scales and efficiently reject background regions.
OpenCV includes support for haar cascades for object detection, including face detection.
This is carried out using pre-trained Haar cascade classifiers for various objects, including faces.
Trained face detection cascade values are provided in the form of an xml file. You can download the xml from here.
Put this haar cascade xml file in the resource folder inside the package.
Add the entry points to setup.py inside console_scripts section:
'face_detector_pub = face_detector.face_detector_publisher:main',
Since we already specified our dependencies during the package creation itself, we do not need to edit the package.xml file.
Build the package.
$ cd ~/ros2_ws
$ colcon build --packages-select face_detector
Source the new package.
$ source install/setup.bash
Run the face detector publisher node to start publishing the camera frames.
$ ros2 run face_detector face_detector_pub
Run the camera stream subscriber node in a separate terminal.
$ cd ~/ros2_ws
$ source install/setup.bash$ ros2 run camera_stream camera_stream_sub
The camera frames with the detected faces will be displayed in an OpenCV window.
Press ESC on the active OpenCV window to exit.