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
00038
00039
00040
00041
00042
00043
00044
00045 from numpy import reshape, array, zeros, matrix, diag, real
00046
00047 import roslib; roslib.load_manifest('pr2_calibration_estimation')
00048 import rospy
00049 import numpy
00050
00051
00052 class TiltingLaserBundler:
00053 def __init__(self, valid_configs):
00054 self._valid_configs = valid_configs
00055
00056
00057 def build_blocks(self, M_robot):
00058 sensors = []
00059 for cur_config in self._valid_configs:
00060 rospy.logdebug("On Config Block [%s]" % cur_config["laser_id"])
00061 if cur_config["laser_id"] in [ x.laser_id for x in M_robot.M_laser ] :
00062 rospy.logdebug(" Found block!")
00063 cur_M_laser = M_robot.M_laser[ [ x.laser_id for x in M_robot.M_laser ].index(cur_config["laser_id"]) ]
00064 cur_sensor = TiltingLaserSensor(cur_config, cur_M_laser)
00065 sensors.append(cur_sensor)
00066 else:
00067 rospy.logdebug(" Didn't find block")
00068 return sensors
00069
00070 class TiltingLaserSensor:
00071 def __init__(self, config_dict, M_laser):
00072 self._config_dict = config_dict
00073 self.sensor_type = "laser"
00074 self.sensor_id = config_dict["laser_id"]
00075 self._M_laser = M_laser
00076 self.terms_per_sample = 3
00077
00078 def update_config(self, robot_params):
00079 self._tilting_laser = robot_params.tilting_lasers[ self._config_dict["laser_id"] ]
00080
00081 def compute_residual(self, target_pts):
00082 z_mat = self.get_measurement()
00083 h_mat = self.compute_expected(target_pts)
00084 assert(z_mat.shape[0] == 4)
00085 assert(h_mat.shape[0] == 4)
00086 assert(z_mat.shape[1] == z_mat.shape[1])
00087 r = array(reshape(h_mat[0:3,:].T - z_mat[0:3,:].T, [-1,1]))[:,0]
00088 return r
00089
00090 def compute_residual_scaled(self, target_pts):
00091 r = self.compute_residual(target_pts)
00092 gamma_sqrt = self.compute_marginal_gamma_sqrt(target_pts)
00093 r_scaled = gamma_sqrt * matrix(r).T
00094 return array(r_scaled.T)[0]
00095
00096 def compute_marginal_gamma_sqrt(self, target_pts):
00097 import scipy.linalg
00098
00099 cov = self.compute_cov(target_pts)
00100 gamma = matrix(zeros(cov.shape))
00101 num_pts = self.get_residual_length()/3
00102
00103 for k in range(num_pts):
00104
00105 first = 3*k
00106 last = 3*k+3
00107 sub_cov = matrix(cov[first:last, first:last])
00108 sub_gamma_sqrt_full = matrix(scipy.linalg.sqrtm(sub_cov.I))
00109 sub_gamma_sqrt = real(sub_gamma_sqrt_full)
00110 assert(scipy.linalg.norm(sub_gamma_sqrt_full - sub_gamma_sqrt) < 1e-6)
00111 gamma[first:last, first:last] = sub_gamma_sqrt
00112
00113 return gamma
00114
00115 def get_residual_length(self):
00116 N = len(self._M_laser.joint_points)
00117 return N*3
00118
00119
00120
00121 def get_measurement(self):
00122
00123 laser_pts_root = self._tilting_laser.project_to_3D([x.position for x in self._M_laser.joint_points])
00124
00125 return laser_pts_root
00126
00127 def compute_cov(self, target_pts):
00128 epsilon = 1e-8
00129
00130
00131
00132
00133
00134 Jt = zeros([3, self.get_residual_length()])
00135
00136 import copy
00137 x = [copy.copy(x.position) for x in self._M_laser.joint_points]
00138
00139 f0 = reshape(array(self._tilting_laser.project_to_3D(x)[0:3,:].T), [-1])
00140 for i in range(3):
00141 x = [ [y for y in x.position] for x in self._M_laser.joint_points]
00142 for cur_pt in x:
00143 cur_pt[i] += epsilon
00144 fTest = reshape(array(self._tilting_laser.project_to_3D(x)[0:3,:].T), [-1])
00145 Jt[i] = (fTest - f0)/epsilon
00146
00147 num_pts = len(x)
00148 std_dev_sensor = [self._tilting_laser._cov_dict['tilt'],
00149 self._tilting_laser._cov_dict['bearing'],
00150 self._tilting_laser._cov_dict['range']]
00151 cov_sensor = [x*x for x in std_dev_sensor]
00152
00153
00154 cov = matrix(Jt).T * matrix(diag(cov_sensor)) * matrix(Jt)
00155 return cov
00156
00157
00158
00159
00160
00161
00162
00163
00164 def compute_expected(self, target_pts):
00165
00166 return target_pts
00167
00168
00169 def build_sparsity_dict(self):
00170 sparsity = dict()
00171
00172 sparsity['tilting_lasers'] = {}
00173 sparsity['tilting_lasers'][self.sensor_id] = {'before_joint':[1,1,1,1,1,1],
00174 'after_joint':[1,1,1,1,1,1],
00175 'gearing':1}
00176
00177 return sparsity