Skip to content

Commit 538210a

Browse files
committed
Reindent arguments for very long function names.
This is to conform to the style. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 240089c commit 538210a

File tree

2 files changed

+58
-61
lines changed

2 files changed

+58
-61
lines changed

image_tools_py/src/cam2image_py.py

Lines changed: 31 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -48,15 +48,15 @@ def flip_image_cb(msg):
4848
def mat2encoding(frame):
4949
encoding = ''
5050

51-
encodings = {1:'mono', 3:'bgr', 4:'rgba'}
51+
encodings = {1: 'mono', 3: 'bgr', 4: 'rgba'}
5252
for channels, prefix in encodings.items():
5353
if frame.shape[2] == channels:
5454
encoding += prefix
5555
break
5656
else:
5757
raise Exception("Unsupported frame shape %d" % (frame.shape[2]))
5858

59-
types = {'uint8':'8', 'int16':'16'}
59+
types = {'uint8': '8', 'int16': '16'}
6060
for dtype, num in types.items():
6161
if frame.dtype == dtype:
6262
encoding += num
@@ -87,33 +87,31 @@ def main():
8787

8888
# Parse the command-line options.
8989
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
90-
parser.add_argument('-b', '--burger', dest='burger_mode',
91-
action='store_true', default=False,
92-
help='Produce images of burgers rather than connecting to a camera')
93-
parser.add_argument('-d', '--depth', dest='queue_depth',
94-
action='store', default=10,
95-
type=int, help='Queue depth')
96-
parser.add_argument('-f', '--frequency', dest='frequency',
97-
action='store', default=30,
98-
type=int, help='Publish frequency in Hz')
99-
parser.add_argument('-k', '--keep', dest='keep',
100-
action='store', default=1,
101-
type=int, choices=[0, 1],
102-
help='History QoS setting, 0 - keep last sample, 1 - keep all the samples')
103-
parser.add_argument('-r', '--reliability', dest='reliability_policy',
104-
action='store', default=1,
105-
type=int, choices=[0, 1],
106-
help='Reliability QoS setting, 0 - best effort, 1 - reliable')
107-
parser.add_argument('-s', '--show', dest='show_camera',
108-
action='store', default=0,
109-
type=int, choices=[0, 1],
110-
help='Show the camera stream')
111-
parser.add_argument('-x', '--width', dest='width',
112-
action='store', default=320,
113-
type=int, help='Image width')
114-
parser.add_argument('-y', '--height', dest='height',
115-
action='store', default=240,
116-
type=int, help='Image height')
90+
parser.add_argument(
91+
'-b', '--burger', dest='burger_mode', action='store_true', default=False,
92+
help='Produce images of burgers rather than connecting to a camera')
93+
parser.add_argument(
94+
'-d', '--depth', dest='queue_depth', action='store', default=10, type=int,
95+
help='Queue depth')
96+
parser.add_argument(
97+
'-f', '--frequency', dest='frequency', action='store', default=30, type=int,
98+
help='Publish frequency in Hz')
99+
parser.add_argument(
100+
'-k', '--keep', dest='keep', action='store', default=1, type=int, choices=[0, 1],
101+
help='History QoS setting, 0 - keep last sample, 1 - keep all the samples')
102+
parser.add_argument(
103+
'-r', '--reliability', dest='reliability_policy', action='store', default=1, type=int,
104+
choices=[0, 1],
105+
help='Reliability QoS setting, 0 - best effort, 1 - reliable')
106+
parser.add_argument(
107+
'-s', '--show', dest='show_camera', action='store', default=0, type=int, choices=[0, 1],
108+
help='Show the camera stream')
109+
parser.add_argument(
110+
'-x', '--width', dest='width', action='store', default=320, type=int,
111+
help='Image width')
112+
parser.add_argument(
113+
'-y', '--height', dest='height', action='store', default=240, type=int,
114+
help='Image height')
117115
args = parser.parse_args()
118116

119117
# Initialize a ROS 2 node to publish images read from the OpenCV interface to
@@ -122,17 +120,16 @@ def main():
122120

123121
# Set the parameters of the quality of service profile. Initialize as the
124122
# default profile and set the QoS parameters specified on the command line.
125-
custom_camera_qos_profile = image_qos_profile.create_qos_profile(args.queue_depth,
126-
args.reliability_policy,
127-
args.keep)
123+
custom_camera_qos_profile = image_qos_profile.create_qos_profile(
124+
args.queue_depth, args.reliability_policy, args.keep)
128125

129126
# Create the image publisher with our custom QoS profile.
130127
pub = node.create_publisher(sensor_msgs.msg.Image, 'image', custom_camera_qos_profile)
131128

