Skip to content

Commit c5615ee

Browse files
Pavlos-Tosidispassalis
andauthoredFeb 11, 2022
Face Recognition ROS and bug fixes (#219)
* This commit contains: 1. face_recognition.py script and perception README.md update 2. updated benchmarking_demo.py to correctly measure GPU memory allocation 3. Added torch setting in model_mobilenet.py for faster CPU inference 4. Sped up utils.py pair generation script 5. Fixed a minor bug in face_recognition_learner.py * This commit contains: 1. face_recognition.py script and perception README.md update 2. updated benchmarking_demo.py to correctly measure GPU memory allocation 3. Added torch setting in model_mobilenet.py for faster CPU inference 4. Sped up utils.py pair generation script 5. Fixed a minor bug in face_recognition_learner.py 6. Added create_new flag on face_recognition_learner.fit_reference() * Update docs/reference/face-recognition.md Co-authored-by: Nikolaos Passalis <[email protected]> * Update benchmarking_demo.py * Update benchmarking_demo.py Co-authored-by: Nikolaos Passalis <[email protected]>
1 parent 2280fd3 commit c5615ee

File tree

9 files changed

+132
-92
lines changed

9 files changed

+132
-92
lines changed
 

‎docs/reference/face-recognition.md

+3-1
Original file line numberDiff line numberDiff line change
@@ -152,7 +152,7 @@ When 'ExternalDataset' is of type 'ImageFolder', images should be placed in a de
152152

153153
#### `FaceRecognitionLearner.fit_reference`
154154
```python
155-
FaceRecognitionLearner.fit_reference(self, path, save_path)
155+
FaceRecognitionLearner.fit_reference(self, path, save_path, create_new)
156156
```
157157

158158
This method is used to create a reference database to be used in inference when mode='backbone_only'.
@@ -164,6 +164,8 @@ Parameters:
164164
Path containing the reference images. If a reference database was already created can be left blank.
165165
- **save_path**: *str, default=None*\
166166
Path to save (load if already created) the .pkl reference file.
167+
- **create_new**: *bool, default=True*\
168+
Whether to create a new or load an existing .pkl reference file.
167169

168170
**Notes**
169171

‎projects/opendr_ws/src/perception/README.md

+20-19
Original file line numberDiff line numberDiff line change
@@ -23,49 +23,50 @@ rosrun perception image_dataset.py
2323
By default, it downloads a `nano_MOT20` dataset from OpenDR's FTP server and uses it to publish data to the ROS topic. You can create an instance of this node with any `DatasetIterator` object that returns `(Image, Target)` as elements.
2424

2525
## Pose Estimation ROS Node
26-
Assuming that you have already [built your workspace](../../README.md) and started roscore (i.e., just run `roscore`), then you can
27-
28-
29-
1. Add OpenDR to `PYTHONPATH` (please make sure you do not overwrite `PYTHONPATH` ), e.g.,
30-
```shell
31-
export PYTHONPATH="/home/user/opendr/src:$PYTHONPATH"
32-
```
26+
Assuming that you have already [activated the OpenDR environment](../../../../docs/reference/installation.md), [built your workspace](../../README.md) and started roscore (i.e., just run `roscore`), then you can
3327

34-
2. Start the node responsible for publishing images. If you have a usb camera, then you can use the corresponding node (assuming you have installed the corresponding package):
28+
1. Start the node responsible for publishing images. If you have a usb camera, then you can use the corresponding node (assuming you have installed the corresponding package):
3529

3630
```shell
3731
rosrun usb_cam usb_cam_node
3832
```
3933

40-
3. You are then ready to start the pose detection node
34+
2. You are then ready to start the pose detection node
4135

4236
```shell
4337
rosrun perception pose_estimation.py
4438
```
4539

46-
4. You can examine the annotated image stream using `rqt_image_view` (select the topic `/opendr/image_pose_annotated`) or
40+
3. You can examine the annotated image stream using `rqt_image_view` (select the topic `/opendr/image_pose_annotated`) or
4741
`rostopic echo /opendr/poses`
4842

4943
## Face Recognition ROS Node
50-
Assuming that you have already [built your workspace](../../README.md) and started roscore (i.e., just run `roscore`), then you can
44+
Assuming that you have already [activated the OpenDR environment](../../../../docs/reference/installation.md), [built your workspace](../../README.md) and started roscore (i.e., just run `roscore`), then you can
5145

5246

53-
1. Add OpenDR to `PYTHONPATH` (please make sure you do not overwrite `PYTHONPATH` ), e.g.,
54-
```shell
55-
export PYTHONPATH="/home/user/opendr/src:$PYTHONPATH"
56-
```
57-
58-
2. Start the node responsible for publishing images. If you have a usb camera, then you can use the corresponding node (assuming you have installed the corresponding package):
47+
1. Start the node responsible for publishing images. If you have a usb camera, then you can use the corresponding node (assuming you have installed the corresponding package):
5948

6049
```shell
6150
rosrun usb_cam usb_cam_node
6251
```
6352

64-
3. You are then ready to start the face recognition node
53+
2. You are then ready to start the face recognition node. Note that you should pass the folder containing the images of known faces as argument to create the corresponding database of known persons.
6554

6655
```shell
67-
rosrun perception face_recognition.py
56+
rosrun perception face_recognition.py _database_path:='./database'
6857
```
58+
**Notes**
59+
60+
Reference images should be placed in a defined structure like:
61+
- imgs
62+
- ID1
63+
- image1
64+
- image2
65+
- ID2
66+
- ID3
67+
- ...
68+
69+
Τhe name of the sub-folder, e.g. ID1, will be published under `/opendr/face_recognition_id`.
6970

7071
4. The database entry and the returned confidence is published under the topic name `/opendr/face_recognition`, and the human-readable ID
7172
under `/opendr/face_recognition_id`.

‎projects/opendr_ws/src/perception/scripts/face_recognition.py

+70-46
Original file line numberDiff line numberDiff line change
@@ -20,13 +20,18 @@
2020
from std_msgs.msg import String
2121
from sensor_msgs.msg import Image as ROS_Image
2222
from opendr_bridge import ROSBridge
23+
2324
from opendr.perception.face_recognition import FaceRecognitionLearner
25+
from opendr.perception.object_detection_2d import RetinaFaceLearner
26+
from opendr.perception.object_detection_2d.datasets.transforms import BoundingBoxListToNumpyArray
2427

2528

2629
class FaceRecognitionNode:
2730

28-
def __init__(self, input_image_topic="/usb_cam/image_raw", face_recognition_topic="/opendr/face_recognition",
29-
face_id_topic="/opendr/face_recognition_id", database_path="./database", device="cuda",
31+
def __init__(self, input_image_topic="/usb_cam/image_raw",
32+
face_recognition_topic="/opendr/face_recognition",
33+
face_id_topic="/opendr/face_recognition_id",
34+
database_path="./database", device="cuda",
3035
backbone='mobilefacenet'):
3136
"""
3237
Creates a ROS Node for face recognition
@@ -42,6 +47,18 @@ def __init__(self, input_image_topic="/usb_cam/image_raw", face_recognition_topi
4247
:type device: str
4348
"""
4449

50+
# Initialize the face recognizer
51+
self.recognizer = FaceRecognitionLearner(device=device, mode='backbone_only', backbone=backbone)
52+
self.recognizer.download(path=".")
53+
self.recognizer.load(".")
54+
self.recognizer.fit_reference(database_path, save_path=".", create_new=True)
55+
56+
# Initialize the face detector
57+
self.face_detector = RetinaFaceLearner(backbone='mnet', device=device)
58+
self.face_detector.download(path=".", verbose=True)
59+
self.face_detector.load("retinaface_{}".format('mnet'))
60+
self.class_names = ["face", "masked_face"]
61+
4562
if face_recognition_topic is not None:
4663
self.face_publisher = rospy.Publisher(face_recognition_topic, ObjectHypothesis, queue_size=10)
4764
else:
@@ -52,61 +69,54 @@ def __init__(self, input_image_topic="/usb_cam/image_raw", face_recognition_topi
5269
else:
5370
self.face_id_publisher = None
5471

55-
rospy.Subscriber(input_image_topic, ROS_Image, self.callback)
56-
5772
self.bridge = ROSBridge()
58-
59-
# Initialize the pose estimation
60-
self.recognizer = FaceRecognitionLearner(device=device, mode='backbone_only', backbone=backbone)
61-
self.recognizer.download(path=".")
62-
self.recognizer.load(".")
63-
self.recognizer.fit_reference(database_path, save_path=".")
64-
65-
def listen(self):
66-
"""
67-
Start the node and begin processing input data
68-
"""
69-
rospy.init_node('opendr_face_recognition', anonymous=True)
70-
rospy.loginfo("Face recognition node started!")
71-
rospy.spin()
73+
rospy.Subscriber(input_image_topic, ROS_Image, self.callback)
7274

7375
def callback(self, data):
7476
"""
7577
Callback that process the input data and publishes to the corresponding topics
7678
:param data: input message
7779
:type data: sensor_msgs.msg.Image
7880
"""
79-
8081
# Convert sensor_msgs.msg.Image into OpenDR Image
8182
image = self.bridge.from_ros_image(data)
8283
image = image.opencv()
8384

84-
# Run face recognition
85+
# Run face detection and recognition
8586
if image is not None:
86-
result = self.recognizer.infer(image)
87-
if result.data is not None:
88-
if self.face_publisher is not None:
89-
ros_face = self.bridge.to_ros_face(result)
90-
self.face_publisher.publish(ros_face)
91-
92-
if self.face_id_publisher is not None:
93-
ros_face_id = self.bridge.to_ros_face_id(result)
94-
self.face_id_publisher.publish(ros_face_id.data)
95-
96-
else:
97-
result.description = "Unknown"
98-
if self.face_publisher is not None:
99-
ros_face = self.bridge.to_ros_face(result)
100-
self.face_publisher.publish(ros_face)
101-
102-
if self.face_id_publisher is not None:
103-
ros_face_id = self.bridge.to_ros_face_id(result)
104-
self.face_id_publisher.publish(ros_face_id.data)
105-
106-
# We get can the data back using self.bridge.from_ros_face(ros_face)
107-
# e.g.
108-
# face = self.bridge.from_ros_face(ros_face)
109-
# face.description = self.recognizer.database[face.id][0]
87+
bounding_boxes = self.face_detector.infer(image)
88+
if bounding_boxes:
89+
bounding_boxes = BoundingBoxListToNumpyArray()(bounding_boxes)
90+
boxes = bounding_boxes[:, :4]
91+
for idx, box in enumerate(boxes):
92+
(startX, startY, endX, endY) = int(box[0]), int(box[1]), int(box[2]), int(box[3])
93+
img = image[startY:endY, startX:endX]
94+
result = self.recognizer.infer(img)
95+
96+
if result.data is not None:
97+
if self.face_publisher is not None:
98+
ros_face = self.bridge.to_ros_face(result)
99+
self.face_publisher.publish(ros_face)
100+
101+
if self.face_id_publisher is not None:
102+
ros_face_id = self.bridge.to_ros_face_id(result)
103+
self.face_id_publisher.publish(ros_face_id.data)
104+
105+
else:
106+
result.description = "Unknown"
107+
if self.face_publisher is not None:
108+
ros_face = self.bridge.to_ros_face(result)
109+
self.face_publisher.publish(ros_face)
110+
111+
if self.face_id_publisher is not None:
112+
ros_face_id = self.bridge.to_ros_face_id(result)
113+
self.face_id_publisher.publish(ros_face_id.data)
114+
115+
# We get can the data back using self.bridge.from_ros_face(ros_face)
116+
# e.g.
117+
# face = self.bridge.from_ros_face(ros_face)
118+
# face.description = self.recognizer.database[face.id][0]
119+
110120

111121
if __name__ == '__main__':
112122
# Select the device for running the
@@ -120,5 +130,19 @@ def callback(self, data):
120130
except:
121131
device = 'cpu'
122132

123-
face_recognition_node = FaceRecognitionNode(device=device)
124-
face_recognition_node.listen()
133+
# initialize ROS node
134+
rospy.init_node('opendr_face_recognition', anonymous=True)
135+
rospy.loginfo("Face recognition node started!")
136+
137+
# get network backbone
138+
backbone = rospy.get_param("~backbone", "mobilefacenet")
139+
input_image_topic = rospy.get_param("~input_image_topic", "/usb_cam/image_raw")
140+
database_path = rospy.get_param('~database_path', './')
141+
rospy.loginfo("Using backbone: {}".format(backbone))
142+
assert backbone in ["mobilefacenet", "ir_50"], "backbone should be one of ['mobilefacenet', 'ir_50']"
143+
144+
face_recognition_node = FaceRecognitionNode(device=device, backbone=backbone,
145+
input_image_topic=input_image_topic,
146+
database_path=database_path)
147+
# begin ROS communications
148+
rospy.spin()

‎projects/perception/face_recognition/demos/benchmarking_demo.py

+21-15
Original file line numberDiff line numberDiff line change
@@ -25,40 +25,46 @@
2525
parser.add_argument("--onnx", help="Use ONNX", default=False, action="store_true")
2626
parser.add_argument("--backbone", help="Backbone to use (mobilefacenet, ir_50)", type=str, default='mobilefacenet')
2727
parser.add_argument("--device", help="Device to use (cpu, cuda)", type=str, default="cuda")
28+
parser.add_argument("--create_new", help="Whether to create or load a database", type=bool, default=True)
2829
args = parser.parse_args()
2930

3031
onnx, device, backbone = args.onnx, args.device, args.backbone
31-
32+
nvml = False
33+
try:
34+
if 'cuda' in device:
35+
from pynvml import nvmlInit, nvmlDeviceGetMemoryInfo, nvmlDeviceGetHandleByIndex
36+
nvmlInit()
37+
nvml = True
38+
except ImportError:
39+
print('You can install pynvml to also monitor the allocated GPU memory')
40+
pass
41+
if nvml:
42+
info_before = nvmlDeviceGetMemoryInfo(nvmlDeviceGetHandleByIndex(0))
43+
info_before = info_before.used / 1024 ** 2
3244
recognizer = FaceRecognitionLearner(device=device, backbone=backbone, mode='backbone_only')
3345
recognizer.download(path=".")
3446
recognizer.load(path=".")
35-
47+
if nvml:
48+
info_after = nvmlDeviceGetMemoryInfo(nvmlDeviceGetHandleByIndex(0))
49+
info_after = info_after.used / 1024 ** 2
3650
# Download one sample image
3751
recognizer.download(path=".", mode="test_data")
38-
recognizer.fit_reference("./test_data", ".")
52+
recognizer.fit_reference("./test_data", ".", create_new=args.create_new)
3953
image_path = join(".", "test_data", "images", "1", "1.jpg")
4054
img = cv2.imread(image_path)
4155

4256
if onnx:
4357
recognizer.optimize()
4458

4559
fps_list = []
60+
4661
print("Benchmarking...")
47-
for i in tqdm(range(50)):
62+
for i in tqdm(range(100)):
4863
start_time = time.perf_counter()
4964
# Perform inference
5065
result = recognizer.infer(img)
5166
end_time = time.perf_counter()
5267
fps_list.append(1.0 / (end_time - start_time))
5368
print("Average FPS: %.2f" % (np.mean(fps_list)))
54-
55-
# If pynvml is available, try to get memory stats for cuda
56-
try:
57-
if 'cuda' in device:
58-
from pynvml import nvmlInit, nvmlDeviceGetMemoryInfo, nvmlDeviceGetHandleByIndex
59-
60-
nvmlInit()
61-
info = nvmlDeviceGetMemoryInfo(nvmlDeviceGetHandleByIndex(0))
62-
print("Memory allocated: %.2f MB " % (info.used / 1024 ** 2))
63-
except ImportError:
64-
pass
69+
if nvml:
70+
print("Memory allocated: %.2f MB " % (info_after - info_before))

‎projects/perception/face_recognition/demos/inference_demo.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
recognizer.load(".")
3333

3434
recognizer.download(path=".", mode="test_data")
35-
recognizer.fit_reference(path=join(".", "test_data", "images"), save_path=".")
35+
recognizer.fit_reference(path=join(".", "test_data", "images"), save_path=".", create_new=True)
3636
image_path = join(".", "test_data", "images", "1", "1.jpg")
3737
img = Image.open(image_path)
3838

‎projects/perception/face_recognition/demos/inference_tutorial.ipynb

+2-2
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@
117117
"id": "Ms6Xj8GDYt5C"
118118
},
119119
"source": [
120-
"When we have the sample images, we need to create a reference database of our known people:"
120+
"When we have the sample images, we need to create a reference database of our known people (if we already created one we can set 'create_new=False' to load the existing database):"
121121
]
122122
},
123123
{
@@ -137,7 +137,7 @@
137137
],
138138
"source": [
139139
"from os.path import join\n",
140-
"recognizer.fit_reference(path=join(\".\", \"test_data\", \"images\"), save_path=\".\")"
140+
"recognizer.fit_reference(path=join(\".\", \"test_data\", \"images\"), save_path=\".\", create_new=True)"
141141
]
142142
},
143143
{

‎src/opendr/perception/face_recognition/algorithm/backbone/model_mobilenet.py

+5
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,9 @@
11
from torch import nn
2+
import torch
3+
import warnings
4+
5+
warnings.simplefilter("ignore", UserWarning)
6+
torch.set_flush_denormal(True)
27

38

49
def _make_divisible(v, divisor, min_value=None):

‎src/opendr/perception/face_recognition/algorithm/util/utils.py

+4-5
Original file line numberDiff line numberDiff line change
@@ -184,7 +184,8 @@ def hflip_batch(imgs_tensor):
184184

185185

186186
def ccrop_batch(imgs_tensor):
187-
ccropped_imgs = torch.empty_like(imgs_tensor)
187+
ccropped_imgs = torch.empty((len(imgs_tensor),
188+
imgs_tensor[0].shape[0], imgs_tensor[0].shape[1], imgs_tensor[0].shape[2]))
188189
for i, img_ten in enumerate(imgs_tensor):
189190
ccropped_imgs[i] = ccrop(img_ten)
190191

@@ -247,14 +248,12 @@ def perform_val_imagefolder(device, embedding_size, batch_size, backbone, carray
247248
transforms.Normalize(mean=[0.5, 0.5, 0.5],
248249
std=[0.5, 0.5, 0.5])])
249250
for i in range(len(image1)):
250-
image1[i] = np.array(transform(Image.open(image1[i])))
251-
image2[i] = np.array(transform(Image.open(image2[i])))
251+
image1[i] = transform(Image.open(image1[i]))
252+
image2[i] = transform(Image.open(image2[i]))
252253
if labels[i] == 'True':
253254
pairs.append(True)
254255
else:
255256
pairs.append(False)
256-
image1 = torch.tensor(image1)
257-
image2 = torch.tensor(image2)
258257
if tta:
259258
ccropped = ccrop_batch(image1)
260259
fliped = hflip_batch(ccropped)

