timor.utilities.transformation
Attributes
Classes
A namespace for norms of transformations. |
|
A namespace for transformation projections |
|
A transformation describes a translation and rotation in cartesian space. |
Module Contents
- class timor.utilities.transformation.Norm(transformation)
A namespace for norms of transformations.
Norms are directly defined on transformations. They return a single, non-negative scalar
- Parameters:
transformation (Transformation)
- property rotation_angle: float
The rotation angle of this transformation about any axis, expressed in radian.
- Return type:
- property rotation_angle_degree: float
The rotation angle of this transformation about any axis, expressed in degree.
- Return type:
- transformation
- property translation_euclidean: float
The Euclidean / L2 norm of this transformation’s translation.
- Return type:
- class timor.utilities.transformation.Projection(transformation)
A namespace for transformation projections
Projections are directly defined on transformations.
- Parameters:
transformation (Transformation)
- property axis_angles: numpy.ndarray
Returns the rotation part of the placement as (4,)-shaped axis angle representation.
- Source:
https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation
- Returns:
Rotation representation \((n_x, n_y, n_z, \theta_R)\).
- Return type:
- property axis_angles3: numpy.ndarray
Returns the rotation part of the placement as (3,)-shaped axis angle representation.
- Source:
https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation
- Returns:
Rotation representation \((n_x * \theta_R, n_y * \theta_R, n_z * \theta_R), \theta \in [0, \pi]\).
- Return type:
- property cartesian: numpy.ndarray
Returns the x, y, z coordinates in a cartesian coordinate system
- Return type:
- property cylindrical: numpy.ndarray
Returns the position in cylindrical coordinates [r, phi, z].
- Return type:
- property rotation_angle: float
The rotation angle of this transformation about any axis, expressed in radian.
Use some rounding to avoid floating point errors at the edge of arccos domain.
- Source:
https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation
- Return type:
- property roto_translation_vector: numpy.ndarray
Stacks the axis-angle-rotation vec[:3] and translation vec[3:] of a transformation in a (6,)-vector.
- Returns:
A vector \((n_x * \theta_R, n_y * \theta_R, n_z * \theta_R, x, y, z)\), where the first three elements are the rotation (in axis angle representation) of the transformation and the last three elements are the translation of the transformation.
- Return type:
- property spherical: numpy.ndarray
Returns the position in spherical coordinates [r, theta, phi].
- Return type:
- transformation
- class timor.utilities.transformation.Transformation(transformation, set_safe=False)

