8 from jsk_recognition_msgs.msg
import ClusterPointIndices
9 from jsk_recognition_msgs.msg
import RectArray
10 from jsk_topic_tools
import ConnectionBasedTransport
11 from pcl_msgs.msg
import PointIndices
12 from sensor_msgs.msg
import CameraInfo
18 super(RectArrayToClusterPointIndices, self).
__init__()
19 self.
pub = self.advertise(
'~output', ClusterPointIndices, queue_size=1)
22 if rospy.get_param(
'~use_info',
False):
25 self.
subs = [sub_rects, sub_info]
26 queue_size = rospy.get_param(
'~queue_size', 10)
27 if rospy.get_param(
'~approximate_sync',
False):
28 slop = rospy.get_param(
'~slop', 0.1)
29 sync = message_filters.ApproximateTimeSynchronizer(
30 self.
subs, queue_size=queue_size, slop=slop)
33 self.
subs, queue_size=queue_size)
38 sub_rects = rospy.Subscriber(
'~input', RectArray, self.
_convert)
39 self.
subs = [sub_rects]
50 def _convert(self, rects_msg, img_height=None, img_width=None):
51 H = self.
img_height if img_height
is None else img_height
52 W = self.
img_width if img_width
is None else img_width
53 cpi_msg = ClusterPointIndices(header=rects_msg.header)
54 for rect
in rects_msg.rects:
55 indices_msg = PointIndices(header=rects_msg.header)
56 ymin = max(0, int(np.floor(rect.y)))
57 xmin = max(0, int(np.floor(rect.x)))
58 ymax = min(H, int(np.ceil(rect.y + rect.height)))
59 xmax = min(W, int(np.ceil(rect.x + rect.width)))
60 indices = [list(range(W*y+xmin, W*y+xmax))
for y
in range(ymin, ymax)]
61 indices_msg.indices = np.array(indices, dtype=np.int32).flatten()
62 cpi_msg.cluster_indices.append(indices_msg)
63 self.
pub.publish(cpi_msg)
66 if __name__ ==
'__main__':
67 rospy.init_node(
'rect_array_to_cluster_point_indices')