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 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         
00082         
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         
00101         
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