@@ -48,18 +48,18 @@ def _get_service_response(srv, args):
48
48
49
49
50
50
class PeopleRecognizer2D (object ):
51
- def __init__ (self , openpose_srv_name , openface_srv_name ,
52
- keras_srv_name , color_extractor_srv_name ,
51
+ def __init__ (self , pose_est_srv_name , face_reg_srv_name ,
52
+ face_prop_srv_name , color_extractor_srv_name ,
53
53
enable_age_gender_detection , enable_shirt_color_extraction ):
54
54
55
- self ._openpose_srv = _get_and_wait_for_service (openpose_srv_name , Recognize )
56
- self ._openface_srv = _get_and_wait_for_service (openface_srv_name , Recognize )
55
+ self ._pose_est_srv = _get_and_wait_for_service (pose_est_srv_name , Recognize )
56
+ self ._face_reg_srv = _get_and_wait_for_service (face_reg_srv_name , Recognize )
57
57
58
58
self ._enable_age_gender_detection = enable_age_gender_detection
59
59
self ._enable_shirt_color_extraction = enable_shirt_color_extraction
60
60
61
61
if self ._enable_age_gender_detection :
62
- self ._keras_srv = _get_and_wait_for_service (keras_srv_name , GetFaceProperties )
62
+ self ._face_prop_srv = _get_and_wait_for_service (face_prop_srv_name , GetFaceProperties )
63
63
64
64
if self ._enable_shirt_color_extraction :
65
65
self ._color_extractor_srv = _get_and_wait_for_service (color_extractor_srv_name , Recognize )
@@ -80,12 +80,12 @@ def _is_label_recognition(recognition):
80
80
return [r for r in recognitions if _is_label_recognition (r )]
81
81
82
82
@staticmethod
83
- def _get_face_rois_ids_openpose (recognitions ):
83
+ def _get_face_rois_ids_pose_estimation (recognitions ):
84
84
"""
85
- Get ROIs of faces from openpose recognitions using the nose, left ear
85
+ Get ROIs of faces from pose estimation using the nose, left ear
86
86
and right ear
87
87
88
- :param: recognitions from openpose
88
+ :param: recognitions from pose estimation
89
89
"""
90
90
nose_recognitions = PeopleRecognizer2D ._get_recognitions_with_label ("Nose" , recognitions )
91
91
left_ear_recognitions = PeopleRecognizer2D ._get_recognitions_with_label ("LEar" , recognitions )
@@ -129,23 +129,23 @@ def _get_face_rois_ids_openpose(recognitions):
129
129
return rois , group_ids
130
130
131
131
@staticmethod
132
- def _get_body_parts_openpose (group_id , recognitions ):
132
+ def _get_body_parts_pose_estimation (group_id , recognitions ):
133
133
"""
134
134
Get a list of all bodyparts associated with a particular group ID
135
135
136
136
:param: group_id: The group ID of the bodyparts to be fetched
137
- :param: recognitions: All bodyparts recieved from openpose
137
+ :param: recognitions: All bodyparts recieved from pose estimation
138
138
:return: List of body_parts
139
139
"""
140
140
return [r for r in recognitions if r .group_id == group_id ]
141
141
142
142
@staticmethod
143
143
def _get_container_recognition (roi , recognitions , padding_factor = 0.1 ):
144
144
"""
145
- Associate OpenPose ROI with best OpenPose face ROI
145
+ Associate pose estimation ROI with best pose estimation face ROI
146
146
147
- :param: roi: openpose face roi
148
- :recognitions: openface recognitions
147
+ :param: roi: pose estimation face roi
148
+ :param: recognitions: face recognitions
149
149
"""
150
150
x = roi .x_offset + .5 * roi .width
151
151
y = roi .y_offset + .5 * roi .height
@@ -244,25 +244,25 @@ def recognize(self, image_msg):
244
244
image_annotations = []
245
245
people = []
246
246
247
- # OpenPose and OpenFace service calls
247
+ # Pose estimation and face recognition service calls
248
248
rospy .loginfo ("Starting pose and face recognition..." )
249
249
start_recognize = time .time ()
250
- openpose_response = _get_service_response (self ._openpose_srv , image_msg )
251
- openface_response = _get_service_response (self ._openface_srv , image_msg )
250
+ pose_est_response = _get_service_response (self ._pose_est_srv , image_msg )
251
+ face_reg_response = _get_service_response (self ._face_reg_srv , image_msg )
252
252
rospy .logdebug ("Recognize took %.4f seconds" , time .time () - start_recognize )
253
- rospy .loginfo ("_get_face_rois_ids_openpose ..." )
253
+ rospy .loginfo ("_get_face_rois_ids_pose_estimation ..." )
254
254
255
- # Extract face ROIs and their corresponding group ids from recognitions of openpose
256
- openpose_face_rois , openpose_face_group_ids = PeopleRecognizer2D ._get_face_rois_ids_openpose (
257
- openpose_response .recognitions )
255
+ # Extract face ROIs and their corresponding group ids from recognitions of pose estimation
256
+ pose_est_face_rois , pose_est_face_group_ids = PeopleRecognizer2D ._get_face_rois_ids_pose_estimation (
257
+ pose_est_response .recognitions )
258
258
259
- body_parts_array = [PeopleRecognizer2D ._get_body_parts_openpose (group_id ,
260
- openpose_response .recognitions ) for group_id in
261
- openpose_face_group_ids ]
259
+ body_parts_array = [PeopleRecognizer2D ._get_body_parts_pose_estimation (group_id ,
260
+ pose_est_response .recognitions ) for group_id in
261
+ pose_est_face_group_ids ]
262
262
263
- face_recognitions = [PeopleRecognizer2D ._get_container_recognition (openpose_face_roi ,
264
- openface_response .recognitions )
265
- for openpose_face_roi in openpose_face_rois ]
263
+ face_recognitions = [PeopleRecognizer2D ._get_container_recognition (pose_est_face_group_ids ,
264
+ face_reg_response .recognitions )
265
+ for pose_est_face_roi in pose_est_face_rois ]
266
266
267
267
face_labels = [PeopleRecognizer2D ._get_best_label (r ) for r in face_recognitions ]
268
268
@@ -271,8 +271,8 @@ def recognize(self, image_msg):
271
271
rospy .loginfo ("_get_face_properties..." )
272
272
face_image_msg_array = [self ._bridge .cv2_to_imgmsg (PeopleRecognizer2D ._image_from_roi (image , r .roi ), "bgr8" ) for
273
273
r in face_recognitions ]
274
- keras_response = _get_service_response (self ._keras_srv , face_image_msg_array )
275
- face_properties_array = keras_response .properties_array
274
+ face_prop_response = _get_service_response (self ._face_prop_srv , face_image_msg_array )
275
+ face_properties_array = face_prop_response .properties_array
276
276
else :
277
277
face_properties_array = [FaceProperties ()] * len (face_recognitions )
278
278
0 commit comments