capture_client_interface.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 capture client interface.  This takes care of all setup required
00038 to talk to the capture_server. Based on Ken's idea that we should expose
00039 the user to simple interfaces that take care of dirty actionlib setup
00040 and pub sub stuff...
00041 
00042 Authors: Ethan Rublee, Ken Conley
00043 
00044 See capture_client for a simple use case of the CaptureClientInterface
00045 """
00046 import roslib; roslib.load_manifest('pano_ros')
00047 import rospy
00048 import actionlib
00049 import sys
00050 import pano_ros.msg
00051 from std_msgs.msg import Empty
00052 
00053 class CaptureClientInterface(object):
00054     """
00055     An attempt at a common capture client interface
00056     This does all boot strapping for you to hook up to the pano_capture action server
00057     this will look for the capture_server at 'pano_capture'
00058     TODO make this resolve pano_capture instead of hardcoding
00059     """
00060     def __init__(self):
00061         self._setupClient()
00062         self.n_captures = 0
00063     def _setupClient(self):
00064         """
00065         setup pubs and subs, and feedback callback with the actionlib pano_capture server
00066         """
00067         self.client = actionlib.SimpleActionClient(
00068                   'pano_capture',
00069                   pano_ros.msg.PanoCaptureAction)
00070         self.client.wait_for_server()  
00071        
00072         self.snap_pub = rospy.Publisher('pano_capture/snap',Empty)
00073         self.stop_pub = rospy.Publisher('pano_capture/stop',Empty)
00074 
00075     def start(self,bag_filename = None):
00076         """
00077         start capturing a pano to a bag file
00078         bag_filename is the absolute pathname of the bagfile to record to
00079         """ 
00080         self.n_captures = 0
00081         #start capturing, atleast give the name of 
00082         #the bag file to capture to
00083         goal = pano_ros.msg.PanoCaptureGoal(bag_filename = bag_filename)
00084         self.client.send_goal(goal = goal,feedback_cb = self.feedback)
00085         
00086     def snap(self):
00087         """
00088         send a snap message to the capture server, will request a photo to be captured
00089         expect a call to feedback_c
00090         """
00091         print "requesting to snap"
00092         self.snap_pub.publish()
00093     def stop(self):
00094         """
00095         send a stop message to the capture server
00096         todo handle ctrl-c escape properly!
00097         """        
00098         self.stop_pub.publish()
00099         self.client.wait_for_result()            
00100         #the capture_result contains some meta information about the capture,
00101         #including the number of frames and bag location    
00102         return self.client.get_result()
00103         
00104     def feedback(self, feedback):
00105         """
00106         High jack me if you would like to receive feedback calls.
00107         Keep in mind that this is called asynchronously
00108         """                
00109         self.n_captures = feedback.n_captures
00110         print "captured a photo: %d" % (self.n_captures)
00111         


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