pr2_left_arm_fk_unittest.py
Go to the documentation of this file.
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 calibration_estimation.full_chain import FullChainRobotParams
00043 from calibration_estimation.urdf_params import UrdfParams
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         config = yaml.load(open(rospy.get_param('config_file')))
00054         self.robot_params = UrdfParams(rospy.get_param('robot_description'), config)
00055 
00056         rospy.wait_for_service('fk', 3.0)
00057         self._fk_ref = rospy.ServiceProxy('fk', FkTest)
00058 
00059     def loadCommands(self, param_name):
00060         command_str = rospy.get_param(param_name)
00061         cmds = [ [float(y) for y in x.split()] for x in command_str.strip().split('\n')]
00062         return cmds
00063 
00064     def getExpected(self, root, tip, cmd):
00065         resp = self._fk_ref(root, tip, cmd)
00066         T = matrix(zeros((4,4)), float)
00067         T[0:3, 0:3] = reshape( matrix(resp.rot, float), (3,3))
00068         T[3,3] = 1.0;
00069         T[0:3,3] = reshape( matrix(resp.pos, float), (3,1))
00070         return T
00071 
00072 class TestPR2LeftArmFk(LoadData):
00073 
00074     def run_test(self, full_chain, root, tip, cmds):
00075         for cmd in cmds:
00076             print "On Command: %s" % cmd
00077 
00078             expected_T = self.getExpected(root, tip, cmd)
00079             chain_state = JointState(position=cmd)
00080             actual_T = full_chain.calc_block.fk(chain_state)
00081 
00082             print "Expected_T:"
00083             print expected_T
00084             print "Actual T:"
00085             print actual_T
00086 
00087             self.assertAlmostEqual(numpy.linalg.norm(expected_T-actual_T), 0.0, 6)
00088 
00089 
00090     def test_left_arm_fk(self):
00091         print ""
00092         full_chain = FullChainRobotParams('left_arm_chain','l_wrist_roll_link')
00093         full_chain.update_config(self.robot_params)
00094         cmds = self.loadCommands('l_arm_commands')
00095         self.run_test(full_chain, 'torso_lift_link', 'l_wrist_roll_link', cmds)
00096 
00097 
00098     def test_left_forearm_roll_fk(self):
00099         print ""
00100         full_chain = FullChainRobotParams('left_arm_chain','l_forearm_roll_link')
00101         full_chain.update_config(self.robot_params)
00102         cmds = self.loadCommands('l_arm_commands')
00103         self.run_test(full_chain, 'torso_lift_link', 'l_forearm_roll_link', cmds)
00104 
00105 
00106     def test_left_forearm_cam_fk(self):
00107         print ""
00108         full_chain = FullChainRobotParams('left_arm_chain','l_forearm_cam_frame')
00109         full_chain.update_config(self.robot_params)
00110         cmds = self.loadCommands('l_arm_commands')
00111         self.run_test(full_chain, 'torso_lift_link', 'l_forearm_cam_frame', cmds)
00112 
00113 
00114     def test_right_forearm_cam_optical_fk(self):
00115         print ""
00116         full_chain = FullChainRobotParams('left_arm_chain','l_forearm_cam_optical_frame')
00117         full_chain.update_config(self.robot_params)
00118         cmds = self.loadCommands('l_arm_commands')
00119         self.run_test(full_chain, 'torso_lift_link', 'l_forearm_cam_optical_frame', cmds)
00120 
00121 if __name__ == '__main__':
00122     import rostest
00123     rospy.init_node("fk_test")
00124     rostest.unitrun('pr2_calibration_estimation', 'test_left_arm_FK', TestPR2LeftArmFk)


pr2_calibration_launch
Author(s): Vijay Pradeep
autogenerated on Fri Aug 28 2015 12:06:40