cv_bridge_demo.py 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138
  1. #!/usr/bin/env python
  2. """ cv_bridge_demo.py - Version 1.1 2013-12-20
  3. A ROS-to-OpenCV node that uses cv_bridge to map a ROS image topic and optionally a ROS
  4. depth image topic to the equivalent OpenCV image stream(s).
  5. Created for the Pi Robot Project: http://www.pirobot.org
  6. Copyright (c) 2011 Patrick Goebel. All rights reserved.
  7. This program is free software; you can redistribute it and/or modify
  8. it under the terms of the GNU General Public License as published by
  9. the Free Software Foundation; either version 2 of the License, or
  10. (at your option) any later version.
  11. This program is distributed in the hope that it will be useful,
  12. but WITHOUT ANY WARRANTY; without even the implied warranty of
  13. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  14. GNU General Public License for more details at:
  15. http://www.gnu.org/licenses/gpl.html
  16. """
  17. import rospy
  18. import sys
  19. import cv2
  20. import cv2.cv as cv
  21. from sensor_msgs.msg import Image, CameraInfo
  22. from cv_bridge import CvBridge, CvBridgeError
  23. import numpy as np
  24. class cvBridgeDemo():
  25. def __init__(self):
  26. self.node_name = "cv_bridge_demo"
  27. rospy.init_node(self.node_name)
  28. # What we do during shutdown
  29. rospy.on_shutdown(self.cleanup)
  30. # Create the OpenCV display window for the RGB image
  31. self.cv_window_name = self.node_name
  32. cv.NamedWindow(self.cv_window_name, cv.CV_WINDOW_NORMAL)
  33. cv.MoveWindow(self.cv_window_name, 25, 75)
  34. # And one for the depth image
  35. cv.NamedWindow("Depth Image", cv.CV_WINDOW_NORMAL)
  36. cv.MoveWindow("Depth Image", 25, 350)
  37. # Create the cv_bridge object
  38. self.bridge = CvBridge()
  39. # Subscribe to the camera image and depth topics and set
  40. # the appropriate callbacks
  41. self.image_sub = rospy.Subscriber("input_rgb_image", Image, self.image_callback, queue_size=1)
  42. self.depth_sub = rospy.Subscriber("input_depth_image", Image, self.depth_callback, queue_size=1)
  43. rospy.loginfo("Waiting for image topics...")
  44. rospy.wait_for_message("input_rgb_image", Image)
  45. rospy.loginfo("Ready.")
  46. def image_callback(self, ros_image):
  47. # Use cv_bridge() to convert the ROS image to OpenCV format
  48. try:
  49. frame = self.bridge.imgmsg_to_cv2(ros_image, "bgr8")
  50. except CvBridgeError, e:
  51. print e
  52. # Convert the image to a numpy array since most cv2 functions
  53. # require numpy arrays.
  54. frame = np.array(frame, dtype=np.uint8)
  55. # Process the frame using the process_image() function
  56. display_image = self.process_image(frame)
  57. # Display the image.
  58. cv2.imshow(self.node_name, display_image)
  59. # Process any keyboard commands
  60. self.keystroke = cv2.waitKey(5)
  61. if self.keystroke != -1:
  62. cc = chr(self.keystroke & 255).lower()
  63. if cc == 'q':
  64. # The user has press the q key, so exit
  65. rospy.signal_shutdown("User hit q key to quit.")
  66. def depth_callback(self, ros_image):
  67. # Use cv_bridge() to convert the ROS image to OpenCV format
  68. try:
  69. # Convert the depth image using the default passthrough encoding
  70. depth_image = self.bridge.imgmsg_to_cv2(ros_image, "passthrough")
  71. except CvBridgeError, e:
  72. print e
  73. # Convert the depth image to a Numpy array since most cv2 functions require Numpy arrays.
  74. depth_array = np.array(depth_image, dtype=np.float32)
  75. # Normalize the depth image to fall between 0 (black) and 1 (white)
  76. cv2.normalize(depth_array, depth_array, 0, 1, cv2.NORM_MINMAX)
  77. # Process the depth image
  78. depth_display_image = self.process_depth_image(depth_array)
  79. # Display the result
  80. cv2.imshow("Depth Image", depth_display_image)
  81. def process_image(self, frame):
  82. # Convert to greyscale
  83. grey = cv2.cvtColor(frame, cv.CV_BGR2GRAY)
  84. # Blur the image
  85. grey = cv2.blur(grey, (7, 7))
  86. # Compute edges using the Canny edge filter
  87. edges = cv2.Canny(grey, 15.0, 30.0)
  88. return edges
  89. def process_depth_image(self, frame):
  90. # Just return the raw image for this demo
  91. return frame
  92. def cleanup(self):
  93. print "Shutting down vision node."
  94. cv2.destroyAllWindows()
  95. def main(args):
  96. try:
  97. cvBridgeDemo()
  98. rospy.spin()
  99. except KeyboardInterrupt:
  100. print "Shutting down vision node."
  101. cv.DestroyAllWindows()
  102. if __name__ == '__main__':
  103. main(sys.argv)