Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 """
00037 Panorama time based capture client.
00038
00039 Authors: Ethan Rublee, Ken Conley
00040
00041 Sample run command, assuming the capture_server has been started, will
00042 take 30 images and store them in `pwd`/pano.bag
00043
00044 rosrun pano_ros capture_client.py `pwd`/pano.bag 30
00045 """
00046
00047 import roslib; roslib.load_manifest('pano_ros')
00048 import rospy
00049 import sys
00050 from pano_ros.msg import PanoCaptureResult
00051 from pano_ros.capture_client_interface import CaptureClientInterface
00052
00053
00054 class TimedCapture(object):
00055 """
00056 Uses the CaptureClientInterface to take photos
00057 regularly at a time interval and will snap until
00058 the desired number of frames are taken
00059 """
00060 def __init__(self):
00061
00062
00063 self._capture = CaptureClientInterface()
00064
00065 def capture(self,bag_filename, total_captures = 20, time_interval = 1):
00066 """
00067 This is a timed interval capture.
00068 total_captures the number of images to take
00069 time_interval attempt to take an image at
00070 this time interval, specified in seconds
00071 """
00072 capture = self._capture
00073
00074
00075 capture.start(bag_filename)
00076 result = PanoCaptureResult()
00077 try:
00078
00079
00080 while ( capture.n_captures < total_captures
00081 and not rospy.is_shutdown() ):
00082
00083 capture.snap()
00084
00085 rospy.sleep(time_interval)
00086 finally:
00087 tresult = capture.stop()
00088 result = tresult if tresult else result
00089
00090 return result
00091
00092
00093 def usage():
00094 return """usage:
00095 rosrun pano_ros capture_client.py `pwd`/pano.bag 30 [1]
00096 where `pwd`/pano.bag is the output bag of the capture session
00097 30 is the number of images to capture
00098 1 is the time interval"""
00099
00100 if __name__ == '__main__':
00101 try:
00102 bag_filename = ""
00103 n_images = 20
00104 time_step = 1
00105 if len(sys.argv) == 3 or len(sys.argv) == 4:
00106 bag_filename = sys.argv[1]
00107 n_images = int(sys.argv[2])
00108 if len(sys.argv) == 4:
00109 time_step = float(sys.argv[3])
00110 else:
00111 print usage()
00112 sys.exit(1)
00113 rospy.init_node('capture_client_py')
00114 capture_client = TimedCapture()
00115 result = capture_client.capture(bag_filename,n_images,time_step)
00116 print "Captured:%d photos. Saved to %s" % (result.n_captures,
00117 result.bag_filename)
00118 except rospy.ROSInterruptException:
00119 print "program interrupted before completion"