34 from numpy
import matrix, vsplit, sin, cos, reshape
40 param_names = [
'gearing']
45 rospy.logdebug(
"Initializing tilting laser")
53 parent = robot_params.urdf.joint_map[self.
_config[
'joint']].parent
54 child = robot_params.urdf.joint_map[self.
_config[
'joint']].child
55 before_chain = robot_params.urdf.get_chain(robot_params.base_link, parent, links=
False)
56 before_chain.append(self.
_config[
'joint'])
57 after_chain = robot_params.urdf.get_chain(child, self.
_config[
'frame_id'], links=
False)
58 self.
_before_chain_Ts = [robot_params.transforms[transform_name]
for transform_name
in before_chain]
59 self.
_after_chain_Ts = [robot_params.transforms[transform_name]
for transform_name
in after_chain]
62 param_vec = matrix(numpy.zeros((1,1), float))
63 param_vec[0,0] = config[
'gearing']
67 return {
'joint' : self.
_config[
'joint'],
68 'frame_id' : self.
_config[
'frame_id'],
69 "gearing" : float(param_vec[0,0]),
73 return [free_config[
'gearing'] == 1]
81 param_vec = matrix(numpy.zeros((1,1), float))
87 return len(param_names)
90 pose = matrix(numpy.eye(4))
92 pose = pose * before_chain_T.transform
95 pose = pose * after_chain_T.transform
104 ray = reshape(matrix([cos(p)*r, sin(p)*r, 0, 1]), (-1,1))
def inflate(self, param_vec)
def project_point_to_3D(self, joint_pos)
def calc_free(self, free_config)
def compute_pose(self, joint_pos)
def project_to_3D(self, joint_pos)
def dict_to_params(self, config)
def __init__(self, config)
def update_config(self, robot_params)
def params_to_config(self, param_vec)