‎src/opendr/perception/face_recognition/face_recognition_learner.py

+6-3
Original file line numberDiff line numberDiff line change
@@ -385,7 +385,7 @@ def fit(self, dataset, val_dataset=None, logging_path='', silent=False, verbose=
385385

386386
return {'Training_statistics': results, 'Evaluation_statistics': eval_results}
387387

388-
def fit_reference(self, path=None, save_path=None):
388+
def fit_reference(self, path=None, save_path=None, create_new=True):
389389
"""
390390
Implementation to create reference database. Provided with a path with reference images and a save_path,
391391
it creates a .pkl file containing the features of the reference images, and saves it
@@ -394,10 +394,13 @@ def fit_reference(self, path=None, save_path=None):
394394
:type path: str
395395
:param save_path: path to save the .pkl file
396396
:type save_path: str
397+
:param create_new: create new reference.pkl file. If false it will attempt to load an existing reference.pkl
398+
file from save_path.
399+
:type create_new: bool, default=True
397400
"""
398401
if self._model is None and self.ort_backbone_session is None:
399402
raise UserWarning('A model should be loaded first')
400-
if os.path.exists(os.path.join(save_path, 'reference.pkl')):
403+
if os.path.exists(os.path.join(save_path, 'reference.pkl')) and not create_new:
401404
print('Loading Reference')
402405
self.database = pickle.load(open(os.path.join(save_path, 'reference.pkl'), "rb"))
403406
else:
@@ -588,7 +591,7 @@ def eval(self, dataset=None, num_pairs=1000, silent=False, verbose=True):
588591
transforms.Normalize(mean=self.rgb_mean, std=self.rgb_std)]
589592
)
590593

591-
dataset_eval = datasets.ImageFolder(os.path.join(dataset.path, dataset.dataset_type), eval_transform)
594+
dataset_eval = datasets.ImageFolder(dataset.path, eval_transform)
592595
eval_loader = torch.utils.data.DataLoader(
593596
dataset_eval, batch_size=self.batch_size, pin_memory=self.pin_memory,
594597
num_workers=self.num_workers, drop_last=self.drop_last

0 commit comments

Comments
 (0)
Please sign in to comment.