timor.utilities.transformation ============================== .. py:module:: timor.utilities.transformation Attributes ---------- .. autoapisummary:: timor.utilities.transformation.TransformationConvertable timor.utilities.transformation.TransformationLike timor.utilities.transformation._TransformationConvertable Classes ------- .. autoapisummary:: timor.utilities.transformation.Norm timor.utilities.transformation.Projection timor.utilities.transformation.Transformation Module Contents --------------- .. py:class:: Norm(transformation) A namespace for norms of transformations. Norms are directly defined on transformations. They return a single, non-negative scalar .. py:property:: rotation_angle :type: float The rotation angle of this transformation about any axis, expressed in radian. .. py:property:: rotation_angle_degree :type: float The rotation angle of this transformation about any axis, expressed in degree. .. py:attribute:: transformation .. py:property:: translation_euclidean :type: float The Euclidean / L2 norm of this transformation's translation. .. py:property:: translation_manhattan :type: float The manhattan / absolute / L1 norm of this transformation's translation .. py:property:: translation_maximum :type: float The maximum / infinity norm of the transformation't translation. .. py:class:: Projection(transformation) A namespace for transformation projections Projections are directly defined on transformations. .. py:property:: axis_angles :type: 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 :math:`(n_x, n_y, n_z, \theta_R)`. .. py:property:: axis_angles3 :type: 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 :math:`(n_x * \theta_R, n_y * \theta_R, n_z * \theta_R), \theta \in [0, \pi]`. .. py:property:: cartesian :type: numpy.ndarray Returns the x, y, z coordinates in a cartesian coordinate system .. py:property:: cylindrical :type: numpy.ndarray Returns the position in cylindrical coordinates [r, phi, z]. .. py:property:: rotation_angle :type: 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 .. py:property:: roto_translation_vector :type: numpy.ndarray Stacks the axis-angle-rotation vec[:3] and translation vec[3:] of a transformation in a (6,)-vector. :returns: A vector :math:`(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. .. py:property:: spherical :type: numpy.ndarray Returns the position in spherical coordinates [r, theta, phi]. .. py:attribute:: transformation .. py:class:: Transformation(transformation, set_safe = False) .. autoapi-inheritance-diagram:: timor.utilities.transformation.Transformation :parts: 1 :private-bases: A transformation describes a translation and rotation in cartesian space. Initialize a spatial transform with a 4x4 matrix which must be a homogeneous transformation. :param transformation: 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. :param set_safe: 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. .. py:method:: __eq__(other) Allows comparison of transformations .. py:method:: __getitem__(item) Allows indexing the transformation without accessing the homogeneous attribute .. py:method:: __getstate__() Return objects which will be pickled and saved. .. py:method:: __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. .. py:method:: __repr__() Show transformation as homog. matrix in debug mode .. py:method:: __setstate__(state) Take object from parameter and use it to retrieve class state. .. py:method:: __str__(precision = 3) Defaults to numpy homogeneous. :param precision: How many decimals to show. .. py:method:: _deduce_package_dir(filepath, content) :staticmethod: Logic for deducing the package directory if the JSONable object is loaded from a file. :param filepath: The path to the file. :param content: 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. .. py:method:: as_transform3f() Returns this transformation as a hppfcl Transform3f .. py:method:: 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. :param other: A Transformation-Like object representing a placement and orientation in space to which the distance shall be measured. .. py:method:: from_json_data(d, *args, **kwargs) :classmethod: Create Transformation from data available in json. .. py:method:: from_json_file(filepath, *args, **kwargs) :classmethod: Factory method to load a class instance from a json file. :param filepath: The path to the json file. :param args: Additional arguments to pass to the from_json_data factory method of the specific class. :param kwargs: Additional arguments to pass to the from_json_data factory method of the specific class. .. py:method:: from_json_string(s, *args, **kwargs) :classmethod: Create from a json string. .. py:method:: from_rotation(R) :classmethod: Create a placement from a rotation/orientation in the origin. .. py:method:: from_roto_translation(R, p) :classmethod: 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 :math:`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! :param R: A 3x3 rotation matrix. :param p: A 3x1 translation vector. .. py:method:: from_roto_translation_vector(v) :classmethod: Create a transformation from a stacked roto-translation vector with v[:3]~rotation, v[3:]~translation. :param v: A vector :math:`(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. .. py:method:: from_translation(p) :classmethod: Create a placement from a point with default orientation. .. py:property:: homogeneous :type: numpy.ndarray The nominal placement as a 4x4 matrix. Alias for placement. .. py:method:: interpolate(other, alpha) Interpolate between self and other transformation. :param other: Transformation to interpolate to. Returned if alpha=1 :param alpha: 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) .. py:property:: inv :type: Transformation The inverse of the placement. .. py:method:: 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. :param other: A numpy array to multiply. :return: A new placement. .. py:method:: neutral() :classmethod: Returns a neutral transformation. .. py:property:: norm :type: Norm Returns the norm object of this transformation; can be queried with different measures. .. py:property:: projection :type: Projection Returns a projection object that can be used to get projections to different conventions for this placement. .. py:method:: random(rng = None) :classmethod: Returns a random transformation where the L1-Norm of the translation :math:`\leq` 3. .. py:property:: rotation :type: numpy.ndarray The rotation part of the nominal placement as a 3x3 matrix. .. py:property:: serialized :type: List[List[float]] Returns a serialized description if the nominal placement. .. py:attribute:: shape :type: Tuple[int, int] :value: (4, 4) .. py:method:: to_json_data() Returns a serialized description if the nominal placement. .. py:method:: to_json_file(save_at, *args, **kwargs) Writes the instance to a json file. :param save_at: File location or folder to write the class to. .. py:method:: to_json_string() Return the json string representation. .. py:property:: translation :type: numpy.ndarray The translation part of the nominal placement as a 3x1 vector. .. py:method:: visualize(viz, name, scale = 1.0, text = None, text_color = 'black', background_color = 'transparent') Draws this placement inside the visualizer object :param viz: Visualizer to add placement to :param name: label to add geometry to viewer under (overwrites existing!) :param scale: Size in meter of each axis of placement :param text: Optional descriptive text put next to placement :param text_color: Color of text (e.g. "red", "#ff0000", or any CSS color definition, see https://developer.mozilla.org/en-US/docs/Web/CSS/color_value) :param background_color: 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) .. py:data:: TransformationConvertable .. py:data:: TransformationLike .. py:data:: _TransformationConvertable