|
@@ -0,0 +1,30 @@
|
|
|
+#!/usr/bin/env python
|
|
|
+import rospy, cv2, cv_bridge
|
|
|
+import face_recognition
|
|
|
+from sensor_msgs.msg import Image
|
|
|
+
|
|
|
+class Face_Detection:
|
|
|
+
|
|
|
+ def __init__(self):
|
|
|
+ self.bridge = cv_bridge.CvBridge()
|
|
|
+ self.image_sub = rospy.Subscriber("/usb_cam/image_raw", Image, self.image_callback)
|
|
|
+
|
|
|
+ def image_callback(self, msg):
|
|
|
+ image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8")
|
|
|
+ image_resize = cv2.resize(image, (0, 0), fx=0.25, fy=0.25)
|
|
|
+
|
|
|
+ face_locations = face_recognition.face_locations(image_resize)
|
|
|
+
|
|
|
+ for (top, right, bottom, left) in face_locations:
|
|
|
+ top *= 4
|
|
|
+ right *= 4
|
|
|
+ bottom *= 4
|
|
|
+ left *= 4
|
|
|
+ cv2.rectangle(image, (left, top), (right, bottom), (0, 0, 255), 2)
|
|
|
+ cv2.imshow("face_detection", image)
|
|
|
+ cv2.waitKey(3)
|
|
|
+
|
|
|
+if __name__ == '__main__':
|
|
|
+ rospy.init_node("face_detection_adam")
|
|
|
+ Face_Detection()
|
|
|
+ rospy.spin()
|