Public Member Functions | Public Attributes | List of all members
dual_quaternions.dual_quaternions.DualQuaternion Class Reference
Inheritance diagram for dual_quaternions.dual_quaternions.DualQuaternion:
Inheritance graph
[legend]

Public Member Functions

def __add__ (self, other)
 
def __div__ (self, other)
 
def __eq__ (self, other)
 
def __imul__ (self, other)
 
def __init__ (self, q_r, q_d, normalize=False)
 
def __mul__ (self, other)
 
def __ne__ (self, other)
 
def __repr__ (self)
 
def __rmul__ (self, other)
 
def __str__ (self)
 
def __truediv__ (self, other)
 
def as_dict (self)
 
def combined_conjugate (self)
 
def dq_array (self)
 
def dual_number_conjugate (self)
 
def from_dq_array (cls, r_wxyz_t_wxyz)
 
def from_file (cls, path)
 
def from_homogeneous_matrix (cls, arr)
 
def from_quat_pose_array (cls, r_wxyz_t_xyz)
 
def from_screw (cls, l, m, theta, d)
 
def from_translation_vector (cls, t_xyz)
 
def homogeneous_matrix (self)
 
def identity (cls)
 
def inverse (self)
 
def is_normalized (self)
 
def nlerp (self, other, t)
 
def normalize (self)
 
def normalized (self)
 
def pow (self, exponent)
 
def quat_pose_array (self)
 
def quaternion_conjugate (self)
 
def save (self, path)
 
def sclerp (cls, start, stop, t)
 
def screw (self)
 
def transform_point (self, point_xyz)
 
def translation (self)
 

Public Attributes

 q_d
 
 q_r
 

Detailed Description

dual number representation of quaternions to represent rigid transforms

A quaternion q can be represented as q_r + q_d * eps with eps^2 = 0 and eps != 0

