2 DualQuaternions operations, interpolation, conversions 4 Author: Achille Verheye 8 from pyquaternion
import Quaternion
14 dual number representation of quaternions to represent rigid transforms 16 A quaternion q can be represented as q_r + q_d * eps with eps^2 = 0 and eps != 0 18 Several ways to instantiate: 19 $ dq = DualQuaternion(q_rot, q_dual) with both arguments instance of numpy-quaternion 20 $ dq = DualQuaternion.from_dq_array(np.array([q_rw, q_rx, q_ry, q_rz, q_tx, q_ty, q_tz]) 21 $ dq = DualQuaternion.from_homogeneous_matrix([[r11, r12, r13, tx], 25 $ dq = DualQuaternion.from_quat_pose_array([q_w, q_x, q_y, q_z, x, y, z]) 26 $ dq = DualQuaternion.from_translation_vector([x y z]) 27 $ dq = DualQuaternion.identity() --> zero translation, unit rotation 28 $ dq = DualQuaternion.from_screw([lx, ly, lz], [mx, my, mz], theta, d) 30 The underlying representation for a single quaternion uses the format [w x y z] 31 The rotation part (non-dual) will always be normalized. 35 if not isinstance(q_r, Quaternion)
or not isinstance(q_d, Quaternion):
36 raise ValueError(
"q_r and q_d must be of type pyquaternion.Quaternion. Instead received: {} and {}".format(
37 type(q_r), type(q_d)))
39 self.
q_d = q_d / q_r.norm()
40 self.
q_r = q_r.normalised
46 return "rotation: {}, translation: {}, \n".format(repr(self.
q_r), repr(self.
q_d)) + \
47 "translation vector: {}".format(repr(self.
translation()))
50 return "<DualQuaternion: {0} + {1}e>".format(repr(self.
q_r), repr(self.
q_d))
54 Dual quaternion multiplication 56 :param other: right hand side of the multiplication: DualQuaternion instance 57 :return product: DualQuaternion object. Math: 58 dq1 * dq2 = dq1_r * dq2_r + (dq1_r * dq2_d + dq1_d * dq2_r) * eps 60 q_r_prod = self.
q_r * other.q_r
61 q_d_prod = self.
q_r * other.q_d + self.
q_d * other.q_r
68 Dual quaternion multiplication with self-assignment: dq1 *= dq2 74 """Multiplication with a scalar 82 Dual quaternion division. See __truediv__ 84 :param other: DualQuaternion instance 85 :return: DualQuaternion instance 91 Dual quaternion division. 93 :param other: DualQuaternion instance 94 :return: DualQuaternion instance 96 other_r_sq = other.q_r * other.q_r
97 prod_r = self.
q_r * other.q_r / other_r_sq
98 prod_d = (other.q_r * self.
q_d - self.
q_r * other.q_d) / other_r_sq
104 Dual Quaternion addition. 105 :param other: dual quaternion 106 :return: DualQuaternion(self.q_r + other.q_r, self.q_d + other.q_d) 111 return (self.
q_r == other.q_r
or self.
q_r == -other.q_r) \
112 and (self.
q_d == other.q_d
or self.
q_d == -other.q_d)
115 return not self == other
119 Convenience function to apply the transformation to a given vector. 120 dual quaternion way of applying a rotation and translation using matrices Rv + t or H[v; 1] 121 This works out to be: sigma @ (1 + ev) @ sigma.combined_conjugate() 123 If we write self = p + eq, this can be expanded to 1 + eps(rvr* + t) 124 with r = p and t = 2qp* which should remind you of Rv + t and the quaternion 125 transform_point() equivalent (rvr*) 127 Does not check frames - make sure you do this yourself. 128 :param point_xyz: list or np.array in order: [x y z] 129 :return: vector of length 3 131 dq_point = DualQuaternion.from_dq_array([1, 0, 0, 0,
132 0, point_xyz[0], point_xyz[1], point_xyz[2]])
135 return res_dq.dq_array()[5:]
140 Create a DualQuaternion instance from two quaternions in list format 142 :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] 144 return cls(Quaternion(*r_wxyz_t_wxyz[:4]), Quaternion(*r_wxyz_t_wxyz[4:]))
149 Create a DualQuaternion instance from a 4 by 4 homogeneous transformation matrix 151 :param arr: 4 by 4 list or np.array 153 q_r = Quaternion(matrix=arr[:3, :3])
154 quat_pose_array = np.zeros(7)
155 quat_pose_array[:4] = np.array([q_r.w, q_r.x, q_r.y, q_r.z])
157 quat_pose_array[4:] = arr[:3, 3]
164 Create a DualQuaternion object from an array of a quaternion r and translation t 165 sigma = r + eps/2 * t * r 167 :param r_wxyz_t_xyz: list or np.array in order: [q_rw, q_rx, q_ry, q_rz, tx, ty, tz] 169 q_r = Quaternion(*r_wxyz_t_xyz[:4]).normalised
170 q_d = 0.5 * Quaternion(0., *r_wxyz_t_xyz[4:]) * q_r
177 Create a DualQuaternion object from a cartesian point 178 :param t_xyz: list or np.array in order: [x y z] 184 return cls(Quaternion(1., 0., 0., 0.), Quaternion(0., 0., 0., 0.))
188 Return the individual quaternion conjugates (qr, qd)* = (qr*, qd*) 190 This is equivalent to inverse of a homogeneous matrix. It is used in applying 191 a transformation to a line expressed in Plucker coordinates. 192 See also DualQuaternion.dual_conjugate() and DualQuaternion.combined_conjugate(). 198 Return the dual number conjugate (qr, qd)* = (qr, -qd) 200 This form of conjugate is seldom used. 201 See also DualQuaternion.quaternion_conjugate() and DualQuaternion.combined_conjugate(). 207 Return the combination of the quaternion conjugate and dual number conjugate 208 (qr, qd)* = (qr*, -qd*) 210 This form is commonly used to transform a point 211 See also DualQuaternion.dual_number_conjugate() and DualQuaternion.quaternion_conjugate(). 217 Return the dual quaternion inverse 219 For unit dual quaternions dq.inverse = dq.quaternion_conjugate() 221 q_r_inv = self.q_r.inverse
225 """Check if the dual quaternion is normalized""" 226 if np.isclose(self.q_r.norm, 0):
228 rot_normalized = np.isclose(self.q_r.norm, 1)
229 trans_normalized = (self.
q_d / self.q_r.norm) == self.
q_d 230 return rot_normalized
and trans_normalized
234 Normalize this dual quaternion 236 Modifies in place, so this will not preserve self 239 self.
q_r = normalized.q_r
240 self.
q_d = normalized.q_d
245 :param exponent: single float 247 exponent = float(exponent)
249 theta = 2*np.arccos(self.q_r.w)
250 if np.isclose(theta, 0):
251 return DualQuaternion.from_translation_vector(exponent*np.array(self.
translation()))
253 s0 = self.q_r.vector / np.sin(theta/2)
254 d = -2. * self.q_d.w / np.sin(theta / 2)
255 se = (self.q_d.vector - s0 * d/2 * np.cos(theta/2)) / np.sin(theta/2)
257 q_r = Quaternion(scalar=np.cos(exponent*theta/2),
258 vector=np.sin(exponent*theta/2) * s0)
260 q_d = Quaternion(scalar=-exponent*d/2 * np.sin(exponent*theta/2),
261 vector=exponent*d/2 * np.cos(exponent*theta/2) * s0 + np.sin(exponent*theta/2) * se)
267 """Screw Linear Interpolation 269 Generalization of Quaternion slerp (Shoemake et al.) for rigid body motions 270 ScLERP guarantees both shortest path (on the manifold) and constant speed 271 interpolation and is independent of the choice of coordinate system. 272 ScLERP(dq1, dq2, t) = dq1 * dq12^t where dq12 = dq1^-1 * dq2 274 :param start: DualQuaternion instance 275 :param stop: DualQuaternion instance 276 :param t: fraction betweem [0, 1] representing how far along and around the 277 screw axis to interpolate 280 if (start.q_r * stop.q_r).w < 0:
282 return start * (start.inverse() * stop).
pow(t)
285 raise NotImplementedError()
288 """Save the transformation to file 290 :param path: absolute folder path and filename + extension 291 :raises IOError: when the path does not exist 293 with open(path,
'w')
as outfile:
294 json.dump(self.
as_dict(), outfile)
298 """Load a DualQuaternion from file""" 299 with open(path)
as json_file:
300 qdict = json.load(json_file)
302 return cls.
from_dq_array([qdict[
'r_w'], qdict[
'r_x'], qdict[
'r_y'], qdict[
'r_z'],
303 qdict[
'd_w'], qdict[
'd_x'], qdict[
'd_y'], qdict[
'd_z']])
306 """Homogeneous 4x4 transformation matrix from the dual quaternion 308 :return 4 by 4 np.array 310 homogeneous_mat = self.q_r.transformation_matrix
311 homogeneous_mat[:3, 3] = np.array(self.
translation())
313 return homogeneous_mat
317 Get the list version of the dual quaternion as a quaternion followed by the translation vector 318 given a dual quaternion p + eq, the rotation in quaternion form is p and the translation in 319 quaternion form is 2qp* 321 :return: list [q_w, q_x, q_y, q_z, x, y, z] 323 return [self.q_r.w, self.q_r.x, self.q_r.y, self.q_r.z] + self.
translation()
327 Get the list version of the dual quaternion as the rotation quaternion followed by the translation quaternion 329 :return: list [q_rw, q_rx, q_ry, q_rz, q_tx, q_ty, q_tz] 331 return [self.q_r.w, self.q_r.x, self.q_r.y, self.q_r.z,
332 self.q_d.w, self.q_d.x, self.q_d.y, self.q_d.z]
335 """Get the translation component of the dual quaternion in vector form 337 :return: list [x y z] 339 mult = (2.0 * self.
q_d) * self.q_r.conjugate
341 return [mult.x, mult.y, mult.z]
344 """Return a copy of the normalized dual quaternion""" 345 norm_qr = self.q_r.norm
349 """dictionary containing the dual quaternion""" 350 return {
'r_w': self.q_r.w,
'r_x': self.q_r.x,
'r_y': self.q_r.y,
'r_z': self.q_r.z,
351 'd_w': self.q_d.w,
'd_x': self.q_d.x,
'd_y': self.q_d.y,
'd_z': self.q_d.z}
355 Get the screw parameters for this dual quaternion. 356 Chasles' theorem (Mozzi, screw theorem) states that any rigid displacement is equivalent to a rotation about 357 some line and a translation in the direction of the line. This line does not go through the origin! 358 This function returns the Plucker coordinates for the screw axis (l, m) as well as the amount of rotation 359 and translation, theta and d. 360 If the dual quaternion represents a pure translation, theta will be zero and the screw moment m will be at 363 :return: l (unit length), m, theta, d 364 :rtype np.array(3), np.array(3), float, float 367 theta = self.q_r.angle
368 theta_close_to_zero = np.isclose(theta, 0)
371 if not theta_close_to_zero:
372 l = self.q_r.vector / np.sin(theta/2)
378 m = 0.5 * (np.cross(t, l) + np.cross(l, np.cross(t, l) / np.tan(theta / 2)))
381 d = np.linalg.norm(t)
382 if not np.isclose(d, 0):
386 m = np.array([np.inf, np.inf, np.inf])
388 return l, m, theta, d
393 Create a DualQuaternion from screw parameters 395 :param l: unit vector defining screw axis direction 396 :param m: screw axis moment, perpendicular to l and through the origin 397 :param theta: screw angle; rotation around the screw axis 398 :param d: displacement along the screw axis 402 if not np.isclose(np.linalg.norm(l), 1):
403 raise AttributeError(
"Expected l to be a unit vector, received {} with norm {} instead" 404 .format(l, np.linalg.norm(l)))
407 q_r = Quaternion(scalar=np.cos(theta/2), vector=np.sin(theta/2) * l)
408 q_d = Quaternion(scalar=-d/2 * np.sin(theta/2), vector=np.sin(theta/2) * m + d/2 * np.cos(theta/2) * l)
def sclerp(cls, start, stop, t)
def from_translation_vector(cls, t_xyz)
def dual_number_conjugate(self)
def from_dq_array(cls, r_wxyz_t_wxyz)
def combined_conjugate(self)
def nlerp(self, other, t)
def from_screw(cls, l, m, theta, d)
def transform_point(self, point_xyz)
def __truediv__(self, other)
def quaternion_conjugate(self)
def quat_pose_array(self)
def from_homogeneous_matrix(cls, arr)
def __rmul__(self, other)
def homogeneous_matrix(self)
def __init__(self, q_r, q_d, normalize=False)
def from_quat_pose_array(cls, r_wxyz_t_xyz)
def __imul__(self, other)