00001 #!/usr/bin/python 00002 # 00003 # Copyright (c) 2010, Georgia Tech Research Corporation 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions are met: 00008 # * Redistributions of source code must retain the above copyright 00009 # notice, this list of conditions and the following disclaimer. 00010 # * Redistributions in binary form must reproduce the above copyright 00011 # notice, this list of conditions and the following disclaimer in the 00012 # documentation and/or other materials provided with the distribution. 00013 # * Neither the name of the Georgia Tech Research Corporation nor the 00014 # names of its contributors may be used to endorse or promote products 00015 # derived from this software without specific prior written permission. 00016 # 00017 # THIS SOFTWARE IS PROVIDED BY GEORGIA TECH RESEARCH CORPORATION ''AS IS'' AND 00018 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 # DISCLAIMED. IN NO EVENT SHALL GEORGIA TECH BE LIABLE FOR ANY DIRECT, INDIRECT, 00021 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 00022 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 00023 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 00024 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE 00025 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 00026 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 # 00028 00029 # \author Jason Okerman (Healthcare Robotics Lab, Georgia Tech.) 00030 import roslib; roslib.load_manifest('pr2_clutter_helper') 00031 #depnds on sensor_msgs, opencv2, cv_bridge 00032 import rospy 00033 from sensor_msgs.msg import Image as msgImage 00034 import cv #version 2.1 expected 00035 from cv_bridge import CvBridge 00036 #may need image_transport? 00037 00038 import time #sleep 00039 from random import * #randint 00040 00041 global_ros_image = None 00042 00043 def imageCallback(data): 00044 print 'callback called' 00045 #Note: data should be of type sensor_msgs.msg.Image 00046 #rospy.loginfo(rospy.get_name()+"I heard some data from camera") 00047 global global_ros_image 00048 global_ros_image = data 00049 00050 def listener(): 00051 rospy.init_node('my_image_listener', anonymous=True) 00052 rospy.Subscriber("wide_stereo/right/image_rect_color", msgImage, imageCallback) 00053 rospy.spin() 00054 00055 if __name__ == '__main__': 00056 cv.NamedWindow('view') 00057 cv.StartWindowThread() 00058 rospy.init_node('my_image_listener', anonymous=True) 00059 a = rospy.Subscriber("wide_stereo/right/image_rect_color", msgImage, imageCallback) 00060 00061 print 'sleeping now' #spin cycle. Similar to "spin_once" ? 00062 while (not global_ros_image): 00063 rospy.sleep(.1) 00064 if rospy.is_shutdown(): 00065 print '\nforcing an exit' 00066 break; 00067 print 'waking and exiting now' 00068 00069 if not rospy.is_shutdown(): 00070 a.unregister() 00071 00072 br = CvBridge() 00073 im = br.imgmsg_to_cv(global_ros_image) 00074 cv.Erode(im, im, None, 5) 00075 cv.Dilate(im, im, None, 5) 00076 cv.ShowImage('view', im) 00077 cv.WaitKey() 00078 cv.SaveImage('~/Desktop/this_is_a_temporary_image.png', im) 00079 00080 #IDEA: -- 'sleep spin until callback received. then kill subscriber. 00081 00082 00083 00084 00085 00086 00087 00088 00089