$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of Willow Garage, Inc. nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 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 #config_filename = "config/system.yaml" 00057 #f = open(config_filename) 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 #f.close() 00068 00069 def loadCommands(self, param_name): 00070 #f = open(filename) 00071 #cmds = [ [ float(y) for y in x.split()] for x in f.readlines()] 00072 #f.close() 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 #print resp 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 TestPR2Fk(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_right_arm_fk(self): 00109 print "" 00110 00111 config_str = ''' 00112 before_chain: [r_shoulder_pan_joint] 00113 chain_id: right_arm_chain 00114 after_chain: [right_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('r_arm_commands') 00122 00123 self.run_test(full_chain, 'torso_lift_link', 'r_wrist_roll_link', cmds) 00124 00125 def test_head_tilt_link(self): 00126 print "" 00127 00128 config_str = ''' 00129 before_chain: [head_pan_joint] 00130 chain_id: head_chain 00131 after_chain: [head_chain_tip_adj] 00132 dh_link_num: 1 00133 ''' 00134 00135 full_chain = FullChainRobotParams(yaml.load(config_str)) 00136 full_chain.update_config(self.robot_params) 00137 00138 cmds = self.loadCommands('head_commands') 00139 00140 self.run_test(full_chain, 'torso_lift_link', 'head_tilt_link', cmds) 00141 00142 def test_head_plate(self): 00143 print "" 00144 config_str = ''' 00145 before_chain: [head_pan_joint] 00146 chain_id: head_chain 00147 after_chain: [head_chain_tip_adj, head_plate_frame_joint] 00148 dh_link_num: 1''' 00149 full_chain = FullChainRobotParams(yaml.load(config_str)) 00150 full_chain.update_config(self.robot_params) 00151 cmds = self.loadCommands('head_commands') 00152 self.run_test(full_chain, 'torso_lift_link', 'head_plate_frame', cmds) 00153 00154 def test_double_stereo(self): 00155 print "" 00156 config_str = ''' 00157 before_chain: [head_pan_joint] 00158 chain_id: head_chain 00159 after_chain: [head_chain_tip_adj, head_plate_frame_joint, double_stereo_frame_joint] 00160 dh_link_num: 1 ''' 00161 full_chain = FullChainRobotParams(yaml.load(config_str)) 00162 full_chain.update_config(self.robot_params) 00163 cmds = self.loadCommands('head_commands') 00164 self.run_test(full_chain, 'torso_lift_link', 'double_stereo_link', cmds) 00165 00166 def test_wide_stereo(self): 00167 print "" 00168 config_str = ''' 00169 before_chain: [head_pan_joint] 00170 chain_id: head_chain 00171 after_chain: [head_chain_tip_adj, head_plate_frame_joint, double_stereo_frame_joint, wide_stereo_frame_joint] 00172 dh_link_num: 1 ''' 00173 full_chain = FullChainRobotParams(yaml.load(config_str)) 00174 full_chain.update_config(self.robot_params) 00175 cmds = self.loadCommands('head_commands') 00176 self.run_test(full_chain, 'torso_lift_link', 'wide_stereo_link', cmds) 00177 00178 def test_wide_stereo_optical(self): 00179 print "" 00180 config_str = ''' 00181 before_chain: [head_pan_joint] 00182 chain_id: head_chain 00183 after_chain: [head_chain_tip_adj, head_plate_frame_joint, double_stereo_frame_joint, wide_stereo_frame_joint, wide_stereo_optical_frame_joint] 00184 dh_link_num: 1 ''' 00185 full_chain = FullChainRobotParams(yaml.load(config_str)) 00186 full_chain.update_config(self.robot_params) 00187 cmds = self.loadCommands('head_commands') 00188 self.run_test(full_chain, 'torso_lift_link', 'wide_stereo_optical_frame', cmds) 00189 00190 def test_narrow_stereo(self): 00191 print "" 00192 config_str = ''' 00193 before_chain: [head_pan_joint] 00194 chain_id: head_chain 00195 after_chain: [head_chain_tip_adj, head_plate_frame_joint, double_stereo_frame_joint, narrow_stereo_frame_joint] 00196 dh_link_num: 1 ''' 00197 full_chain = FullChainRobotParams(yaml.load(config_str)) 00198 full_chain.update_config(self.robot_params) 00199 cmds = self.loadCommands('head_commands') 00200 self.run_test(full_chain, 'torso_lift_link', 'narrow_stereo_link', cmds) 00201 00202 def test_narrow_stereo_optical(self): 00203 print "" 00204 config_str = ''' 00205 before_chain: [head_pan_joint] 00206 chain_id: head_chain 00207 after_chain: [head_chain_tip_adj, head_plate_frame_joint, double_stereo_frame_joint, narrow_stereo_frame_joint, narrow_stereo_optical_frame_joint] 00208 dh_link_num: 1 ''' 00209 full_chain = FullChainRobotParams(yaml.load(config_str)) 00210 full_chain.update_config(self.robot_params) 00211 cmds = self.loadCommands('head_commands') 00212 self.run_test(full_chain, 'torso_lift_link', 'narrow_stereo_optical_frame', cmds) 00213 00214 def check_tilt_laser(self, cmd): 00215 actual_T = self.robot_params.tilting_lasers["tilt_laser"].compute_pose([cmd]) 00216 expected_T = self.getExpected("torso_lift_link", "laser_tilt_link", [cmd]) 00217 00218 print "Expected_T:" 00219 print expected_T 00220 print "Actual T:" 00221 print actual_T 00222 00223 self.assertAlmostEqual(numpy.linalg.norm(expected_T-actual_T), 0.0, 6) 00224 00225 def test_tilt_laser(self): 00226 print "" 00227 self.check_tilt_laser(0) 00228 self.check_tilt_laser(1) 00229 00230 if __name__ == '__main__': 00231 import rostest 00232 rospy.init_node("fk_test") 00233 rostest.unitrun('pr2_calibration_estimation', 'test_PR2Fk', TestPR2Fk)