$search
00001 #!/usr/bin/env python 00002 00003 """ ros2opencv.py - Version 0.2 2011-11-09 00004 00005 A ROS-to-OpenCV node that uses cv_bridge to map a ROS image topic and optionally a ROS 00006 depth image topic to the equivalent OpenCV image stream(s). 00007 00008 Includes variables and helper functions to store detection and tracking information and display 00009 markers on the image. 00010 00011 Creates an ROI publisher to publish the region of interest on the /roi topic. 00012 00013 Publishes a 3D PointStamped message on the /target_point topic. 00014 00015 Created for the Pi Robot Project: http://www.pirobot.org 00016 Copyright (c) 2011 Patrick Goebel. All rights reserved. 00017 00018 This program is free software; you can redistribute it and/or modify 00019 it under the terms of the GNU General Public License as published by 00020 the Free Software Foundation; either version 2 of the License, or 00021 (at your option) any later version. 00022 00023 This program is distributed in the hope that it will be useful, 00024 but WITHOUT ANY WARRANTY; without even the implied warranty of 00025 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00026 GNU General Public License for more details at: 00027 00028 http://www.gnu.org/licenses/gpl.html 00029 00030 """ 00031 00032 import roslib 00033 roslib.load_manifest('ros2opencv') 00034 import rospy 00035 import cv 00036 import sys 00037 from std_msgs.msg import String 00038 from sensor_msgs.msg import Image, RegionOfInterest, CameraInfo 00039 from geometry_msgs.msg import PointStamped 00040 from cv_bridge import CvBridge, CvBridgeError 00041 import time 00042 00043 class ROS2OpenCV: 00044 def __init__(self, node_name): 00045 rospy.init_node(node_name) 00046 00047 rospy.on_shutdown(self.cleanup) 00048 00049 self.node_name = node_name 00050 self.input_rgb_image = "input_rgb_image" 00051 self.input_depth_image = "input_depth_image" 00052 self.output_image = "output_image" 00053 self.show_text = rospy.get_param("~show_text", True) 00054 self.show_features = rospy.get_param("~show_features", True) 00055 00056 """ Initialize the Region of Interest and its publisher """ 00057 self.ROI = RegionOfInterest() 00058 self.pubROI = rospy.Publisher("/roi", RegionOfInterest) 00059 00060 """ Do the same for the point cluster publisher """ 00061 self.cluster3d = PointStamped() 00062 self.pub_cluster3d = rospy.Publisher("/target_point", PointStamped) 00063 00064 """ Initialize a number of global variables """ 00065 self.image = None 00066 self.image_size = None 00067 self.depth_image = None 00068 self.grey = None 00069 self.selected_point = None 00070 self.selection = None 00071 self.drag_start = None 00072 self.keystroke = None 00073 self.key_command = None 00074 self.detect_box = None 00075 self.track_box = None 00076 self.display_box = None 00077 self.keep_marker_history = False 00078 self.night_mode = False 00079 self.auto_face_tracking = True 00080 self.cps = 0 # Cycles per second = number of processing loops per second. 00081 self.cps_values = list() 00082 self.cps_n_values = 20 00083 self.flip_image = False 00084 00085 """ Create the display window """ 00086 self.cv_window_name = self.node_name 00087 cv.NamedWindow(self.cv_window_name, cv.CV_NORMAL) 00088 cv.ResizeWindow(self.cv_window_name, 640, 480) 00089 00090 """ Create the cv_bridge object """ 00091 self.bridge = CvBridge() 00092 00093 """ Set a call back on mouse clicks on the image window """ 00094 cv.SetMouseCallback (self.node_name, self.on_mouse_click, None) 00095 00096 """ A publisher to output the display image back to a ROS topic """ 00097 self.output_image_pub = rospy.Publisher(self.output_image, Image) 00098 00099 """ Subscribe to the raw camera image topic and set the image processing callback """ 00100 self.image_sub = rospy.Subscriber(self.input_rgb_image, Image, self.image_callback, queue_size=1) 00101 self.depth_sub = rospy.Subscriber(self.input_depth_image, Image, self.depth_callback, queue_size=1) 00102 00103 rospy.loginfo("Starting " + self.node_name) 00104 00105 def on_mouse_click(self, event, x, y, flags, param): 00106 """ We will usually use the mouse to select points to track or to draw a rectangle 00107 around a region of interest. """ 00108 if not self.image: 00109 return 00110 00111 if self.image.origin: 00112 y = self.image.height - y 00113 00114 if event == cv.CV_EVENT_LBUTTONDOWN and not self.drag_start: 00115 self.detect_box = None 00116 self.selected_point = (x, y) 00117 self.drag_start = (x, y) 00118 00119 if event == cv.CV_EVENT_LBUTTONUP: 00120 self.drag_start = None 00121 self.detect_box = self.selection 00122 00123 if self.drag_start: 00124 xmin = max(0, min(x, self.drag_start[0])) 00125 ymin = max(0, min(y, self.drag_start[1])) 00126 xmax = min(self.image.width, max(x, self.drag_start[0])) 00127 ymax = min(self.image.height, max(y, self.drag_start[1])) 00128 self.selection = (xmin, ymin, xmax - xmin, ymax - ymin) 00129 00130 def depth_callback(self, data): 00131 depth_image = self.convert_depth_image(data) 00132 00133 if self.flip_image: 00134 cv.Flip(depth_image) 00135 00136 if not self.depth_image: 00137 (cols, rows) = cv.GetSize(depth_image) 00138 self.depth_image = cv.CreateMat(rows, cols, cv.CV_32FC1) 00139 00140 cv.Copy(depth_image, self.depth_image) 00141 00142 def image_callback(self, data): 00143 """ Time this loop to get cycles per second """ 00144 start = rospy.Time.now() 00145 00146 """ Convert the raw image to OpenCV format using the convert_image() helper function """ 00147 cv_image = self.convert_image(data) 00148 00149 """ Some webcams invert the image """ 00150 if self.flip_image: 00151 cv.Flip(cv_image) 00152 00153 """ Create a few images we will use for display """ 00154 if not self.image: 00155 self.image_size = cv.GetSize(cv_image) 00156 self.image = cv.CreateImage(self.image_size, 8, 3) 00157 self.marker_image = cv.CreateImage(self.image_size, 8, 3) 00158 self.display_image = cv.CreateImage(self.image_size, 8, 3) 00159 self.processed_image = cv.CreateImage(self.image_size, 8, 3) 00160 cv.Zero(self.marker_image) 00161 00162 """ Copy the current frame to the global image in case we need it elsewhere""" 00163 cv.Copy(cv_image, self.image) 00164 00165 if not self.keep_marker_history: 00166 cv.Zero(self.marker_image) 00167 00168 """ Process the image to detect and track objects or features """ 00169 processed_image = self.process_image(cv_image) 00170 00171 """ If the result is a greyscale image, convert to 3-channel for display purposes """ 00172 if processed_image.channels == 1: 00173 cv.CvtColor(processed_image, self.processed_image, cv.CV_GRAY2BGR) 00174 else: 00175 cv.Copy(processed_image, self.processed_image) 00176 00177 """ Display the user-selection rectangle or point.""" 00178 self.display_markers() 00179 00180 if self.night_mode: 00181 """ Night mode: only display the markers """ 00182 cv.SetZero(self.processed_image) 00183 00184 """ Merge the processed image and the marker image """ 00185 cv.Or(self.processed_image, self.marker_image, self.display_image) 00186 00187 if self.track_box: 00188 if self.auto_face_tracking: 00189 cv.EllipseBox(self.display_image, self.track_box, cv.CV_RGB(255, 0, 0), 2) 00190 else: 00191 (center, size, angle) = self.track_box 00192 pt1 = (int(center[0] - size[0] / 2), int(center[1] - size[1] / 2)) 00193 pt2 = (int(center[0] + size[0] / 2), int(center[1] + size[1] / 2)) 00194 00195 cv.Rectangle(self.display_image, pt1, pt2, cv.RGB(255, 0, 0), 2, 8, 0) 00196 00197 elif self.detect_box: 00198 (pt1_x, pt1_y, w, h) = self.detect_box 00199 cv.Rectangle(self.display_image, (pt1_x, pt1_y), (pt1_x + w, pt1_y + h), cv.RGB(255, 0, 0), 2, 8, 0) 00200 00201 """ Handle keyboard events """ 00202 self.keystroke = cv.WaitKey(5) 00203 00204 duration = rospy.Time.now() - start 00205 duration = duration.to_sec() 00206 fps = int(1.0 / duration) 00207 self.cps_values.append(fps) 00208 if len(self.cps_values) > self.cps_n_values: 00209 self.cps_values.pop(0) 00210 self.cps = int(sum(self.cps_values) / len(self.cps_values)) 00211 00212 if self.show_text: 00213 hscale = 0.2 * self.image_size[0] / 160. + 0.1 00214 vscale = 0.2 * self.image_size[1] / 120. + 0.1 00215 text_font = cv.InitFont(cv.CV_FONT_VECTOR0, hscale, vscale, 0, 1, 8) 00216 """ Print cycles per second (CPS) and resolution (RES) at top of the image """ 00217 if self.image_size[0] >= 640: 00218 vstart = 25 00219 voffset = int(50 + self.image_size[1] / 120.) 00220 elif self.image_size[0] == 320: 00221 vstart = 15 00222 voffset = int(35 + self.image_size[1] / 120.) 00223 else: 00224 vstart = 10 00225 voffset = int(20 + self.image_size[1] / 120.) 00226 cv.PutText(self.display_image, "CPS: " + str(self.cps), (10, vstart), text_font, cv.RGB(255, 255, 0)) 00227 cv.PutText(self.display_image, "RES: " + str(self.image_size[0]) + "X" + str(self.image_size[1]), (10, voffset), text_font, cv.RGB(255, 255, 0)) 00228 # Now display the image. 00229 cv.ShowImage(self.node_name, self.display_image) 00230 00231 """ Publish the display image back to ROS """ 00232 try: 00233 self.output_image_pub.publish(self.bridge.cv_to_imgmsg(self.display_image, "bgr8")) 00234 except CvBridgeError, e: 00235 print e 00236 00237 """ Process any keyboard commands or command sent via the key_command service """ 00238 if self.key_command: 00239 self.keystroke = ord(self.key_command) 00240 self.key_command = None 00241 if 32 <= self.keystroke and self.keystroke < 128: 00242 cc = chr(self.keystroke).lower() 00243 if cc == 'c': 00244 self.features = [] 00245 self.track_box = None 00246 self.detect_box = None 00247 elif cc == 'n': 00248 self.night_mode = not self.night_mode 00249 elif cc == 'f': 00250 self.show_features = not self.show_features 00251 elif cc == 't': 00252 self.show_text = not self.show_text 00253 elif cc == 'a': 00254 self.auto_face_tracking = not self.auto_face_tracking 00255 if self.auto_face_tracking: 00256 self.features = [] 00257 self.track_box = None 00258 self.detect_box = None 00259 elif cc == 'q': 00260 """ user has press the q key, so exit """ 00261 rospy.signal_shutdown("User hit q key to quit.") 00262 00263 00264 def convert_image(self, ros_image): 00265 try: 00266 cv_image = self.bridge.imgmsg_to_cv(ros_image, "bgr8") 00267 return cv_image 00268 except CvBridgeError, e: 00269 print e 00270 00271 def convert_depth_image(self, ros_image): 00272 try: 00273 depth_image = self.bridge.imgmsg_to_cv(ros_image, "32FC1") 00274 return depth_image 00275 00276 except CvBridgeError, e: 00277 print e 00278 00279 def process_image(self, cv_image): 00280 if not self.grey: 00281 """ Allocate temporary images """ 00282 self.grey = cv.CreateImage(self.image_size, 8, 1) 00283 00284 """ Convert color input image to grayscale """ 00285 cv.CvtColor(cv_image, self.grey, cv.CV_BGR2GRAY) 00286 cv.EqualizeHist(self.grey, self.grey) 00287 00288 # Since we aren't applying any filters in this base class, set the ROI to the selected region, if any. 00289 if not self.drag_start and not self.detect_box is None: 00290 self.ROI = RegionOfInterest() 00291 self.ROI.x_offset = self.detect_box[0] 00292 self.ROI.y_offset = self.detect_box[1] 00293 self.ROI.width = self.detect_box[2] 00294 self.ROI.height = self.detect_box[3] 00295 00296 self.pubROI.publish(self.ROI) 00297 00298 return self.grey 00299 00300 def display_markers(self): 00301 # If the user is selecting a region with the mouse, display the corresponding rectangle for feedback. 00302 if self.drag_start and self.is_rect_nonzero(self.selection): 00303 x,y,w,h = self.selection 00304 cv.Rectangle(self.marker_image, (x, y), (x + w, y + h), (0, 255, 255), 2) 00305 self.selected_point = None 00306 00307 # Else if the user has clicked on a point on the image, display it as a small circle. 00308 elif not self.selected_point is None: 00309 x = self.selected_point[0] 00310 y = self.selected_point[1] 00311 cv.Circle(self.marker_image, (x, y), 3, (0, 255, 255), 2) 00312 00313 def is_rect_nonzero(self, r): 00314 # First assume a simple CvRect type 00315 try: 00316 (_,_,w,h) = r 00317 return (w > 0) and (h > 0) 00318 except: 00319 try: 00320 # Otherwise, assume a CvBox2D type 00321 ((_,_),(w,h),a) = r 00322 return (w > 0) and (h > 0) 00323 except: 00324 return False 00325 00326 def cleanup(self): 00327 print "Shutting down vision node." 00328 cv.DestroyAllWindows() 00329 00330 def main(args): 00331 # Display a help message if appropriate. 00332 help_message = "" 00333 00334 print help_message 00335 00336 try: 00337 # Fire up the node. 00338 ROS2OpenCV("ros2opencv") 00339 # Spin so our services will work 00340 rospy.spin() 00341 except KeyboardInterrupt: 00342 print "Shutting down vision node." 00343 cv.DestroyAllWindows() 00344 00345 if __name__ == '__main__': 00346 main(sys.argv)