full_chain.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2008-2011, 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 from sensor_msgs.msg import JointState
00034 from numpy import matrix
00035 import numpy
00036 
00037 class FullChainRobotParams:
00038     '''
00039     Wraps a full set of transforms, including a joint_chain
00040 
00041       root
00042           \    
00043            fixed links before -- chain -- fixed links after
00044     '''
00045     def __init__(self, chain_id, tip, root=None):
00046         self.chain_id = chain_id
00047         self.root = root
00048         self.tip = tip
00049         self.calc_block = FullChainCalcBlock()
00050 
00051     def update_config(self, robot_params):
00052         if self.root == None: 
00053             self.root = robot_params.base_link
00054         try:
00055             chain = robot_params.chains[self.chain_id]
00056             before_chain = robot_params.urdf.get_chain(self.root, chain.root, links=False)
00057             full_chain = robot_params.urdf.get_chain(chain.root, chain.tip)
00058             try:
00059                 after_chain = robot_params.urdf.get_chain(chain.tip, self.tip, links=False)
00060                 link_num = -1
00061             except:
00062                 # using only part of the chain, have to calculate link_num
00063                 tip_chain = robot_params.urdf.get_chain(chain.root,self.tip)
00064                 new_root = full_chain[0]
00065                 i = 1
00066                 link_num = -1
00067                 while i < len(full_chain):
00068                     if full_chain[i] in tip_chain:
00069                         if full_chain[i] in chain._active:
00070                             link_num += 1
00071                             new_root = full_chain[i+1]
00072                     i += 1
00073                 after_chain = robot_params.urdf.get_chain(new_root, self.tip, links=False)
00074         except KeyError:
00075             chain = None
00076             before_chain = robot_params.urdf.get_chain(self.root, self.tip, links=False)
00077             after_chain = []
00078             link_num = None
00079         before_chain_Ts = [robot_params.transforms[transform_name] for transform_name in before_chain]
00080         after_chain_Ts  = [robot_params.transforms[transform_name] for transform_name in after_chain]
00081         self.calc_block.update_config(before_chain_Ts, chain, link_num, after_chain_Ts)
00082 
00083     def build_sparsity_dict(self):
00084         """
00085         Build a dictionary that defines which parameters will in fact affect a measurement for a sensor using this chain.
00086         """
00087         sparsity = dict()
00088         sparsity['transforms'] = {}
00089         sparsity['chains'] = {}
00090         if self.chain_id is not None:
00091             for cur_transform in ( self.calc_block._before_chain_Ts + \
00092                                    self.calc_block._chain._transforms.values() + \
00093                                    self.calc_block._after_chain_Ts ):
00094                 sparsity['transforms'][cur_transform._name] = [1, 1, 1, 1, 1, 1]
00095             sparsity['chains'][self.chain_id] = {}
00096             link_num = self.calc_block._link_num
00097             if link_num < 0:
00098                 link_num = self.calc_block._chain._M
00099             sparsity['chains'][self.chain_id]['gearing'] = [1 for i in range(link_num)]
00100         else:
00101             for cur_transform in ( self.calc_block._before_chain_Ts + \
00102                                    self.calc_block._after_chain_Ts ):
00103                 sparsity['transforms'][cur_transform._name] = [1, 1, 1, 1, 1, 1]
00104         return sparsity
00105 
00106 class FullChainCalcBlock:
00107     def update_config(self, before_chain_Ts, chain, link_num, after_chain_Ts):
00108         self._before_chain_Ts = before_chain_Ts
00109         self._chain = chain
00110         self._link_num = link_num
00111         self._after_chain_Ts = after_chain_Ts
00112 
00113     def fk(self, chain_state):
00114         pose = matrix(numpy.eye(4))
00115 
00116         # Apply the 'before chain' transforms
00117         for before_chain_T in self._before_chain_Ts:
00118             pose = pose * before_chain_T.transform
00119 
00120         # Apply the Chain
00121         if self._chain is not None:
00122             chain_T = self._chain.fk(chain_state, self._link_num)
00123             pose = pose * chain_T
00124 
00125         # Apply the 'after chain' transforms
00126         for after_chain_T in self._after_chain_Ts:
00127             pose = pose * after_chain_T.transform
00128 
00129         return pose
00130 


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Wed Aug 26 2015 10:56:21