Several ways to instantiate:
$ dq = DualQuaternion(q_rot, q_dual) with both arguments instance of numpy-quaternion
$ dq = DualQuaternion.from_dq_array(np.array([q_rw, q_rx, q_ry, q_rz, q_tx, q_ty, q_tz])
$ dq = DualQuaternion.from_homogeneous_matrix([[r11, r12, r13, tx],
                                               [r21, r22, r23, ty],
                                               [r31, r32, r33, tz],
                                               [  0,   0,   0,  1])
$ dq = DualQuaternion.from_quat_pose_array([q_w, q_x, q_y, q_z, x, y, z])
$ dq = DualQuaternion.from_translation_vector([x y z])
$ dq = DualQuaternion.identity() --> zero translation, unit rotation
$ dq = DualQuaternion.from_screw([lx, ly, lz], [mx, my, mz], theta, d)

The underlying representation for a single quaternion uses the format [w x y z]
The rotation part (non-dual) will always be normalized.

Definition at line 12 of file dual_quaternions.py.

Constructor & Destructor Documentation

def dual_quaternions.dual_quaternions.DualQuaternion.__init__ (   self,
  q_r,
  q_d,
  normalize = False 
)

Definition at line 34 of file dual_quaternions.py.

Member Function Documentation

def dual_quaternions.dual_quaternions.DualQuaternion.__add__ (   self,
  other 
)
Dual Quaternion addition.
:param other: dual quaternion
:return: DualQuaternion(self.q_r + other.q_r, self.q_d + other.q_d)

Definition at line 102 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__div__ (   self,
  other 
)
Dual quaternion division. See __truediv__

:param other: DualQuaternion instance
:return: DualQuaternion instance

Definition at line 80 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__eq__ (   self,
  other 
)

Definition at line 110 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__imul__ (   self,
  other 
)
Dual quaternion multiplication with self-assignment: dq1 *= dq2
See __mul__

Definition at line 66 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__mul__ (   self,
  other 
)
Dual quaternion multiplication

:param other: right hand side of the multiplication: DualQuaternion instance
:return product: DualQuaternion object. Math:
      dq1 * dq2 = dq1_r * dq2_r + (dq1_r * dq2_d + dq1_d * dq2_r) * eps

Definition at line 52 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__ne__ (   self,
  other 
)

Definition at line 114 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__repr__ (   self)

Definition at line 49 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__rmul__ (   self,
  other 
)
Multiplication with a scalar

:param other: scalar

Definition at line 73 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__str__ (   self)

Definition at line 45 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.__truediv__ (   self,
  other 
)
Dual quaternion division.

:param other: DualQuaternion instance
:return: DualQuaternion instance

Definition at line 89 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.as_dict (   self)
dictionary containing the dual quaternion

Definition at line 348 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.combined_conjugate (   self)
Return the combination of the quaternion conjugate and dual number conjugate
(qr, qd)* = (qr*, -qd*)

This form is commonly used to transform a point
See also DualQuaternion.dual_number_conjugate() and DualQuaternion.quaternion_conjugate().

Definition at line 205 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.dq_array (   self)
Get the list version of the dual quaternion as the rotation quaternion followed by the translation quaternion

:return: list [q_rw, q_rx, q_ry, q_rz, q_tx, q_ty, q_tz]

Definition at line 325 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.dual_number_conjugate (   self)
Return the dual number conjugate (qr, qd)* = (qr, -qd)

This form of conjugate is seldom used.
See also DualQuaternion.quaternion_conjugate() and DualQuaternion.combined_conjugate().

Definition at line 196 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.from_dq_array (   cls,
  r_wxyz_t_wxyz 
)
Create a DualQuaternion instance from two quaternions in list format

:param r_wxyz_t_wxyz: np.array or python list: np.array([q_rw, q_rx, q_ry, q_rz, q_tx, q_ty, q_tz]

Definition at line 138 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.from_file (   cls,
  path 
)
Load a DualQuaternion from file

Definition at line 297 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.from_homogeneous_matrix (   cls,
  arr 
)
Create a DualQuaternion instance from a 4 by 4 homogeneous transformation matrix

:param arr: 4 by 4 list or np.array

Definition at line 147 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.from_quat_pose_array (   cls,
  r_wxyz_t_xyz 
)
Create a DualQuaternion object from an array of a quaternion r and translation t
sigma = r + eps/2 * t * r

:param r_wxyz_t_xyz: list or np.array in order: [q_rw, q_rx, q_ry, q_rz, tx, ty, tz]

Definition at line 162 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.from_screw (   cls,
  l,
  m,
  theta,
  d 
)
Create a DualQuaternion from screw parameters

:param l: unit vector defining screw axis direction
:param m: screw axis moment, perpendicular to l and through the origin
:param theta: screw angle; rotation around the screw axis
:param d: displacement along the screw axis

Definition at line 391 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.from_translation_vector (   cls,
  t_xyz 
)
Create a DualQuaternion object from a cartesian point
:param t_xyz: list or np.array in order: [x y z]

Definition at line 175 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.homogeneous_matrix (   self)
Homogeneous 4x4 transformation matrix from the dual quaternion

:return 4 by 4 np.array

Definition at line 305 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.identity (   cls)

Definition at line 183 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.inverse (   self)
Return the dual quaternion inverse

For unit dual quaternions dq.inverse = dq.quaternion_conjugate()

Definition at line 215 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.is_normalized (   self)
Check if the dual quaternion is normalized

Definition at line 224 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.nlerp (   self,
  other,
  t 
)

Definition at line 284 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.normalize (   self)
Normalize this dual quaternion

Modifies in place, so this will not preserve self

Definition at line 232 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.normalized (   self)
Return a copy of the normalized dual quaternion

Definition at line 343 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.pow (   self,
  exponent 
)
self^exponent

:param exponent: single float

Definition at line 242 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.quat_pose_array (   self)
Get the list version of the dual quaternion as a quaternion followed by the translation vector
given a dual quaternion p + eq, the rotation in quaternion form is p and the translation in
quaternion form is 2qp*

:return: list [q_w, q_x, q_y, q_z, x, y, z]

Definition at line 315 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.quaternion_conjugate (   self)
Return the individual quaternion conjugates (qr, qd)* = (qr*, qd*)

This is equivalent to inverse of a homogeneous matrix. It is used in applying
a transformation to a line expressed in Plucker coordinates.
See also DualQuaternion.dual_conjugate() and DualQuaternion.combined_conjugate().

Definition at line 186 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.save (   self,
  path 
)
Save the transformation to file

:param path: absolute folder path and filename + extension
:raises IOError: when the path does not exist

Definition at line 287 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.sclerp (   cls,
  start,
  stop,
  t 
)
Screw Linear Interpolation

Generalization of Quaternion slerp (Shoemake et al.) for rigid body motions
ScLERP guarantees both shortest path (on the manifold) and constant speed
interpolation and is independent of the choice of coordinate system.
ScLERP(dq1, dq2, t) = dq1 * dq12^t where dq12 = dq1^-1 * dq2

:param start: DualQuaternion instance
:param stop: DualQuaternion instance
:param t: fraction betweem [0, 1] representing how far along and around the
  screw axis to interpolate

Definition at line 266 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.screw (   self)
Get the screw parameters for this dual quaternion.
Chasles' theorem (Mozzi, screw theorem) states that any rigid displacement is equivalent to a rotation about
some line and a translation in the direction of the line. This line does not go through the origin!
This function returns the Plucker coordinates for the screw axis (l, m) as well as the amount of rotation
and translation, theta and d.
If the dual quaternion represents a pure translation, theta will be zero and the screw moment m will be at
infinity.

:return: l (unit length), m, theta, d
:rtype np.array(3), np.array(3), float, float

Definition at line 353 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.transform_point (   self,
  point_xyz 
)
Convenience function to apply the transformation to a given vector.
dual quaternion way of applying a rotation and translation using matrices Rv + t or H[v; 1]
This works out to be: sigma @ (1 + ev) @ sigma.combined_conjugate()

If we write self = p + eq, this can be expanded to 1 + eps(rvr* + t)
with r = p and t = 2qp* which should remind you of Rv + t and the quaternion
transform_point() equivalent (rvr*)

Does not check frames - make sure you do this yourself.
:param point_xyz: list or np.array in order: [x y z]
:return: vector of length 3

Definition at line 117 of file dual_quaternions.py.

def dual_quaternions.dual_quaternions.DualQuaternion.translation (   self)
Get the translation component of the dual quaternion in vector form

:return: list [x y z]

Definition at line 334 of file dual_quaternions.py.

Member Data Documentation

dual_quaternions.dual_quaternions.DualQuaternion.q_d

Definition at line 39 of file dual_quaternions.py.

dual_quaternions.dual_quaternions.DualQuaternion.q_r

Definition at line 40 of file dual_quaternions.py.


The documentation for this class was generated from the following file:


dual_quaternions
Author(s): achille
autogenerated on Mon Aug 17 2020 03:24:44