$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 actionlib 00039 import joint_states_settler.msg 00040 import time 00041 import threading 00042 00043 import pr2_calibration_executive 00044 from pr2_calibration_executive.config_manager import ConfigManager 00045 from pr2_calibration_executive.sensor_managers import * 00046 from pr2_calibration_executive.robot_measurement_cache import RobotMeasurementCache 00047 00048 from calibration_msgs.msg import RobotMeasurement 00049 00050 class CaptureExecutive: 00051 def __init__(self, config_dir): 00052 #config_dir = "/u/vpradeep/ros/pkgs-trunk/wg-ros-pkg/calibration_experimental/pr2_calibration_executive/hardware_config/" 00053 self.cam_config = yaml.load(open(config_dir + "/cam_config.yaml")) 00054 self.chain_config = yaml.load(open(config_dir + "/chain_config.yaml")) 00055 self.laser_config = yaml.load(open(config_dir + "/laser_config.yaml")) 00056 self.controller_config = yaml.load(open(config_dir + "/controller_config.yaml")) 00057 00058 self.cache = RobotMeasurementCache() 00059 self.lock = threading.Lock() 00060 00061 # Specifies if we're currently waiting for a sample 00062 self.active = False 00063 00064 # Construct Configuration Manager (manages configuration of nodes in the pipeline) 00065 self.config_manager = ConfigManager(self.cam_config, 00066 self.chain_config, 00067 self.laser_config, 00068 self.controller_config) 00069 00070 # Construct a manager for each sensor stream (Don't enable any of them) 00071 self.cam_managers = [ (cam_id, CamManager( cam_id, self.add_cam_measurement) ) for cam_id in self.cam_config.keys() ] 00072 self.chain_managers = [ (chain_id, ChainManager(chain_id, self.add_chain_measurement) ) for chain_id in self.chain_config.keys() ] 00073 self.laser_managers = [ (laser_id, LaserManager(laser_id, self.add_laser_measurement) ) for laser_id in self.laser_config.keys() ] 00074 00075 # Subscribe to topic containing stable intervals 00076 self.request_interval_sub = rospy.Subscriber("request_interval", calibration_msgs.msg.Interval, self.request_callback) 00077 00078 # Hardcoded cache sizes. Not sure where these params should live 00079 # ... 00080 00081 00082 def capture(self, next_configuration, timeout): 00083 done = False 00084 self.m_robot = None 00085 00086 timeout_time = rospy.Time().now() + timeout 00087 00088 self.lock.acquire() 00089 if self.active: 00090 print "Can't capture since we're already active" 00091 done = True 00092 self.lock.release() 00093 00094 # Set up the pipeline 00095 self.config_manager.reconfigure(next_configuration) 00096 00097 time.sleep(2.0) 00098 00099 # Set up the cache with only the sensors we care about 00100 cam_ids = [x["cam_id"] for x in next_configuration["camera_measurements"]] 00101 chain_ids = [x["chain_id"] for x in next_configuration["joint_measurements"]] 00102 laser_ids = [x["laser_id"] for x in next_configuration["laser_measurements"]] 00103 self.cache.reconfigure(cam_ids, chain_ids, laser_ids) 00104 00105 00106 print "Setting up sensor managers" 00107 enable_list = [] 00108 disable_list = [] 00109 # Set up the sensor managers 00110 for cam_id, cam_manager in self.cam_managers: 00111 if cam_id in [x["cam_id"] for x in next_configuration["camera_measurements"]]: 00112 #print " Enabling camera [%s]" % cam_id 00113 enable_list.append(cam_id) 00114 cam_manager.enable(True) 00115 else: 00116 #print " Disabling camera [%s]" % cam_id 00117 disable_list.append(cam_id) 00118 cam_manager.disable() 00119 00120 for chain_id, chain_manager in self.chain_managers: 00121 if chain_id in [x["chain_id"] for x in next_configuration["joint_measurements"]]: 00122 #print " Enabling chain [%s]" % chain_id 00123 enable_list.append(chain_id) 00124 chain_manager.enable() 00125 else: 00126 #print " Disabling chain [%s]" % chain_id 00127 disable_list.append(chain_id) 00128 chain_manager.disable() 00129 00130 for laser_id, laser_manager in self.laser_managers: 00131 enabled_lasers = [x["laser_id"] for x in next_configuration["laser_measurements"]] 00132 #print "Enabled Lasers: %s" % enabled_lasers 00133 if laser_id in enabled_lasers: 00134 #print " Enabling laser [%s]" % laser_id 00135 enable_list.append(laser_id) 00136 laser_manager.enable(True) 00137 else: 00138 #print " Disabling laser [%s]" % laser_id 00139 disable_list.append(laser_id) 00140 laser_manager.disable() 00141 00142 print "Enabling" 00143 for cur_enabled in enable_list: 00144 print " + %s" % cur_enabled 00145 print "Disabling" 00146 for cur_disabled in disable_list: 00147 print " - %s" % cur_disabled 00148 00149 self.lock.acquire() 00150 #print "In Capture(). Setting pipeline state to 'active'" 00151 self.active = True 00152 self.lock.release() 00153 00154 # Keep waiting until the request_callback function populates the m_robot msg 00155 while (not rospy.is_shutdown()) and (not done) and (rospy.Time().now() < timeout_time): 00156 time.sleep(.1) 00157 self.lock.acquire() 00158 if self.m_robot is not None: 00159 done = True 00160 self.lock.release() 00161 00162 # Stop listening to all the sensor streams 00163 for cam_id, cam_manager in self.cam_managers: 00164 cam_manager.disable() 00165 for chain_id, chain_manager in self.chain_managers: 00166 chain_manager.disable() 00167 for laser_id, laser_manager in self.laser_managers: 00168 laser_manager.disable() 00169 00170 # Turn off the entire pipeline 00171 self.config_manager.stop() 00172 00173 # Fill in meta information about the sample 00174 if self.m_robot is not None: 00175 self.m_robot.sample_id = next_configuration["sample_id"] 00176 self.m_robot.target_id = next_configuration["target"]["target_id"] 00177 self.m_robot.chain_id = next_configuration["target"]["chain_id"] 00178 00179 self.lock.acquire() 00180 self.active = False 00181 self.lock.release() 00182 00183 return self.m_robot 00184 00185 00186 def request_callback(self, msg): 00187 00188 # See if the interval is big enough to care 00189 if (msg.end - msg.start) < rospy.Duration(1,0): 00190 return 00191 00192 self.lock.acquire() 00193 if self.active: 00194 # Do some query into the cache, and possibly stop stuff from running 00195 self.m_robot = self.cache.request_robot_measurement(msg.start, msg.end) 00196 00197 # We found a sample, so we can deactive (kind of a race condition, since 'active' triggers capture() to exit... I don't care) 00198 if self.m_robot is not None: 00199 self.active = False 00200 self.lock.release() 00201 00202 def add_cam_measurement(self, cam_id, msg): 00203 if len(msg.image_points) > 0: 00204 self.lock.acquire() 00205 self.cache.add_cam_measurement(cam_id, msg) 00206 self.lock.release() 00207 00208 def add_chain_measurement(self, chain_id, msg): 00209 self.lock.acquire() 00210 self.cache.add_chain_measurement(chain_id, msg) 00211 self.lock.release() 00212 00213 def add_laser_measurement(self, laser_id, msg, interval_start, interval_end): 00214 self.lock.acquire() 00215 print "Adding laser measurement" 00216 self.cache.add_laser_measurement(laser_id, msg, interval_start, interval_end) 00217 self.lock.release()