capture_client.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2010, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 # Revision $Id: capture_client.py 47138 2010-12-15 05:22:19Z ethanrublee $
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         #CaptureClientInterface does all of the setup
00062         #for connecting to the pano_capture server
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         #start up the capture client, giving absolute path to a 
00074         #bag where the data will be stored
00075         capture.start(bag_filename)
00076         result = PanoCaptureResult()
00077         try:     
00078             #we'll just capture total_captures images, 
00079             #1 every time_interval seconds
00080             while ( capture.n_captures < total_captures 
00081                    and not rospy.is_shutdown() ):
00082                 #request a snap
00083                 capture.snap()   
00084                 #sleep for 1 seconds to allow the camera to be moved
00085                 rospy.sleep(time_interval)
00086         finally:
00087             tresult = capture.stop()
00088             result = tresult if tresult else result
00089         #this will return the PanoCapture result message
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"


pano_ros
Author(s): Ethan Rublee, Ken Conley
autogenerated on Mon Oct 6 2014 08:06:11