Skip to content

Commit

Permalink
feat: face detection/recognition skills (LASR-at-Home#195)
Browse files Browse the repository at this point in the history
* refactor: detect -> recognise

* refactor: detect_face -> _extract_face.

* WIP

* fix: dumb bug.

* refactor: remove erratic comment.

* feat: DetectFaces and Recognise skills.
  • Loading branch information
jws-1 authored May 7, 2024
1 parent d8fbf4f commit 52dfe45
Show file tree
Hide file tree
Showing 12 changed files with 278 additions and 90 deletions.
5 changes: 3 additions & 2 deletions common/vision/lasr_vision_deepface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ find_package(catkin REQUIRED catkin_virtualenv)
catkin_python_setup()
catkin_generate_virtualenv(
INPUT_REQUIREMENTS requirements.in
PYTHON_INTERPRETER python3.10
PYTHON_INTERPRETER python3.8
)

################################################
Expand Down Expand Up @@ -161,7 +161,8 @@ include_directories(
## in contrast to setup.py, you can choose the destination
catkin_install_python(PROGRAMS
scripts/create_dataset
examples/relay
examples/relay_recognise
examples/relay_detect_faces
examples/greet
nodes/service
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
Expand Down
54 changes: 54 additions & 0 deletions common/vision/lasr_vision_deepface/examples/relay_detect_faces
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
#!/usr/bin/env python3

import sys
import rospy
import threading

from sensor_msgs.msg import Image

from lasr_vision_msgs.srv import DetectFaces, DetectFacesRequest

if len(sys.argv) < 2:
print("Usage: rosrun lasr_vision_deepface relay <source_topic>")
exit()

listen_topic = sys.argv[1]

processing = False


def detect(image):
global processing
processing = True
rospy.loginfo("Received image message")

try:
detect_service = rospy.ServiceProxy("/detect_faces", DetectFaces)
req = DetectFacesRequest()
req.image_raw = image
resp = detect_service(req)
print(resp)
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s" % e)
finally:
processing = False


def image_callback(image):
global processing
if processing:
return

t = threading.Thread(target=detect, args=(image,))
t.start()


def listener():
rospy.init_node("image_listener", anonymous=True)
rospy.wait_for_service("/recognise")
rospy.Subscriber(listen_topic, Image, image_callback)
rospy.spin()


if __name__ == "__main__":
listener()
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ from sensor_msgs.msg import Image
from lasr_vision_msgs.srv import Recognise, RecogniseRequest

if len(sys.argv) < 3:
print("Usage: rosrun lase_recognition relay <source_topic> <dataset>")
print("Usage: rosrun lasr_vision_deepface relay <source_topic> <dataset>")
exit()

listen_topic = sys.argv[1]
Expand Down
29 changes: 20 additions & 9 deletions common/vision/lasr_vision_deepface/nodes/service
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

import re
import rospy
import lasr_vision_deepface as face_recognition
import lasr_vision_deepface.deepface as face_recognition
from sensor_msgs.msg import Image
from lasr_vision_msgs.srv import (
Recognise,
Expand All @@ -11,6 +11,9 @@ from lasr_vision_msgs.srv import (
LearnFace,
LearnFaceRequest,
LearnFaceResponse,
DetectFaces,
DetectFacesRequest,
DetectFacesResponse,
)


Expand All @@ -21,6 +24,8 @@ DEBUG = rospy.get_param("~debug", False)

recognise_debug_publishers = {}
learn_face_debug_publishers = {}
detect_faces_debug_publisher = None

if DEBUG:
recognise_debug_publisher = rospy.Publisher("/recognise/debug", Image, queue_size=1)
learn_face_debug_publisher = rospy.Publisher(
Expand All @@ -29,19 +34,20 @@ if DEBUG:
cropped_face_publisher = rospy.Publisher(
"/learn_face/debug/cropped_query_face", Image, queue_size=1
)
detect_faces_debug_publisher = rospy.Publisher(
"/detect_faces/debug", Image, queue_size=1
)


def detect(request: RecogniseRequest) -> RecogniseResponse:
def recognise(request: RecogniseRequest) -> RecogniseResponse:
debug_publisher = None
similar_face_debug_publisher = None
cropped_face_publisher = None
if DEBUG:
if request.dataset in recognise_debug_publishers:
debug_publisher = recognise_debug_publishers[request.dataset][0]
similar_face_debug_publisher = recognise_debug_publishers[request.dataset][
1
]
cropped_face_publisher = recognise_debug_publisher[request.dataset][2]
debug_publisher, similar_face_debug_publisher, cropped_face_publisher = (
recognise_debug_publishers[request.dataset]
)
else:
topic_name = re.sub(r"[\W_]+", "", request.dataset)
debug_publisher = rospy.Publisher(
Expand All @@ -58,7 +64,7 @@ def detect(request: RecogniseRequest) -> RecogniseResponse:
similar_face_debug_publisher,
cropped_face_publisher,
)
return face_recognition.detect(
return face_recognition.recognise(
request, debug_publisher, similar_face_debug_publisher, cropped_face_publisher
)

Expand All @@ -83,7 +89,12 @@ def learn_face(request: LearnFaceRequest) -> LearnFaceResponse:
return LearnFaceResponse()


rospy.Service("/recognise", Recognise, detect)
def detect_faces(request: DetectFacesRequest) -> DetectFacesResponse:
return face_recognition.detect_faces(request, detect_faces_debug_publisher)


rospy.Service("/recognise", Recognise, recognise)
rospy.Service("/learn_face", LearnFace, learn_face)
rospy.Service("/detect_faces", DetectFaces, detect_faces)
rospy.loginfo("Face Recognition service started")
rospy.spin()
3 changes: 2 additions & 1 deletion common/vision/lasr_vision_deepface/requirements.in
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
deepface==0.0.83
deepface==0.0.91
tensorflow==2.9.0
numpy>=1.2.1
97 changes: 50 additions & 47 deletions common/vision/lasr_vision_deepface/requirements.txt
Original file line number Diff line number Diff line change
@@ -1,65 +1,68 @@
absl-py==2.1.0 # via tensorboard, tensorflow
astunparse==1.6.3 # via tensorflow
beautifulsoup4==4.12.3 # via gdown
blinker==1.7.0 # via flask
cachetools==5.3.2 # via google-auth
certifi==2023.11.17 # via requests
blinker==1.8.1 # via flask
cachetools==5.3.3 # via google-auth
certifi==2024.2.2 # via requests
charset-normalizer==3.3.2 # via requests
click==8.1.7 # via flask
deepface==0.0.83 # via -r requirements.in
filelock==3.13.1 # via gdown
fire==0.5.0 # via deepface
flask==3.0.1 # via deepface
flatbuffers==23.5.26 # via tensorflow
gast==0.5.4 # via tensorflow
gdown==5.0.1 # via deepface, retina-face
google-auth==2.27.0 # via google-auth-oauthlib, tensorboard
google-auth-oauthlib==1.2.0 # via tensorboard
deepface==0.0.91 # via -r requirements.in
filelock==3.14.0 # via gdown
fire==0.6.0 # via deepface
flask==3.0.3 # via deepface
flatbuffers==1.12 # via tensorflow
gast==0.4.0 # via tensorflow
gdown==5.1.0 # via deepface, retina-face
google-auth==2.29.0 # via google-auth-oauthlib, tensorboard
google-auth-oauthlib==0.4.6 # via tensorboard
google-pasta==0.2.0 # via tensorflow
grpcio==1.60.0 # via tensorboard, tensorflow
gunicorn==21.2.0 # via deepface
h5py==3.10.0 # via tensorflow
idna==3.6 # via requests
itsdangerous==2.1.2 # via flask
grpcio==1.63.0 # via tensorboard, tensorflow
gunicorn==22.0.0 # via deepface
h5py==3.11.0 # via tensorflow
idna==3.7 # via requests
importlib-metadata==7.1.0 # via flask, markdown
itsdangerous==2.2.0 # via flask
jinja2==3.1.3 # via flask
keras==2.15.0 # via deepface, mtcnn, tensorflow
libclang==16.0.6 # via tensorflow
markdown==3.5.2 # via tensorboard
markupsafe==2.1.4 # via jinja2, werkzeug
ml-dtypes==0.2.0 # via tensorflow
keras==2.9.0 # via deepface, mtcnn, tensorflow
keras-preprocessing==1.1.2 # via tensorflow
libclang==18.1.1 # via tensorflow
markdown==3.6 # via tensorboard
markupsafe==2.1.5 # via jinja2, werkzeug
mtcnn==0.1.1 # via deepface
numpy==1.26.3 # via -r requirements.in, deepface, h5py, ml-dtypes, opencv-python, opt-einsum, pandas, retina-face, tensorboard, tensorflow
numpy==1.24.4 # via -r requirements.in, deepface, h5py, keras-preprocessing, opencv-python, opt-einsum, pandas, retina-face, tensorboard, tensorflow
oauthlib==3.2.2 # via requests-oauthlib
opencv-python==4.9.0.80 # via deepface, mtcnn, retina-face
opt-einsum==3.3.0 # via tensorflow
packaging==23.2 # via gunicorn, tensorflow
pandas==2.2.0 # via deepface
pillow==10.2.0 # via deepface, retina-face
protobuf==4.23.4 # via tensorboard, tensorflow
pyasn1==0.5.1 # via pyasn1-modules, rsa
pyasn1-modules==0.3.0 # via google-auth
packaging==24.0 # via gunicorn, tensorflow
pandas==2.0.3 # via deepface
pillow==10.3.0 # via deepface, retina-face
protobuf==3.19.6 # via tensorboard, tensorflow
pyasn1==0.6.0 # via pyasn1-modules, rsa
pyasn1-modules==0.4.0 # via google-auth
pysocks==1.7.1 # via requests
python-dateutil==2.8.2 # via pandas
pytz==2023.4 # via pandas
requests[socks]==2.31.0 # via gdown, requests-oauthlib, tensorboard
requests-oauthlib==1.3.1 # via google-auth-oauthlib
retina-face==0.0.14 # via deepface
python-dateutil==2.9.0.post0 # via pandas
pytz==2024.1 # via pandas
requests[socks]==2.31.0 # via deepface, gdown, requests-oauthlib, tensorboard
requests-oauthlib==2.0.0 # via google-auth-oauthlib
retina-face==0.0.17 # via deepface
rsa==4.9 # via google-auth
six==1.16.0 # via astunparse, fire, google-pasta, python-dateutil, tensorboard, tensorflow
six==1.16.0 # via astunparse, fire, google-pasta, keras-preprocessing, python-dateutil, tensorflow
soupsieve==2.5 # via beautifulsoup4
tensorboard==2.15.1 # via tensorflow
tensorboard-data-server==0.7.2 # via tensorboard
tensorflow==2.15.0.post1 # via deepface, retina-face
tensorflow-estimator==2.15.0 # via tensorflow
tensorflow-io-gcs-filesystem==0.35.0 # via tensorflow
tensorboard==2.9.1 # via tensorflow
tensorboard-data-server==0.6.1 # via tensorboard
tensorboard-plugin-wit==1.8.1 # via tensorboard
tensorflow==2.9.0 # via -r requirements.in, deepface, retina-face
tensorflow-estimator==2.9.0 # via tensorflow
tensorflow-io-gcs-filesystem==0.34.0 # via tensorflow
termcolor==2.4.0 # via fire, tensorflow
tqdm==4.66.1 # via deepface, gdown
typing-extensions==4.9.0 # via tensorflow
tzdata==2023.4 # via pandas
urllib3==2.1.0 # via requests
werkzeug==3.0.1 # via flask, tensorboard
wheel==0.42.0 # via astunparse
wrapt==1.14.1 # via tensorflow
tqdm==4.66.4 # via deepface, gdown
typing-extensions==4.11.0 # via tensorflow
tzdata==2024.1 # via pandas
urllib3==2.2.1 # via requests
werkzeug==3.0.2 # via flask, tensorboard
wheel==0.43.0 # via astunparse, tensorboard
wrapt==1.16.0 # via tensorflow
zipp==3.18.1 # via importlib-metadata

# The following packages are considered to be unsafe in a requirements file:
# setuptools
Loading

0 comments on commit 52dfe45

Please sign in to comment.