A class defining a translation vector.
More...
A class defining a translation vector.
◆ __init__()
def spatial_casadi.spatial.Translation.__init__ |
( |
|
self, |
|
|
|
t |
|
) |
| |
Initializer for the Translation class.
@param t A 3-dimensional translation vector.
@return An instance of the Translation class.
◆ __add__()
def spatial_casadi.spatial.Translation.__add__ |
( |
|
self, |
|
|
|
other |
|
) |
| |
Compose this translation with the other via vector addition.
@param other Object containing the translation to be composed with this one.
@return The translation that is the result of A + B.
◆ __neg__()
def spatial_casadi.spatial.Translation.__neg__ |
( |
|
self | ) |
|
Negated translation.
@return The translation that is the negation of this translation, i.e. -t.
◆ __sub__()
def spatial_casadi.spatial.Translation.__sub__ |
( |
|
self, |
|
|
|
other |
|
) |
| |
Compose this translation with the other via vector subtraction.
@param other Object containing the translation to be composed with this one via subtraction.
@return The translation that is the result of A - B.
◆ as_matrix()
def spatial_casadi.spatial.Translation.as_matrix |
( |
|
self | ) |
|
Represent as homogenous transformation matrix.
@return A 4-by-4 homogenous transformation matrix.
◆ as_transformation()
def spatial_casadi.spatial.Translation.as_transformation |
( |
|
self | ) |
|
Represent as homogenous transformation.
@return A instance of the Transformation class with identity rotation.
◆ as_vector()
def spatial_casadi.spatial.Translation.as_vector |
( |
|
self | ) |
|
Represent as a translation vector.
@return A 3-dimensional translation vector.
◆ from_matrix()
def spatial_casadi.spatial.Translation.from_matrix |
( |
|
T | ) |
|
|
static |
Initialize from a homogenous transformation matrix.
@param T A 4-by-4 homogenous transformation matrix.
@return Object containing the translation represented by the input matrix.
◆ from_vector()
def spatial_casadi.spatial.Translation.from_vector |
( |
|
t | ) |
|
|
static |
Initialize from translation vector.
@param t A 3-dimensional translation vector.
@return Object containing the translation represented by the input vector.
◆ identity()
def spatial_casadi.spatial.Translation.identity |
( |
| ) |
|
|
static |
Get the identity translation.
◆ magnitude()
def spatial_casadi.spatial.Translation.magnitude |
( |
|
self | ) |
|
Get the magnitude of the translation.
◆ random()
def spatial_casadi.spatial.Translation.random |
( |
| ) |
|
|
static |
Generate uniformly distributed translations.
@return Random translation.
◆ symbolic()
def spatial_casadi.spatial.Translation.symbolic |
( |
| ) |
|
|
static |
Symbolic representation.
@return Symbolic translation.
◆ x()
def spatial_casadi.spatial.Translation.x |
( |
|
self | ) |
|
◆ y()
def spatial_casadi.spatial.Translation.y |
( |
|
self | ) |
|
◆ z()
def spatial_casadi.spatial.Translation.z |
( |
|
self | ) |
|
◆ _t
spatial_casadi.spatial.Translation._t |
|
private |
The documentation for this class was generated from the following file: