Go to the documentation of this file.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 import numpy
00034 from numpy import matrix, vsplit, sin, cos, reshape
00035 import rospy
00036 from calibration_estimation.single_transform import SingleTransform
00037
00038
00039
00040 param_names = ['gearing']
00041
00042 class TiltingLaser:
00043
00044 def __init__(self, config ):
00045 rospy.logdebug("Initializing tilting laser")
00046 self._config = config
00047 self._cov_dict = config['cov']
00048
00049 param_vec = self.dict_to_params(config)
00050 self.inflate(param_vec)
00051
00052 def update_config(self, robot_params):
00053 parent = robot_params.urdf.joint_map[self._config['joint']].parent
00054 child = robot_params.urdf.joint_map[self._config['joint']].child
00055 before_chain = robot_params.urdf.get_chain(robot_params.base_link, parent, links=False)
00056 before_chain.append(self._config['joint'])
00057 after_chain = robot_params.urdf.get_chain(child, self._config['frame_id'], links=False)
00058 self._before_chain_Ts = [robot_params.transforms[transform_name] for transform_name in before_chain]
00059 self._after_chain_Ts = [robot_params.transforms[transform_name] for transform_name in after_chain]
00060
00061 def dict_to_params(self, config):
00062 param_vec = matrix(numpy.zeros((1,1), float))
00063 param_vec[0,0] = config['gearing']
00064 return param_vec
00065
00066 def params_to_config(self, param_vec):
00067 return {'joint' : self._config['joint'],
00068 'frame_id' : self._config['frame_id'],
00069 "gearing" : float(param_vec[0,0]),
00070 "cov" : self._cov_dict }
00071
00072 def calc_free(self, free_config):
00073 return [free_config['gearing'] == 1]
00074
00075
00076 def inflate(self, param_vec):
00077 self._gearing = param_vec[0,0]
00078
00079
00080 def deflate(self):
00081 param_vec = matrix(numpy.zeros((1,1), float))
00082 param_vec[0,0] = self._gearing
00083 return param_vec
00084
00085
00086 def get_length(self):
00087 return len(param_names)
00088
00089 def compute_pose(self, joint_pos):
00090 pose = matrix(numpy.eye(4))
00091 for before_chain_T in self._before_chain_Ts:
00092 pose = pose * before_chain_T.transform
00093 pose = pose * SingleTransform([0, 0, 0, 0, joint_pos[0]*self._gearing, 0]).transform
00094 for after_chain_T in self._after_chain_Ts:
00095 pose = pose * after_chain_T.transform
00096 return pose
00097
00098
00099
00100
00101 def project_point_to_3D(self, joint_pos):
00102 p = joint_pos[1]
00103 r = joint_pos[2]
00104 ray = reshape(matrix([cos(p)*r, sin(p)*r, 0, 1]), (-1,1))
00105
00106 result = self.compute_pose(joint_pos) * ray
00107 return result
00108
00109
00110
00111
00112
00113
00114
00115
00116 def project_to_3D(self, joint_pos):
00117 result = numpy.concatenate( [self.project_point_to_3D(x) for x in joint_pos], 1 )
00118 return result
00119