single_transform.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 import numpy
34 from numpy import matrix, vsplit, sin, cos, reshape, zeros, pi
35 import rospy
36 
37 import PyKDL
38 import yaml, math
39 
40 # This represents the transform for a single joint in the URDF
41 # parameters are x,y,z and rotation as angle-axis
42 
43 param_names = ['x','y','z','a','b','c']
44 
46  def __init__(self, config = [0, 0, 0, 0, 0, 0], name=""):
47  self._name = name
48  eval_config = [eval(str(x)) for x in config]
49  self._config = reshape(matrix(eval_config, float), (-1,1))
50 
51  rospy.logdebug("Initializing single transform %s with params [%s]", name, ", ".join(["% 2.4f" % x for x in eval_config]))
52  self.inflate(self._config)
53 
54  def calc_free(self, free_config):
55  return [x == 1 for x in free_config]
56 
57  def params_to_config(self, param_vec):
58  return param_vec.T.tolist()[0]
59 
60  # Convert column vector of params into config
61  def inflate(self, p):
62  self._config = p.copy() # Once we can back compute p from T, we don't need _config
63 
64  # Init output matrix
65  T = matrix( zeros((4,4,), float))
66  T[3,3] = 1.0
67 
68  # Copy position into matrix
69  T[0:3,3] = p[0:3,0]
70 
71  # Renormalize the rotation axis to be unit length
72  U,S,Vt = numpy.linalg.svd(p[3:6,0])
73  a = U[:,0]
74  rot_angle = S[0]*Vt[0,0]
75 
76  # Build rotation matrix
77  c = cos(rot_angle)
78  s = sin(rot_angle)
79  R = matrix( [ [ a[0,0]**2+(1-a[0,0]**2)*c, a[0,0]*a[1,0]*(1-c)-a[2,0]*s, a[0,0]*a[2,0]*(1-c)+a[1,0]*s],
80  [a[0,0]*a[1,0]*(1-c)+a[2,0]*s, a[1,0]**2+(1-a[1,0]**2)*c, a[1,0]*a[2,0]*(1-c)-a[0,0]*s],
81  [a[0,0]*a[2,0]*(1-c)-a[1,0]*s, a[1,0]*a[2,0]*(1-c)+a[0,0]*s, a[2,0]**2+(1-a[2,0]**2)*c] ] )
82 
83  T[0:3,0:3] = R
84  self.transform = T
85 
86  # Take transform, and convert into 6 param vector
87  def deflate(self):
88  # todo: This currently a hacky stub. To be correct, this should infer the parameter vector from the 4x4 transform
89  return self._config
90 
91  # Returns # of params needed for inflation & deflation
92  def get_length(self):
93  return len(param_names)
94 
95 
96 # Convert from rotation-axis-with-angle-as-magnitude representation to Euler RPY
98  angle = math.sqrt(sum([vec[i]**2 for i in range(3)]))
99  hsa = math.sin(angle/2.)
100  if epsEq(angle, 0):
101  return (0.,0.,0.)
102  quat = [vec[0]/angle*hsa, vec[1]/angle*hsa, vec[2]/angle*hsa, math.cos(angle/2.)]
103  rpy = quat_to_rpy(quat)
104  return rpy
105 
106 # Convert from Euler RPY to rotation-axis-with-angle-as-magnitude
108  if epsEq(vec[0], 0) and epsEq(vec[1], 0) and epsEq(vec[2], 0):
109  return [0.0, 0.0, 0.0]
110  quat = rpy_to_quat(vec)
111  angle = math.acos(quat[3])*2.0
112  hsa = math.sin(angle/2.)
113  axis = [quat[0]/hsa*angle, quat[1]/hsa*angle, quat[2]/hsa*angle]
114  return axis
115 
116 def rpy_to_quat(rpy):
117  return PyKDL.Rotation.RPY(rpy[0], rpy[1], rpy[2]).GetQuaternion()
118 
119 def quat_to_rpy(q):
120  return PyKDL.Rotation.Quaternion(q[0], q[1], q[2], q[3]).GetRPY()
121 
122 #return 1 if value1 and value2 are within eps of each other, 0 otherwise
123 def epsEq(value1, value2, eps = 1e-10):
124  if math.fabs(value1-value2) <= eps:
125  return 1
126  return 0
127 
def epsEq(value1, value2, eps=1e-10)


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Thu Jun 6 2019 19:17:16