$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, 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 import roslib; roslib.load_manifest('pr2_calibration_launch') 00035 import rospy 00036 import yaml 00037 import sys 00038 import pr2_calibration_executive.capture_exec 00039 import time 00040 from calibration_msgs.msg import RobotMeasurement 00041 import os 00042 00043 rospy.init_node("capture_executive_node") 00044 00045 # Determine if we want everything to automatically run 00046 autorun = (rospy.myargv()[1] == "auto") 00047 samples_dir = rospy.myargv()[2] 00048 config_dir = rospy.myargv()[3] 00049 00050 executive = pr2_calibration_executive.capture_exec.CaptureExecutive(config_dir) 00051 time.sleep(1.0) 00052 00053 #samples_dir = "/u/vpradeep/ros/pkgs-trunk/wg-ros-pkg/calibration_experimental/pr2_calibration_executive/samples" 00054 #sample_names = ["test_sample_0001", "test_sample_0002"] 00055 #sample_names = ["cam_sample_0001"] 00056 00057 #samples_dir = "/u/vpradeep/dataset_port/samples" 00058 #sample_names = [ "%06u_OldRun7"%n for n in range(1,266) ] 00059 00060 #samples_dir = "/u/vpradeep/ros/pkgs-trunk/wg-ros-pkg/sandbox/trajectory_playback/samples" 00061 #sample_names = [ "r_arm_%04u" % n for n in range(0,15) ] 00062 00063 sample_names = [x for x in os.listdir(samples_dir) if ".yaml" in x] 00064 sample_names.sort() 00065 00066 print "Going to execute samples: %s" % sample_names 00067 00068 pub = rospy.Publisher("robot_measurement", RobotMeasurement) 00069 00070 ok = True 00071 00072 n = 0 00073 try: 00074 while ok and not rospy.is_shutdown() and n < len(sample_names): 00075 sample_name = sample_names[n] 00076 print "Currently on sample [%s]" % sample_name 00077 print "(L)oad, (B)ackwards, (F)orwards, (Q)uit" 00078 if autorun: 00079 if n == len(sample_names): 00080 print "Done. Exiting..." 00081 ok = False 00082 resp = "Q" 00083 else: 00084 resp = "L" 00085 n += 1 # accidentally skipping first sample... oh well 00086 else: 00087 resp = raw_input("> ").upper() 00088 if resp == "L": 00089 cur_config = yaml.load(open(samples_dir + "/" + sample_name)) 00090 m_robot = executive.capture(cur_config, rospy.Duration(40)) 00091 if m_robot is None: 00092 print "************** Didn't get a sample *****************" 00093 else: 00094 print "__________ Got a sample! ____________________" 00095 pub.publish(m_robot) 00096 elif resp == "B": 00097 if n is 0: 00098 print "Already on first sample. Can't do anything" 00099 else: 00100 n -= 1 00101 elif resp == "F": 00102 if n is len(sample_names)-1: 00103 print "Already on last sample. Can't do anything" 00104 else: 00105 n += 1 00106 elif resp == "Q": 00107 print "Exiting..." 00108 ok = False 00109 else: 00110 print "Unknown request" 00111 print "" 00112 except EOFError: 00113 print "Exiting" 00114 00115 rospy.spin()