35 import roslib; roslib.load_manifest(
'calibration_estimation')
42 from sensor_msgs.msg
import JointState
54 <link name="base_link"/>
55 <joint name="j0" type="fixed">
56 <origin xyz="10 0 0" rpy="0 0 0"/>
57 <parent link="base_link"/>
58 <child link="j0_link"/>
60 <link name="j0_link"/>
61 <joint name="j1" type="revolute">
63 <origin xyz="1 0 0" rpy="0 0 0"/>
64 <parent link="j0_link"/>
65 <child link="j1_link"/>
67 <link name="j1_link"/>
68 <joint name="j2" type="revolute">
70 <origin xyz="0 0 0" rpy="0 0 0"/>
71 <parent link="j1_link"/>
72 <child link="j2_link"/>
74 <link name="j2_link"/>
75 <joint name="j3" type="fixed">
76 <origin xyz="0 0 20" rpy="0 0 0"/>
77 <parent link="j2_link"/>
78 <child link="j3_link"/>
80 <link name="j3_link"/>
83 config = yaml.safe_load(
'''
90 joint_angles: [0.001, 0.001]
106 chain.update_config(params)
108 chain_state = JointState(position=[0, 0])
109 result = chain.calc_block.fk(chain_state)
110 expected = numpy.matrix( [[ 1, 0, 0,11],
113 [ 0, 0, 0, 1]], float )
115 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
121 chain.update_config(params)
123 chain_state = JointState(position=[pi/2, 0])
124 result = chain.calc_block.fk(chain_state)
125 expected = numpy.matrix( [[ 0,-1, 0,11],
128 [ 0, 0, 0, 1]], float )
130 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
136 chain.update_config(params)
138 chain_state = JointState(position=[0, 0])
139 result = chain.calc_block.fk(chain_state)
140 expected = numpy.matrix( [[ 1, 0, 0,11],
143 [ 0, 0, 0, 1]], float )
145 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
148 if __name__ ==
'__main__':
150 rostest.unitrun(
'calibration_estimation',
'test_FullChainCalcBlock', TestFullChainCalcBlock, coverage_packages=[
'calibration_estimation.full_chain',
'calibration_estimation.urdf_params'])