Skip to content

Commit df7827e

Browse files
committed
Make the flip_image_cb a local function.
This lets us get the is_flipped message out of the global namespace. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 79be7bb commit df7827e

File tree

1 file changed

+11
-12
lines changed

1 file changed

+11
-12
lines changed

image_tools_py/src/cam2image_py.py

Lines changed: 11 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -29,17 +29,6 @@
2929
import burger_py
3030
import image_qos_profile
3131

32-
is_flipped = False
33-
34-
35-
def flip_image_cb(msg):
36-
global is_flipped
37-
is_flipped = msg.data
38-
39-
output = 'on' if is_flipped else 'off'
40-
41-
print('Set flip mode to: ' + output)
42-
4332

4433
# Convert an OpenCV matrix encoding type to a string format recognized by
4534
# sensor_msgs::Image
@@ -124,6 +113,17 @@ def main():
124113
# Create the image publisher with our custom QoS profile.
125114
pub = node.create_publisher(sensor_msgs.msg.Image, 'image', custom_camera_qos_profile)
126115

116+
is_flipped = False
117+
118+
def flip_image_cb(msg):
119+
nonlocal is_flipped
120+
121+
is_flipped = msg.data
122+
123+
output = 'on' if is_flipped else 'off'
124+
125+
print('Set flip mode to: ' + output)
126+
127127
custom_flip_qos_profile = qos_profile_sensor_data
128128
custom_flip_qos_profile.depth = 10
129129
node.create_subscription(
@@ -154,7 +154,6 @@ def main():
154154

155155
# Check if the frame was grabbed correctly.
156156
if frame is not None:
157-
global is_flipped
158157
# Convert to a ROS image
159158
if is_flipped:
160159
# Flip the frame if needed

0 commit comments

Comments
 (0)