35 import roslib; roslib.load_manifest(
'calibration_estimation')
48 from sensor_msgs.msg
import JointState, CameraInfo
63 <link name="base_link"/> 64 <joint name="j0" type="fixed"> 65 <origin xyz="0 0 0" rpy="0 0 0"/> 66 <parent link="base_link"/> 67 <child link="j0_link"/> 69 <link name="j0_link"/> 70 <joint name="j1" type="revolute"> 72 <origin xyz="1 0 0" rpy="0 0 0"/> 73 <parent link="j0_link"/> 74 <child link="j1_link"/> 76 <link name="j1_link"/> 77 <joint name="j2" type="revolute"> 79 <origin xyz="1 0 0" rpy="0 0 0"/> 80 <parent link="j1_link"/> 81 <child link="j2_link"/> 83 <link name="j2_link"/> 84 <joint name="j3" type="fixed"> 85 <origin xyz="0 0 0" rpy="0 0 0"/> 86 <parent link="j2_link"/> 87 <child link="j3_link"/> 89 <link name="j3_link"/> 92 config = yaml.load(
''' 112 chainA_cb: [0, 0, 0, 0, 0, 0] 113 chainB_cb: [0, 0, 0, 0, 0, 0] 122 return config[
"sensors"][
"chains"],
UrdfParams(urdf, config)
131 M_robot = RobotMeasurement( target_id =
"targetA",
134 M_chain = [ ChainMeasurement(chain_id=
"chainA") ])
136 blocks = bundler.build_blocks(M_robot)
138 self.assertEqual( len(blocks), 1)
140 self.assertEqual( block._M_chain.chain_id,
"chainA")
141 self.assertEqual( block._target_id,
"targetA")
148 M_robot = RobotMeasurement( target_id =
"targetA",
150 M_chain = [ ChainMeasurement(chain_id=
"chainB") ])
152 blocks = bundler.build_blocks(M_robot)
154 self.assertEqual( len(blocks), 0)
160 ChainMeasurement(chain_id=
"chainA",
161 chain_state=JointState(position=[0]) ),
163 block.update_config(robot_params)
164 cov = block.compute_cov(
None)
175 ChainMeasurement(chain_id=
"chainA",
176 chain_state=JointState(position=[0]) ),
178 block.update_config(robot_params)
180 target = matrix([[0.5, 1.5, 0.5, 1.5],
181 [0.5, 0.5, -0.5, -0.5],
185 h = block.compute_expected(target)
186 z = block.get_measurement()
187 r = block.compute_residual(target)
189 self.assertAlmostEqual(numpy.linalg.norm(target-h), 0.0, 6)
192 print "target=\n",target
194 self.assertAlmostEqual(numpy.linalg.norm(target-z), 0.0, 6)
195 self.assertAlmostEqual(numpy.linalg.norm(r - numpy.zeros([12])), 0.0, 6)
200 ChainMeasurement(chain_id=
"chainA",
201 chain_state=JointState(position=[numpy.pi / 2.0]) ),
203 block.update_config(robot_params)
205 target = matrix([[0.5, 0.5,1.5,1.5],
206 [-0.5, 0.5, -0.5, 0.5],
210 h = block.compute_expected(target)
211 z = block.get_measurement()
212 r = block.compute_residual(target)
214 self.assertAlmostEqual(numpy.linalg.norm(target-h), 0.0, 6)
217 print "target=\n",target
219 self.assertAlmostEqual(numpy.linalg.norm(target-z), 0.0, 6)
220 self.assertAlmostEqual(numpy.linalg.norm(r - numpy.zeros([12])), 0.0, 6)
225 ChainMeasurement(chain_id=
"chainB",
226 chain_state=JointState(position=[0.0, 0.0]) ),
228 block.update_config(robot_params)
230 target = matrix([[1.5, 2.5, 1.5, 2.5],
231 [0.5, 0.5, -0.5, -0.5],
235 h = block.compute_expected(target)
236 z = block.get_measurement()
237 r = block.compute_residual(target)
239 self.assertAlmostEqual(numpy.linalg.norm(target-h), 0.0, 6)
242 print "target=\n",target
244 self.assertAlmostEqual(numpy.linalg.norm(target-z), 0.0, 6)
245 self.assertAlmostEqual(numpy.linalg.norm(r - numpy.zeros([12])), 0.0, 6)
250 ChainMeasurement(chain_id=
"chainA",
251 chain_state=JointState(position=[numpy.pi / 2.0]) ),
253 block.update_config(robot_params)
254 sparsity = block.build_sparsity_dict()
255 self.assertEqual(sparsity[
'transforms'][
'j0'], [1,1,1,1,1,1])
256 self.assertEqual(sparsity[
'transforms'][
'j1'], [1,1,1,1,1,1])
257 self.assertEqual(sparsity[
'chains'][
'chainA'], {
'gearing':[1]})
259 if __name__ ==
'__main__':
261 rostest.unitrun(
'calibration_estimation',
'test_ChainBundler', TestChainBundler)
262 rostest.unitrun(
'calibration_estimation',
'test_ChainSensor', TestChainSensor)
def test_basic_match(self)
def test_basic_no_match(self)