Skip to content

Commit 2b14588

Browse files
(2d) get rid of implementation names
1 parent bccbc89 commit 2b14588

File tree

1 file changed

+28
-28
lines changed

1 file changed

+28
-28
lines changed

people_recognition_2d/src/people_recognition_2d/people_recognizer_2d.py

Lines changed: 28 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -48,18 +48,18 @@ def _get_service_response(srv, args):
4848

4949

5050
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,
5353
enable_age_gender_detection, enable_shirt_color_extraction):
5454

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)
5757

5858
self._enable_age_gender_detection = enable_age_gender_detection
5959
self._enable_shirt_color_extraction = enable_shirt_color_extraction
6060

6161
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)
6363

6464
if self._enable_shirt_color_extraction:
6565
self._color_extractor_srv = _get_and_wait_for_service(color_extractor_srv_name, Recognize)
@@ -80,12 +80,12 @@ def _is_label_recognition(recognition):
8080
return [r for r in recognitions if _is_label_recognition(r)]
8181

8282
@staticmethod
83-
def _get_face_rois_ids_openpose(recognitions):
83+
def _get_face_rois_ids_pose_estimation(recognitions):
8484
"""
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
8686
and right ear
8787
88-
:param: recognitions from openpose
88+
:param: recognitions from pose estimation
8989
"""
9090
nose_recognitions = PeopleRecognizer2D._get_recognitions_with_label("Nose", recognitions)
9191
left_ear_recognitions = PeopleRecognizer2D._get_recognitions_with_label("LEar", recognitions)
@@ -129,23 +129,23 @@ def _get_face_rois_ids_openpose(recognitions):
129129
return rois, group_ids
130130

131131
@staticmethod
132-
def _get_body_parts_openpose(group_id, recognitions):
132+
def _get_body_parts_pose_estimation(group_id, recognitions):
133133
"""
134134
Get a list of all bodyparts associated with a particular group ID
135135
136136
: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
138138
:return: List of body_parts
139139
"""
140140
return [r for r in recognitions if r.group_id == group_id]
141141

142142
@staticmethod
143143
def _get_container_recognition(roi, recognitions, padding_factor=0.1):
144144
"""
145-
Associate OpenPose ROI with best OpenPose face ROI
145+
Associate pose estimation ROI with best pose estimation face ROI
146146
147-
:param: roi: openpose face roi
148-
:recognitions: openface recognitions
147+
:param: roi: pose estimation face roi
148+
:param: recognitions: face recognitions
149149
"""
150150
x = roi.x_offset + .5 * roi.width
151151
y = roi.y_offset + .5 * roi.height
@@ -244,25 +244,25 @@ def recognize(self, image_msg):
244244
image_annotations = []
245245
people = []
246246

247-
# OpenPose and OpenFace service calls
247+
# Pose estimation and face recognition service calls
248248
rospy.loginfo("Starting pose and face recognition...")
249249
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)
252252
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...")
254254

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)
258258

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]
262262

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]
266266

267267
face_labels = [PeopleRecognizer2D._get_best_label(r) for r in face_recognitions]
268268

@@ -271,8 +271,8 @@ def recognize(self, image_msg):
271271
rospy.loginfo("_get_face_properties...")
272272
face_image_msg_array = [self._bridge.cv2_to_imgmsg(PeopleRecognizer2D._image_from_roi(image, r.roi), "bgr8") for
273273
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
276276
else:
277277
face_properties_array = [FaceProperties()] * len(face_recognitions)
278278

0 commit comments

Comments
 (0)