7 from jsk_topic_tools
import ConnectionBasedTransport
8 from jsk_recognition_msgs.msg
import RectArray, Rect
11 from sensor_msgs.msg
import Image
18 return max(self.
rect.width, self.
rect.height) - max(another.rect.width, another.rect.height)
20 return min(self.
rect.width, self.
rect.height) - min(another.rect.width, another.rect.height)
22 return self.
rect.height - another.rect.height
24 return self.
rect.width - another.rect.width
33 def fit(self, blocks):
36 self.
root =
Block(Rect(x=0, y=0, width=blocks[0].rect.width, height=blocks[0].rect.height))
38 node = self.
find_node(self.
root, block.rect.width, block.rect.height)
40 block.fit_location = self.
split(node, block.rect.width, block.rect.height)
42 block.fit_location = self.
grow_node(block.rect.width, block.rect.height)
46 elif w <= root.rect.width
and h <= root.rect.height:
52 node.down =
Block(Rect(x=node.rect.x, y=node.rect.y + h, width=w, height=node.rect.height - h))
53 node.right =
Block(Rect(x=node.rect.x + w, y=node.rect.y, width=node.rect.width - w, height=h))
56 can_grow_down = w <= self.
root.rect.width
57 can_grow_right = h <= self.
root.rect.height
58 should_grow_right = can_grow_right
and self.
root.rect.height >= self.
root.rect.width + w
59 should_grow_down = can_grow_down
and self.
root.rect.width >= self.
root.rect.height + h
62 elif should_grow_down:
72 self.
root =
Block(Rect(x=0, y=0, width=self.
root.rect.width + w, height=self.
root.rect.height))
73 self.
root.down = prev_root
74 self.
root.right =
Block(Rect(x=prev_root.rect.width, y=0, width=w, height=prev_root.rect.height))
78 return self.
split(node, w, h)
83 self.
root =
Block(Rect(x=0, y=0, width=self.
root.rect.width, height=self.
root.rect.height + h))
84 self.
root.right = prev_root
85 self.
root.down =
Block(Rect(x=0, y=prev_root.rect.height, width=prev_root.rect.width, height=h))
89 return self.
split(node, w, h)
101 self.
pub_ = self.advertise(
'~output', Image, queue_size=10)
107 if rospy.get_param(
'~approximate_sync',
False):
108 self.
sync = message_filters.ApproximateTimeSynchronizer(
115 self.
sub_.sub.unregister()
118 bridge = cv_bridge.CvBridge()
119 img = bridge.imgmsg_to_cv2(img_msg)
120 root_rect, blocks = self.
bin_pack(rects)
121 output_img = np.zeros((root_rect.height, root_rect.width, img.shape[2]), dtype=img.dtype)
123 location = block.fit_location
124 output_img[location.rect.y:location.rect.y + block.rect.height,
125 location.rect.x:location.rect.x + block.rect.width] = img[block.rect.y:block.rect.y+block.rect.height, block.rect.x:block.rect.x + block.rect.width]
126 output_img_msg = bridge.cv2_to_imgmsg(output_img, encoding=img_msg.encoding)
127 output_img_msg.header = img_msg.header
128 self.
pub_.publish(output_img_msg)
132 blocks = [
Block(rect)
for rect
in rects.rects]
135 blocks.sort(reverse=
True)
137 print((packer.root.rect.width, packer.root.rect.height))
138 return (packer.root.rect, blocks)
145 if __name__ ==
'__main__':
146 rospy.init_node(
'binpack')