From 8a3f217901d8ea3bdf9179012d4b3965e6df74e4 Mon Sep 17 00:00:00 2001 From: Michael Jeronimo Date: Tue, 13 Oct 2020 15:02:14 -0700 Subject: [PATCH 1/3] Fix a few minor issues in image_helper * Used ByteIO rather than StringIO is now required for PIL's Image.open * Remove unused variable, 'alpha' * Added support for '8UC1' and '32FC1' image types * Only do bgr2rgb if it's definitely a BGR type Fixes #60 Signed-off-by: Michael Jeronimo --- .../src/rqt_bag_plugins/image_helper.py | 25 ++++++++++--------- 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py b/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py index 3a7f2b4..1a7a511 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py @@ -32,10 +32,7 @@ from __future__ import print_function import array -try: - from cStringIO import StringIO -except ImportError: - from io import StringIO +from io import BytesIO import sys from PIL import Image @@ -49,14 +46,13 @@ def imgmsg_to_pil(img_msg, rgba=True): try: if img_msg._type == 'sensor_msgs/CompressedImage': - pil_img = Image.open(StringIO(img_msg.data)) - if pil_img.mode != 'L': + pil_img = Image.open(BytesIO(img_msg.data)) + if pil_img.mode.startswith('BGR'): pil_img = pil_bgr2rgb(pil_img) pil_mode = 'RGB' else: - alpha = False pil_mode = 'RGB' - if img_msg.encoding == 'mono8': + if img_msg.encoding in ['mono8', '8UC1']: mode = 'L' elif img_msg.encoding == 'rgb8': mode = 'RGB' @@ -67,21 +63,25 @@ def imgmsg_to_pil(img_msg, rgba=True): elif img_msg.encoding in ['bayer_rggb16', 'bayer_bggr16', 'bayer_gbrg16', 'bayer_grbg16']: pil_mode = 'I;16' if img_msg.is_bigendian: - mode='I;16B' + mode = 'I;16B' else: - mode='I;16L' + mode = 'I;16L' elif img_msg.encoding == 'mono16' or img_msg.encoding == '16UC1': pil_mode = 'F' if img_msg.is_bigendian: mode = 'F;16B' else: mode = 'F;16' + elif img_msg.encoding == '32FC1': + pil_mode = 'F' + if img_msg.is_bigendian: + mode = 'F;32BF' + else: + mode = 'F;32F' elif img_msg.encoding == 'rgba8': mode = 'BGR' - alpha = True elif img_msg.encoding == 'bgra8': mode = 'RGB' - alpha = True else: raise Exception("Unsupported image format: %s" % img_msg.encoding) pil_img = Image.frombuffer( @@ -90,6 +90,7 @@ def imgmsg_to_pil(img_msg, rgba=True): # 16 bits conversion to 8 bits if pil_mode == 'I;16': pil_img = pil_img.convert('I').point(lambda i: i * (1. / 256.)).convert('L') + if pil_img.mode == 'F': pil_img = pil_img.point(lambda i: i * (1. / 256.)).convert('L') pil_img = ImageOps.autocontrast(pil_img) From fafe2eec2689ff1e5b8a2d128eff07942a80178b Mon Sep 17 00:00:00 2001 From: Michael Jeronimo Date: Mon, 26 Oct 2020 14:34:21 -0700 Subject: [PATCH 2/3] Add a missing encode() call --- rqt_bag/src/rqt_bag/plugins/raw_view.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rqt_bag/src/rqt_bag/plugins/raw_view.py b/rqt_bag/src/rqt_bag/plugins/raw_view.py index cad3faf..c3df80d 100644 --- a/rqt_bag/src/rqt_bag/plugins/raw_view.py +++ b/rqt_bag/src/rqt_bag/plugins/raw_view.py @@ -204,7 +204,7 @@ def _add_msg_object(self, parent, path, name, obj, obj_type): elif type(obj) in [str, bool, int, long, float, complex, rospy.Time]: # Ignore any binary data - obj_repr = codecs.utf_8_decode(str(obj), 'ignore')[0] + obj_repr = codecs.utf_8_decode(str(obj).encode(), 'ignore')[0] # Truncate long representations if len(obj_repr) >= 50: From 9f26c0689fc7d71039f2cae542f3255965821ddd Mon Sep 17 00:00:00 2001 From: Michael Jeronimo Date: Wed, 28 Oct 2020 09:37:10 -0700 Subject: [PATCH 3/3] Invert 32F depth images so that closer is lighter and farther is darker Signed-off-by: Michael Jeronimo --- rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py | 1 + 1 file changed, 1 insertion(+) diff --git a/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py b/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py index 1a7a511..8d9e486 100755 --- a/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py +++ b/rqt_bag_plugins/src/rqt_bag_plugins/image_helper.py @@ -94,6 +94,7 @@ def imgmsg_to_pil(img_msg, rgba=True): if pil_img.mode == 'F': pil_img = pil_img.point(lambda i: i * (1. / 256.)).convert('L') pil_img = ImageOps.autocontrast(pil_img) + pil_img = ImageOps.invert(pil_img) if rgba and pil_img.mode != 'RGBA': pil_img = pil_img.convert('RGBA')