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 time
00041
00042 from pr2_calibration_estimation.full_chain import FullChainRobotParams
00043 from pr2_calibration_estimation.robot_params import RobotParams
00044 from sensor_msgs.msg import JointState
00045
00046 import yaml
00047 from pr2_calibration_estimation.srv import FkTest
00048 from numpy import *
00049 import numpy
00050
00051 class LoadData(unittest.TestCase):
00052 def setUp(self):
00053
00054
00055
00056
00057
00058 f = rospy.get_param("system")
00059 all_config = yaml.load(f)
00060
00061 self.robot_params = RobotParams()
00062 self.robot_params.configure(all_config)
00063
00064
00065 rospy.wait_for_service('fk', 3.0)
00066 self._fk_ref = rospy.ServiceProxy('fk', FkTest)
00067
00068
00069 def loadCommands(self, param_name):
00070
00071
00072
00073
00074 command_str = rospy.get_param(param_name)
00075
00076
00077 cmds = [ [float(y) for y in x.split()] for x in command_str.strip().split('\n')]
00078
00079 return cmds
00080
00081 def getExpected(self, root, tip, cmd):
00082 resp = self._fk_ref(root, tip, cmd)
00083
00084 T = matrix(zeros((4,4)), float)
00085 T[0:3, 0:3] = reshape( matrix(resp.rot, float), (3,3))
00086 T[3,3] = 1.0;
00087 T[0:3,3] = reshape( matrix(resp.pos, float), (3,1))
00088 return T
00089
00090 class TestPR2LeftArmFk(LoadData):
00091
00092 def run_test(self, full_chain, root, tip, cmds):
00093 for cmd in cmds:
00094 print "On Command: %s" % cmd
00095
00096 expected_T = self.getExpected(root, tip, cmd)
00097 chain_state = JointState(position=cmd)
00098 actual_T = full_chain.calc_block.fk(chain_state)
00099
00100 print "Expected_T:"
00101 print expected_T
00102 print "Actual T:"
00103 print actual_T
00104
00105 self.assertAlmostEqual(numpy.linalg.norm(expected_T-actual_T), 0.0, 6)
00106
00107
00108 def test_left_arm_fk(self):
00109 print ""
00110
00111 config_str = '''
00112 before_chain: [l_shoulder_pan_joint]
00113 chain_id: left_arm_chain
00114 after_chain: [left_arm_tip_adj]
00115 dh_link_num: 6
00116 '''
00117
00118 full_chain = FullChainRobotParams(yaml.load(config_str))
00119 full_chain.update_config(self.robot_params)
00120
00121 cmds = self.loadCommands('l_arm_commands')
00122
00123 self.run_test(full_chain, 'torso_lift_link', 'l_wrist_roll_link', cmds)
00124
00125 def test_left_forearm_roll_fk(self):
00126 print ""
00127
00128 config_str = '''
00129 before_chain: [l_shoulder_pan_joint]
00130 chain_id: left_arm_chain
00131 after_chain: [l_forearm_roll_adj]
00132 dh_link_num: 4
00133 '''
00134
00135 full_chain = FullChainRobotParams(yaml.load(config_str))
00136 full_chain.update_config(self.robot_params)
00137
00138 cmds = self.loadCommands('l_arm_commands')
00139
00140 self.run_test(full_chain, 'torso_lift_link', 'l_forearm_roll_link', cmds)
00141
00142 def test_left_forearm_cam_fk(self):
00143 print ""
00144
00145 config_str = '''
00146 before_chain: [l_shoulder_pan_joint]
00147 chain_id: left_arm_chain
00148 after_chain: [l_forearm_roll_adj, l_forearm_cam_frame_joint]
00149 dh_link_num: 4
00150 '''
00151
00152 full_chain = FullChainRobotParams(yaml.load(config_str))
00153 full_chain.update_config(self.robot_params)
00154
00155 cmds = self.loadCommands('l_arm_commands')
00156
00157 self.run_test(full_chain, 'torso_lift_link', 'l_forearm_cam_frame', cmds)
00158
00159 def test_right_forearm_cam_optical_fk(self):
00160 print ""
00161
00162 config_str = '''
00163 before_chain: [l_shoulder_pan_joint]
00164 chain_id: left_arm_chain
00165 after_chain: [l_forearm_roll_adj, l_forearm_cam_frame_joint, l_forearm_cam_optical_frame_joint]
00166 dh_link_num: 4
00167 '''
00168
00169 full_chain = FullChainRobotParams(yaml.load(config_str))
00170 full_chain.update_config(self.robot_params)
00171
00172 cmds = self.loadCommands('l_arm_commands')
00173
00174 self.run_test(full_chain, 'torso_lift_link', 'l_forearm_cam_optical_frame', cmds)
00175
00176 if __name__ == '__main__':
00177 import rostest
00178 rospy.init_node("fk_test")
00179 rostest.unitrun('pr2_calibration_estimation', 'test_left_arm_FK', TestPR2LeftArmFk)