loop.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import roslib; roslib.load_manifest('turtlebot3_panorama')
3 import rospy
4 from turtlebot_panorama.srv import *
5 from sensor_msgs.msg import Image
6 
7 in_progress = False
8 
9 def imageCallback(msg):
10  global in_progress
11  rospy.loginfo("Final Image")
12  in_progress = False
13 
14 if __name__ == '__main__':
15  global in_progress
16  rospy.init_node('loop_panorama')
17 
18  # Setting service
19  srv_takepano = rospy.ServiceProxy('/turtlebot_panorama/take_pano',TakePano)
20  takepanoReq = TakePanoRequest()
21  takepanoReq.angle = 360
22  takepanoReq.snap_interval = 0.5
23  takepanoReq.zvel = -0.2
24 
25  # Setting final image subscriber
26  sub_pano = rospy.Subscriber('/turtlebot_panorama/pano_server/stitch',Image,imageCallback)
27 
28  in_progress = False
29 
30  iteration = 1
31  print str(takepanoReq)
32 
33  rospy.loginfo("Initialized")
34  while not rospy.is_shutdown():
35  rospy.loginfo("Iteration " + str(iteration))
36  # send take panorama call
37  takepanoReq.zvel = -takepanoReq.zvel
38  srv_takepano(takepanoReq)
39  in_progress = True
40  # wait until the final image
41  while (not rospy.is_shutdown()) and in_progress == True:
42  print "is_shutdown" + str(rospy.is_shutdown())
43  print "inprogress " + str(in_progress)
44 
45  rospy.sleep(1.0)
46 
47  iteration = iteration + 1
48 
49  rospy.loginfo("Bye Bye")
50 # takepanoReq.angle = -1
51 # srv_takepano(takepanoReq)
srv_takepano
Definition: loop.py:19
def imageCallback(msg)
Definition: loop.py:9


turtlebot3_panorama
Author(s): Younghun Ju, Jihoon Lee, Marcus Liebhardt, Christopher Tatsch
autogenerated on Wed May 6 2020 03:15:44