Go to the documentation of this file.00001
00002
00003
00004
00005 import roslib; roslib.load_manifest('turtlebot_panorama')
00006 import rospy
00007 from turtlebot_panorama.srv import *
00008 from sensor_msgs.msg import Image
00009
00010
00011 in_progress = False
00012
00013 def imageCallback(msg):
00014 global in_progress
00015 rospy.loginfo("Final Image")
00016 in_progress = False
00017
00018
00019 if __name__ == '__main__':
00020 global in_progress
00021 rospy.init_node('loop_panorama')
00022
00023
00024
00025 srv_takepano = rospy.ServiceProxy('/turtlebot_panorama/take_pano',TakePano)
00026 takepanoReq = TakePanoRequest()
00027 takepanoReq.angle = 360
00028 takepanoReq.snap_interval = 0.5
00029 takepanoReq.zvel = -0.2
00030
00031
00032 sub_pano = rospy.Subscriber('/turtlebot_panorama/pano_server/stitch',Image,imageCallback)
00033
00034 in_progress = False
00035
00036 iteration = 1
00037 print str(takepanoReq)
00038
00039 rospy.loginfo("Initialized")
00040 while not rospy.is_shutdown():
00041 rospy.loginfo("Iteration " + str(iteration))
00042
00043 takepanoReq.zvel = -takepanoReq.zvel
00044 srv_takepano(takepanoReq)
00045 in_progress = True
00046
00047 while (not rospy.is_shutdown()) and in_progress == True:
00048 print "is_shutdown" + str(rospy.is_shutdown())
00049 print "inprogress " + str(in_progress)
00050
00051 rospy.sleep(1.0)
00052
00053 iteration = iteration + 1
00054
00055 rospy.loginfo("Bye Bye")
00056
00057
00058
00059