-
Notifications
You must be signed in to change notification settings - Fork 0
/
rgbd_detect_3d_dir.py
1502 lines (1273 loc) · 62.2 KB
/
rgbd_detect_3d_dir.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#!/usr/bin/env python
# -*- coding: utf-8 -*-
# TODO : sort imports
# mmdet and mmpose import
from mmpose.apis import (
get_track_id,
inference_top_down_pose_model,
init_pose_model,
process_mmdet_results,
)
from mmpose.datasets import DatasetInfo
try:
from mmdet.apis import inference_detector, init_detector
has_mmdet = True
except (ImportError, ModuleNotFoundError):
has_mmdet = False
# ros related import
import rospy
from sensor_msgs.msg import Image, PointCloud2
from geometry_msgs.msg import TransformStamped
from cv_bridge import CvBridge
import tf2_ros
# other import
import cv2
import os
import matplotlib.pyplot as plt
from argparse import ArgumentParser
from datetime import datetime
import time
import json
import warnings
import numpy as np
from PyKDL import Rotation
from PIL import Image as PILImage
# custom utils import
from utils import *
# torch import
import torch
# transform for bounding boxes from keypoints
from transform_utils import head_transform
# 6D Rep import
try:
has_sixdrep = True
from sixdrep.util import FaceDetector, compute_euler
from sixdrep.utils import sixdreptransform
except:
has_sixdrep = False
prWarning("No 6D Rep import, fail")
# remove numpy scientific notation
np.set_printoptions(suppress=True)
class InferenceNodeRGBD(object):
def __init__(self, args):
# init args
self.args = args
# init detector and pose
self.det_model = init_detector(
args.det_config, args.det_checkpoint, device=args.device.lower()
)
self.pose_model = init_pose_model(
args.pose_config, args.pose_checkpoint, device=args.device.lower()
)
# if enabled, init 6DRep
if self.args.use_six_d_rep:
self.sixdrep_model = torch.load(f=args.six_d_rep_checkpoint, map_location='cuda')
self.sixdrep_model = self.sixdrep_model['model'].float().fuse()
if self.args.use_face_detector:
self.sixdrep_detector = FaceDetector(args.six_d_rep_face_detector_checkpoint)
else:
self.sixdrep_detector = None
self.sixdrep_model.half()
self.sixdrep_model.eval()
# dataset object for detection and pose from MMPose
self.dataset = self.pose_model.cfg.data["test"]["type"]
self.dataset_info = self.pose_model.cfg.data["test"].get(
"self.dataset_info", None
)
if self.dataset_info is None:
warnings.warn(
"Please set `self.dataset_info` in the config."
"Check https://github.com/open-mmlab/mmpose/pull/663 for details.",
DeprecationWarning,
)
else:
self.dataset_info = DatasetInfo(self.dataset_info)
self.return_heatmap = False
# variables to keep tracks along time or in the current frame
self.next_id = 0
self.pose_results = []
self.tracks_in_current_image = {}
self.tracks = {} # all the tracks along time, we need to keep and history with some data
# shared variables for the received images and pcl
self.rgb = None # Image frame
self.depth = None # Image frame
self.pcl_array_rgb = None
self.pcl_array_xyz = None
# viewing options
self.depth_array_max_threshold = 20000
self.depth_cmap = get_mpl_colormap(args.depth_cmap)
self.confidence_cmap = get_mpl_colormap("viridis")
self.vis_img = None # output image RGB + detections
self.view_all_classes_dets = True
self.display_all_detection = args.display_all_detection
# counter for the incoming frames
self.pcl_current_seq = -1
self.rgb_current_seq = -1
self.last_inferred_seq = -1
self.depth_current_seq = -1
self.current_image_count = 0
self.rgb_frame_id = None # received from ROS image, used as frame_id in publisher
# CV Bridge for receiving frames
self.br = CvBridge()
# Set ROS node rate
prInfo("Setting node rate to {} fps".format(args.fps))
self.loop_rate = rospy.Rate(args.fps)
# create the output path
now = datetime.now()
timestamp = now.strftime("%Y_%m_%d_%H_%M_%S")
self.save_dir = os.path.join("output", "record_{:s}".format(timestamp))
self.metadata = os.path.join(self.save_dir, "metadata.json")
self.save_dir_rgb = os.path.join(self.save_dir, "rgb")
self.save_dir_depth = os.path.join(self.save_dir, "depth")
self.save_dir_result = os.path.join(self.save_dir, "output")
self.save_dir_pcl_bin = os.path.join(self.save_dir, "pcl")
if args.save:
prInfo(
"Saving to {}/[rgb][depth][depth_color][output][pcl]".format(
self.save_dir
)
)
if not os.path.exists(self.save_dir):
prInfo(
"Creating directories to {}/[rgb][depth][depth_color][output][pcl]".format(
self.save_dir
)
)
os.makedirs(self.save_dir)
os.makedirs(self.save_dir_rgb)
os.makedirs(self.save_dir_pcl_bin)
if args.save:
os.makedirs(self.save_dir_depth)
os.makedirs(self.save_dir_result)
args_dic = vars(args)
with open(self.metadata, "w") as fp:
json.dump(args_dic, fp)
prSuccess(
"Created directories to {}/[rgb][depth][depth_color][output][pcl]".format(
self.save_dir
)
)
time.sleep(1)
# ROS publishers
self.goal_pub = rospy.Publisher(
args.namespace + "/human", TransformStamped, queue_size=1
)
self.tf_br = tf2_ros.TransformBroadcaster()
# ROS subscribers
rgb_topic = args.namespace + "/rgb"
depth_topic = args.namespace + "/depth"
pcl_topic = args.namespace + "/pcl"
prInfo("Subscribing to {} for RGB".format(rgb_topic))
rospy.Subscriber(rgb_topic, Image, self.callback_rgb)
prInfo("Subscribing to {} for depth".format(depth_topic))
rospy.Subscriber(depth_topic, Image, self.callback_depth)
prInfo("Subscribing to {} for PCL".format(pcl_topic))
rospy.Subscriber(pcl_topic, PointCloud2, self.callback_pcl)
def callback_pcl(self, msg):
if self.args.flip:
pcl_array = np.frombuffer(msg.data, dtype=np.float32).reshape(
(msg.height, msg.width, -1)
)[::-1, ::-1, :]
else:
pcl_array = np.frombuffer(msg.data, dtype=np.float32).reshape(
(msg.height, msg.width, -1)
)
self.pcl_array_xyz = pcl_array[:, :, :3]
# self.pcl_array_rgb = pcl_array[:,:,3:]
self.pcl_current_seq = msg.header.seq
# rospy.loginfo('pcl received ({})...'.format(msg.header.seq))
def callback_rgb(self, msg):
if self.rgb_frame_id != msg.header.frame_id:
self.rgb_frame_id = msg.header.frame_id
if self.args.flip:
self.rgb = cv2.flip(self.br.imgmsg_to_cv2(msg, "bgr8"), -1)
else:
self.rgb = self.br.imgmsg_to_cv2(msg, "bgr8")
self.rgb_current_seq = msg.header.seq
# rospy.loginfo('RGB received ({})...'.format(msg.header.seq))
self.rgb_timestamp = msg.header.stamp
def callback_depth(self, msg):
if self.args.flip:
self.depth = cv2.flip(self.br.imgmsg_to_cv2(msg, "mono16"), -1)
else:
self.depth = self.br.imgmsg_to_cv2(msg, "mono16")
self.depth_current_seq = msg.header.seq
# rospy.loginfo('Depth received ({})...'.format(msg.header.seq))
def is_ready(self):
""" Make sure the node is ready to process (i.e. it has received an RGB image, a depth image and a PCL)
Returns:
bool: True if ready
"""
ready = (
(self.rgb is not None)
and (self.depth is not None)
and (self.pcl_array_xyz is not None)
)
return ready
@timeit
def save_rgb(self, image_count, image_seq_unique, timestamp):
rgb_path = os.path.join(
self.save_dir_rgb,
"{:08d}_seq_{:010d}_ts_{}.png".format(
image_count, image_seq_unique, timestamp
),
)
cv2.imwrite(rgb_path, self.rgb)
prSuccess("Saved RGB to {}".format(rgb_path))
@timeit
def save_depth(self, image_count, image_seq_unique, timestamp):
depth_path = os.path.join(
self.save_dir_depth,
"{:08d}_seq_{:010d}_ts_{}.png".format(
image_count, image_seq_unique, timestamp
),
)
cv2.imwrite(depth_path, self.depth)
prSuccess("Saved depth to {}".format(depth_path))
@timeit
def save_output_image(self, image_count, image_seq_unique, timestamp):
results_path = os.path.join(
self.save_dir_result,
"{:08d}_seq_{:010d}_ts_{}.png".format(
image_count, image_seq_unique, timestamp
),
)
cv2.imwrite(results_path, self.vis_img)
prSuccess("Saved result to {}".format(results_path))
@timeit
def save_pcl(self, image_count, image_seq_unique, timestamp):
pcl_path = os.path.join(
self.save_dir_pcl_bin,
"{:08d}_seq_{:010d}_ts_{}.bin".format(
image_count, image_seq_unique, timestamp
),
)
self.pcl_array_xyz.tofile(pcl_path)
prSuccess("Saved pcl to {}".format(pcl_path))
@timeit
def plot_mmdet_bbox(self, mmdet_results, array_shape):
""" Plot all the bounding box detected in the image by the mmdet model (eg. YOLOv3) if score is superior to bbox_thr. Add classes names (assuming it is from YOLO_COCO_80_CLASSES).
Args:
mmdet_results (list): list of detections following the format of mmdet output
array_shape (np.array): array describing the output image width and height
"""
for c in range(len(mmdet_results)):
if len(mmdet_results[c]) > 0:
for bi in range(mmdet_results[c].shape[0]):
if mmdet_results[c][bi, 4] > self.args.bbox_thr:
bbox = (
mmdet_results[c][bi, :4]
.copy()
.astype(np.int32)
)
bbox_ints = [
int(bbox[0]),
int(bbox[1]),
int(bbox[2]),
int(bbox[3]),
]
pt1 = (
min(
max(0, bbox_ints[0]),
array_shape[1],
),
min(
max(0, bbox_ints[1]),
array_shape[0],
),
)
pt2 = (
min(
max(0, bbox_ints[2]),
array_shape[1],
),
min(
max(0, bbox_ints[3]),
array_shape[0],
),
)
cv2.rectangle(
self.vis_img, pt1, pt2, (255, 255, 255), 1
)
cv2.putText(
self.vis_img,
"{:s} ({:.0f}%)".format(
YOLO_COCO_80_CLASSES[c],
mmdet_results[c][bi, 4] * 100,
),
pt1,
cv2.FONT_HERSHEY_SIMPLEX,
0.5 * TEXT_SCALE,
(255, 255, 255),
1,
)
@timeit
def plot_xyxy_person_bbox(self, idx, bbox, array_shape, track, poses_torso = None, attention_score = None):
""" Plot the bounding box of detected humans with associated informations
Args:
idx (int): track if of the detected human
bbox (np.array or list): bounding box of the detected human [x_min, y_min, x_max, y_max, score]
array_shape (np.array or list): array describing the output image width and height
track (dict): current track (human) information, may include gaze orientation information
poses_torso (np.ndarray, optional): position of the body center in camera frame. Defaults to None.
attention_score (float): score between 0 and 1 indicating the person is looking at the camera
"""
bbox_ints = [
int(bbox[0]),
int(bbox[1]),
int(bbox[2]),
int(bbox[3]),
]
if attention_score is None:
attention_score = 0
else:
attention_score = int(attention_score * 100)
pt1 = (
min(max(0, bbox_ints[0]), array_shape[1]),
min(max(0, bbox_ints[1]), array_shape[0]),
)
pt2 = (
min(max(0, bbox_ints[2]), array_shape[1]),
min(max(0, bbox_ints[3]), array_shape[0]),
)
color = RANDOM_COLORS[idx]
# color_tuple = (int(color[0]), int(color[1]), int(color[2]))
color_tuple = (255,255,255)
# yolo score
score = bbox[4]
# current gaze
if len(track["gaze_yaw_rad"]) > 0:
yaw_g = int(np.rad2deg(track["gaze_yaw_rad"][-1]))
pitch_g = int(np.rad2deg(track["gaze_pitch_rad"][-1]))
if yaw_g == 180 or pitch_g == 180:
yaw_g = "Unk"
pitch_g = "Unk"
else:
yaw_g = "Unk"
pitch_g = "Unk"
# curent depth
if len(track["depth_face"]) > 0:
depth_f = track["depth_face"][-1]
else:
depth_f = "Unk"
# position
if poses_torso is not None:
pose_body = np.array(poses_torso).mean(axis=0)
pose_body_n = pose_body.copy()
if type(pose_body) == np.ndarray:
pose_body_n[0] = pose_body[2]
pose_body_n[1] = -pose_body[0]
pose_body_n[2] = -pose_body[1]
else:
pose_body_n = ["Unk", "Unk", "Unk"]
else:
pose_body_n = ["Unk", "Unk", "Unk"]
draw_bbox_with_corners(self.vis_img, bbox_ints, color = color_tuple, thickness = 5, proportion = 0.2)
text = "ID : {} | Person : {}% | Attention : {}%".format(idx, score, attention_score)
if poses_torso is not None and type(pose_body) == np.ndarray:
text2 = "Yaw = {} | Pitch = {} | pos = ({:.2f}, {:.2f}, {:.2f})".format(yaw_g, pitch_g, pose_body_n[0], pose_body_n[1], pose_body_n[2])
else:
text2 = "Pose undefined (shoulder and/or hips not visible) | Yaw = {} | Pitch = {}".format(yaw_g, pitch_g)
cv2.putText(
self.vis_img,
text,
(bbox_ints[0], bbox_ints[1] - 30),
cv2.FONT_HERSHEY_SIMPLEX,
0.5 * TEXT_SCALE,
color_tuple,
1,
)
# if poses_torso is not None and type(pose_body) == np.ndarray:
cv2.putText(
self.vis_img,
text2,
(bbox_ints[0], bbox_ints[1] - 15),
cv2.FONT_HERSHEY_SIMPLEX,
0.35 * TEXT_SCALE,
color_tuple,
1,
)
@timeit
def process_keypoints(self, keypoints, depth_array, idx):
"""Iterate over all keypoints detected for the given track and process them, add special keypoints (wrists) to the track informations in self.tracks_in_current_image
Args:
keypoints (np.ndarray): array of keypoints detected in the image shape is expected to be ([17,3] : COCO17 format with x,y pixel coordinates + score)
depth_array (np.ndarray): array of depth calibrated with the RGB image (depth in mm)
idx (int): id of the current track
Returns:
List: list of body center joints (arrays of size [3] : x,y pixel coordinates + score), i.e. hips and shoulders, only if they are detected with a score > kpt_thr and inside the frame
"""
body_center_joints = (
[]
) # to store center of lsho, rsho, lhip, rhip in pixels
color = RANDOM_COLORS[idx]
# color_tuple = (int(color[0]), int(color[1]), int(color[2]))
color_tuple = (255,255,255)
for j in range(keypoints.shape[0]):
kp = keypoints[j, :]
confidence = int(kp[2] * 255)
confidence_color = (
self.confidence_cmap[min(255, confidence)] * 255
).astype(np.uint8)
if (
kp[2] > self.args.kpt_thr
and kp[0] > 0
and kp[1] > 0
and kp[0] < depth_array.shape[1]
and kp[1] < depth_array.shape[0]
):
if (j == 5) or (j == 6) or (j == 11) or (j == 12):
# one keypoint of the torso
body_center_joints.append(kp)
if not self.args.no_show:
# kp_color_tuple = (int(confidence_color[0]), int(confidence_color[1]), int(confidence_color[2]))
cv2.circle(
self.vis_img,
(int(kp[0]), int(kp[1])),
2,
color_tuple,
thickness=3,
)
# if wrists, find depth and pose
if j == 10:
# right wrist
depth_wrist = depth_array[int(kp[1]), int(kp[0])]
pose_wrist = self.pcl_array_xyz[
int(kp[1]), int(kp[0]), :
]
self.tracks_in_current_image[idx][
"right_wrist_depth"
] = depth_wrist
self.tracks_in_current_image[idx][
"right_wrist_pose"
] = pose_wrist
if not self.args.no_show:
cv2.drawMarker(
self.vis_img,
(int(kp[0]), int(kp[1])),
color=color_tuple,
thickness=3,
markerType=cv2.MARKER_CROSS,
line_type=cv2.LINE_AA,
markerSize=8,
)
elif j == 9:
# left wrist
depth_wrist = depth_array[int(kp[1]), int(kp[0])]
pose_wrist = self.pcl_array_xyz[
int(kp[1]), int(kp[0]), :
]
self.tracks_in_current_image[idx][
"left_wrist_depth"
] = depth_wrist
self.tracks_in_current_image[idx][
"left_wrist_pose"
] = pose_wrist
if not self.args.no_show:
cv2.drawMarker(
self.vis_img,
(int(kp[0]), int(kp[1])),
color=color_tuple,
thickness=3,
markerType=cv2.MARKER_CROSS,
line_type=cv2.LINE_AA,
markerSize=8,
)
return body_center_joints
@timeit
def get_depth_and_poses_of_torso(self, depth_array, lsho, rsho, lhip, rhip, idx):
""" Compute the depth and position of the detected human using multiple points on its torso
Args:
depth_array (np.ndarray): depth image calibrated with RGB image (in mm)
lsho (np.array): array of size [3] with left shoulder keypoint data : x,y pixel coordinates and score
rsho (np.array): array of size [3] with right shoulder keypoint data : x,y pixel coordinates and score
lhip (np.array): array of size [3] with left hip keypoint data : x,y pixel coordinates and score
rhip (np.array): array of size [3] with right hip keypoint data : x,y pixel coordinates and score
idx (int): id of the current description
Returns:
List, List: lists of valid depth and poses (if depth is 0, ie. pixel is a blank spot in the depth image, then it is discarded)
"""
color = RANDOM_COLORS[idx]
# color_tuple = (int(color[0]), int(color[1]), int(color[2]))
color_tuple = (255,255,255)
# find 4 points between lsho and rhip and 4 points between rsho and lhip to find something more precise
seg_steps = [0.0, 0.25, 0.50, 0.75, 1.0]
depths_torso = []
poses_torso = []
for step in seg_steps:
p1 = step * lsho + (1 - step) * rhip
if (
p1[0] < depth_array.shape[1]
and p1[1] < depth_array.shape[0]
):
depth_p1 = depth_array[int(p1[1]), int(p1[0])]
pose_p1 = self.pcl_array_xyz[
int(p1[1]), int(p1[0]), :
]
if depth_p1 > 0:
depths_torso.append(depth_p1)
poses_torso.append(pose_p1)
p2 = step * rsho + (1 - step) * lhip
if (
p2[0] < depth_array.shape[1]
and p2[1] < depth_array.shape[0]
):
depth_p2 = depth_array[int(p2[1]), int(p2[0])]
pose_p2 = self.pcl_array_xyz[
int(p2[1]), int(p2[0]), :
]
if depth_p2 > 0:
depths_torso.append(depth_p2)
poses_torso.append(pose_p2)
if not self.args.no_show:
# draw to check
cv2.drawMarker(
self.vis_img,
(int(p1[0]), int(p1[1])),
color=color_tuple,
thickness=1,
markerType=cv2.MARKER_DIAMOND,
line_type=cv2.LINE_AA,
markerSize=8,
)
cv2.drawMarker(
self.vis_img,
(int(p2[0]), int(p2[1])),
color=color_tuple,
thickness=1,
markerType=cv2.MARKER_DIAMOND,
line_type=cv2.LINE_AA,
markerSize=8,
)
return depths_torso, poses_torso
@timeit
def plot_body_pose_data(self, body_center, depth_body, pose_body, idx):
color = RANDOM_COLORS[idx]
# color_tuple = (int(color[0]), int(color[1]), int(color[2]))
color_tuple = (255,255,255)
cv2.drawMarker(
self.vis_img,
body_center,
color = color_tuple,
thickness=1,
markerType=cv2.MARKER_TILTED_CROSS,
line_type=cv2.LINE_AA,
markerSize=16,
)
# cv2.putText(
# self.vis_img,
# "{:.0f}cm | {:.2f} {:.2f} {:.2f}".format(
# depth_body / 10,
# pose_body[0],
# pose_body[1],
# pose_body[2],
# ),
# (int(body_center[0]), int(body_center[1])),
# cv2.FONT_HERSHEY_SIMPLEX,
# 0.8 * TEXT_SCALE,
# (0, 255, 0),
# 3,
# )
cv2.putText(
self.vis_img,
"{:.0f}cm".format(
depth_body / 10
),
(int(body_center[0]), int(body_center[1])),
cv2.FONT_HERSHEY_SIMPLEX,
0.5 * TEXT_SCALE,
(255, 255, 255),
1,
)
@timeit
def plot_skeleton_2d(self, keypoints, idx):
"""Plot skeleton limbds assuming the keypoints are COCO17 format
Args:
keypoints (np.ndarray): array of shape [17,3] with the body keypoints
idx (int): id of the track
"""
color = RANDOM_COLORS[idx]
# color_tuple = (int(color[0]), int(color[1]), int(color[2]))
color_tuple = (255,255,255)
for limb in COCO17_JOINTS_LIMBS:
start = keypoints[limb[0], :]
end = keypoints[limb[1], :]
start_point = (int(start[0]), int(start[1]))
end_point = (int(end[0]), int(end[1]))
if (start[2] > self.args.kpt_thr) and (
end[2] > self.args.kpt_thr
):
cv2.line(
self.vis_img,
start_point,
end_point,
color = color_tuple,
thickness=1,
)
@timeit
def plot_det_text_info(self, pose_closest):
if pose_closest is not None:
cv2.putText(
self.vis_img,
"{:.2f} {:.2f} {:.2f}".format(
pose_closest[0], pose_closest[1], pose_closest[2]
),
(30, 30),
cv2.FONT_HERSHEY_SIMPLEX,
1.2 * TEXT_SCALE,
(255, 255, 255),
5,
)
cv2.putText(
self.vis_img,
"{:.2f} {:.2f} {:.2f}".format(
pose_closest[0], pose_closest[1], pose_closest[2]
),
(30, 30),
cv2.FONT_HERSHEY_SIMPLEX,
1.2 * TEXT_SCALE,
(0, 0, 0),
3,
)
else:
cv2.putText(
self.vis_img,
"No tracks with pose found",
(30, 30),
cv2.FONT_HERSHEY_SIMPLEX,
1.2 * TEXT_SCALE,
(255, 255, 255),
5,
)
cv2.putText(
self.vis_img,
"No tracks with pose found",
(30, 30),
cv2.FONT_HERSHEY_SIMPLEX,
1.2 * TEXT_SCALE,
(0, 0, 0),
3,
)
@timeit
def plot_gaze_from_pitch_yaw(self, pitch, yaw, head_bb_abs, idx, keypoints):
""" Plot 2D reprojection of the computed gaze direction
Args:
pitch (float): pitch of gaze in rad
yaw (float): yaw of gaze in rad (0 = facing camera)
head_bb_abs (lsit of np.array): bounding box of the head with format [x_min, y_min, width, height]
idx (int): id of the current track
keypoints (np.ndarray): array of shape [17,3] with the body keypoints
"""
# color = RANDOM_COLORS[idx]
# color_tuple = (int(color[0]), int(color[1]), int(color[2]))
color_tuple = (0,0,255)
head_bb_abs[2] += head_bb_abs[0]
head_bb_abs[3] += head_bb_abs[1]
prediction_show = np.zeros(3)
prediction_show[0] = -np.sin(pitch) * np.cos(yaw)
prediction_show[1] = -np.sin(yaw)
prediction_show[2] = 999
# prediction_show_norm = prediction_show / np.linalg.norm(prediction_show)
gaze_dir_2d = prediction_show[0:2]
# head_center = (int(head_bb_abs[0] / 2 + head_bb_abs[2] / 2), int(head_bb_abs[1] / 2 + head_bb_abs[3] / 2))
head_center = (int(keypoints[1,0] / 2 + keypoints[2,0] / 2), int(keypoints[1,1] / 2 + keypoints[2,1] / 2))
des = (head_center[0] + int(gaze_dir_2d[0]*150), int(head_center[1] + gaze_dir_2d[1]*150))
# cv2.arrowedLine(self.vis_img, head_center, des, (255,255,255), 3, tipLength=0.3)
cv2.arrowedLine(self.vis_img, head_center, des, color_tuple, 2, tipLength=0.1)
cv2.circle(self.vis_img, head_center, 5, color = color_tuple, thickness=-1)
@timeit
def plot_overlay_face_attention_6d(self, track, head_bbox, keypoints, attention_score = 0):
""" Plot ellipse around the eyes, colored depending on the attention of the person
Args:
track (dict): information oin the current track including yaw and pitch of gaze in the last frames
head_bbox (np.array): array of size [4] or [5] with bounding box as [x_min, y_min, x_max, y_max, (score)]
keypoints (np.ndarray): array of shape [17,3] with the body keypoints
attention_score (float): score between 0 and 1 indicating if the person is looking at the camera
"""
x_min, y_min, x_max, y_max = map(int, head_bbox[:4])
valid_depths = []
valid_yaws = []
valid_pitchs = []
# heat_count = 0
# history = 20
# length = min(len(track["depth_face"]), history)
# for i in range(length):
# index = len(track["depth_face"]) - i - 1
# yaw = np.rad2deg(track["gaze_yaw_rad"][index])
# pitch = np.rad2deg(track["gaze_pitch_rad"][index])
# depth = track["depth_face"][index]
# thresh = (int(depth / 1000) + 1) * 5 # 5 deg per meter
# if np.abs(yaw) < thresh and pitch < 0:
# heat_count += 1
# # suppose we are looking down
overlay_img = self.vis_img.copy()
nose = keypoints[0,:2]
leye = keypoints[1,:2]
reye = keypoints[2,:2]
colorval = min(attention_score * 2, 1.0) # color at max with 50%
strength = 0.5 + (attention_score) * 0.5
cmap = get_mpl_colormap("Reds")
color = (cmap[int(colorval * 255)] * 255)
color_tuple = (int(color[0]), int(color[1]), int(color[2]))
ellipse_center = (int(leye[0] / 2 + reye[0] / 2), int(leye[1] / 2 + reye[1] / 2))
ellipse_height = int(nose[1] - (leye[1] / 2 + reye[1] / 2))
ellipse_width = int((leye[0] - reye[0]) * 1.1)
if ellipse_width > 0 and ellipse_height > 0:
cv2.ellipse(overlay_img, ellipse_center, (ellipse_width, ellipse_height), 0, 0, 360, color_tuple, 3)
self.vis_img = cv2.addWeighted(self.vis_img,(1-strength),overlay_img,strength,0)
def get_depth_face(self, keypoints, depth_array):
""" Get depth of face from the median of 3 keypoints
Args:
keypoints (np.ndarray): array of shape [17,3] with the body keypoints
depth_array (np.ndarray): depth image array (in mm)
"""
nose = keypoints[0,:2].astype(np.uint32)
leye = keypoints[1,:2].astype(np.uint32)
reye = keypoints[2,:2].astype(np.uint32)
depth_nose = depth_array[np.clip(nose[1], 0, depth_array.shape[0] - 1), np.clip(nose[0], 0, depth_array.shape[1] - 1)]
depth_leye = depth_array[np.clip(leye[1], 0, depth_array.shape[0] - 1), np.clip(leye[0], 0, depth_array.shape[1] - 1)]
depth_reye = depth_array[np.clip(reye[1], 0, depth_array.shape[0] - 1), np.clip(reye[0], 0, depth_array.shape[1] - 1)]
depth_face = np.median([depth_nose, depth_leye, depth_reye])
return depth_face
def get_attention_score_from_track(self, track):
""" Compute an attention score from the history of gaze angle. Compute the percentage of frames meeting the condition (+- 10 deg yaw and pitch in -10-0 deg, ie looking down).
Args:
track (dict): informations about the tracked face, depth, yaw and pitch
Returns:
float: attention score between 0 and 1
"""
heat_count = 0
history = self.args.fps # 1 sec history (if all frames)
length = min(len(track["depth_face"]), history)
if length < 5:
# too short to estimate
attention_score = 0
else:
for i in range(length):
index = len(track["depth_face"]) - i - 1
yaw = np.rad2deg(track["gaze_yaw_rad"][index])
pitch = np.rad2deg(track["gaze_pitch_rad"][index])
depth = track["depth_face"][index]
thresh = 10 #(int(depth / 1000) + 1) * 6 # 6 deg per meter
thresh_wide = 20
if np.abs(yaw) < thresh and pitch < 0 and pitch > -10:
heat_count += 1
elif np.abs(yaw) < thresh_wide and pitch < 5 and pitch > -15:
# still count this
heat_count += 0.5
attention_score = (heat_count / history)
return attention_score
def start(self):
while not rospy.is_shutdown():
if self.is_ready():
image_count = self.current_image_count
image_seq_unique = self.rgb_current_seq
now = datetime.now()
timestamp = now.strftime("%Y_%m_%d_%H_%M_%S_%f")
if self.args.save:
self.save_rgb(image_count, image_seq_unique, timestamp)
rgb_array = self.rgb.copy()
if self.args.save:
self.save_depth(image_count, image_seq_unique, timestamp)
depth_array = np.array(self.depth)
depth_array[depth_array > self.depth_array_max_threshold] = (
self.depth_array_max_threshold
)
assert depth_array.shape[0] == rgb_array.shape[0]
assert depth_array.shape[1] == rgb_array.shape[1]
# Process RGB array
if self.last_inferred_seq < self.rgb_current_seq:
current_frame_processing = self.rgb_current_seq
current_timestamp = self.rgb_timestamp
current_frame_id = self.rgb_frame_id
prInfo("Do inference on frame {}".format(current_frame_processing))
# keep old poses for tracking
pose_results_last = self.pose_results
tic = time.time()
mmdet_results = inference_detector(
self.det_model, rgb_array
) # list of detection rectangle i.e [(x1,y1,x2,y2), ...]
tac = time.time()
prTimer("YOLO detection", tic, tac)
# keep the person class bounding boxes.
person_results = process_mmdet_results(
mmdet_results, self.args.det_cat_id
)
new_persons = []
for person in person_results:
bbox = person["bbox"]
pt1 = (max(0, min(bbox[0], depth_array.shape[1]-1)), max(0,min(bbox[1], depth_array.shape[0]-1)) )
pt2 = (max(0, min(bbox[2], depth_array.shape[1]-1)), max(0,min(bbox[3], depth_array.shape[0]-1)) )
if abs(pt1[0] - pt2[0]) > self.args.bb_min_threshold/2 or abs(pt1[1]-pt2[1]) > self.args.bb_min_threshold:
# Filter bbox if they are too small
new_persons.append(person)
person_results = new_persons
tic = time.time()
# test a single image, with a list of bboxes.
self.pose_results, returned_outputs = inference_top_down_pose_model(
self.pose_model,
rgb_array,
person_results,
bbox_thr=self.args.bbox_thr,
format="xyxy",
dataset=self.dataset,
dataset_info=self.dataset_info,
return_heatmap=self.return_heatmap,
outputs=None,
)
tac = time.time()
prTimer("ViTPose", tic, tac)
# get track id for each person instance
self.pose_results, self.next_id = get_track_id(
self.pose_results,
pose_results_last,
self.next_id,
use_oks=False,
tracking_thr=self.args.tracking_thr,
use_one_euro=False,
fps=10,
)
# produce an output image
if not self.args.no_show:
self.vis_img = rgb_array.copy()
if self.display_all_detection and not self.args.no_show:
self.plot_mmdet_bbox(mmdet_results, depth_array.shape)
#### post processing, 3D lifting (if enabled) and gaze estimation (if enabled) ####
# remove too old tracks
for idx, track in list(self.tracks.items()):
if abs(image_count - track["last_seen"]) > self.args.max_frames_remove_tracks:
prInfo("Removing track {}, not seen since frame {}, current is {}".format(idx, track["last_seen"], image_count))
self.tracks.pop(idx)
self.tracks_in_current_image = {}
for res in self.pose_results:
# for each instance
bbox = res["bbox"]
keypoints = res["keypoints"]