Skip to content

Commit

Permalink
Show image script to display image- it looks to be working (why doesn…
Browse files Browse the repository at this point in the history
…'t image_tools showimage?), but the frame rate is very slow ros-drivers#103
  • Loading branch information
lucasw committed Oct 31, 2018
1 parent 0c4bf6b commit bbbad03
Show file tree
Hide file tree
Showing 2 changed files with 62 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ ament_target_dependencies(${PROJECT_NAME}
)

install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node DESTINATION lib/${PROJECT_NAME})
install(PROGRAMS scripts/show_image.py DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})

Expand Down
61 changes: 61 additions & 0 deletions scripts/show_image.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
#!/usr/bin/env python3

import cv2
import numpy as np
import rclpy

from rclpy.node import Node
from sensor_msgs.msg import Image


class ExamineImage(Node):
def __init__(self):
super().__init__('examine_image')

self.mat = None
self.sub = self.create_subscription(
Image,
'image_raw',
self.image_callback)
# print("subscribed to " + self.sub.getTopic())

def image_callback(self, msg):
sz = (msg.height, msg.width)
print(msg.header.stamp)
if False:
print("{encoding} {width} {height} {step} {data_size}".format(
encoding=msg.encoding, width=msg.width, height=msg.height,
step=msg.step, data_size=len(msg.data)))
if msg.step * msg.height != len(msg.data):
print("bad step/height/data size")
return

if msg.encoding == "rgb8":
dirty = (self.mat is None or msg.width != self.mat.shape[1] or
msg.height != self.mat.shape[0] or len(self.mat.shape) < 2 or
self.mat.shape[2] != 3)
if dirty:
self.mat = np.zeros([msg.height, msg.width, 3], dtype=np.uint8)
self.mat[:, :, 2] = np.array(msg.data[0::3]).reshape(sz)
self.mat[:, :, 1] = np.array(msg.data[1::3]).reshape(sz)
self.mat[:, :, 0] = np.array(msg.data[2::3]).reshape(sz)
elif msg.encoding == "mono8":
self.mat = np.array(msg.data).reshape(sz)
else:
print("unsupported encoding {}".format(msg.encoding))
return
if self.mat is not None:
cv2.imshow("image", self.mat)
cv2.waitKey(5)

def main(args=None):
rclpy.init(args=args)

examine_image = ExamineImage()
rclpy.spin(examine_image)

examine_image.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()

0 comments on commit bbbad03

Please sign in to comment.