$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 00033 # author: Vijay Pradeep 00034 00035 import roslib; roslib.load_manifest('pr2_calibration_estimation') 00036 00037 import sys 00038 import rospy 00039 import numpy 00040 00041 from pr2_calibration_estimation.dh_chain import DhChain 00042 from pr2_calibration_estimation.tilting_laser import TiltingLaser 00043 from pr2_calibration_estimation.single_transform import SingleTransform 00044 from pr2_calibration_estimation.camera import RectifiedCamera 00045 from pr2_calibration_estimation.checkerboard import Checkerboard 00046 00047 # Construct a dictionary of all the primitives of the specified type 00048 def init_primitive_dict(start_index, config_dict, PrimitiveType): 00049 cur_index = start_index 00050 00051 # Init the dictionary to store the constructed primitives 00052 primitive_dict = dict() 00053 00054 # Process each primitive in the list of configs 00055 for key, elem in config_dict.items(): 00056 #import code; code.interact(local=locals()) 00057 primitive_dict[key] = PrimitiveType(elem) 00058 # Store lookup indices 00059 primitive_dict[key].start = cur_index 00060 primitive_dict[key].end = cur_index + primitive_dict[key].get_length() 00061 cur_index = primitive_dict[key].end 00062 00063 # Return the primitives, as well as the end index 00064 return primitive_dict, cur_index 00065 00066 # Given a dictionary of initialized primitives, inflate 00067 # their configuration, given a parameter vector 00068 def inflate_primitive_dict(param_vec, primitive_dict): 00069 for key, elem in primitive_dict.items(): 00070 elem.inflate(param_vec[elem.start:elem.end,0]) 00071 00072 # Given a dictionary of initialized primitives, deflate 00073 # their configuration, into the specified parameter vector 00074 def deflate_primitive_dict(param_vec, primitive_dict): 00075 for key, elem in primitive_dict.items(): 00076 param_vec[elem.start:elem.end,0] = elem.deflate() 00077 00078 # Iterate over config dictionary and determine which parameters should be free, 00079 # based on the the flags in the free dictionary. Once computed, update the part 00080 # of the target vector that corresponds to this primitive 00081 def update_primitive_free(target_list, config_dict, free_dict): 00082 for key, elem in config_dict.items(): 00083 if key in free_dict.keys(): 00084 free = elem.calc_free(free_dict[key]) 00085 target_list[elem.start:elem.end] = free 00086 00087 # Given a parameter vector, Compute the configuration of all the primitives of a given type 00088 def primitive_params_to_config(param_vec, primitive_dict): 00089 config_dict = dict() 00090 for key, elem in primitive_dict.items(): 00091 config_dict[key] = elem.params_to_config(param_vec[elem.start:elem.end,0]) 00092 return config_dict 00093 00094 # Stores the current configuration of all the primitives in the system 00095 class RobotParams: 00096 def __init__(self): 00097 pass 00098 00099 def configure(self, config_dict): 00100 00101 # Where the next primitive should stored 00102 cur_index = 0 00103 00104 self.dh_chains, cur_index = init_primitive_dict(cur_index, config_dict["dh_chains"], DhChain) 00105 self.tilting_lasers, cur_index = init_primitive_dict(cur_index, config_dict["tilting_lasers"], TiltingLaser) 00106 self.transforms, cur_index = init_primitive_dict(cur_index, config_dict["transforms"], SingleTransform) 00107 self.rectified_cams, cur_index = init_primitive_dict(cur_index, config_dict["rectified_cams"], RectifiedCamera) 00108 self.checkerboards, cur_index = init_primitive_dict(cur_index, config_dict["checkerboards"], Checkerboard) 00109 00110 self.length = cur_index 00111 00112 def calc_free(self, free_dict): 00113 # Initilize free list 00114 free_list = [0] * self.length 00115 #import code; code.interact(local=locals()) 00116 update_primitive_free(free_list, self.dh_chains, free_dict["dh_chains"]) 00117 update_primitive_free(free_list, self.tilting_lasers, free_dict["tilting_lasers"]) 00118 update_primitive_free(free_list, self.transforms, free_dict["transforms"]) 00119 update_primitive_free(free_list, self.rectified_cams, free_dict["rectified_cams"]) 00120 update_primitive_free(free_list, self.checkerboards, free_dict["checkerboards"]) 00121 return free_list 00122 00123 def params_to_config(self, param_vec): 00124 assert(self.length == param_vec.size) 00125 config_dict = dict() 00126 config_dict["dh_chains"] = primitive_params_to_config(param_vec, self.dh_chains) 00127 config_dict["tilting_lasers"] = primitive_params_to_config(param_vec, self.tilting_lasers) 00128 config_dict["transforms"] = primitive_params_to_config(param_vec, self.transforms) 00129 config_dict["rectified_cams"] = primitive_params_to_config(param_vec, self.rectified_cams) 00130 config_dict["checkerboards"] = primitive_params_to_config(param_vec, self.checkerboards) 00131 return config_dict 00132 00133 def inflate(self, param_vec): 00134 assert(self.length == param_vec.size) 00135 00136 inflate_primitive_dict(param_vec, self.dh_chains) 00137 inflate_primitive_dict(param_vec, self.tilting_lasers) 00138 inflate_primitive_dict(param_vec, self.transforms) 00139 inflate_primitive_dict(param_vec, self.rectified_cams) 00140 inflate_primitive_dict(param_vec, self.checkerboards) 00141 00142 def deflate(self): 00143 param_vec = numpy.matrix( numpy.zeros((self.length,1), float)) 00144 deflate_primitive_dict(param_vec, self.dh_chains) 00145 deflate_primitive_dict(param_vec, self.tilting_lasers) 00146 deflate_primitive_dict(param_vec, self.transforms) 00147 deflate_primitive_dict(param_vec, self.rectified_cams) 00148 deflate_primitive_dict(param_vec, self.checkerboards) 00149 return param_vec