A class for representing spatial rotations.
More...
A class for representing spatial rotations.
◆ __init__()
def spatial_casadi.spatial.Rotation.__init__ |
( |
|
self, |
|
|
ArrayType |
quat, |
|
|
bool |
normalize = True |
|
) |
| |
Initializer for the Rotation class.
- Parameters
-
quat | Quaternion representing the rotation. |
normalize | When true, the quaternion is normalized. |
- Returns
- An instance of the Rotation class.
◆ __mul__()
def spatial_casadi.spatial.Rotation.__mul__ |
( |
|
self, |
|
|
|
other |
|
) |
| |
Compose this rotation with the other.
- Parameters
-
other | Object containing the rotation or translation to be composed with this one. Note that compositions are not commutative, so p * q is different from q * p. In the case of translations q * p is undefined. |
- Returns
- The product A * B, if other is a rotation the output will be a rotation. However, if other is a translation then the output will also be a translation.
◆ as_euler()
ArrayType spatial_casadi.spatial.Rotation.as_euler |
( |
|
self, |
|
|
str |
seq, |
|
|
bool |
degrees = False |
|
) |
| |
Represent as Euler angles.
- Parameters
-
seq | Specifies sequence of axes for rotations. Up to 3 characters belonging to the set {‘X’, ‘Y’, ‘Z’} for intrinsic rotations, or {‘x’, ‘y’, ‘z’} for extrinsic rotations. Extrinsic and intrinsic rotations cannot be mixed in one function call. |
degrees | Returned angles are in degrees if this flag is True, else they are in radians. Default is False. |
- Returns
- Euler angles specified in radians (degrees is False) or degrees (degrees is True).
◆ as_matrix()
ArrayType spatial_casadi.spatial.Rotation.as_matrix |
( |
|
self | ) |
|
Represent as rotation matrix.
- Returns
- A 3-by-3 rotation matrix.
◆ as_mrp()
ArrayType spatial_casadi.spatial.Rotation.as_mrp |
( |
|
self | ) |
|
Represent as Modified Rodrigues Parameters (MRPs).
- Returns
- A vector giving the MRP, a 3 dimensional vector co-directional to the axis of rotation and whose magnitude is equal to tan(theta / 4), where theta is the angle of rotation (in radians).
◆ as_quat()
ArrayType spatial_casadi.spatial.Rotation.as_quat |
( |
|
self, |
|
|
str |
seq = "xyzw" |
|
) |
| |
Represent as quaternions.
- Parameters
-
seq | Specifies the ordering of the quaternion. Available options are 'wxyz' (i.e. scalar-first) and 'xyzw' (i.e. scalar-last). The default is the scalar-last format given by 'xyzw'. |
- Returns
- A quaternion vector.
◆ as_rotvec()
ArrayType spatial_casadi.spatial.Rotation.as_rotvec |
( |
|
self, |
|
|
bool |
degrees = False |
|
) |
| |
Represent as rotation vector.
- Parameters
-
degrees | If True, then the given magnitudes are assumed to be in degrees. Default is False. |
- Returns
- A 3-dimensional rotation vector
◆ from_euler()
def spatial_casadi.spatial.Rotation.from_euler |
( |
|
seq, |
|
|
|
angles, |
|
|
|
degrees = False |
|
) |
| |
|
static |
Initialize from Euler angles.
- Parameters
-
seq | Specifies sequence of axes for rotations. Up to 3 characters belonging to the set {‘X’, ‘Y’, ‘Z’} for intrinsic rotations, or {‘x’, ‘y’, ‘z’} for extrinsic rotations. Extrinsic and intrinsic rotations cannot be mixed in one function call. |
angles | Euler angles specified in radians (degrees is False) or degrees (degrees is True). For a single character seq, angles can be:
- a single value.
- array_like with shape (N,), where each angle[i] corresponds to a single rotation.
|
degrees | If True, then the given angles are assumed to be in degrees. Default is False. |
- Returns
- Object containing the rotation represented by the rotation around given axes with given angles.
◆ from_matrix()
def spatial_casadi.spatial.Rotation.from_matrix |
( |
ArrayType |
matrix | ) |
|
|
static |
Initialize from rotation matrix.
- Parameters
-
matrix | A 3-by-3 rotation matrix or 4-by-4 homogeneous transformation matrix. |
- Returns
- Object containing the rotation represented by the rotation matrix.
◆ from_mrp()
def spatial_casadi.spatial.Rotation.from_mrp |
( |
ArrayType |
mrp | ) |
|
|
static |
Initialize from Modified Rodrigues Parameters (MRPs).
- Parameters
-
mrp | A vector giving the MRP, a 3 dimensional vector co-directional to the axis of rotation and whose magnitude is equal to tan(theta / 4), where theta is the angle of rotation (in radians). |
◆ from_quat()
def spatial_casadi.spatial.Rotation.from_quat |
( |
ArrayType |
quat, |
|
|
str |
seq = "xyzw" |
|
) |
| |
|
static |
Initialize from quaternion.
- Parameters
-
quat | The quaternion. The quaternion will be normalized to unit norm. |
seq | Specifies the ordering of the quaternion. Available options are 'wxyz' (i.e. scalar-first) and 'xyzw' (i.e. scalar-last). The default is the scalar-last format given by 'xyzw'. |
- Returns
- Object containing the rotation represented by the input quaternion.
◆ from_rotvec()
def spatial_casadi.spatial.Rotation.from_rotvec |
( |
ArrayType |
rotvec, |
|
|
bool |
degrees = False |
|
) |
| |
|
static |
Initialize from rotation vectors.
- Parameters
-
rotvec | A 3-dimensional rotation vector |
degrees | If True, then the given magnitudes are assumed to be in degrees. Default is False. |
◆ identity()
def spatial_casadi.spatial.Rotation.identity |
( |
| ) |
|
|
static |
Get the identity rotation.
◆ inv()
def spatial_casadi.spatial.Rotation.inv |
( |
|
self | ) |
|
◆ random()
def spatial_casadi.spatial.Rotation.random |
( |
| ) |
|
|
static |
Generate uniformly distributed rotations.
- Returns
- Random rotation.
◆ symbolic()
def spatial_casadi.spatial.Rotation.symbolic |
( |
| ) |
|
|
static |
Symbolic representation.
- Returns
- Symbolic rotation.
◆ _quat
spatial_casadi.spatial.Rotation._quat |
|
private |
The documentation for this class was generated from the following file: