Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | List of all members
pyquaternion.pyquaternion.Quaternion Class Reference
Inheritance diagram for pyquaternion.pyquaternion.Quaternion:
Inheritance graph
[legend]

Public Member Functions

def __abs__ (self)
 
def __add__ (self, other)
 
def __bool__ (self)
 
def __complex__ (self)
 
def __copy__ (self)
 
def __deepcopy__ (self, memo)
 
def __div__ (self, other)
 
def __eq__ (self, other)
 
def __float__ (self)
 
def __format__ (self, formatstr)
 
def __getitem__ (self, index)
 
def __hash__ (self)
 
def __iadd__ (self, other)
 
def __idiv__ (self, other)
 
def __imatmul__ (self, other)
 
def __imul__ (self, other)
 
def __init__ (self, args, kwargs)
 
def __int__ (self)
 
def __invert__ (self)
 
def __ipow__ (self, other)
 
def __isub__ (self, other)
 
def __itruediv__ (self, other)
 
def __matmul__ (self, other)
 
def __mul__ (self, other)
 
def __neg__ (self)
 
def __nonzero__ (self)
 
def __pow__ (self, exponent)
 
def __radd__ (self, other)
 
def __rdiv__ (self, other)
 
def __repr__ (self)
 
def __rmatmul__ (self, other)
 
def __rmul__ (self, other)
 
def __rpow__ (self, other)
 
def __rsub__ (self, other)
 
def __rtruediv__ (self, other)
 
def __setitem__ (self, index, value)
 
def __str__ (self)
 
def __sub__ (self, other)
 
def __truediv__ (self, other)
 
def absolute_distance (cls, q0, q1)
 
def angle (self)
 
def axis (self)
 
def conjugate (self)
 
def degrees (self)
 
def derivative (self, rate)
 
def distance (cls, q0, q1)
 
def elements (self)
 
def exp (cls, q)
 
def exp_map (cls, q, eta)
 
def get_axis (self, undefined=np.zeros(3))
 
def imaginary (self)
 
def integrate (self, rate, timestep)
 
def intermediates (cls, q0, q1, n, include_endpoints=False)
 
def inverse (self)
 
def is_unit (self, tolerance=1e-14)
 
def log (cls, q)
 
def log_map (cls, q, p)
 
def magnitude (self)
 
def norm (self)
 
def normalised (self)
 
def polar_angle (self)
 
def polar_decomposition (self)
 
def polar_unit_vector (self)
 
def radians (self)
 
def random (cls)
 
def real (self)
 
def rotate (self, vector)
 
def rotation_matrix (self)
 
def scalar (self)
 
def slerp (cls, q0, q1, amount=0.5)
 
def sym_distance (cls, q0, q1)
 
def sym_exp_map (cls, q, eta)
 
def sym_log_map (cls, q, p)
 
def transformation_matrix (self)
 
def unit (self)
 
def vector (self)
 
def vector (self, v)
 
def w (self)
 
def x (self)
 
def y (self)
 
def yaw_pitch_roll (self)
 
def z (self)
 

Static Public Member Functions

def to_degrees (angle_rad)
 
def to_radians (angle_deg)
 

Public Attributes

 q
 

Private Member Functions

def _fast_normalise (self)
 
def _from_axis_angle (cls, axis, angle)
 
def _from_matrix (cls, matrix, rtol=1e-05, atol=1e-08)
 
def _normalise (self)
 
def _q_bar_matrix (self)
 
def _q_matrix (self)
 
def _rotate_quaternion (self, q)
 
def _sum_of_squares (self)
 
def _validate_number_sequence (self, seq, n)
 
def _vector_conjugate (self)
 
def _wrap_angle (self, theta)
 

Detailed Description

Class to represent a 4-dimensional complex number or quaternion.

Quaternion objects can be used generically as 4D numbers,
or as unit quaternions to represent rotations in 3D space.

Attributes:
    q: Quaternion 4-vector represented as a Numpy array

Definition at line 42 of file pyquaternion.py.

Constructor & Destructor Documentation

def pyquaternion.pyquaternion.Quaternion.__init__ (   self,
  args,
  kwargs 
)
Initialise a new Quaternion object.

See Object Initialisation docs for complete behaviour:

http://kieranwynn.github.io/pyquaternion/initialisation/

Definition at line 53 of file pyquaternion.py.

Member Function Documentation

def pyquaternion.pyquaternion.Quaternion.__abs__ (   self)

Definition at line 363 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__add__ (   self,
  other 
)

Definition at line 367 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__bool__ (   self)

Definition at line 334 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__complex__ (   self)
Implements type conversion to complex.

Truncates the Quaternion object by only considering the real
component and the first imaginary component.
This is equivalent to a projection from the 4-dimensional hypersphere
to the 2-dimensional complex plane.

Definition at line 324 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__copy__ (   self)

Definition at line 1173 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__deepcopy__ (   self,
  memo 
)

Definition at line 1177 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__div__ (   self,
  other 
)

Definition at line 412 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__eq__ (   self,
  other 
)
Returns true if the following is true for each element:
`absolute(a - b) <= (atol + rtol * absolute(b))`

Definition at line 344 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__float__ (   self)
Implements type conversion to float.

Truncates the Quaternion object by only considering the real
component.

Definition at line 316 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__format__ (   self,
  formatstr 
)
Inserts a customisable, nicely printable string representation of the Quaternion object

The syntax for `format_spec` mirrors that of the built in format specifiers for floating point types.
Check out the official Python [format specification mini-language](https://docs.python.org/3.4/library/string.html#formatspec) for details.

Definition at line 290 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__getitem__ (   self,
  index 
)

Definition at line 1165 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__hash__ (   self)

Definition at line 135 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__iadd__ (   self,
  other 
)

Definition at line 372 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__idiv__ (   self,
  other 
)

Definition at line 419 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__imatmul__ (   self,
  other 
)

Definition at line 405 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__imul__ (   self,
  other 
)

Definition at line 394 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__int__ (   self)
Implements type conversion to int.

Truncates the Quaternion object by only considering the real
component and rounding to the next integer value towards zero.
Note: to round to the closest integer, use int(round(float(q)))

Definition at line 307 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__invert__ (   self)

Definition at line 340 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__ipow__ (   self,
  other 
)

Definition at line 448 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__isub__ (   self,
  other 
)

Definition at line 382 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__itruediv__ (   self,
  other 
)

Definition at line 428 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__matmul__ (   self,
  other 
)

Definition at line 400 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__mul__ (   self,
  other 
)

Definition at line 389 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__neg__ (   self)

Definition at line 359 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__nonzero__ (   self)

Definition at line 337 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__pow__ (   self,
  exponent 
)

Definition at line 435 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__radd__ (   self,
  other 
)

Definition at line 375 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__rdiv__ (   self,
  other 
)

Definition at line 422 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__repr__ (   self)
The 'official' string representation of the Quaternion object.

This is a string representation of a valid Python expression that could be used
to recreate an object with the same value (given an appropriate environment)

Definition at line 282 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__rmatmul__ (   self,
  other 
)

Definition at line 408 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__rmul__ (   self,
  other 
)

Definition at line 397 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__rpow__ (   self,
  other 
)

Definition at line 451 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__rsub__ (   self,
  other 
)

Definition at line 385 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__rtruediv__ (   self,
  other 
)

Definition at line 431 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__setitem__ (   self,
  index,
  value 
)

Definition at line 1169 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__str__ (   self)
An informal, nicely printable string representation of the Quaternion object.

Definition at line 277 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__sub__ (   self,
  other 
)

Definition at line 379 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.__truediv__ (   self,
  other 
)

Definition at line 425 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._fast_normalise (   self)
private
Normalise the object to a unit quaternion using a fast approximation method if appropriate.

Object is guaranteed to be a quaternion of approximately unit length
after calling this operation UNLESS the object is equivalent to Quaternion(0)

Definition at line 513 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._from_axis_angle (   cls,
  axis,
  angle 
)
private
Initialise from axis and angle representation

Create a Quaternion by specifying the 3-vector rotation axis and rotation
angle (in radians) from which the quaternion's rotation should be created.

Params:
    axis: a valid numpy 3-vector
    angle: a real valued angle in radians

Definition at line 238 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._from_matrix (   cls,
  matrix,
  rtol = 1e-05,
  atol = 1e-08 
)
private
Initialise from matrix representation

Create a Quaternion by specifying the 3x3 rotation or 4x4 transformation matrix
(as a numpy array) from which the quaternion's rotation should be created.

Definition at line 160 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._normalise (   self)
private
Object is guaranteed to be a unit quaternion after calling this
operation UNLESS the object is equivalent to Quaternion(0)

Definition at line 504 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._q_bar_matrix (   self)
private
Matrix representation of quaternion for multiplication purposes.

Definition at line 589 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._q_matrix (   self)
private
Matrix representation of quaternion for multiplication purposes.

Definition at line 580 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._rotate_quaternion (   self,
  q 
)
private
Rotate a quaternion vector using the stored rotation.

Params:
    q: The vector to be rotated, in quaternion form (0 + xi + yj + kz)

Returns:
    A Quaternion object representing the rotated vector in quaternion from (0 + xi + yj + kz)

Definition at line 598 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._sum_of_squares (   self)
private

Definition at line 458 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._validate_number_sequence (   self,
  seq,
  n 
)
private
Validate a sequence to be of a certain length and ensure it's a numpy array of floats.

Raises:
    ValueError: Invalid length or non-numeric value

Definition at line 138 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._vector_conjugate (   self)
private

Definition at line 455 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion._wrap_angle (   self,
  theta 
)
private
Helper method: Wrap any angle to lie between -pi and pi

Odd multiples of pi are wrapped to +pi (as opposed to -pi)

Definition at line 1033 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.absolute_distance (   cls,
  q0,
  q1 
)
Quaternion absolute distance.

Find the distance between two quaternions accounting for the sign ambiguity.

Params:
    q0: the first quaternion
    q1: the second quaternion

Returns:
   A positive scalar corresponding to the chord of the shortest path/arc that
   connects q0 to q1.

Note:
   This function does not measure the distance on the hypersphere, but
   it takes into account the fact that q and -q encode the same rotation.
   It is thus a good indicator for rotation similarities.

Definition at line 772 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.angle (   self)
Get the angle (in radians) describing the magnitude of the quaternion rotation about its rotation axis.

This is guaranteed to be within the range (-pi:pi) with the direction of
rotation indicated by the sign.

When a particular rotation describes a 180 degree rotation about an arbitrary
axis vector `v`, the conversion to axis / angle representation may jump
discontinuously between all permutations of `(-pi, pi)` and `(-v, v)`,
each being geometrically equivalent (see Note in documentation).

Returns:
    A real number in the range (-pi:pi) describing the angle of rotation
in radians about a Quaternion object's axis of rotation.

Note:
    This feature only makes sense when referring to a unit quaternion.
    Calling this method will implicitly normalise the Quaternion object to a unit quaternion if it is not already one.

Definition at line 1076 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.axis (   self)

Definition at line 1072 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.conjugate (   self)
Quaternion conjugate, encapsulated in a new instance.

For a unit quaternion, this is the same as the inverse.

Returns:
    A new Quaternion object clone with its vector part negated

Definition at line 462 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.degrees (   self)

Definition at line 1100 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.derivative (   self,
  rate 
)
Get the instantaneous quaternion derivative representing a quaternion rotating at a 3D rate vector `rate`

Params:
    rate: numpy 3-array (or array-like) describing rotation rates about the global x, y and z axes respectively.

Returns:
    A unit quaternion describing the rotation rate

Definition at line 936 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.distance (   cls,
  q0,
  q1 
)
Quaternion intrinsic distance.

Find the intrinsic geodesic distance between q0 and q1.

Params:
    q0: the first quaternion
    q1: the second quaternion

Returns:
   A positive amount corresponding to the length of the geodesic arc
   connecting q0 to q1.

Note:
   Although the q0^(-1)*q1 != q1^(-1)*q0, the length of the path joining
   them is given by the logarithm of those product quaternions, the norm
   of which is the same.

Definition at line 800 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.elements (   self)
Return all the elements of the quaternion object.

Returns:
    A numpy 4-array of floats. NOT guaranteed to be a unit vector

Definition at line 1157 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.exp (   cls,
  q 
)
Quaternion Exponential.

Find the exponential of a quaternion amount.

Params:
     q: the input quaternion/argument as a Quaternion object.

Returns:
     A quaternion amount representing the exp(q). See [Source](https://math.stackexchange.com/questions/1030737/exponential-function-of-quaternion-derivation for more information and mathematical background).

Note:
     The method can compute the exponential of any quaternion.

Definition at line 641 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.exp_map (   cls,
  q,
  eta 
)
Quaternion exponential map.

Find the exponential map on the Riemannian manifold described
by the quaternion space.

Params:
     q: the base point of the exponential map, i.e. a Quaternion object
   eta: the argument of the exponential map, a tangent vector, i.e. a Quaternion object

Returns:
    A quaternion p such that p is the endpoint of the geodesic starting at q
    in the direction of eta, having the length equal to the magnitude of eta.

Note:
    The exponential map plays an important role in integrating orientation
    variations (e.g. angular velocities). This is done by projecting
    quaternion tangent vectors onto the quaternion manifold.

Definition at line 691 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.get_axis (   self,
  undefined = np.zeros(3) 
)
Get the axis or vector about which the quaternion rotation occurs

For a null rotation (a purely real quaternion), the rotation angle will
always be `0`, but the rotation axis is undefined.
It is by default assumed to be `[0, 0, 0]`.

Params:
    undefined: [optional] specify the axis vector that should define a null rotation.
This is geometrically meaningless, and could be any of an infinite set of vectors,
but can be specified if the default (`[0, 0, 0]`) causes undesired behaviour.

Returns:
    A Numpy unit 3-vector describing the Quaternion object's axis of rotation.

Note:
    This feature only makes sense when referring to a unit quaternion.
    Calling this method will implicitly normalise the Quaternion object to a unit quaternion if it is not already one.

Definition at line 1043 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.imaginary (   self)

Definition at line 1137 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.integrate (   self,
  rate,
  timestep 
)
Advance a time varying quaternion to its value at a time `timestep` in the future.

The Quaternion object will be modified to its future value.
It is guaranteed to remain a unit quaternion.

Params:

rate: numpy 3-array (or array-like) describing rotation rates about the
    global x, y and z axes respectively.
timestep: interval over which to integrate into the future.
    Assuming *now* is `T=0`, the integration occurs over the interval
    `T=0` to `T=timestep`. Smaller intervals are more accurate when
    `rate` changes over time.

Note:
    The solution is closed form given the assumption that `rate` is constant
    over the interval of length `timestep`.

Definition at line 948 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.intermediates (   cls,
  q0,
  q1,
  n,
  include_endpoints = False 
)
Generator method to get an iterable sequence of `n` evenly spaced quaternion
rotations between any two existing quaternion endpoints lying on the unit
radius hypersphere.

This is a convenience function that is based on `Quaternion.slerp()` as defined above.

This is a class method and is called as a method of the class itself rather than on a particular instance.

Params:
    q_start: initial endpoint rotation as a Quaternion object
    q_end:   final endpoint rotation as a Quaternion object
    n:       number of intermediate quaternion objects to include within the interval
    include_endpoints: [optional] if set to `True`, the sequence of intermediates
will be 'bookended' by `q_start` and `q_end`, resulting in a sequence length of `n + 2`.
If set to `False`, endpoints are not included. Defaults to `False`.

Yields:
    A generator object iterating over a sequence of intermediate quaternion objects.

Note:
    This feature only makes sense when interpolating between unit quaternions (those lying on the unit radius hypersphere).
    Calling this method will implicitly normalise the endpoints to unit quaternions if they are not already unit length.

Definition at line 904 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.inverse (   self)
Inverse of the quaternion object, encapsulated in a new instance.

For a unit quaternion, this is the inverse rotation, i.e. when combined with the original rotation, will result in the null rotation.

Returns:
    A new Quaternion object representing the inverse of this object

Definition at line 473 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.is_unit (   self,
  tolerance = 1e-14 
)
Determine whether the quaternion is of unit length to within a specified tolerance value.

Params:
    tolerance: [optional] maximum absolute value by which the norm can differ from 1.0 for the object to be considered a unit quaternion. Defaults to `1e-14`.

Returns:
    `True` if the Quaternion object is of unit length to within the specified tolerance value. `False` otherwise.

Definition at line 569 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.log (   cls,
  q 
)
Quaternion Logarithm.

Find the logarithm of a quaternion amount.

Params:
     q: the input quaternion/argument as a Quaternion object.

Returns:
     A quaternion amount representing log(q) := (log(|q|), v/|v|acos(w/|q|)).

Note:
    The method computes the logarithm of general quaternions. See [Source](https://math.stackexchange.com/questions/2552/the-logarithm-of-quaternion/2554#2554) for more details.

Definition at line 664 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.log_map (   cls,
  q,
  p 
)
Quaternion logarithm map.

Find the logarithm map on the quaternion Riemannian manifold.

Params:
     q: the base point at which the logarithm is computed, i.e.
a Quaternion object
     p: the argument of the quaternion map, a Quaternion object

Returns:
    A tangent vector having the length and direction given by the
    geodesic joining q and p.

Definition at line 735 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.magnitude (   self)

Definition at line 501 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.norm (   self)
L2 norm of the quaternion 4-vector.

This should be 1.0 for a unit quaternion (versor)
Slow but accurate. If speed is a concern, consider using _fast_normalise() instead

Returns:
    A scalar real number representing the square root of the sum of the squares of the elements of the quaternion.

Definition at line 488 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.normalised (   self)
Get a unit quaternion (versor) copy of this Quaternion object.

A unit quaternion has a `norm` of 1.0

Returns:
    A new Quaternion object clone that is guaranteed to be a unit quaternion

Definition at line 531 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.polar_angle (   self)

Definition at line 551 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.polar_decomposition (   self)
Returns the unit vector and angle of a non-scalar quaternion according to the following decomposition

q =  q.norm() * (e ** (q.polar_unit_vector * q.polar_angle))

source: https://en.wikipedia.org/wiki/Polar_decomposition#Quaternion_polar_decomposition

Definition at line 555 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.polar_unit_vector (   self)

Definition at line 544 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.radians (   self)

Definition at line 1104 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.random (   cls)
Generate a random unit quaternion.

Uniformly distributed across the rotation space
As per: http://planning.cs.uiuc.edu/node198.html

Definition at line 261 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.real (   self)

Definition at line 1133 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.rotate (   self,
  vector 
)
Rotate a 3D vector by the rotation stored in the Quaternion object.

Params:
    vector: A 3-vector specified as any ordered sequence of 3 real numbers corresponding to x, y, and z values.
Some types that are recognised are: numpy arrays, lists and tuples.
A 3-vector can also be represented by a Quaternion object who's scalar part is 0 and vector part is the required 3-vector.
Thus it is possible to call `Quaternion.rotate(q)` with another quaternion object as an input.

Returns:
    The rotated vector returned as the same type it was specified at input.

Raises:
    TypeError: if any of the vector elements cannot be converted to a real number.
    ValueError: if `vector` cannot be interpreted as a 3-vector or a Quaternion object.

Definition at line 610 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.rotation_matrix (   self)
Get the 3x3 rotation matrix equivalent of the quaternion rotation.

Returns:
    A 3x3 orthogonal rotation matrix as a 3x3 Numpy array

Note:
    This feature only makes sense when referring to a unit quaternion. Calling this method will implicitly normalise the Quaternion object to a unit quaternion if it is not already one.

Definition at line 981 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.scalar (   self)
Return the real or scalar component of the quaternion object.

Returns:
    A real number i.e. float

Definition at line 1108 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.slerp (   cls,
  q0,
  q1,
  amount = 0.5 
)
Spherical Linear Interpolation between quaternions.
Implemented as described in https://en.wikipedia.org/wiki/Slerp

Find a valid quaternion rotation at a specified distance along the
minor arc of a great circle passing through any two existing quaternion
endpoints lying on the unit radius hypersphere.

This is a class method and is called as a method of the class itself rather than on a particular instance.

Params:
    q0: first endpoint rotation as a Quaternion object
    q1: second endpoint rotation as a Quaternion object
    amount: interpolation parameter between 0 and 1. This describes the linear placement position of
the result along the arc between endpoints; 0 being at `q0` and 1 being at `q1`.
Defaults to the midpoint (0.5).

Returns:
    A new Quaternion object representing the interpolated rotation. This is guaranteed to be a unit quaternion.

Note:
    This feature only makes sense when interpolating between unit quaternions (those lying on the unit radius hypersphere).
Calling this method will implicitly normalise the endpoints to unit quaternions if they are not already unit length.

Definition at line 847 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.sym_distance (   cls,
  q0,
  q1 
)
Quaternion symmetrized distance.

Find the intrinsic symmetrized geodesic distance between q0 and q1.

Params:
    q0: the first quaternion
    q1: the second quaternion

Returns:
   A positive amount corresponding to the length of the symmetrized
   geodesic curve connecting q0 to q1.

Note:
   This formulation is more numerically stable when performing
   iterative gradient descent on the Riemannian quaternion manifold.
   However, the distance between q and -q is equal to pi, rendering this
   formulation not useful for measuring rotation similarities when the
   samples are spread over a "solid" angle of more than pi/2 radians
   (the spread refers to quaternions as point samples on the unit hypersphere).

Definition at line 822 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.sym_exp_map (   cls,
  q,
  eta 
)
Quaternion symmetrized exponential map.

Find the symmetrized exponential map on the quaternion Riemannian
manifold.

Params:
     q: the base point as a Quaternion object
   eta: the tangent vector argument of the exponential map
as a Quaternion object

Returns:
    A quaternion p.

Note:
    The symmetrized exponential formulation is akin to the exponential
    formulation for symmetric positive definite tensors [Source](http://www.academia.edu/7656761/On_the_Averaging_of_Symmetric_Positive-Definite_Tensors)

Definition at line 713 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.sym_log_map (   cls,
  q,
  p 
)
Quaternion symmetrized logarithm map.

Find the symmetrized logarithm map on the quaternion Riemannian manifold.

Params:
     q: the base point at which the logarithm is computed, i.e.
a Quaternion object
     p: the argument of the quaternion map, a Quaternion object

Returns:
    A tangent vector corresponding to the symmetrized geodesic curve formulation.

Note:
    Information on the symmetrized formulations given in [Source](https://www.researchgate.net/publication/267191489_Riemannian_L_p_Averaging_on_Lie_Group_of_Nonzero_Quaternions).

Definition at line 752 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.to_degrees (   angle_rad)
static

Definition at line 1183 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.to_radians (   angle_deg)
static

Definition at line 1188 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.transformation_matrix (   self)
Get the 4x4 homogeneous transformation matrix equivalent of the quaternion rotation.

Returns:
    A 4x4 homogeneous transformation matrix as a 4x4 Numpy array

Note:
    This feature only makes sense when referring to a unit quaternion. Calling this method will implicitly normalise the Quaternion object to a unit quaternion if it is not already one.

Definition at line 996 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.unit (   self)

Definition at line 566 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.vector (   self)
Return the imaginary or vector component of the quaternion object.

Returns:
    A numpy 3-array of floats. NOT guaranteed to be a unit vector

Definition at line 1117 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.vector (   self,
  v 
)

Definition at line 1126 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.w (   self)

Definition at line 1141 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.x (   self)

Definition at line 1145 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.y (   self)

Definition at line 1149 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.yaw_pitch_roll (   self)
Get the equivalent yaw-pitch-roll angles aka. intrinsic Tait-Bryan angles following the z-y'-x'' convention

Returns:
    yaw:    rotation angle around the z-axis in radians, in the range `[-pi, pi]`
    pitch:  rotation angle around the y'-axis in radians, in the range `[-pi/2, -pi/2]`
    roll:   rotation angle around the x''-axis in radians, in the range `[-pi, pi]`

The resulting rotation_matrix would be R = R_x(roll) R_y(pitch) R_z(yaw)

Note:
    This feature only makes sense when referring to a unit quaternion. Calling this method will implicitly normalise the Quaternion object to a unit quaternion if it is not already one.

Definition at line 1010 of file pyquaternion.py.

def pyquaternion.pyquaternion.Quaternion.z (   self)

Definition at line 1153 of file pyquaternion.py.

Member Data Documentation

pyquaternion.pyquaternion.Quaternion.q

Definition at line 76 of file pyquaternion.py.


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


pyquaternion
Author(s): achille
autogenerated on Sun Mar 15 2020 03:13:33