132129
custom_flip_qos_profile = qos_profile_sensor_data
133130
custom_flip_qos_profile.depth = 10
134-
node.create_subscription(std_msgs.msg.Bool, 'flip_image',
135-
flip_image_cb, custom_flip_qos_profile)
131+
node.create_subscription(
132+
std_msgs.msg.Bool, 'flip_image', flip_image_cb, custom_flip_qos_profile)
136133

137134
if args.burger_mode:
138135
burger_cap = burger_py.Burger()

image_tools_py/src/showimage_py.py

Lines changed: 27 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -30,14 +30,14 @@
3030

3131

3232
def encoding2mat(encoding):
33-
encodings = {'mono' : 1, 'bgr' : 3, 'rgba' : 4}
33+
encodings = {'mono': 1, 'bgr': 3, 'rgba': 4}
3434
for prefix, channels in encodings.items():
3535
if encoding.startswith(prefix):
3636
break
3737
else:
3838
raise Exception("Unsupported encoding " + encoding)
3939

40-
types = {'8' : 'uint8', '16' : 'int16'}
40+
types = {'8': 'uint8', '16': 'int16'}
4141
for prefix, dtype in types.items():
4242
if encoding[channels:] == prefix:
4343
break
@@ -53,21 +53,19 @@ def main():
5353

5454
# Parse the command-line options.
5555
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
56-
parser.add_argument('-d', '--depth', dest='queue_depth',
57-
action='store', default=10,
58-
type=int, help='Queue depth')
59-
parser.add_argument('-k', '--keep', dest='keep',
60-
action='store', default=1,
61-
type=int, choices=[0, 1],
62-
help='History QoS setting, 0 - keep last sample, 1 - keep all the samples')
63-
parser.add_argument('-r', '--reliability', dest='reliability_policy',
64-
action='store', default=1,
65-
type=int, choices=[0, 1],
66-
help='Reliability QoS setting, 0 - best effort, 1 - reliable')
67-
parser.add_argument('-s', '--show', dest='show_camera',
68-
action='store', default=0,
69-
type=int, choices=[0, 1],
70-
help='Show the camera stream')
56+
parser.add_argument(
57+
'-d', '--depth', dest='queue_depth', action='store', default=10, type=int,
58+
help='Queue depth')
59+
parser.add_argument(
60+
'-k', '--keep', dest='keep', action='store', default=1, type=int, choices=[0, 1],
61+
help='History QoS setting, 0 - keep last sample, 1 - keep all the samples')
62+
parser.add_argument(
63+
'-r', '--reliability', dest='reliability_policy', action='store', default=1, type=int,
64+
choices=[0, 1],
65+
help='Reliability QoS setting, 0 - best effort, 1 - reliable')
66+
parser.add_argument(
67+
'-s', '--show', dest='show_camera', action='store', default=0, type=int, choices=[0, 1],
68+
help='Show the camera stream')
7169
args = parser.parse_args()
7270

7371
if args.show_camera == 1:
@@ -77,9 +75,8 @@ def main():
7775
# the camera.
7876
node = rclpy.create_node('showimagepy')
7977

80-
custom_qos_profile = image_qos_profile.create_qos_profile(args.queue_depth,
81-
args.reliability_policy,
82-
args.keep)
78+
custom_qos_profile = image_qos_profile.create_qos_profile(
79+
args.queue_depth, args.reliability_policy, args.keep)
8380

8481
def image_cb(msg):
8582
print("Received image #" + msg.header.frame_id)
@@ -89,19 +86,22 @@ def image_cb(msg):
8986
dtype = numpy.dtype(dtype)
9087
dtype = dtype.newbyteorder('>' if msg.is_bigendian else '<')
9188
if n_channels == 1:
92-
frame = numpy.ndarray(shape=(msg.height, msg.width),
93-
dtype=dtype, buffer=bytes(msg.data))
89+
frame = numpy.ndarray(
90+
shape=(msg.height, msg.width),
91+
dtype=dtype,
92+
buffer=bytes(msg.data))
9493
else:
95-
frame = numpy.ndarray(shape=(msg.height, msg.width, n_channels),
96-
dtype=dtype, buffer=bytes(msg.data))
94+
frame = numpy.ndarray(
95+
shape=(msg.height, msg.width, n_channels),
96+
dtype=dtype,
97+
buffer=bytes(msg.data))
9798

9899
cv2.imshow("showimagepy", frame)
99100
# Draw the image to the screen and wait 1 millisecond
100101
cv2.waitKey(1)
101102

102-
103-
node.create_subscription(sensor_msgs.msg.Image, 'image',
104-
image_cb, custom_qos_profile)
103+
node.create_subscription(
104+
sensor_msgs.msg.Image, 'image', image_cb, custom_qos_profile)
105105

106106
while rclpy.ok():
107107
rclpy.spin_once(node)

0 commit comments

Comments
 (0)