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
00034
00035 import roslib; roslib.load_manifest('pr2_calibration_estimation')
00036
00037 import sys
00038 import unittest
00039 import rospy
00040 import numpy
00041 from sensor_msgs.msg import JointState
00042 from pr2_calibration_estimation.full_chain import FullChainCalcBlock
00043 from pr2_calibration_estimation.single_transform import SingleTransform
00044 from pr2_calibration_estimation.dh_chain import DhChain
00045
00046 from numpy import *
00047 import numpy
00048
00049 def loadSystem1():
00050 calc_block = FullChainCalcBlock()
00051 before_chain_Ts = [SingleTransform([10, 0, 0, 0, 0, 0])]
00052 chain = DhChain( {'dh':[ [0, 0, 1, 0] ],
00053 'gearing':[1],
00054 'cov':{'joint_angles':[1]}} )
00055 dh_link_num = -1
00056 after_chain_Ts = [SingleTransform([ 0, 0, 20, 0, 0, 0])]
00057
00058 calc_block.update_config(before_chain_Ts, chain, dh_link_num, after_chain_Ts)
00059 return calc_block
00060
00061
00062 class TestFullChainCalcBlock(unittest.TestCase):
00063 def test_fk_1(self):
00064 print ""
00065 calc_block = loadSystem1()
00066 chain_state = JointState(position=[0])
00067 result = calc_block.fk(chain_state)
00068 expected = numpy.matrix( [[ 1, 0, 0,11],
00069 [ 0, 1, 0, 0],
00070 [ 0, 0, 1,20],
00071 [ 0, 0, 0, 1]], float )
00072 print result
00073 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
00074
00075 def test_fk_2(self):
00076 print ""
00077 calc_block = loadSystem1()
00078 chain_state = JointState(position=[pi/2])
00079 result = calc_block.fk(chain_state)
00080 expected = numpy.matrix( [[ 0,-1, 0,10],
00081 [ 1, 0, 0, 1],
00082 [ 0, 0, 1,20],
00083 [ 0, 0, 0, 1]], float )
00084 print result
00085 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
00086
00087 if __name__ == '__main__':
00088 import rostest
00089 rostest.unitrun('pr2_calibration_estimation', 'test_FullChainCalcBlock', TestFullChainCalcBlock, coverage_packages=['pr2_calibration_estimation.full_chain'])