|
| 1 | +#!/usr/bin/env python3 |
| 2 | +from ada_feeding_msgs.msg import FaceDetection |
| 3 | +from ada_feeding_msgs.srv import ToggleFaceDetection |
| 4 | +import cv2 |
| 5 | +from cv_bridge import CvBridge |
| 6 | +from geometry_msgs.msg import PointStamped |
| 7 | +import rclpy |
| 8 | +from rclpy.node import Node |
| 9 | +from sensor_msgs.msg import Image |
| 10 | +from threading import Lock |
| 11 | + |
| 12 | + |
| 13 | +class FaceDetectionNode(Node): |
| 14 | + def __init__( |
| 15 | + self, |
| 16 | + face_detection_interval=150, |
| 17 | + num_images_with_face=60, |
| 18 | + open_mouth_interval=90, |
| 19 | + num_images_with_open_mouth=30, |
| 20 | + ): |
| 21 | + """ |
| 22 | + Initializes the FaceDetection node, which exposes a ToggleFaceDetection |
| 23 | + service that can be used to toggle the face detection on or off and |
| 24 | + publishes information about detected faces to the /face_detection |
| 25 | + topic when face detection is on. |
| 26 | +
|
| 27 | + After face_detection_interval images without a face, this dummy function |
| 28 | + detects a face for num_images_with_face frames. After open_mouth_interval |
| 29 | + images with a face but without an open mouth, this dummy function |
| 30 | + detects an open mouth for num_images_with_open_mouth frames. |
| 31 | +
|
| 32 | + Parameters: |
| 33 | + ---------- |
| 34 | + face_detection_interval: The number of frames between each face detection. |
| 35 | + num_images_with_face: The number of frames that must have a face in them. |
| 36 | + open_mouth_interval: The number of frames between each open mouth detection. |
| 37 | + num_images_with_open_mouth: The number of frames that must have an open mouth in them. |
| 38 | + """ |
| 39 | + super().__init__("face_detection") |
| 40 | + |
| 41 | + # Internal variables to track when a face and/or open mouth should be detected |
| 42 | + self.face_detection_interval = face_detection_interval |
| 43 | + self.num_images_with_face = num_images_with_face |
| 44 | + self.open_mouth_interval = open_mouth_interval |
| 45 | + self.num_images_with_open_mouth = num_images_with_open_mouth |
| 46 | + self.num_consecutive_images_without_face = 0 |
| 47 | + self.num_consecutive_images_with_face = 0 |
| 48 | + self.num_consecutive_images_without_open_mouth = 0 |
| 49 | + self.num_consecutive_images_with_open_mouth = 0 |
| 50 | + |
| 51 | + # Convert between ROS and CV images |
| 52 | + self.bridge = CvBridge() |
| 53 | + |
| 54 | + # Keeps track of whether face detection is on or not |
| 55 | + self.is_on = False |
| 56 | + self.is_on_lock = Lock() |
| 57 | + |
| 58 | + # Create the service |
| 59 | + self.srv = self.create_service( |
| 60 | + ToggleFaceDetection, |
| 61 | + "ToggleFaceDetection", |
| 62 | + self.toggle_face_detection_callback, |
| 63 | + ) |
| 64 | + |
| 65 | + # Subscribe to the camera feed |
| 66 | + self.subscription = self.create_subscription( |
| 67 | + Image, "camera/color/image_raw", self.camera_callback, 1 |
| 68 | + ) |
| 69 | + self.subscription # prevent unused variable warning |
| 70 | + |
| 71 | + # Create the publishers |
| 72 | + self.publisher_results = self.create_publisher( |
| 73 | + FaceDetection, "face_detection", 1 |
| 74 | + ) |
| 75 | + self.publisher_image = self.create_publisher(Image, "face_detection_img", 1) |
| 76 | + |
| 77 | + def toggle_face_detection_callback(self, request, response): |
| 78 | + """ |
| 79 | + Callback function for the ToggleFaceDetection service. Safely toggles |
| 80 | + the face detection on or off depending on the request. |
| 81 | + """ |
| 82 | + self.get_logger().info( |
| 83 | + "Incoming service request. turn_on: %s" % (request.turn_on) |
| 84 | + ) |
| 85 | + if request.turn_on: |
| 86 | + # Reset counters |
| 87 | + self.num_consecutive_images_without_face = 0 |
| 88 | + self.num_consecutive_images_with_face = 0 |
| 89 | + self.num_consecutive_images_without_open_mouth = 0 |
| 90 | + self.num_consecutive_images_with_open_mouth = 0 |
| 91 | + # Turn on face detection |
| 92 | + self.is_on_lock.acquire() |
| 93 | + self.is_on = True |
| 94 | + self.is_on_lock.release() |
| 95 | + response.face_detection_is_on = True |
| 96 | + else: |
| 97 | + self.is_on_lock.acquire() |
| 98 | + self.is_on = False |
| 99 | + self.is_on_lock.release() |
| 100 | + response.face_detection_is_on = False |
| 101 | + return response |
| 102 | + |
| 103 | + def camera_callback(self, msg): |
| 104 | + """ |
| 105 | + Callback function for the camera feed. If face detection is on, this |
| 106 | + function will detect faces in the image and publish information about |
| 107 | + them to the /face_detection topic. |
| 108 | + """ |
| 109 | + self.is_on_lock.acquire() |
| 110 | + is_on = self.is_on |
| 111 | + self.is_on_lock.release() |
| 112 | + if is_on: |
| 113 | + # Update the number of consecutive images with/without a face |
| 114 | + is_face_detected = False |
| 115 | + if self.num_consecutive_images_with_face == self.num_images_with_face: |
| 116 | + self.num_consecutive_images_without_face = 0 |
| 117 | + self.num_consecutive_images_with_face = 0 |
| 118 | + if self.num_consecutive_images_without_face == self.face_detection_interval: |
| 119 | + # Detect a face |
| 120 | + self.num_consecutive_images_with_face += 1 |
| 121 | + is_face_detected = True |
| 122 | + else: |
| 123 | + # Don't detect a face |
| 124 | + self.num_consecutive_images_without_face += 1 |
| 125 | + |
| 126 | + # Update the number of consecutive images with/without an open mouth |
| 127 | + open_mouth_detected = False |
| 128 | + if is_face_detected: |
| 129 | + if ( |
| 130 | + self.num_consecutive_images_with_open_mouth |
| 131 | + == self.num_images_with_open_mouth |
| 132 | + ): |
| 133 | + self.num_consecutive_images_without_open_mouth = 0 |
| 134 | + self.num_consecutive_images_with_open_mouth = 0 |
| 135 | + if ( |
| 136 | + self.num_consecutive_images_without_open_mouth |
| 137 | + == self.open_mouth_interval |
| 138 | + ): |
| 139 | + # Detect an open mouth |
| 140 | + self.num_consecutive_images_with_open_mouth += 1 |
| 141 | + open_mouth_detected = True |
| 142 | + else: |
| 143 | + # Don't detect an open mouth |
| 144 | + self.num_consecutive_images_without_open_mouth += 1 |
| 145 | + |
| 146 | + # Publish the face detection information |
| 147 | + face_detection_msg = FaceDetection() |
| 148 | + face_detection_msg.is_face_detected = is_face_detected |
| 149 | + if is_face_detected: |
| 150 | + # Add a dummy face marker to the sensor_msgs/Image |
| 151 | + cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8") |
| 152 | + cv2.circle( |
| 153 | + cv_image, |
| 154 | + (msg.width // 2, msg.height // 2), |
| 155 | + msg.height // 25, |
| 156 | + (0, 0, 255), |
| 157 | + -1, |
| 158 | + ) |
| 159 | + annotated_msg = self.bridge.cv2_to_imgmsg(cv_image, "bgr8") |
| 160 | + annotated_img = annotated_msg |
| 161 | + # Publish the detected mouth center |
| 162 | + face_detection_msg.detected_mouth_center = PointStamped() |
| 163 | + face_detection_msg.detected_mouth_center.header = msg.header |
| 164 | + face_detection_msg.detected_mouth_center.point.x = msg.width / 2.0 |
| 165 | + face_detection_msg.detected_mouth_center.point.y = msg.height / 2.0 |
| 166 | + face_detection_msg.detected_mouth_center.point.z = 0.0 |
| 167 | + else: |
| 168 | + annotated_img = msg |
| 169 | + face_detection_msg.is_mouth_open = open_mouth_detected |
| 170 | + self.publisher_results.publish(face_detection_msg) |
| 171 | + self.publisher_image.publish(annotated_img) |
| 172 | + |
| 173 | + |
| 174 | +def main(args=None): |
| 175 | + rclpy.init(args=args) |
| 176 | + |
| 177 | + face_detection = FaceDetectionNode() |
| 178 | + |
| 179 | + rclpy.spin(face_detection) |
| 180 | + |
| 181 | + rclpy.shutdown() |
| 182 | + |
| 183 | + |
| 184 | +if __name__ == "__main__": |
| 185 | + main() |
0 commit comments