35 import roslib; roslib.load_manifest(
'calibration_estimation')
47 from sensor_msgs.msg
import JointState
56 active_joints: [j1, j2, j3] 60 joint_angles: [1, 1, 1] 62 config_dict = yaml.load(config)
63 config_dict[
'transforms'] = {
'j1':
SingleTransform([1, 0, 0, 0, 0, 0]),
74 self.assertEqual(self.chain.get_length(), 3)
77 free_config = [ [ 1, 0, 0, 0, 0, 0 ],
79 [ 1, 0, 0, 0, 0, 1 ] ]
81 free_list = self.chain.calc_free({
'transforms':free_config,
'axis': [6,6,6],
'gearing':[0,0,0]})
82 self.assertEqual(free_list[0], 0)
83 self.assertEqual(free_list[1], 0)
84 self.assertEqual(free_list[2], 0)
87 param_vec = self.chain.deflate()
88 self.assertEqual(param_vec[0,0], 1)
89 self.assertEqual(param_vec[1,0], 1)
90 self.assertEqual(param_vec[2,0], 1)
93 param_vec = numpy.reshape(numpy.matrix(numpy.arange(3)),(3,1))
94 self.chain.inflate(param_vec)
95 self.assertEqual(self.chain._gearing[0], 0)
96 self.assertEqual(self.chain._gearing[2], 2)
99 param_vec = self.chain.deflate()
101 config = self.chain.params_to_config(param_vec)
102 self.assertAlmostEqual(config[
'gearing'][0], 10, 6)
105 chain_state = JointState()
106 chain_state.position = [0, 0, 0]
107 eef = self.chain.fk(chain_state, 0)
108 eef_expected = numpy.matrix( [[ 1, 0, 0, 1],
112 self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
115 chain_state = JointState()
116 chain_state.position = [numpy.pi/2, 0, 0]
117 eef = self.chain.fk(chain_state, 0)
119 eef_expected = numpy.matrix( [[ 0,-1, 0, 1],
123 self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
126 chain_state = JointState()
127 chain_state.position = [numpy.pi/2, numpy.pi/2, 0]
128 eef = self.chain.fk(chain_state, 1)
130 eef_expected = numpy.matrix( [[-1, 0, 0, 1],
134 self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
137 chain_state = JointState()
138 chain_state.position = [0, 0, 0]
139 eef = self.chain.fk(chain_state, -1)
141 eef_expected = numpy.matrix( [[ 1, 0, 0, 3],
145 self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
147 if __name__ ==
'__main__':
149 rostest.unitrun(
'calibration_estimation',
'test_JointChain', TestJointChain, coverage_packages=[
'calibration_estimation.joint_chain'])
def test_get_length(self)