46 from numpy
import reshape, array, zeros, diag, matrix, real
47 import roslib; roslib.load_manifest(
'calibration_estimation')
50 from sensor_msgs.msg
import JointState
60 if cur_config[
"sensor_id"] == M_robot.chain_id
and \
61 cur_config[
"sensor_id"]
in [ x.chain_id
for x
in M_robot.M_chain ]:
62 M_chain = [x
for x
in M_robot.M_chain
if cur_config[
"sensor_id"] == x.chain_id][0]
63 cur_sensor =
ChainSensor(cur_config, M_chain, M_robot.target_id)
64 sensors.append(cur_sensor)
66 rospy.logdebug(
" Didn't find block")
70 def __init__(self, config_dict, M_chain, target_id):
90 assert(h_mat.shape == z_mat.shape)
91 assert(h_mat.shape[0] == 4)
92 r_mat = h_mat[0:3,:] - z_mat[0:3,:]
93 r = array(reshape(r_mat.T, [-1,1]))[:,0]
99 r_scaled = gamma_sqrt * matrix(r).T
100 return array(r_scaled.T)[0]
106 gamma = matrix(zeros(cov.shape))
109 for k
in range(num_pts):
113 sub_cov = matrix(cov[first:last, first:last])
114 sub_gamma_sqrt_full = matrix(scipy.linalg.sqrtm(sub_cov.I))
115 sub_gamma_sqrt = real(sub_gamma_sqrt_full)
116 assert(scipy.linalg.norm(sub_gamma_sqrt_full - sub_gamma_sqrt) < 1e-6)
117 gamma[first:last, first:last] = sub_gamma_sqrt
123 num_joints = len(self.
_M_chain.chain_state.position)
127 x.position = self.
_M_chain.chain_state.position[:]
130 for i
in range(num_joints):
131 x.position = list(self.
_M_chain.chain_state.position[:])
132 x.position[i] += epsilon
134 Jt[i] = (fTest - f0)/epsilon
135 cov_angles = [x*x
for x
in self.
_full_chain.calc_block._chain._cov_dict[
'joint_angles']]
136 cov = matrix(Jt).T * matrix(diag(cov_angles)) * matrix(Jt)
139 if (
'translation' in self.
_full_chain.calc_block._chain._cov_dict ):
140 translation_var = self.
_full_chain.calc_block._chain._cov_dict[
'translation'];
142 cov = cov + translation_cov
153 Returns a 4xN matrix with the locations of the checkerboard points in homogenous coords,
154 as per the forward kinematics of the chain
163 target_pose_root = self.
_full_chain.calc_block.fk(chain_state)
166 target_pts_root = target_pose_root * target_pts_tip
168 return target_pts_root
176 sparsity[
'checkerboards'] = {}
177 sparsity[
'checkerboards'][self.
_target_id] = {
'spacing_x': 1,
'spacing_y': 1 }