$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 00033 # author: Vijay Pradeep 00034 00035 import roslib; roslib.load_manifest('pr2_calibration_estimation') 00036 00037 from pr2_calibration_estimation.robot_params import RobotParams 00038 from pr2_calibration_estimation.single_transform import SingleTransform 00039 import numpy 00040 from numpy import array, matrix, zeros, cumsum, concatenate, reshape 00041 import scipy.optimize 00042 import sys 00043 00044 class ErrorCalc: 00045 """ 00046 Helpers for computing errors and jacobians 00047 """ 00048 def __init__(self, robot_params, free_dict, multisensors, use_cov): 00049 self._robot_params = robot_params 00050 self._expanded_params = robot_params.deflate() 00051 self._free_list = robot_params.calc_free(free_dict) 00052 self._multisensors = multisensors 00053 self._use_cov = use_cov 00054 00055 00056 def calculate_full_param_vec(self, opt_param_vec): 00057 ''' 00058 Take the set of optimization params, and expand it into the bigger param vec 00059 ''' 00060 full_param_vec = self._expanded_params.copy() 00061 full_param_vec[numpy.where(self._free_list), 0] = opt_param_vec 00062 00063 return full_param_vec 00064 00065 def calculate_error(self, opt_all_vec): 00066 print "x ", 00067 sys.stdout.flush() 00068 00069 opt_param_vec, full_pose_arr = self.split_all(opt_all_vec) 00070 00071 full_param_vec = self.calculate_full_param_vec(opt_param_vec) 00072 00073 # Update the primitives with the new set of parameters 00074 self._robot_params.inflate(full_param_vec) 00075 00076 # Update all the blocks' configs 00077 for multisensor in self._multisensors: 00078 multisensor.update_config(self._robot_params) 00079 00080 r_list = [] 00081 for multisensor, cb_pose_vec in zip(self._multisensors, list(full_pose_arr)): 00082 # Process cb pose 00083 cb_points = SingleTransform(cb_pose_vec).transform * self._robot_params.checkerboards[multisensor.checkerboard].generate_points() 00084 if (self._use_cov): 00085 r_list.append(multisensor.compute_residual_scaled(cb_points)) 00086 else: 00087 r_list.append(multisensor.compute_residual(cb_points)) 00088 #import code; code.interact(local=locals()) 00089 r_vec = concatenate(r_list) 00090 00091 rms_error = numpy.sqrt( numpy.mean(r_vec**2) ) 00092 print "%.3f " % rms_error, 00093 sys.stdout.flush() 00094 00095 return array(r_vec) 00096 00097 def calculate_jacobian(self, opt_all_vec): 00098 """ 00099 Full Jacobian: 00100 The resulting returned jacobian can be thought of as a set of several concatenated jacobians as follows: 00101 00102 [ J_multisensor_0 ] 00103 J = [ J_multisensor_1 ] 00104 [ : ] 00105 [ J_multisensor_M ] 00106 00107 where M is the number of multisensors, which is generally the number of calibration samples collected. 00108 00109 Multisensor Jacobian: 00110 The Jacobian for a given multisensor is created by concatenating jacobians for each sensor 00111 00112 [ J_sensor_m_0 ] 00113 J_multisensor_m = [ J_sensor_m_1 ] 00114 [ : ] 00115 [ J_sensor_m_S ] 00116 00117 where S is the number of sensors in this multisensor. 00118 00119 Sensor Jacobian: 00120 A single sensor jacobian is created by concatenating jacobians for the system parameters and checkerboards 00121 00122 J_sensor_m_s = [ J_params_m_s | J_m_s_pose0 | J_m_s_pose1 | --- | J_m_s_CB_poseC ] 00123 00124 The number of rows in J_sensor_m_s is equal to the number of rows in this sensor's residual. 00125 J_params_m_s shows how modifying the free system parameters affects the residual. 00126 Each J_m_s_pose_c is 6 columns wide and shows how moving a certain target affects the residual. All 00127 of the J_m_s_pose blocks are zero, except J_sensor_pose_m, since target m is the only target that 00128 was viewed by the sensors in this multisensor. 00129 """ 00130 sys.stdout.write("J-") 00131 sys.stdout.flush() 00132 #import scipy.optimize.slsqp.approx_jacobian as approx_jacobian 00133 #J = approx_jacobian(opt_param_vec, self.calculate_error, 1e-6) 00134 00135 opt_param_vec, full_pose_arr = self.split_all(opt_all_vec) 00136 00137 # Allocate the full jacobian matrix 00138 ms_r_len = [ms.get_residual_length() for ms in self._multisensors] 00139 J = zeros([sum(ms_r_len), len(opt_all_vec)]) 00140 00141 # Calculate at which row each multisensor starts and ends 00142 ms_end_row = list(cumsum(ms_r_len)) 00143 ms_start_row = [0] + ms_end_row[:-1] 00144 00145 # Calculate at which column each multisensor starts and ends 00146 ms_end_col = list(cumsum([6]*len(self._multisensors)) + len(opt_param_vec)) 00147 ms_start_col = [x-6 for x in ms_end_col] 00148 00149 00150 for i,ms in zip(range(len(self._multisensors)), self._multisensors): 00151 # Populate the parameter section for this multisensor 00152 J_ms_params = J[ ms_start_row[i]:ms_end_row[i], 00153 0:len(opt_param_vec) ] 00154 s_r_len = [s.get_residual_length() for s in ms.sensors] 00155 s_end_row = list(cumsum(s_r_len)) 00156 s_start_row = [0] + s_end_row[:-1] 00157 #import code; code.interact(local=locals()) 00158 target_pose_T = SingleTransform(full_pose_arr[i,:]).transform 00159 # Fill in parameter section one sensor at a time 00160 for k,s in zip(range(len(ms.sensors)), ms.sensors): 00161 J_s_params = J_ms_params[ s_start_row[k]:s_end_row[k], :] 00162 J_s_params[:,:] = self.single_sensor_params_jacobian(opt_param_vec, target_pose_T, ms.checkerboard, s) 00163 00164 # Populate the pose section for this multisensor 00165 J_ms_pose = J[ ms_start_row[i]:ms_end_row[i], 00166 ms_start_col[i]:ms_end_col[i]] 00167 assert(J_ms_pose.shape[1] == 6) 00168 J_ms_pose[:,:] = self.multisensor_pose_jacobian(opt_param_vec, full_pose_arr[i,:], ms) 00169 #import code; code.interact(local=locals()) 00170 00171 print "-J", 00172 sys.stdout.flush() 00173 00174 return J 00175 00176 def split_all(self, opt_all_vec): 00177 """ 00178 Splits the input vector into two parts: 00179 1) opt_param_vec: The system parameters that we're optimizing, 00180 2) full_pose_arr: A Nx6 array where each row is a checkerboard pose 00181 """ 00182 opt_param_len = sum(self._free_list) 00183 opt_param_vec = opt_all_vec[0:opt_param_len] 00184 00185 full_pose_vec = opt_all_vec[opt_param_len:] 00186 full_pose_arr = numpy.reshape(full_pose_vec, [-1,6]) 00187 return opt_param_vec, full_pose_arr 00188 00189 def single_sensor_params_jacobian(self, opt_param_vec, target_pose_T, target_id, sensor): 00190 """ 00191 Computes the jacobian from the free system parameters to a single sensor 00192 Inputs: 00193 - opt_param_vec: Vector of the free system parameters (the parameters we're actuall optimizing) 00194 - target_pose_T: The pose of the target that this sensor is viewing 00195 - target_id: String name of the target that this sensor is viewing. This is necessary to generate the 00196 set of feature points on the target 00197 - sensor: The actual sensor definition 00198 Output: 00199 - J_scaled: An mxn jacobian, where m is the length of sensor's residual and n is the length of opt_param_vec. 00200 If covariance calculations are enabled, then the Jacobian is scaled by sqrt(Gamma), where Gamma 00201 is the information matrix for this measurement. 00202 """ 00203 sparsity_dict = sensor.build_sparsity_dict() 00204 required_keys = ['dh_chains', 'tilting_lasers', 'transforms', 'rectified_cams', 'checkerboards'] 00205 for cur_key in required_keys: 00206 if cur_key not in sparsity_dict.keys(): 00207 sparsity_dict[cur_key] = {} 00208 # Generate the full sparsity vector 00209 full_sparsity_list = self._robot_params.calc_free(sparsity_dict) 00210 full_sparsity_vec = numpy.array(full_sparsity_list) 00211 00212 # Extract the sparsity for only the parameters we are optimizing over 00213 00214 #import code; code.interact(local=locals()) 00215 opt_sparsity_vec = full_sparsity_vec[numpy.where(self._free_list)].copy() 00216 00217 # Update the primitives with the new set of parameters 00218 full_param_vec = self.calculate_full_param_vec(opt_param_vec) 00219 self._robot_params.inflate(full_param_vec) 00220 sensor.update_config(self._robot_params) 00221 00222 # based on code from scipy.slsqp 00223 x0 = opt_param_vec 00224 epsilon = 1e-6 00225 target_points = target_pose_T * self._robot_params.checkerboards[target_id].generate_points() 00226 f0 = sensor.compute_residual(target_points) 00227 gamma_sqrt = sensor.compute_marginal_gamma_sqrt(target_points) 00228 Jt = numpy.zeros([len(x0),len(f0)]) 00229 dx = numpy.zeros(len(x0)) 00230 for i in numpy.where(opt_sparsity_vec)[0]: 00231 dx[i] = epsilon 00232 opt_test_param_vec = x0 + dx 00233 full_test_param_vec = self.calculate_full_param_vec(opt_test_param_vec) 00234 self._robot_params.inflate(full_test_param_vec) 00235 sensor.update_config(self._robot_params) 00236 #import code; code.interact(local=locals()) 00237 target_points = target_pose_T * self._robot_params.checkerboards[target_id].generate_points() 00238 Jt[i] = (sensor.compute_residual(target_points) - f0)/epsilon 00239 dx[i] = 0.0 00240 J = Jt.transpose() 00241 if (self._use_cov): 00242 J_scaled = gamma_sqrt * J 00243 else: 00244 J_scaled = J 00245 return J_scaled 00246 00247 def multisensor_pose_jacobian(self, opt_param_vec, pose_param_vec, multisensor): 00248 """ 00249 Generates the jacobian from a target pose to the multisensor's residual. 00250 00251 Input: 00252 - opt_param_vec: Vector of the free system parameters (the parameters we're actuall optimizing) 00253 - pose_param_vec: Vector of length 6 encoding the target's pose 0:3=translation 3:6=rotation_axis 00254 - multisensor: The actual multisensor definition. 00255 Output: 00256 - J_scaled: An mx6 jacobian, where m is the length of multisensor's residual. There are 6 columns since the 00257 target's pose is encoded using 6 parameters. 00258 If covariance calculations are enabled, then the Jacobian is scaled by sqrt(Gamma), where Gamma 00259 is the information matrix for this measurement. 00260 """ 00261 # Update the primitives with the new set of parameters 00262 full_param_vec = self.calculate_full_param_vec(opt_param_vec) 00263 self._robot_params.inflate(full_param_vec) 00264 multisensor.update_config(self._robot_params) 00265 cb_model = self._robot_params.checkerboards[multisensor.checkerboard] 00266 local_cb_points = cb_model.generate_points() 00267 00268 # based on code from scipy.slsqp 00269 x0 = pose_param_vec 00270 epsilon = 1e-6 00271 world_pts = SingleTransform(x0).transform * local_cb_points 00272 f0 = multisensor.compute_residual(world_pts) 00273 gamma_sqrt = multisensor.compute_marginal_gamma_sqrt(world_pts) 00274 00275 Jt = numpy.zeros([len(x0),len(f0)]) 00276 dx = numpy.zeros(len(x0)) 00277 for i in range(len(x0)): 00278 dx[i] = epsilon 00279 test_vec = x0 + dx 00280 fTest = multisensor.compute_residual(SingleTransform(test_vec).transform * local_cb_points) 00281 Jt[i] = (fTest - f0)/epsilon 00282 #import code; code.interact(local=locals()) 00283 dx[i] = 0.0 00284 J = Jt.transpose() 00285 if (self._use_cov): 00286 J_scaled = gamma_sqrt * J 00287 else: 00288 J_scaled = J 00289 return J_scaled 00290 00291 def build_opt_vector(robot_params, free_dict, pose_guess_arr): 00292 """ 00293 Construct vector of all the parameters that we're optimizing over. This includes 00294 both the free system parameters and the checkerboard poses 00295 Inputs: 00296 - robot_params: Dictionary with all of the system parameters 00297 - free_dict: Dictionary that specifies which system parameters are free 00298 - pose_guess_arr: Mx6 array storing the current checkerboard poses, where M is 00299 the number of calibration samples 00300 Returns: Vector of length (F + Mx6), where F is the number of 1's in the free_dict 00301 """ 00302 00303 # Convert the robot parameter dictionary into a vector 00304 expanded_param_vec = robot_params.deflate() 00305 free_list = robot_params.calc_free(free_dict) 00306 00307 # Pull out only the free system parameters from the system parameter vector 00308 opt_param_vec = array(expanded_param_vec[numpy.where(free_list)].T)[0] 00309 00310 assert(pose_guess_arr.shape[1] == 6) 00311 opt_pose_vec = reshape(pose_guess_arr, [-1]) 00312 00313 opt_all = numpy.concatenate([opt_param_vec, opt_pose_vec]) 00314 00315 return opt_all 00316 00317 00318 def compute_errors_breakdown(error_calc, multisensors, opt_pose_arr): 00319 errors_dict = {} 00320 # Compute the error for each sensor type 00321 for ms, k in zip(multisensors, range(len(multisensors))): 00322 cb = error_calc._robot_params.checkerboards[ms.checkerboard] 00323 cb_pose_vec = opt_pose_arr[k] 00324 target_pts = SingleTransform(cb_pose_vec).transform * cb.generate_points() 00325 for sensor in ms.sensors: 00326 r_sensor = sensor.compute_residual(target_pts) * numpy.sqrt(sensor.terms_per_sample) # terms per sample is a hack to find rms distance, instead of a pure rms, based on each term 00327 if sensor.sensor_id not in errors_dict.keys(): 00328 errors_dict[sensor.sensor_id] = [] 00329 errors_dict[sensor.sensor_id].append(r_sensor) 00330 return errors_dict 00331 00332 def opt_runner(robot_params_dict, pose_guess_arr, free_dict, multisensors, use_cov): 00333 """ 00334 Runs a single optimization step for the calibration optimization. 00335 robot_params_dict - Dictionary storing all of the system primitives' parameters (lasers, cameras, chains, transforms, etc) 00336 free_dict - Dictionary storing which parameters are free 00337 multisensor - list of list of measurements. Each multisensor corresponds to a single checkerboard pose 00338 pose_guesses - List of guesses as to where all the checkerboard are. This is used to initialze the optimization 00339 """ 00340 00341 # Load the robot params 00342 robot_params = RobotParams() 00343 robot_params.configure(robot_params_dict) 00344 00345 error_calc = ErrorCalc(robot_params, free_dict, multisensors, use_cov) 00346 00347 # Construct the initial guess 00348 opt_all = build_opt_vector(robot_params, free_dict, pose_guess_arr) 00349 00350 x, cov_x, infodict, mesg, iter = scipy.optimize.leastsq(error_calc.calculate_error, opt_all, Dfun=error_calc.calculate_jacobian, full_output=1) 00351 #x = opt_all 00352 #error_calc.calculate_error(x) 00353 00354 J = error_calc.calculate_jacobian(x) 00355 00356 # A hacky way to inflate x back into robot params 00357 opt_param_vec, pose_vec = error_calc.split_all(x) 00358 expanded_param_vec = error_calc.calculate_full_param_vec(opt_param_vec) 00359 opt_pose_arr = reshape(pose_vec, [-1, 6]) 00360 00361 output_dict = error_calc._robot_params.params_to_config(expanded_param_vec) 00362 00363 errors_dict = compute_errors_breakdown(error_calc, multisensors, opt_pose_arr) 00364 00365 print "" 00366 print "Errors Breakdown:" 00367 for sensor_id, error_list in errors_dict.items(): 00368 error_cat = numpy.concatenate(error_list) 00369 rms_error = numpy.sqrt( numpy.mean(error_cat**2) ) 00370 print " %s: %.6f" % (sensor_id, rms_error) 00371 00372 00373 # Compute the rms error 00374 #final_error = error_calc.calculate_error(x) 00375 #rms_error = numpy.sqrt( numpy.mean(final_error**2) ) 00376 #print "RMS Error: %f" % rms_error 00377 00378 return output_dict, opt_pose_arr, J 00379 00380 00381 00382 00383 00384 00385 00386 00387 00388 00389 00390 00391 00392