4 from distutils.version
import LooseVersion
9 import matplotlib.pyplot
as plt
12 import scipy.ndimage
as ndi
14 from skimage.color
import gray2rgb
15 from skimage.color
import label2rgb
16 from skimage.future.graph
import merge_hierarchical
17 from skimage.future.graph
import RAG
18 from skimage.future.graph.rag
import _add_edge_filter
19 from skimage.morphology.convex_hull
import convex_hull_image
20 from skimage.segmentation
import slic
21 from skimage.util
import img_as_uint
24 from jsk_topic_tools
import ConnectionBasedTransport
25 from jsk_topic_tools
import warn_no_remap
26 import message_filters
28 from sensor_msgs.msg
import Image
30 if LooseVersion(skimage.__version__) >=
'0.13.0':
31 from skimage.future.graph
import show_rag
33 from skimage.future.graph
import draw_rag
47 fp = ndi.generate_binary_structure(labels.ndim, connectivity)
48 for d
in range(fp.ndim):
49 fp = fp.swapaxes(0, d)
51 fp = fp.swapaxes(0, d)
66 function=_add_edge_filter,
69 output=np.zeros(labels.shape, dtype=np.uint8),
70 extra_arguments=(graph,))
78 solidity = 1. * mask.sum() / convex_hull_image(mask).sum()
79 graph.node[n].update({
'labels': [n],
83 if LooseVersion(networkx.__version__) >=
'2':
84 edges_iter = graph.edges(data=
True)
86 edges_iter = graph.edges_iter(data=
True)
87 for x, y, d
in edges_iter:
88 new_mask = np.logical_or(graph.node[x][
'mask'], graph.node[y][
'mask'])
89 new_solidity = 1. * new_mask.sum() / convex_hull_image(new_mask).sum()
90 org_solidity = np.mean([graph.node[x][
'solidity'],
91 graph.node[y][
'solidity']])
92 d[
'weight'] = org_solidity / new_solidity
102 """Callback to handle merging nodes by recomputing solidity.""" 103 org_solidity = np.mean([graph.node[src][
'solidity'],
104 graph.node[dst][
'solidity']])
105 new_mask1 = np.logical_or(graph.node[src][
'mask'], graph.node[n][
'mask'])
106 new_mask2 = np.logical_or(graph.node[dst][
'mask'], graph.node[n][
'mask'])
107 new_solidity1 = 1. * new_mask1.sum() / convex_hull_image(new_mask1).sum()
108 new_solidity2 = 1. * new_mask2.sum() / convex_hull_image(new_mask2).sum()
109 weight1 = org_solidity / new_solidity1
110 weight2 = org_solidity / new_solidity2
111 return {
'weight': min([weight1, weight2])}
115 """Callback called before merging two nodes of a solidity graph.""" 116 new_mask = np.logical_or(graph.node[src][
'mask'], graph.node[dst][
'mask'])
117 graph.node[dst][
'mask'] = new_mask
118 graph.node[dst][
'solidity'] = \
119 1. * np.sum(new_mask) / np.sum(convex_hull_image(new_mask))
127 labels = slic(img, n_segments=n_segments, compactness=compactness)
129 n_labels = len(np.unique(labels))
131 mask = ndi.binary_closing(mask, structure=np.ones((3, 3)), iterations=1)
132 except IndexError
as e:
135 labels[mask == 0] = 0
136 if len(np.unique(labels)) < n_labels - 2:
137 sys.stderr.write(
'WARNING: number of label differs after masking.' 138 ' Maybe this is not good for RAG construction.\n')
143 closed_mask = ndi.binary_closing(
144 mask, structure=np.ones((3, 3)), iterations=8)
145 roi = ndi.find_objects(closed_mask, max_label=1)[0]
156 super(SolidityRagMerge, self).
__init__()
157 self.
pub = self.advertise(
'~output', Image, queue_size=5)
160 self.
pub_rag = self.advertise(
'~debug/rag', Image, queue_size=5)
161 self.
pub_slic = self.advertise(
'~debug/slic', Image, queue_size=5)
162 self.
pub_label = self.advertise(
'~debug/label_viz', Image,
168 self.
use_async = rospy.get_param(
'~approximate_sync',
False)
169 rospy.loginfo(
'~approximate_sync: {}'.format(self.
use_async))
171 sync = message_filters.ApproximateTimeSynchronizer(
172 [self.
sub, self.
sub_mask], queue_size=1000, slop=0.1)
176 sync.registerCallback(self.
_apply)
177 warn_no_remap(
'~input',
'~input/mask')
180 self.sub.unregister()
181 self.sub_mask.unregister()
184 bridge = cv_bridge.CvBridge()
185 img = bridge.imgmsg_to_cv2(imgmsg)
188 mask = bridge.imgmsg_to_cv2(maskmsg, desired_encoding=
'mono8')
189 mask = mask.reshape(mask.shape[:2])
192 roi_labels =
masked_slic(img=img[roi], mask=mask[roi],
193 n_segments=20, compactness=30)
194 if roi_labels
is None:
196 labels = np.zeros(mask.shape, dtype=np.int32)
198 labels[roi] = roi_labels
201 slic_labelmsg = bridge.cv2_to_imgmsg(labels)
202 slic_labelmsg.header = imgmsg.header
203 self.pub_slic.publish(slic_labelmsg)
208 if LooseVersion(skimage.__version__) >=
'0.13.0':
209 fig, ax = plt.subplots(
210 figsize=(img.shape[1] * 0.01, img.shape[0] * 0.01))
211 show_rag(labels, g, img, ax=ax)
213 plt.subplots_adjust(0, 0, 1, 1)
215 w, h = fig.canvas.get_width_height()
216 rag_img = np.fromstring(
217 fig.canvas.tostring_rgb(), dtype=np.uint8)
218 rag_img.shape = (h, w, 3)
221 rag_img = draw_rag(labels, g, img)
222 rag_img = img_as_uint(rag_img)
223 rag_imgmsg = bridge.cv2_to_imgmsg(
224 rag_img.astype(np.uint8), encoding=
'rgb8')
225 rag_imgmsg.header = imgmsg.header
226 self.pub_rag.publish(rag_imgmsg)
228 merged_labels = merge_hierarchical(
229 labels, g, thresh=1, rag_copy=
False,
231 merge_func=_solidity_merge_func,
232 weight_func=_solidity_weight_func)
234 merged_labels[mask == 0] = 0
235 merged_labelmsg = bridge.cv2_to_imgmsg(merged_labels.astype(np.int32))
236 merged_labelmsg.header = imgmsg.header
237 self.pub.publish(merged_labelmsg)
240 out = (out * 255).astype(np.uint8)
241 out_msg = bridge.cv2_to_imgmsg(out, encoding=
'rgb8')
242 out_msg.header = imgmsg.header
243 self.pub_label.publish(out_msg)
246 if __name__ ==
'__main__':
247 rospy.init_node(
'solidity_rag_merge')
def rag_solidity(labels, connectivity=2)
rag function
def _solidity_weight_func(graph, src, dst, n)
rag merging functions
def _solidity_merge_func(graph, src, dst)
def closed_mask_roi(mask)
def label2rgb(lbl, img=None, label_names=None, alpha=0.3, bg_label=0)
def _apply(self, imgmsg, maskmsg)
def masked_slic(img, mask, n_segments, compactness)
utils