Skip to content

Commit 4bd4e8a

Browse files
committed
Review feedback.
Signed-off-by: Chris Lalancette <[email protected]>
1 parent 064ccfb commit 4bd4e8a

File tree

4 files changed

+8
-16
lines changed

4 files changed

+8
-16
lines changed

image_tools_py/burger_py.py

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,11 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
# System imports
1615
import base64
1716
import random
1817

19-
# OpenCV
2018
import cv2
2119

22-
# Numpy
2320
import numpy
2421

2522
# THE FOLLOWING IS A BURGER IN BASE64. RESPECT IT

image_tools_py/cam2image_py.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -12,26 +12,24 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
# System imports
1615
import argparse
1716
import sys
1817

19-
# Local imports
2018
import burger_py
2119

22-
# OpenCV imports
2320
import cv2
2421

25-
# ROS2 imports
2622
import rclpy
2723
from rclpy.qos import qos_profile_system_default, qos_profile_sensor_data
2824
import sensor_msgs.msg
2925
import std_msgs.msg
3026

3127

32-
# Convert an OpenCV matrix encoding type to a string format recognized by
33-
# sensor_msgs::Image
3428
def mat2encoding(frame):
29+
'''
30+
Convert an OpenCV matrix encoding type to a string format recognized by
31+
sensor_msgs::msg::Image
32+
'''
3533
encoding = ''
3634

3735
encodings = {1: 'mono', 3: 'bgr', 4: 'rgba'}
@@ -53,8 +51,10 @@ def mat2encoding(frame):
5351
return encoding
5452

5553

56-
# Convert an OpenCV matrix to a ROS Image message.
5754
def convert_frame_to_message(frame, frame_id, msg):
55+
'''
56+
Convert an OpenCV matrix to a ROS Image message.
57+
'''
5858
msg.height = frame.shape[0]
5959
msg.width = frame.shape[1]
6060
msg.encoding = mat2encoding(frame)
@@ -165,7 +165,6 @@ def flip_image_cb(msg):
165165
frame_number = 1
166166
while rclpy.ok():
167167
# Get the frame from the video capture.
168-
frame = None
169168
if args.burger_mode:
170169
frame = burger_cap.render_burger(args.width, args.height)
171170
else:

image_tools_py/setup.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ def run(self):
4747

4848
setup(
4949
name=package_name,
50-
version='0.0.0',
50+
version='0.1.0',
5151
packages=[],
5252
py_modules=[
5353
'burger_py',

image_tools_py/showimage_py.py

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -12,16 +12,12 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
# System imports
1615
import argparse
1716

18-
# OpenCV imports
1917
import cv2
2018

21-
# Numpy imports
2219
import numpy
2320

24-
# ROS2 imports
2521
import rclpy
2622
from rclpy.qos import qos_profile_system_default
2723
import sensor_msgs.msg

0 commit comments

Comments
 (0)