forked from Kautenja/rosbag-tools
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathplay_superpixel.py
executable file
·181 lines (167 loc) · 6.31 KB
/
play_superpixel.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
"""A script to play camera footage with a super pixel segmentation overlay."""
import argparse
import numpy as np
from rosbag import Bag
from skimage.color import rgb2gray
from skimage.filters import sobel
from skimage.segmentation import felzenszwalb
from skimage.segmentation import mark_boundaries
from skimage.segmentation import slic
from skimage.segmentation import watershed
from skimage.transform import resize
from skimage.util import img_as_float
from src.ros_utils import get_camera_dimensions
from src.ros_utils import get_camera_image
from src.ros_utils import get_depth_image
from src.window import Window
def segment(img,
method: str='felzenszwalb',
downscale: int=2,
mark: bool=True
):
"""
Segment an input image using an iterative method.
Args:
img: the input image to segment
method: the method to use for segmentation
downscale: the factor to downscale the image by before segmentation
mark: whether to return a marked image or the image segmentations
Returns:
a marked image or tensor of segmentations matching input image shape
"""
# downscale the input image by a factor of `downscale`
_img = resize(img, (img.shape[0] / downscale, img.shape[1] / downscale, img.shape[2]),
anti_aliasing=False,
mode='symmetric',
clip=False,
preserve_range=True,
).astype('uint8')
_img = img_as_float(_img)
# apply the segmentation algorithm
if method == 'slic':
segments = slic(_img, n_segments=1000, compactness=0.1, sigma=1)
elif method == 'felzenszwalb':
segments = felzenszwalb(_img, scale=25.0, sigma=0.5, min_size=30)
elif method == 'watershed':
segments = watershed(sobel(rgb2gray(_img)), markers=1e3, compactness=1e-4)
else:
raise ValueError('unexpected segmentation method: {}'.format(method))
print(segments.max())
# restore the segmentations to the original input shape
segments = resize(segments, img.shape[:2],
anti_aliasing=False,
mode='symmetric',
clip=False,
preserve_range=True,
).astype(segments.dtype)
# if mark is enabled, return a marked version of the input image
if mark:
img = mark_boundaries(img_as_float(img[..., :3]), segments)
return (255 * img).astype('uint8')
# otherwise return just the segmentations
else:
return segments
def play_superpixel(
bag_file: Bag,
camera_info: str,
camera: str,
depth: str,
segmentation: str,
downscale: int
) -> None:
"""
Play the camera data in a bag file through a super pixel algorithm.
Args:
bag_file: the bag file to play
camera_info: the topic to use to read metadata about the camera
camera: the topic to use to read compressed or raw camera data
depth: the topic to use to read 32-bit floating point depth measures
segmentation: the algorithm to use for segmentation
downscale: the factor to downscale the image by before segmentation
Returns:
None
"""
# extract the camera dimensions from the bag
dims = get_camera_dimensions(bag, camera_info)
# open a window to stream the data to
window = Window('{} ({})'.format(bag_file.filename, camera), *dims)
# iterate over the messages
for topic, msg, _ in bag.read_messages(topics=[camera, depth]):
# if topic is camera, unwrap the camera data
if topic == camera:
camera_img = get_camera_image(msg.data, dims)
# if topic is depth, unwrap and calculate the segmentation
elif topic == depth:
depth_img = get_depth_image(msg.data, dims)
# combine the image with the depth channel (Red only)
img = np.concatenate([camera_img, depth_img[..., 0:1]], axis=-1)
# segment the image and get a copy of the segmented pixels
img = segment(img, method=segmentation, downscale=downscale)
# send the segmented image to the window
window.show(img)
# shut down the viewer windows
window.close()
# ensure this script is running as the main entry point
if __name__ == '__main__':
# create an argument parser to read arguments from the command line
PARSER = argparse.ArgumentParser(description=__doc__,
formatter_class=argparse.ArgumentDefaultsHelpFormatter,
)
# add an argument for the bag file
PARSER.add_argument('--bag_file', '-b',
type=str,
help='The bag file containing the ZED data to play.',
required=True,
)
# add an argument for selecting the camera info topic
PARSER.add_argument('--camera_info', '-C',
type=str,
help='The topic to get information about the camera from.',
required=False,
default='/zed/left/camera_info_raw',
)
# add an argument for selecting the camera data topic
PARSER.add_argument('--camera', '-c',
type=str,
help='The topic to use to read camera data.',
required=False,
default='/zed/left/image_rect_color/compressed',
)
# add an argument for selecting the depth data topic
PARSER.add_argument('--depth', '-d',
type=str,
help='The topic to use to read depth data.',
required=False,
default='/zed/depth/depth_registered',
)
# add an argument for selecting the segmentation method
PARSER.add_argument('--segmentation_algorithm', '-s',
type=str,
help='The algorithm to use for generating segmentations.',
required=False,
default='felzenszwalb',
choices={'slic', 'felzenszwalb', 'watershed'},
)
# add an argument for selecting the segmentation method
PARSER.add_argument('--downscale', '-D',
type=int,
help='The factor to downscale images by before segmenting them',
required=False,
default=2,
)
# get the arguments from the argument parser
ARGS = PARSER.parse_args()
# play the bag given in the arguments
try:
with Bag(ARGS.bag_file) as bag:
play_superpixel(bag,
ARGS.camera_info,
ARGS.camera,
ARGS.depth,
ARGS.segmentation_algorithm,
ARGS.downscale
)
except KeyboardInterrupt:
pass
# explicitly define the outward facing API of this module
__all__ = [play_superpixel.__name__]