binpack_rect_array.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import numpy as np
4 
5 import cv_bridge
6 from jsk_recognition_utils.depth import split_fore_background
7 from jsk_topic_tools import ConnectionBasedTransport
8 from jsk_recognition_msgs.msg import RectArray, Rect
9 import message_filters
10 import rospy
11 from sensor_msgs.msg import Image
12 
13 class Block():
14  def __init__(self, rect):
15  self.rect = rect
16  self.used = False
17  def max_cmp(self, another):
18  return max(self.rect.width, self.rect.height) - max(another.rect.width, another.rect.height)
19  def min_cmp(self, another):
20  return min(self.rect.width, self.rect.height) - min(another.rect.width, another.rect.height)
21  def height_cmp(self, another):
22  return self.rect.height - another.rect.height
23  def width_cmp(self, another):
24  return self.rect.width - another.rect.width
25  def __cmp__(self, another): # python2
26  return self.max_cmp(another) or self.min_cmp(another) or self.height_cmp(another) or self.width_cmp(another) or 0
27  def __lt__(self, another): # python3
28  return self.max_cmp(another) or self.min_cmp(another) or self.height_cmp(another) or self.width_cmp(another) or 0
29 
30 class Packer():
31  def __init__(self):
32  pass
33  def fit(self, blocks):
34  if len(blocks) == 0:
35  return
36  self.root = Block(Rect(x=0, y=0, width=blocks[0].rect.width, height=blocks[0].rect.height))
37  for block in blocks:
38  node = self.find_node(self.root, block.rect.width, block.rect.height)
39  if node:
40  block.fit_location = self.split(node, block.rect.width, block.rect.height)
41  else:
42  block.fit_location = self.grow_node(block.rect.width, block.rect.height)
43  def find_node(self, root, w, h):
44  if root.used:
45  return self.find_node(root.right, w, h) or self.find_node(root.down, w, h)
46  elif w <= root.rect.width and h <= root.rect.height:
47  return root
48  else:
49  return False
50  def split(self, node, w, h):
51  node.used = True
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))
54  return node
55  def grow_node(self, w, 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
60  if should_grow_right:
61  return self.grow_right(w, h)
62  elif should_grow_down:
63  return self.grow_down(w, h)
64  elif can_grow_right:
65  return self.grow_right(w, h)
66  elif can_grow_down:
67  return self.grow_down(w, h)
68  else:
69  return None
70  def grow_right(self, w, h):
71  prev_root = self.root
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))
75  self.root.used = True
76  node = self.find_node(self.root, w, h)
77  if node:
78  return self.split(node, w, h)
79  else:
80  return None
81  def grow_down(self, w, h):
82  prev_root = self.root
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))
86  self.root.used = True
87  node = self.find_node(self.root, w, h)
88  if node:
89  return self.split(node, w, h)
90  else:
91  return None
92 
93 # def hoge(msg):
94 # print "~input", msg.header.stamp.to_sec()
95 # def fuga(msg):
96 # print "~input/rect_array", msg.header.stamp.to_sec()
97 
98 class BinPack(ConnectionBasedTransport):
99  def __init__(self):
100  super(BinPack, self).__init__()
101  self.pub_ = self.advertise('~output', Image, queue_size=10)
102  def subscribe(self):
103  self.sub_ = message_filters.Subscriber('~input', Image, queue_size=1)
104  self.sub_rects_ = message_filters.Subscriber('~input/rect_array', RectArray, queue_size=1)
105  # self.sub_.registerCallback(hoge)
106  # self.sub_rects_.registerCallback(fuga)
107  if rospy.get_param('~approximate_sync', False):
108  self.sync = message_filters.ApproximateTimeSynchronizer(
109  [self.sub_, self.sub_rects_], queue_size=100, slop=.1)
110  else:
112  [self.sub_, self.sub_rects_], queue_size=100)
113  self.sync.registerCallback(self._apply)
114  def unsubscribe(self):
115  self.sub_.sub.unregister()
116  self.sub_rects_.sub.unregister()
117  def _apply(self, img_msg, rects):
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)
122  for block in blocks:
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)
129  def bin_pack(self, rects):
130  # Solve 2D BinPacking problem
131  packer = Packer()
132  blocks = [Block(rect) for rect in rects.rects]
133  # sort by some algorithms
134  #blocks.sort(key=lambda x: x.rect.width*x.rect.height, reverse=True)
135  blocks.sort(reverse=True)
136  packer.fit(blocks)
137  print((packer.root.rect.width, packer.root.rect.height))
138  return (packer.root.rect, blocks)
139  # for block in blocks:
140  # if block.fit_location:
141  # print (block.fit_location.rect.x, block.fit_location.rect.y, block.fit_location.rect.width, block.fit_location.rect.height)
142  # print " --", (block.rect.x, block.rect.y, block.rect.width, block.rect.height)
143 
144 
145 if __name__ == '__main__':
146  rospy.init_node('binpack')
147  bin_pack = BinPack()
148  rospy.spin()
node_scripts.binpack_rect_array.BinPack.sub_rects_
sub_rects_
Definition: binpack_rect_array.py:104
node_scripts.binpack_rect_array.Block.height_cmp
def height_cmp(self, another)
Definition: binpack_rect_array.py:21
node_scripts.binpack_rect_array.Block
Definition: binpack_rect_array.py:13
node_scripts.binpack_rect_array.Packer.grow_down
def grow_down(self, w, h)
Definition: binpack_rect_array.py:81
node_scripts.binpack_rect_array.Packer.split
def split(self, node, w, h)
Definition: binpack_rect_array.py:50
node_scripts.binpack_rect_array.Block.__init__
def __init__(self, rect)
Definition: binpack_rect_array.py:14
node_scripts.binpack_rect_array.BinPack.unsubscribe
def unsubscribe(self)
Definition: binpack_rect_array.py:114
node_scripts.binpack_rect_array.Packer.root
root
Definition: binpack_rect_array.py:36
node_scripts.binpack_rect_array.Block.__lt__
def __lt__(self, another)
Definition: binpack_rect_array.py:27
node_scripts.binpack_rect_array.Block.__cmp__
def __cmp__(self, another)
Definition: binpack_rect_array.py:25
node_scripts.binpack_rect_array.Packer.grow_right
def grow_right(self, w, h)
Definition: binpack_rect_array.py:70
message_filters::Subscriber
node_scripts.binpack_rect_array.Block.rect
rect
Definition: binpack_rect_array.py:15
node_scripts.binpack_rect_array.BinPack.pub_
pub_
Definition: binpack_rect_array.py:101
node_scripts.binpack_rect_array.BinPack._apply
def _apply(self, img_msg, rects)
Definition: binpack_rect_array.py:117
node_scripts.binpack_rect_array.Packer.find_node
def find_node(self, root, w, h)
Definition: binpack_rect_array.py:43
node_scripts.binpack_rect_array.Block.max_cmp
def max_cmp(self, another)
Definition: binpack_rect_array.py:17
node_scripts.binpack_rect_array.BinPack.subscribe
def subscribe(self)
Definition: binpack_rect_array.py:102
node_scripts.binpack_rect_array.Packer.__init__
def __init__(self)
Definition: binpack_rect_array.py:31
node_scripts.binpack_rect_array.Block.min_cmp
def min_cmp(self, another)
Definition: binpack_rect_array.py:19
node_scripts.binpack_rect_array.BinPack.sub_
sub_
Definition: binpack_rect_array.py:103
node_scripts.binpack_rect_array.BinPack
Definition: binpack_rect_array.py:98
node_scripts.binpack_rect_array.Packer.grow_node
def grow_node(self, w, h)
Definition: binpack_rect_array.py:55
jsk_recognition_utils::depth
node_scripts.binpack_rect_array.Packer
Definition: binpack_rect_array.py:30
node_scripts.binpack_rect_array.Block.used
used
Definition: binpack_rect_array.py:16
node_scripts.binpack_rect_array.Block.width_cmp
def width_cmp(self, another)
Definition: binpack_rect_array.py:23
node_scripts.binpack_rect_array.Packer.fit
def fit(self, blocks)
Definition: binpack_rect_array.py:33
message_filters::TimeSynchronizer
node_scripts.binpack_rect_array.BinPack.sync
sync
Definition: binpack_rect_array.py:108
node_scripts.binpack_rect_array.BinPack.bin_pack
def bin_pack(self, rects)
Definition: binpack_rect_array.py:129
node_scripts.binpack_rect_array.BinPack.__init__
def __init__(self)
Definition: binpack_rect_array.py:99


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16