pointit.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 # Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
4 
5 from jsk_topic_tools import ConnectionBasedTransport
6 import message_filters as MF
7 import numpy as np
8 import rospy
9 import tf2_ros
10 import tf2_geometry_msgs
11 
12 from geometry_msgs.msg import PoseStamped
13 from jsk_recognition_msgs.msg import BoundingBoxArray
14 from jsk_recognition_msgs.msg import ClassificationResult
15 from jsk_recognition_msgs.msg import PeoplePoseArray
16 from visualization_msgs.msg import Marker
17 from visualization_msgs.msg import MarkerArray
18 
19 
20 def find_pose(limb, msg):
21  if isinstance(limb, list):
22  for l in limb:
23  p = find_pose(l, msg)
24  if p is not None:
25  return p
26  return None
27  try:
28  idx = msg.limb_names.index(limb)
29  return msg.poses[idx]
30  except ValueError:
31  return None
32 
33 
34 def remove_slash(frame_id):
35  if frame_id.startswith("/"):
36  return frame_id[1:]
37  else:
38  return frame_id
39 
40 
41 class PointIt(ConnectionBasedTransport):
42  """
43  PointIt class object
44  """
45  def __init__(self):
46  super(PointIt, self).__init__()
47  # variables
48  self.subscribers = []
49  self.objects = []
50 
51  # parameters
52  if rospy.has_param("~dist_threshold"):
53  rospy.logwarn("Parameter ~dist_threshold is deprecated. "
54  "Use ~max_dist_threshold instead.")
55  self.max_dist_threshold = rospy.get_param("~dist_threshold")
56  else:
57  self.max_dist_threshold = rospy.get_param(
58  "~max_dist_threshold", 0.1)
59 
60  self.min_dist_threshold = rospy.get_param("~min_dist_threshold", 0.0)
61  self.min_norm_threshold = rospy.get_param("~min_norm_threshold", 0.2)
62  self.use_arm = rospy.get_param("~use_arm", ["rarm", "larm"])
63 
64  if "rarm" not in self.use_arm and "larm" not in self.use_arm:
65  rospy.logfatal("~use_arm must contain at least 'rarm' or 'larm'.")
66 
67  # tf listener
68  use_tf2_buffer_client = rospy.get_param("~use_tf2_buffer_client", True)
69  if use_tf2_buffer_client:
70  self.tfl = tf2_ros.BufferClient("/tf2_buffer_server")
71  if not self.tfl.wait_for_server(rospy.Duration(10)):
72  rospy.logerr("Waiting /tf2_buffer_server timed out.")
73  use_tf2_buffer_client = False
74  if not use_tf2_buffer_client:
75  self.tfl = tf2_ros.Buffer()
77 
78  # advertise
79  self.pub_bbox = self.advertise("~output", BoundingBoxArray, queue_size=1)
80  self.pub_marker = self.advertise("~output/marker_array", MarkerArray, queue_size=1)
81 
82  def subscribe(self):
83  use_cls = rospy.get_param("~use_classification_result", False)
84  if use_cls:
85  self.subscribers = [
86  MF.Subscriber("~input/boxes", BoundingBoxArray, queue_size=1),
87  MF.Subscriber("~input/class", ClassificationResult, queue_size=1),
88  ]
89  if rospy.get_param("~approximate_sync", True):
90  sync = MF.ApproximateTimeSynchronizer(
91  self.subscribers,
92  queue_size=rospy.get_param("~queue_size", 10),
93  slop=rospy.get_param("~slop", 0.1),
94  )
95  else:
96  sync = MF.TimeSynchronizer(
97  self.subscribers,
98  queue_size=rospy.get_param("~queue_size", 100),
99  )
100  sync.registerCallback(self.on_objects)
101  else:
102  self.subscribers = [
103  rospy.Subscriber("~input/boxes", BoundingBoxArray,
104  self.on_objects, queue_size=1),
105  ]
106 
107  self.subscribers.append(
108  rospy.Subscriber("~input", PeoplePoseArray, self.on_people, queue_size=1))
109 
110  def unsubscribe(self):
111  for sub in self.subs:
112  sub.unregister()
113 
114  def on_objects(self, bbox_msg, cls_msg=None):
115  """
116  bbox_msg (jsk_recognition_msgs/BoundingBoxArray)
117  cls_msg (jsk_recognition_msgs/ClassificationResult)
118  """
119  if cls_msg is not None:
120  if len(bbox_msg.boxes) != len(cls_msg.labels):
121  rospy.logwarn("len(boxes) != len(labels)")
122  return
123  for bbox, label in zip(bbox_msg.boxes, cls_msg.labels):
124  bbox.label = label
125  self.objects = bbox_msg.boxes
126  rospy.loginfo("on_objects")
127 
128  def on_people(self, ppl_msg):
129  """
130  ppl_msg (jsk_recognition_msgs/PeoplePoseArray)
131 
132  refer: https://github.com/CMU-Perceptual-Computing-Lab/openpose/blob/master/doc/output.md
133  """
134  frame_id = remove_slash(ppl_msg.header.frame_id)
135  in_objects = self.objects
136  objects = []
137  for bbox in in_objects:
138  if remove_slash(bbox.header.frame_id) != frame_id:
139  ps = PoseStamped(header=bbox.header, pose=bbox.pose)
140  try:
141  ps = self.tfl.transform(ps, frame_id)
142  bbox.header, bbox.pose = ps.header, ps.pose
143  objects.append(bbox)
144  except tf2_ros.TransformException:
145  continue
146 
147  out_bboxes = []
148  out_markers = []
149  for i, pose in enumerate(ppl_msg.poses):
150  # for each person
151  if "rarm" in self.use_arm:
152  rwrist = find_pose("RWrist", pose)
153  rfinger = find_pose(["RHand5", "RHand6", "RHand7", "RHand8"], pose)
154  if rwrist is not None and rfinger is not None:
155  rclosest, rdist = self.get_closest_bbox((rwrist, rfinger), objects)
156  if rdist is not None and\
157  self.min_dist_threshold <= rdist <= self.max_dist_threshold:
158  out_bboxes.append(rclosest)
159  rmarker = self.get_marker((rwrist, rfinger), frame_id)
160  rmarker.id = 2 * i
161  out_markers.append(rmarker)
162 
163  if "larm" in self.use_arm:
164  lwrist = find_pose("LWrist", pose)
165  lfinger = find_pose(["LHand5", "LHand6", "LHand7", "LHand8"], pose)
166  if lwrist is not None and lfinger is not None:
167  lclosest, ldist = self.get_closest_bbox((lwrist, lfinger), objects)
168  if ldist is not None and\
169  self.min_dist_threshold <= ldist <= self.max_dist_threshold:
170  out_bboxes.append(lclosest)
171  lmarker = self.get_marker((lwrist, lfinger), frame_id)
172  lmarker.id = 2 * i + 1
173  out_markers.append(lmarker)
174 
175  # publish
176  if out_bboxes:
177  msg = BoundingBoxArray()
178  msg.header.stamp = rospy.Time.now()
179  msg.header.frame_id = frame_id
180  msg.boxes = out_bboxes
181  self.pub_bbox.publish(msg)
182  if out_markers:
183  self.pub_marker.publish(MarkerArray(markers=out_markers))
184 
185  def get_marker(self, line_seg, frame_id):
186  p0, p1 = line_seg
187  m = Marker()
188  m.header.stamp = rospy.Time.now()
189  m.header.frame_id = frame_id
190  m.ns = "beam"
191  m.type = Marker.ARROW
192  m.action = Marker.MODIFY
193  m.lifetime = rospy.Duration(1)
194  m.points = [p0.position, p1.position]
195  m.scale.x = 0.02
196  m.scale.y = 0.04
197  m.color.r = 1.0
198  m.color.a = 1.0
199  return m
200 
201  def get_closest_bbox(self, line_seg, bboxes):
202  pose0, pose1 = line_seg
203  p0 = np.asarray([pose0.position.x, pose0.position.y, pose0.position.z])
204  p1 = np.asarray([pose1.position.x, pose1.position.y, pose1.position.z])
205  min_d, closest = None, None
206 
207  n01 = np.linalg.norm(p1 - p0)
208  if n01 == 0.0:
209  return closest, min_d
210 
211  for bbox in bboxes:
212  pos = bbox.pose.position
213  p = np.asarray([pos.x, pos.y, pos.z])
214 
215  # check if the order is p0 -> p1 -> p
216  n = np.linalg.norm(p - p0)
217  ip = np.inner(p1 - p0, p - p0) / (n01 * n)
218  rospy.logdebug("ip: %s, dn: %s" % (ip, n - n01))
219  if ip < 0.0 or n - n01 < self.min_norm_threshold:
220  continue
221 
222  d = np.linalg.norm(np.cross(p1 - p0, p0 - p)) / np.linalg.norm(p1 - p0)
223  if min_d is None or min_d > d:
224  min_d, closest = d, bbox
225 
226  return closest, min_d
227 
228 
229 if __name__ == '__main__':
230  rospy.init_node("pointit")
231  p = PointIt()
232  rospy.spin()
def get_closest_bbox(self, line_seg, bboxes)
Definition: pointit.py:201
def remove_slash(frame_id)
Definition: pointit.py:34
def on_people(self, ppl_msg)
Definition: pointit.py:128
def get_marker(self, line_seg, frame_id)
Definition: pointit.py:185
def on_objects(self, bbox_msg, cls_msg=None)
Definition: pointit.py:114
def find_pose(limb, msg)
Definition: pointit.py:20


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27