A transformation describes a translation and rotation in cartesian space.
Initialize a spatial transform with a 4x4 matrix which must be a homogeneous transformation.
- Parameters:
transformation (Union[Transformation, TransformationConvertable]) – A 4x4 homogeneous matrix representing the transformation. Can also be a sequence of (4x4) transformations, in which this parameter will be interpreted as the resulting transformation when performing all of them after one another.
set_safe (bool) – If true, a safety check will be performed to ensure the transformation is homogeneous. If that is not the case, tries to auto-correct. Defaults to false as the check is expensive and should not be done for every transformation to avoid performance issues.
- __eq__(other)
Allows comparison of transformations
- __getitem__(item)
Allows indexing the transformation without accessing the homogeneous attribute
- __getstate__()
Return objects which will be pickled and saved.
- __matmul__(other)
Allows matrix multiplication with a placement
- Note:
Matmul is only possible if the placement is on the left side. Numpy does raise a ValueError instead of returning NotImplemented on __matmul__ with placement, so __rmatmul__ would never be called if implemented.
- __setstate__(state)
Take object from parameter and use it to retrieve class state.
- __str__(precision=3)
Defaults to numpy homogeneous.
- static _deduce_package_dir(filepath, content)
Logic for deducing the package directory if the JSONable object is loaded from a file.
- Parameters:
filepath (pathlib.Path) – The path to the file.
content (Union[Dict, List]) – The content of the file parsed into a dictionary.
- Note:
This method can be overridden by subclasses to provide custom package directory resolution; e.g. Task.py.
- Return type:
- as_transform3f()
Returns this transformation as a hppfcl Transform3f
- Return type:
hppfcl.Transform3f
- distance(other)
Returns a norm object for the transformation between self and other.
A distance between two poses is not uniquely defined – returning a norm object is one possible way to deal with this problem: The returned object itself has multiple properties, each one according to one possible norm (translational, rotational or a combination) of the transformation representing the relative difference between self and other.
- Parameters:
other (Union[Transformation, TransformationConvertable]) – A Transformation-Like object representing a placement and orientation in space to which the distance shall be measured.
- Return type:
- classmethod from_json_data(d, *args, **kwargs)
Create Transformation from data available in json.
- Parameters:
d (TransformationConvertable)
- classmethod from_json_file(filepath, *args, **kwargs)
Factory method to load a class instance from a json file.
- Parameters:
filepath (Union[pathlib.Path, str]) – The path to the json file.
args – Additional arguments to pass to the from_json_data factory method of the specific class.
kwargs – Additional arguments to pass to the from_json_data factory method of the specific class.
- classmethod from_rotation(R)
Create a placement from a rotation/orientation in the origin.
- Parameters:
R (Collection[Collection[float]])
- classmethod from_roto_translation(R, p)
Create a transformation from a rotation/orientation and a translation.
The resulting transformation: …represents a coordinate system transformation relative to the previous coordinate system s.t. any point x expressed relative to the new coordinate system can be expressed in previous coordinates as \(x_{prev} = T * x_{rel} = R * x_{rel} + p\). …moves a coordinate system by p and rotates it by R (same as above). Note that the rotation is not applied to the translation p!
- Parameters:
- Return type:
- classmethod from_roto_translation_vector(v)
Create a transformation from a stacked roto-translation vector with v[:3]~rotation, v[3:]~translation.
- Parameters:
v (Collection[float]) – A vector \((n_x * \theta_R, n_y * \theta_R, n_z * \theta_R, x, y, z)\), where first three elements are the rotation (in axis angle representation) and the last three elements are the translation of the transformation.
- Return type:
- classmethod from_translation(p)
Create a placement from a point with default orientation.
- Parameters:
p (Collection[float])
- Return type:
- property homogeneous: numpy.ndarray
The nominal placement as a 4x4 matrix. Alias for placement.
- Return type:
- interpolate(other, alpha)
Interpolate between self and other transformation.
- Parameters:
other (Transformation) – Transformation to interpolate to. Returned if alpha=1
alpha (float) – interpolation parameter (0 = self, 1 = other); inbetween linear interpolation in translation and slerp in rotation (linear in axis-angle space between rotation of self and other)
- Return type:
- property inv: Transformation
The inverse of the placement.
- Return type:
- multiply_from_left(other)
Multiply a transformation from the left.
Multiplication (matmul) from the right side with a numpy array is easy, as it can be done with this @ other. However, other @ this fails due to numpys matmul implementation which cannot be overridden. Use this method to multiply from left with a numpy array.
- Parameters:
other (numpy.ndarray) – A numpy array to multiply.
- Returns:
A new placement.
- Return type:
- classmethod neutral()
Returns a neutral transformation.
- Return type:
- property norm: Norm
Returns the norm object of this transformation; can be queried with different measures.
- Return type:
- property projection: Projection
Returns a projection object that can be used to get projections to different conventions for this placement.
- Return type:
- classmethod random(rng=None)
Returns a random transformation where the L1-Norm of the translation \(\leq\) 3.
- Parameters:
rng (Optional[numpy.random.Generator])
- Return type:
- property rotation: numpy.ndarray
The rotation part of the nominal placement as a 3x3 matrix.
- Return type:
- property serialized: List[List[float]]
Returns a serialized description if the nominal placement.
- Return type:
List[List[float]]
- to_json_data()
Returns a serialized description if the nominal placement.
- to_json_file(save_at, *args, **kwargs)
Writes the instance to a json file.
- Parameters:
save_at (Union[pathlib.Path, str]) – File location or folder to write the class to.
- property translation: numpy.ndarray
The translation part of the nominal placement as a 3x1 vector.
- Return type:
- visualize(viz, name, scale=1.0, text=None, text_color='black', background_color='transparent')
Draws this placement inside the visualizer object
- Parameters:
viz (pinocchio.visualize.MeshcatVisualizer) – Visualizer to add placement to
name (str) – label to add geometry to viewer under (overwrites existing!)
scale (float) – Size in meter of each axis of placement
text (Optional[str]) – Optional descriptive text put next to placement
text_color (str) – Color of text (e.g. “red”, “#ff0000”, or any CSS color definition, see https://developer.mozilla.org/en-US/docs/Web/CSS/color_value)
background_color (str) – Color of background of text (e.g. “red”, “#ff0000”, or any CSS color definition, see https://developer.mozilla.org/en-US/docs/Web/CSS/color_value)
- timor.utilities.transformation.TransformationConvertable
- timor.utilities.transformation.TransformationLike
- timor.utilities.transformation._TransformationConvertable