$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 numpy 00041 import yaml 00042 from pr2_calibration_estimation.sensors.tilting_laser_sensor import TiltingLaserBundler, TiltingLaserSensor 00043 from calibration_msgs.msg import * 00044 from sensor_msgs.msg import JointState, CameraInfo 00045 from pr2_calibration_estimation.robot_params import RobotParams 00046 00047 from pr2_calibration_estimation.single_transform import SingleTransform 00048 from pr2_calibration_estimation.dh_chain import DhChain 00049 from pr2_calibration_estimation.camera import RectifiedCamera 00050 from pr2_calibration_estimation.tilting_laser import TiltingLaser 00051 from pr2_calibration_estimation.full_chain import FullChainCalcBlock 00052 00053 import numpy 00054 from numpy import * 00055 00056 def loadConfigList(): 00057 00058 config_yaml = ''' 00059 - laser_id: laser1 00060 ''' 00061 config_dict = yaml.load(config_yaml) 00062 return config_dict 00063 00064 class TestTiltingLaserBundler(unittest.TestCase): 00065 def test_basic(self): 00066 config_list = loadConfigList() 00067 00068 bundler = TiltingLaserBundler(config_list) 00069 00070 M_robot = RobotMeasurement() 00071 M_robot.M_laser.append( LaserMeasurement(laser_id="laser1")) 00072 00073 blocks = bundler.build_blocks(M_robot) 00074 00075 self.assertEqual( len(blocks), 1) 00076 self.assertEqual( blocks[0]._M_laser.laser_id, "laser1") 00077 00078 def loadSystem(): 00079 00080 config = yaml.load(''' 00081 laser_id: laserA 00082 ''') 00083 00084 robot_params = RobotParams() 00085 robot_params.configure( yaml.load(''' 00086 dh_chains: {} 00087 tilting_lasers: 00088 laserA: 00089 before_joint: [0, 0, 0, 0, 0, 0] 00090 after_joint: [0, 0, 0, 0, 0, 0] 00091 gearing: 1 00092 cov: 00093 bearing: 1 00094 range: 1 00095 tilt: 1 00096 rectified_cams: {} 00097 transforms: {} 00098 checkerboards: {} 00099 ''' ) ) 00100 00101 return config, robot_params 00102 00103 00104 class TestTiltingLaser(unittest.TestCase): 00105 00106 def test_cov(self): 00107 print "" 00108 config, robot_params = loadSystem() 00109 00110 joint_points = [ JointState(position=[0,0,1]), 00111 JointState(position=[pi/2,0,2]) ] 00112 00113 sensor = TiltingLaserSensor(config, LaserMeasurement(laser_id="laserA", 00114 joint_points=joint_points)) 00115 00116 sensor.update_config(robot_params) 00117 00118 cov = sensor.compute_cov(None) 00119 00120 print "Cov:" 00121 print cov 00122 00123 #numpy.savetxt('cov.txt', cov, "% 6.4f") 00124 00125 self.assertAlmostEqual(cov[0,0], 1.0, 6) 00126 self.assertAlmostEqual(cov[1,1], 1.0, 6) 00127 self.assertAlmostEqual(cov[2,2], 1.0, 6) 00128 self.assertAlmostEqual(cov[3,3], 4.0, 6) 00129 self.assertAlmostEqual(cov[4,4], 4.0, 6) 00130 self.assertAlmostEqual(cov[5,5], 1.0, 6) 00131 00132 def test_gamma(self): 00133 print "" 00134 config, robot_params = loadSystem() 00135 00136 joint_points = [ JointState(position=[0,0,1]), 00137 JointState(position=[pi/2,0,2]) ] 00138 00139 sensor = TiltingLaserSensor(config, LaserMeasurement(laser_id="laserA", 00140 joint_points=joint_points)) 00141 00142 sensor.update_config(robot_params) 00143 gamma = sensor.compute_marginal_gamma_sqrt(None) 00144 00145 print "Gamma:" 00146 print gamma 00147 #numpy.savetxt('gamma.txt', gamma, "% 6.4f") 00148 self.assertAlmostEqual(gamma[0,0], 1.0, 6) 00149 self.assertAlmostEqual(gamma[1,1], 1.0, 6) 00150 self.assertAlmostEqual(gamma[2,2], 1.0, 6) 00151 self.assertAlmostEqual(gamma[3,3], 0.5, 6) 00152 self.assertAlmostEqual(gamma[4,4], 0.5, 6) 00153 self.assertAlmostEqual(gamma[5,5], 1.0, 6) 00154 00155 def test_tilting_laser_1(self): 00156 print "" 00157 config, robot_params = loadSystem() 00158 00159 joint_points = [ JointState(position=[0,0,0]), 00160 JointState(position=[0,pi/2,1]), 00161 JointState(position=[pi/2,0,1]) ] 00162 00163 block = TiltingLaserSensor(config, LaserMeasurement(laser_id="laserA", 00164 joint_points=joint_points)) 00165 00166 block.update_config(robot_params) 00167 00168 target_pts = matrix( [ [ 0, 0, 0 ], 00169 [ 0, 1, 0 ], 00170 [ 0, 0, -1 ], 00171 [ 1, 1, 1 ] ] ) 00172 00173 h = block.compute_expected(target_pts) 00174 z = block.get_measurement() 00175 r = block.compute_residual(target_pts) 00176 00177 self.assertAlmostEqual(numpy.linalg.norm(h-target_pts), 0.0, 6) 00178 self.assertAlmostEqual(numpy.linalg.norm(z-target_pts), 0.0, 6) 00179 self.assertAlmostEqual(numpy.linalg.norm(r), 0.0, 6) 00180 00181 00182 # Test Sparsity 00183 sparsity = block.build_sparsity_dict() 00184 self.assertEqual(sparsity['tilting_lasers']['laserA']['before_joint'], [1,1,1,1,1,1]) 00185 self.assertEqual(sparsity['tilting_lasers']['laserA']['after_joint'], [1,1,1,1,1,1]) 00186 00187 00188 if __name__ == '__main__': 00189 import rostest 00190 rostest.unitrun('pr2_calibration_estimation', 'test_TiltingLaserBundler', TestTiltingLaserBundler, coverage_packages=['pr2_calibration_estimation.sensors.tilting_laser_sensor']) 00191 rostest.unitrun('pr2_calibration_estimation', 'test_TiltingLaser', TestTiltingLaser, coverage_packages=['pr2_calibration_estimation.sensors.tilting_laser_sensor'])