10 from jsk_topic_tools 
import ConnectionBasedTransport
 
   11 from jsk_recognition_msgs.msg 
import PeoplePoseArray
 
   12 from sensor_msgs.msg 
import Image
 
   39         super(self.__class__, self).
__init__()
 
   41         self.
limb_part = rospy.get_param(
'~limb_part', 
'all')
 
   45             '~arms_score_threshold', 0.25)
 
   52         self.
pub = self.advertise(
'~output', Image, queue_size=1)
 
   53         self.
debug_pub = self.advertise(
'~debug/output', Image, queue_size=1)
 
   56         queue_size = rospy.get_param(
'~queue_size', 10)
 
   58             '~input', Image, queue_size=1, buff_size=2**24)
 
   60             '~input/pose', PeoplePoseArray, queue_size=1, buff_size=2**24)
 
   61         self.
subs = [sub_img, sub_pose]
 
   62         if rospy.get_param(
'~approximate_sync', 
False):
 
   63             slop = rospy.get_param(
'~slop', 0.1)
 
   64             sync = message_filters.ApproximateTimeSynchronizer(
 
   65                 fs=self.
subs, queue_size=queue_size, slop=slop)
 
   68                 fs=self.
subs, queue_size=queue_size)
 
   69         sync.registerCallback(self.
_cb)
 
   75     def _cb(self, img_msg, people_pose_array_msg):
 
   76         br = cv_bridge.CvBridge()
 
   77         img = br.imgmsg_to_cv2(img_msg, desired_encoding=
'bgr8')
 
   81             indices = indices[indices < len(people_pose_array_msg.poses)]
 
   82             people_pose = np.array(people_pose_array_msg.poses)[indices]
 
   84             people_pose = people_pose_array_msg.poses
 
   86         mask_img = np.zeros((img.shape[0], img.shape[1]), dtype=np.bool)
 
   87         arm = [limb_prefix 
for limb_prefix 
in [
'R', 
'L']
 
   88                if limb_prefix + 
'Hand' in self.
limb_part]
 
   92             mask_img = np.bitwise_or(mask_img, arm_mask_img)
 
   95             mask_img = np.bitwise_or(mask_img, nose_mask_img)
 
   97         mask_msg = br.cv2_to_imgmsg(np.uint8(mask_img * 255.0), encoding=
'mono8')
 
   98         mask_msg.header = img_msg.header
 
  100         debug_msg = br.cv2_to_imgmsg(debug_img, encoding=
'bgr8')
 
  101         debug_msg.header = img_msg.header
 
  103         self.
pub.publish(mask_msg)
 
  107         rectangle_thickness = 5
 
  108         rectangle_colors = [(0, 255, 0), (0, 0, 255)]
 
  110         mask_img = np.zeros((img.shape[0], img.shape[1]), dtype=np.bool)
 
  111         for person_pose 
in people_pose:
 
  112             for limb_prefix, color 
in zip(arm, rectangle_colors):
 
  114                     shoulder_index = person_pose.limb_names.index(
 
  115                         limb_prefix + 
'Shoulder')
 
  116                     elbow_index = person_pose.limb_names.index(
 
  117                         limb_prefix + 
'Elbow')
 
  118                     wrist_index = person_pose.limb_names.index(
 
  119                         limb_prefix + 
'Wrist')
 
  123                 if not np.all(np.array(person_pose.scores)[[elbow_index, shoulder_index, wrist_index]] > self.
arms_score_threshold):
 
  126                 shoulder = person_pose.poses[shoulder_index]
 
  127                 elbow = person_pose.poses[elbow_index]
 
  128                 wrist = person_pose.poses[wrist_index]
 
  131                     (wrist.position.x - elbow.position.x)
 
  133                     (wrist.position.y - elbow.position.y)
 
  135                 wrist_to_elbow_length = ((wrist.position.x - elbow.position.x)
 
  136                                          ** 2 + (wrist.position.y - elbow.position.y) ** 2) ** 0.5
 
  137                 elbow_to_shoulder_length = ((shoulder.position.x - elbow.position.x) ** 2 + (
 
  138                     shoulder.position.y - elbow.position.y) ** 2) ** 0.5
 
  140                     max(wrist_to_elbow_length, 0.9 * elbow_to_shoulder_length)
 
  151                 mask_img[max(y, 0):max(min(y + height, img.shape[0]), 0),
 
  152                          max(x, 0):max(min(x + width, img.shape[1]), 0)] = 
True 
  153                 cv2.rectangle(img, (x, y), (x + width, y + height),
 
  154                               color, rectangle_thickness)
 
  158         rectangle_thickness = 5
 
  161         mask_img = np.zeros((img.shape[0], img.shape[1]), dtype=np.bool)
 
  162         for person_pose 
in people_pose:
 
  169             target_limb_names = [
'Nose',
 
  175             for limb_name 
in target_limb_names:
 
  177                     limb_index = person_pose.limb_names.index(limb_name)
 
  178                     limb_pose = person_pose.poses[limb_index]
 
  179                     limb_poses.append(limb_pose)
 
  180                     if limb_name == 
'Nose':
 
  181                         nose_pose = limb_pose
 
  182                     elif limb_name == 
'Neck':
 
  183                         neck_pose = limb_pose
 
  187             shoulder_limb_poses = []
 
  188             shoulder_limb_names = [
'RShoulder',
 
  190             for limb_name 
in shoulder_limb_names:
 
  192                     shoulder_limb_index = person_pose.limb_names.index(limb_name)
 
  193                     shoulder_limb_pose = person_pose.poses[shoulder_limb_index]
 
  194                     shoulder_limb_poses.append(shoulder_limb_pose)
 
  197             if len(shoulder_limb_poses) == 2:
 
  198                 positions_x = [pose.position.x 
for pose 
in shoulder_limb_poses]
 
  199                 x_mid = sum(positions_x) / len(positions_x)
 
  205             if nose_pose == 
None or neck_pose == 
None:
 
  208             positions_x = [pose.position.x 
for pose 
in limb_poses]
 
  209             x_max = max(max(positions_x), x_max)
 
  210             x_min = min(min(positions_x), x_min)
 
  212             x = (x_max + x_min) / 2.0 - width / 2.0
 
  214             positions_y = [pose.position.y 
for pose 
in limb_poses]
 
  215             y_min = min(positions_y)
 
  217                      abs(nose_pose.position.y - neck_pose.position.y) * 2.0
 
  218             y_min = min(y_min, nose_pose.position.y - height / 2.0)
 
  219             y_max = nose_pose.position.y + height / 2.0
 
  221             height = y_max - y_min
 
  228             mask_img[max(y, 0):max(min(y + height, img.shape[0]), 0),
 
  229                      max(x, 0):max(min(x + width, img.shape[1]), 0)] = 
True 
  230             cv2.rectangle(img, (x, y), (x + width, y + height),
 
  231                           color, rectangle_thickness)
 
  234 if __name__ == 
'__main__':
 
  235     rospy.init_node(
'people_mask_publisher')