Module: lieGroupBasics
Lie group methods and formulas for Lie group integration.
Author: Stefan Holzinger, Johannes Gerstmayr
Date: 2020-09-11
- References:For details on Lie group methods used here, see the references . Lie group methods for rotation vector are described in Holzinger and Gerstmayr .
Function: Sinc
Sinc(x
)
- function description:compute the cardinal sine function in radians
- input:scalar float or int value
- output:float value in radians
- author:Stefan Holzinger
Function: Cot
Cot(x
)
- function description:compute the cotangent function cot(x)=1/tan(x) in radians
- input:scalar float or int value
- output:float value in radians
- author:Stefan Holzinger
Function: R3xSO3Matrix2RotationMatrix
R3xSO3Matrix2RotationMatrix(G
)
- function description:computes 3x3 rotation matrix from 7x7 R3xSO(3) matrix, see
- input:G: 7x7 matrix as np.array
- output:3x3 rotation matrix as np.array
- author:Stefan Holzinger
Function: R3xSO3Matrix2Translation
- function description:computes translation part of R3xSO(3) matrix, see
- input:G: 7x7 matrix as np.array
- output:3D vector as np.array containg translational part of R3xSO(3)
- author:Stefan Holzinger
Function: R3xSO3Matrix
R3xSO3Matrix(x
, R
)
- function description:builds 7x7 matrix as element of the Lie group R3xSO(3), see
- input:
x
: 3D vector as np.array representing the translation part corresponding to R3R
: 3x3 rotation matrix as np.array - output:7x7 matrix as np.array
- author:Stefan Holzinger
Function: ExpSO3
ExpSO3(Omega
)
- function description:compute the matrix exponential map on the Lie group SO(3), see
- input:3D rotation vector as np.array
- output:3x3 matrix as np.array
- author:Stefan Holzinger
Function: ExpS3
ExpS3(Omega
)
- function description:compute the quaternion exponential map on the Lie group S(3), see
- input:3D rotation vector as np.array
- output:4D vector as np.array containing four Euler parametersentry zero of output represent the scalar part of Euler parameters
- author:Stefan Holzinger
Function: LogSO3
LogSO3(R
)
- function description:compute the matrix logarithmic map on the Lie group SO(3)
- input:3x3 rotation matrix as np.array
- output:3x3 skew symmetric matrix as np.array
- author:Johannes Gerstmayr
- notes:improved accuracy for very small angles as well as angles phi close to pi AS WELL AS at phi=pi
Function: TExpSO3
TExpSO3(Omega
)
- function description:compute the tangent operator corresponding to ExpSO3, see
- input:3D rotation vector as np.array
- output:3x3 matrix as np.array
- author:Stefan Holzinger
Function: TExpSO3Inv
TExpSO3Inv(Omega
)
- function description:compute the inverse of the tangent operator TExpSO3, seethis function was improved, see coordinateMaps.pdf by Stefan Holzinger
- input:3D rotation vector as np.array
- output:3x3 matrix as np.array
- author:Stefan Holzinger
Function: ExpSE3
ExpSE3(x
)
- function description:compute the matrix exponential map on the Lie group SE(3), see
- input:6D incremental motion vector as np.array
- output:4x4 homogeneous transformation matrix as np.array
- author:Stefan Holzinger
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
Function: LogSE3
LogSE3(H
)
- function description:compute the matrix logarithm on the Lie group SE(3), see
- input:4x4 homogeneous transformation matrix as np.array
- output:4x4 skew symmetric matrix as np.array
- author:Stefan Holzinger
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
Function: TExpSE3
TExpSE3(x
)
- function description:compute the tangent operator corresponding to ExpSE3, see
- input:6D incremental motion vector as np.array
- output:6x6 matrix as np.array
- author:Stefan Holzinger
- notes:improved accuracy for very small angles as well as angles phi
Function: TExpSE3Inv
TExpSE3Inv(x
)
- function description:compute the inverse of tangent operator TExpSE3, see
- input:6D incremental motion vector as np.array
- output:6x6 matrix as np.array
- author:Stefan Holzinger
- notes:improved accuracy for very small angles as well as angles phi
Function: ExpR3xSO3
ExpR3xSO3(x
)
- function description:compute the matrix exponential map on the Lie group R3xSO(3), see
- input:6D incremental motion vector as np.array
- output:7x7 matrix as np.array
- author:Stefan Holzinger
Function: TExpR3xSO3
TExpR3xSO3(x
)
- function description:compute the tangent operator corresponding to ExpR3xSO3, see
- input:6D incremental motion vector as np.array
- output:6x6 matrix as np.array
- author:Stefan Holzinger
Function: TExpR3xSO3Inv
- function description:compute the inverse of tangent operator TExpR3xSO3
- input:6D incremental motion vector as np.array
- output:6x6 matrix as np.array
- author:Stefan Holzinger
Function: CompositionRuleDirectProductR3AndS3
CompositionRuleDirectProductR3AndS3(q0
, incrementalMotionVector
)
- function description:compute composition operation for pairs in the Lie group R3xS3
- input:
q0
: 7D vector as np.array containing position coordinates and Euler parametersincrementalMotionVector
: 6D incremental motion vector as np.array - output:7D vector as np.array containing composed position coordinates and composed Euler parameters
- author:Stefan Holzinger
Function: CompositionRuleSemiDirectProductR3AndS3
CompositionRuleSemiDirectProductR3AndS3(q0
, incrementalMotionVector
)
- function description:compute composition operation for pairs in the Lie group R3 semiTimes S3 (corresponds to SE(3))
- input:
q0
: 7D vector as np.array containing position coordinates and Euler parametersincrementalMotionVector
: 6D incremental motion vector as np.array - output:7D vector as np.array containing composed position coordinates and composed Euler parameters
- author:Stefan Holzinger
Function: CompositionRuleDirectProductR3AndR3RotVec
CompositionRuleDirectProductR3AndR3RotVec(q0
, incrementalMotionVector
)
- function description:compute composition operation for pairs in the group obtained from the direct product of R3 and R3, seethe rotation vector is used as rotation parametrizationsthis composition operation can be used in formulations which represent the translational velocities in the global (inertial) frame
- input:
q0
: 6D vector as np.array containing position coordinates and rotation vectorincrementalMotionVector
: 6D incremental motion vector as np.array - output:7D vector as np.array containing composed position coordinates and composed rotation vector
- author:Stefan Holzinger
Function: CompositionRuleSemiDirectProductR3AndR3RotVec
CompositionRuleSemiDirectProductR3AndR3RotVec(q0
, incrementalMotionVector
)
- function description:compute composition operation for pairs in the group obtained from the direct product of R3 and R3.the rotation vector is used as rotation parametrizationsthis composition operation can be used in formulations which represent the translational velocities in the local (body-attached) frame
- input:
q0
: 6D vector as np.array containing position coordinates and rotation vectorincrementalMotionVector
: 6D incremental motion vector as np.array - output:6D vector as np.array containing composed position coordinates and composed rotation vector
- author:Stefan Holzinger
Function: CompositionRuleDirectProductR3AndR3RotXYZAngles
CompositionRuleDirectProductR3AndR3RotXYZAngles(q0
, incrementalMotionVector
)
- function description:compute composition operation for pairs in the group obtained from the direct product of R3 and R3.Cardan-Tait/Bryan (CTB) angles are used as rotation parametrizationsthis composition operation can be used in formulations which represent the translational velocities in the global (inertial) frame
- input:
q0
: 6D vector as np.array containing position coordinates and Cardan-Tait/Bryan anglesincrementalMotionVector
: 6D incremental motion vector as np.array - output:6D vector as np.array containing composed position coordinates and composed Cardan-Tait/Bryan angles
- author:Stefan Holzinger
Function: CompositionRuleSemiDirectProductR3AndR3RotXYZAngles
CompositionRuleSemiDirectProductR3AndR3RotXYZAngles(q0
, incrementalMotionVector
)
- function description:compute composition operation for pairs in the group obtained from the direct product of R3 and R3.Cardan-Tait/Bryan (CTB) angles are used as rotation parametrizationsthis composition operation can be used in formulations which represent the translational velocities in the local (body-attached) frame
- input:
q0
: 6D vector as np.array containing position coordinates and Cardan-Tait/Bryan anglesincrementalMotionVector
: 6D incremental motion vector as np.array - output:6D vector as np.array containing composed position coordinates and composed Cardan-Tait/Bryan angles
- author:Stefan Holzinger
Function: CompositionRuleForEulerParameters
CompositionRuleForEulerParameters(q
, p
)
- function description:compute composition operation for Euler parameters (unit quaternions)this composition operation is quaternion multiplication, see
- input:
q
: 4D vector as np.array containing Euler parametersp
: 4D vector as np.array containing Euler parameters - output:4D vector as np.array containing composed (multiplied) Euler parameters
- author:Stefan Holzinger
Function: CompositionRuleForRotationVectors
CompositionRuleForRotationVectors(v0
, Omega
)
- function description:compute composition operation for rotation vectors v0 and Omega, see
- input:
v0
: 3D rotation vector as np.arrayOmega
: 3D (incremental) rotation vector as np.array - output:3D vector as np.array containing composed rotation vector v
- author:Stefan Holzinger
Function: CompositionRuleRotXYZAnglesRotationVector
CompositionRuleRotXYZAnglesRotationVector(alpha0
, Omega
)
- function description:compute composition operation for RotXYZ angles, see
- input:
alpha0
: 3D vector as np.array containing RotXYZ anglesOmega
: 3D vector as np.array containing the (incremental) rotation vector - output:3D vector as np.array containing composed RotXYZ angles
- author:Stefan Holzinger