$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 # author: Vijay Pradeep 00035 00036 import roslib; roslib.load_manifest('pr2_calibration_estimation') 00037 00038 import sys 00039 import rospy 00040 import time 00041 import numpy 00042 import rosrecord 00043 import yaml 00044 import os.path 00045 import numpy 00046 00047 from pr2_calibration_estimation.robot_params import RobotParams 00048 from pr2_calibration_estimation.blocks import robot_measurement_bundler 00049 00050 def usage(): 00051 rospy.logerr("Not enough arguments") 00052 print "Usage:" 00053 print " ./proto1.py [bagfile] [output_dir]" 00054 sys.exit(0) 00055 00056 class ErrorCalc: 00057 def __init__(self, robot_params, expanded_params, free_list, blocks): 00058 self._robot_params = robot_params 00059 self._expanded_params = expanded_params 00060 self._free_list = free_list 00061 self._blocks = blocks 00062 00063 # Take the set of optimization params, and expand it into the bigger param vec 00064 def calculate_full_param_vec(self, opt_param_vec): 00065 full_param_vec = self._expanded_params.copy() 00066 00067 #import code; code.interact(local=locals()) 00068 00069 full_param_vec[numpy.where(self._free_list), 0] = opt_param_vec 00070 00071 return full_param_vec 00072 00073 def calculate_error(self, opt_param_vec): 00074 # print "x ", 00075 # sys.stdout.flush() 00076 00077 full_param_vec = self.calculate_full_param_vec(opt_param_vec) 00078 00079 # Update the primitives with the new set of parameters 00080 self._robot_params.inflate(full_param_vec) 00081 # Update all the blocks' configs (This might not be necessary, because everything should point to the correct object 00082 for block in self._blocks: 00083 block.update_config(self._robot_params) 00084 00085 # Compute Errors 00086 errors = [numpy.reshape(block.compute_error()*block.error_scalar, (-1,1)) for block in self._blocks] 00087 00088 error_vec = numpy.concatenate(errors, 0) 00089 00090 error_array = numpy.array(error_vec).T[0] 00091 00092 rms_error = numpy.sqrt( numpy.mean(error_array**2) ) 00093 print "%.3f " % rms_error, 00094 sys.stdout.flush() 00095 00096 return error_array.copy() 00097 00098 def opt_runner(robot_params_dict, free_dict, blocks): 00099 # Load the robot params 00100 robot_params = RobotParams() 00101 robot_params.configure(robot_params_dict) 00102 00103 for block in blocks: 00104 block.update_config(robot_params) 00105 00106 # Load the free configuration 00107 free_list = robot_params.calc_free(free_dict) 00108 expanded_param_vec = robot_params.deflate() 00109 00110 error_calc = ErrorCalc(robot_params, expanded_param_vec, free_list, blocks) 00111 00112 # Construct the initial guess 00113 opt_guess_mat = expanded_param_vec[numpy.where(free_list), 0].copy() 00114 opt_guess = numpy.array(opt_guess_mat)[0] 00115 00116 import scipy.optimize 00117 x, cov_x, infodict, mesg, iter = scipy.optimize.leastsq(error_calc.calculate_error, opt_guess.copy(), full_output=1) 00118 00119 # A hacky way to inflate x back into robot params 00120 full_param_vec = error_calc.calculate_full_param_vec(x) 00121 00122 output_dict = error_calc._robot_params.params_to_config(full_param_vec) 00123 00124 # Compute the rms error 00125 final_error = error_calc.calculate_error(x) 00126 rms_error = numpy.sqrt( numpy.mean(final_error**2) ) 00127 print "RMS Error: %f" % rms_error 00128 00129 return output_dict 00130 00131 if __name__ == '__main__': 00132 rospy.init_node("multi_step_estimator") 00133 00134 print "Starting The Multi Step Estimator Node\n" 00135 00136 if (len(rospy.myargv()) < 2): 00137 usage() 00138 elif (len(rospy.myargv()) < 3): 00139 bag_filename = rospy.myargv()[1] 00140 output_dir = "." 00141 else: 00142 bag_filename = rospy.myargv()[1] 00143 output_dir = rospy.myargv()[2] 00144 00145 print "Using Bagfile: %s\n" % bag_filename 00146 if not os.path.isfile(bag_filename): 00147 rospy.logerr("Bagfile does not exist. Exiting...") 00148 sys.exit(1) 00149 00150 config_param_name = "calibration_config" 00151 if not rospy.has_param(config_param_name): 00152 rospy.logerr("Could not find parameter [%s]. Please populate this namespace with the estimation configuration.", config_param_name) 00153 sys.exit(1) 00154 config = rospy.get_param(config_param_name) 00155 00156 # Process all the block definitions that are on the parameter server 00157 blocks_name = "blocks" 00158 if blocks_name not in config.keys(): 00159 rospy.logerr("Could not find namespace [%s/%s]. Please populate this namespace with blocks.", (config_param_name, blocks_name)) 00160 sys.exit(1) 00161 blocks_dump = [yaml.load(x) for x in config[blocks_name].values()] 00162 00163 # There could be multiple defitions of blocks in the blocks namespace. We 00164 # need to merge all of these into a single consistent dictionary 00165 all_blocks_dict = dict() 00166 #import code; code.interact(local=locals()) 00167 for cur_blocks_file in blocks_dump: 00168 for cur_block_type, cur_block_list in cur_blocks_file.items(): 00169 for cur_block in cur_block_list: 00170 # We want block_ids to be unique. Thus, we should warn the user if there are duplicate block IDs being loaded 00171 if cur_block['block_id'] in all_blocks_dict.keys(): 00172 rospy.logwarn("Loading a duplicate [%s]. Overwriting previous" % cur_block['block_id']) 00173 all_blocks_dict[cur_block['block_id']] = cur_block 00174 all_blocks_dict[cur_block['block_id']]['block_type'] = cur_block_type 00175 00176 print "The following error blocks have been loaded into the estimator:\n" 00177 # We want to sort by the types of blocks 00178 all_block_types = list(set([x['block_type'] for x in all_blocks_dict.values()])) 00179 00180 00181 for cur_block_type in all_block_types: 00182 print " %s Blocks" % cur_block_type 00183 cur_block_ids = [cur_block_id for cur_block_id,cur_block in all_blocks_dict.items() if cur_block['block_type'] == cur_block_type] 00184 cur_block_ids.sort() 00185 for cur_block_id in cur_block_ids: 00186 print " - %s" % cur_block_id 00187 print "" 00188 00189 # Load all the calibration steps. 00190 # We want to execute the calibration in alphabetical order, based on the key names 00191 step_keys = config["cal_steps"].keys() 00192 step_keys.sort() 00193 step_list = [] 00194 for step_name in step_keys: 00195 # Add the step name to the dict (since we'll lose this info once we listify) 00196 config["cal_steps"][step_name]["name"] = step_name 00197 step_list.append(config["cal_steps"][step_name]) 00198 print "Executing the calibration steps in the following order:" 00199 for cur_step in step_list: 00200 print " - %s" % cur_step['name'] 00201 00202 00203 # Specify which system the first calibration step should use. 00204 # Normally this would be set at the end of the calibration loop, but for the first step, 00205 # this is grabbed from the param server 00206 previous_system = yaml.load(config["initial_system"]) 00207 00208 # Load all the blocks from the bagfile and config file 00209 for cur_step in step_list: 00210 print "" 00211 print "*"*30 00212 print "Beginning [%s]" % cur_step["name"] 00213 00214 # Need to load only the blocks that we're interested in 00215 cur_blocks = dict([(x,[]) for x in all_block_types]) 00216 for req_block_id in cur_step['blocks']: 00217 # We need to now find req_block_id in our library of blocks 00218 if req_block_id in all_blocks_dict.keys(): 00219 cur_block_type = all_blocks_dict[req_block_id]['block_type'] 00220 cur_blocks[cur_block_type].append(all_blocks_dict[req_block_id]) 00221 else: 00222 rospy.logerr("Could not find [%s] in block library. Skipping this block") 00223 00224 bundler = robot_measurement_bundler.RobotMeasurementBundler(cur_blocks) 00225 blocks = bundler.load_from_bag(bag_filename) 00226 00227 print "Executing step with the following blocks:" 00228 for cur_block_type, cur_block_list in cur_blocks.items(): 00229 print " %s Blocks:" % cur_block_type 00230 cur_block_ids = [cur_block['block_id'] for cur_block in cur_block_list] 00231 cur_block_ids.sort() 00232 for cur_block_id in cur_block_ids: 00233 count = len([0 for x in blocks if x.block_id == cur_block_id]) 00234 print " - %s (%u)" % (cur_block_id, count) 00235 print "" 00236 00237 if len(blocks) == 0: 00238 rospy.logwarn("No error blocks were generated for this optimization step. Skipping this step. This will result in a miscalibrated sensor") 00239 output_dict = previous_system 00240 else: 00241 free_dict = yaml.load(cur_step["free_params"]) 00242 output_dict = opt_runner(previous_system, free_dict, blocks) 00243 00244 out_f = open(output_dir + "/" + cur_step["output_filename"], 'w') 00245 yaml.dump(output_dict, out_f) 00246 out_f.close() 00247 00248 previous_system = output_dict 00249