5 from jsk_topic_tools
import ConnectionBasedTransport
6 import message_filters
as MF
10 import tf2_geometry_msgs
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
21 if isinstance(limb, list):
28 idx = msg.limb_names.index(limb)
35 if frame_id.startswith(
"/"):
52 if rospy.has_param(
"~dist_threshold"):
53 rospy.logwarn(
"Parameter ~dist_threshold is deprecated. " 54 "Use ~max_dist_threshold instead.")
58 "~max_dist_threshold", 0.1)
62 self.
use_arm = rospy.get_param(
"~use_arm", [
"rarm",
"larm"])
65 rospy.logfatal(
"~use_arm must contain at least 'rarm' or 'larm'.")
68 use_tf2_buffer_client = rospy.get_param(
"~use_tf2_buffer_client",
True)
69 if use_tf2_buffer_client:
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:
79 self.
pub_bbox = self.advertise(
"~output", BoundingBoxArray, queue_size=1)
80 self.
pub_marker = self.advertise(
"~output/marker_array", MarkerArray, queue_size=1)
83 use_cls = rospy.get_param(
"~use_classification_result",
False)
86 MF.Subscriber(
"~input/boxes", BoundingBoxArray, queue_size=1),
87 MF.Subscriber(
"~input/class", ClassificationResult, queue_size=1),
89 if rospy.get_param(
"~approximate_sync",
True):
90 sync = MF.ApproximateTimeSynchronizer(
92 queue_size=rospy.get_param(
"~queue_size", 10),
93 slop=rospy.get_param(
"~slop", 0.1),
96 sync = MF.TimeSynchronizer(
98 queue_size=rospy.get_param(
"~queue_size", 100),
103 rospy.Subscriber(
"~input/boxes", BoundingBoxArray,
107 self.subscribers.append(
108 rospy.Subscriber(
"~input", PeoplePoseArray, self.
on_people, queue_size=1))
111 for sub
in self.subs:
116 bbox_msg (jsk_recognition_msgs/BoundingBoxArray) 117 cls_msg (jsk_recognition_msgs/ClassificationResult) 119 if cls_msg
is not None:
120 if len(bbox_msg.boxes) != len(cls_msg.labels):
121 rospy.logwarn(
"len(boxes) != len(labels)")
123 for bbox, label
in zip(bbox_msg.boxes, cls_msg.labels):
126 rospy.loginfo(
"on_objects")
130 ppl_msg (jsk_recognition_msgs/PeoplePoseArray) 132 refer: https://github.com/CMU-Perceptual-Computing-Lab/openpose/blob/master/doc/output.md 137 for bbox
in in_objects:
139 ps = PoseStamped(header=bbox.header, pose=bbox.pose)
141 ps = self.tfl.transform(ps, frame_id)
142 bbox.header, bbox.pose = ps.header, ps.pose
144 except tf2_ros.TransformException:
149 for i, pose
in enumerate(ppl_msg.poses):
153 rfinger =
find_pose([
"RHand5",
"RHand6",
"RHand7",
"RHand8"], pose)
154 if rwrist
is not None and rfinger
is not None:
156 if rdist
is not None and\
158 out_bboxes.append(rclosest)
159 rmarker = self.
get_marker((rwrist, rfinger), frame_id)
161 out_markers.append(rmarker)
165 lfinger =
find_pose([
"LHand5",
"LHand6",
"LHand7",
"LHand8"], pose)
166 if lwrist
is not None and lfinger
is not None:
168 if ldist
is not None and\
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)
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)
183 self.pub_marker.publish(MarkerArray(markers=out_markers))
188 m.header.stamp = rospy.Time.now()
189 m.header.frame_id = frame_id
191 m.type = Marker.ARROW
192 m.action = Marker.MODIFY
193 m.lifetime = rospy.Duration(1)
194 m.points = [p0.position, p1.position]
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 207 n01 = np.linalg.norm(p1 - p0)
209 return closest, min_d
212 pos = bbox.pose.position
213 p = np.asarray([pos.x, pos.y, pos.z])
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))
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
226 return closest, min_d
229 if __name__ ==
'__main__':
230 rospy.init_node(
"pointit")
def get_closest_bbox(self, line_seg, bboxes)
def remove_slash(frame_id)
def on_people(self, ppl_msg)
def get_marker(self, line_seg, frame_id)
def on_objects(self, bbox_msg, cls_msg=None)