:py:mod:`jaxlie` ================ .. py:module:: jaxlie Subpackages ----------- .. toctree:: :titlesonly: :maxdepth: 3 hints/index.rst manifold/index.rst utils/index.rst Package Contents ---------------- Classes ~~~~~~~ .. autoapisummary:: jaxlie.MatrixLieGroup jaxlie.SEBase jaxlie.SOBase jaxlie.SE2 jaxlie.SE3 jaxlie.SO2 jaxlie.SO3 .. py:class:: MatrixLieGroup(parameters) Bases: :py:obj:`abc.ABC` .. autoapi-inheritance-diagram:: jaxlie.MatrixLieGroup :parts: 1 Interface definition for matrix Lie groups. .. py:attribute:: matrix_dim :type: ClassVar[int] Dimension of square matrix output from ``.as_matrix()``. .. py:attribute:: parameters_dim :type: ClassVar[int] Dimension of underlying parameters, ``.parameters()``. .. py:attribute:: tangent_dim :type: ClassVar[int] Dimension of tangent space. .. py:attribute:: space_dim :type: ClassVar[int] Dimension of coordinates that can be transformed. .. py:method:: __matmul__(other: GroupType) -> GroupType __matmul__(other: jaxlie.hints.Array) -> jax.Array Overload for the ``@`` operator. Switches between the group action (\ ``.apply()``\ ) and multiplication (\ ``.multiply()``\ ) based on the type of ``other``. .. py:method:: identity() :classmethod: :abstractmethod: Returns identity element. :returns: Identity element. .. py:method:: from_matrix(matrix) :classmethod: :abstractmethod: Get group member from matrix representation. :param matrix: Matrix representaiton. :returns: Group member. .. py:method:: as_matrix() :abstractmethod: Get transformation as a matrix. Homogeneous for SE groups. .. py:method:: parameters() :abstractmethod: Get underlying representation. .. py:method:: apply(target) :abstractmethod: Applies group action to a point. :param target: Point to transform. :returns: Transformed point. .. py:method:: multiply(other) :abstractmethod: Composes this transformation with another. :returns: self @ other .. py:method:: exp(tangent) :classmethod: :abstractmethod: Computes ``expm(wedge(tangent))``. :param tangent: Tangent vector to take the exponential of. :returns: Output. .. py:method:: log() :abstractmethod: Computes ``vee(logm(transformation matrix))``. :returns: Output. Shape should be ``(tangent_dim,)``. .. py:method:: adjoint() :abstractmethod: Computes the adjoint, which transforms tangent vectors between tangent spaces. More precisely, for a transform ``GroupType``\ : .. code-block:: GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames. :returns: Output. Shape should be ``(tangent_dim, tangent_dim)``. .. py:method:: inverse() :abstractmethod: Computes the inverse of our transform. :returns: Output. .. py:method:: normalize() :abstractmethod: Normalize/projects values and returns. :returns: *GroupType* -- Normalized group member. .. py:method:: sample_uniform(key) :classmethod: :abstractmethod: Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1]. :param key: PRNG key, as returned by ``jax.random.PRNGKey()``. :returns: Sampled group member. .. py:method:: get_batch_axes() :abstractmethod: Return any leading batch axes in contained parameters. If an array of shape ``(100, 4)`` is placed in the wxyz field of an SO3 object, for example, this will return ``(100,)``. This should generally be implemented by ``jdc.EnforcedAnnotationsMixin``. .. py:class:: SEBase(parameters) Bases: :py:obj:`Generic`\ [\ :py:obj:`ContainedSOType`\ ], :py:obj:`MatrixLieGroup` .. autoapi-inheritance-diagram:: jaxlie.SEBase :parts: 1 Base class for special Euclidean groups. Each SE(N) group member contains an SO(N) rotation, as well as an N-dimensional translation vector. .. py:method:: from_rotation_and_translation(rotation, translation) :classmethod: :abstractmethod: Construct a rigid transform from a rotation and a translation. :param rotation: Rotation term. :param translation: translation term. :returns: Constructed transformation. .. py:method:: from_rotation(rotation) :classmethod: .. py:method:: rotation() :abstractmethod: Returns a transform's rotation term. .. py:method:: translation() :abstractmethod: Returns a transform's translation term. .. py:method:: apply(target) Applies group action to a point. :param target: Point to transform. :returns: Transformed point. .. py:method:: multiply(other) Composes this transformation with another. :returns: self @ other .. py:method:: inverse() Computes the inverse of our transform. :returns: Output. .. py:method:: normalize() Normalize/projects values and returns. :returns: *GroupType* -- Normalized group member. .. py:class:: SOBase(parameters) Bases: :py:obj:`MatrixLieGroup` .. autoapi-inheritance-diagram:: jaxlie.SOBase :parts: 1 Base class for special orthogonal groups. .. py:class:: SE2(parameters) Bases: :py:obj:`jax_dataclasses.EnforcedAnnotationsMixin`, :py:obj:`jaxlie.SEBase`\ [\ :py:obj:`jaxlie.SO2`\ ] .. autoapi-inheritance-diagram:: jaxlie.SE2 :parts: 1 Special Euclidean group for proper rigid transforms in 2D. Internal parameterization is ``(cos, sin, x, y)``. Tangent parameterization is ``(vx, vy, omega)``. .. py:attribute:: unit_complex_xy :type: typing_extensions.Annotated[jax.Array, (Ellipsis, 4), jax.numpy.floating] Internal parameters. ``(cos, sin, x, y)``. .. py:method:: __repr__() Return repr(self). .. py:method:: from_xy_theta(x, y, theta) :staticmethod: Construct a transformation from standard 2D pose parameters. Note that this is not the same as integrating over a length-3 twist. .. py:method:: from_rotation_and_translation(rotation, translation) :staticmethod: Construct a rigid transform from a rotation and a translation. :param rotation: Rotation term. :param translation: translation term. :returns: Constructed transformation. .. py:method:: rotation() Returns a transform's rotation term. .. py:method:: translation() Returns a transform's translation term. .. py:method:: identity() :staticmethod: Returns identity element. :returns: Identity element. .. py:method:: from_matrix(matrix) :staticmethod: Get group member from matrix representation. :param matrix: Matrix representaiton. :returns: Group member. .. py:method:: parameters() Get underlying representation. .. py:method:: as_matrix() Get transformation as a matrix. Homogeneous for SE groups. .. py:method:: exp(tangent) :staticmethod: Computes ``expm(wedge(tangent))``. :param tangent: Tangent vector to take the exponential of. :returns: Output. .. py:method:: log() Computes ``vee(logm(transformation matrix))``. :returns: Output. Shape should be ``(tangent_dim,)``. .. py:method:: adjoint() Computes the adjoint, which transforms tangent vectors between tangent spaces. More precisely, for a transform ``GroupType``\ : .. code-block:: GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames. :returns: Output. Shape should be ``(tangent_dim, tangent_dim)``. .. py:method:: sample_uniform(key) :staticmethod: Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1]. :param key: PRNG key, as returned by ``jax.random.PRNGKey()``. :returns: Sampled group member. .. py:class:: SE3(parameters) Bases: :py:obj:`jax_dataclasses.EnforcedAnnotationsMixin`, :py:obj:`jaxlie.SEBase`\ [\ :py:obj:`jaxlie.SO3`\ ] .. autoapi-inheritance-diagram:: jaxlie.SE3 :parts: 1 Special Euclidean group for proper rigid transforms in 3D. Internal parameterization is ``(qw, qx, qy, qz, x, y, z)``. Tangent parameterization is ``(vx, vy, vz, omega_x, omega_y, omega_z)``. .. py:attribute:: wxyz_xyz :type: typing_extensions.Annotated[jax.Array, (Ellipsis, 7), jax.numpy.floating] Internal parameters. wxyz quaternion followed by xyz translation. .. py:method:: __repr__() Return repr(self). .. py:method:: from_rotation_and_translation(rotation, translation) :staticmethod: Construct a rigid transform from a rotation and a translation. :param rotation: Rotation term. :param translation: translation term. :returns: Constructed transformation. .. py:method:: rotation() Returns a transform's rotation term. .. py:method:: translation() Returns a transform's translation term. .. py:method:: identity() :staticmethod: Returns identity element. :returns: Identity element. .. py:method:: from_matrix(matrix) :staticmethod: Get group member from matrix representation. :param matrix: Matrix representaiton. :returns: Group member. .. py:method:: as_matrix() Get transformation as a matrix. Homogeneous for SE groups. .. py:method:: parameters() Get underlying representation. .. py:method:: exp(tangent) :staticmethod: Computes ``expm(wedge(tangent))``. :param tangent: Tangent vector to take the exponential of. :returns: Output. .. py:method:: log() Computes ``vee(logm(transformation matrix))``. :returns: Output. Shape should be ``(tangent_dim,)``. .. py:method:: adjoint() Computes the adjoint, which transforms tangent vectors between tangent spaces. More precisely, for a transform ``GroupType``\ : .. code-block:: GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames. :returns: Output. Shape should be ``(tangent_dim, tangent_dim)``. .. py:method:: sample_uniform(key) :staticmethod: Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1]. :param key: PRNG key, as returned by ``jax.random.PRNGKey()``. :returns: Sampled group member. .. py:class:: SO2(parameters) Bases: :py:obj:`jax_dataclasses.EnforcedAnnotationsMixin`, :py:obj:`jaxlie.SOBase` .. autoapi-inheritance-diagram:: jaxlie.SO2 :parts: 1 Special orthogonal group for 2D rotations. Internal parameterization is ``(cos, sin)``. Tangent parameterization is ``(omega,)``. .. py:attribute:: unit_complex :type: typing_extensions.Annotated[jax.Array, (Ellipsis, 2), jax.numpy.floating] Internal parameters. ``(cos, sin)``. .. py:method:: __repr__() Return repr(self). .. py:method:: from_radians(theta) :staticmethod: Construct a rotation object from a scalar angle. .. py:method:: as_radians() Compute a scalar angle from a rotation object. .. py:method:: identity() :staticmethod: Returns identity element. :returns: Identity element. .. py:method:: from_matrix(matrix) :staticmethod: Get group member from matrix representation. :param matrix: Matrix representaiton. :returns: Group member. .. py:method:: as_matrix() Get transformation as a matrix. Homogeneous for SE groups. .. py:method:: parameters() Get underlying representation. .. py:method:: apply(target) Applies group action to a point. :param target: Point to transform. :returns: Transformed point. .. py:method:: multiply(other) Composes this transformation with another. :returns: self @ other .. py:method:: exp(tangent) :staticmethod: Computes ``expm(wedge(tangent))``. :param tangent: Tangent vector to take the exponential of. :returns: Output. .. py:method:: log() Computes ``vee(logm(transformation matrix))``. :returns: Output. Shape should be ``(tangent_dim,)``. .. py:method:: adjoint() Computes the adjoint, which transforms tangent vectors between tangent spaces. More precisely, for a transform ``GroupType``\ : .. code-block:: GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames. :returns: Output. Shape should be ``(tangent_dim, tangent_dim)``. .. py:method:: inverse() Computes the inverse of our transform. :returns: Output. .. py:method:: normalize() Normalize/projects values and returns. :returns: *GroupType* -- Normalized group member. .. py:method:: sample_uniform(key) :staticmethod: Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1]. :param key: PRNG key, as returned by ``jax.random.PRNGKey()``. :returns: Sampled group member. .. py:class:: SO3(parameters) Bases: :py:obj:`jax_dataclasses.EnforcedAnnotationsMixin`, :py:obj:`jaxlie.SOBase` .. autoapi-inheritance-diagram:: jaxlie.SO3 :parts: 1 Special orthogonal group for 3D rotations. Internal parameterization is ``(qw, qx, qy, qz)``. Tangent parameterization is ``(omega_x, omega_y, omega_z)``. .. py:attribute:: wxyz :type: typing_extensions.Annotated[jax.Array, (Ellipsis, 4), jax.numpy.floating] Internal parameters. ``(w, x, y, z)`` quaternion. .. py:method:: __repr__() Return repr(self). .. py:method:: from_x_radians(theta) :staticmethod: Generates a x-axis rotation. :param angle: X rotation, in radians. :returns: Output. .. py:method:: from_y_radians(theta) :staticmethod: Generates a y-axis rotation. :param angle: Y rotation, in radians. :returns: Output. .. py:method:: from_z_radians(theta) :staticmethod: Generates a z-axis rotation. :param angle: Z rotation, in radians. :returns: Output. .. py:method:: from_rpy_radians(roll, pitch, yaw) :staticmethod: Generates a transform from a set of Euler angles. Uses the ZYX mobile robot convention. :param roll: X rotation, in radians. Applied first. :param pitch: Y rotation, in radians. Applied second. :param yaw: Z rotation, in radians. Applied last. :returns: Output. .. py:method:: from_quaternion_xyzw(xyzw) :staticmethod: Construct a rotation from an ``xyzw`` quaternion. Note that ``wxyz`` quaternions can be constructed using the default dataclass constructor. :param xyzw: xyzw quaternion. Shape should be (4,). :returns: Output. .. py:method:: as_quaternion_xyzw() Grab parameters as xyzw quaternion. .. py:method:: as_rpy_radians() Computes roll, pitch, and yaw angles. Uses the ZYX mobile robot convention. :returns: Named tuple containing Euler angles in radians. .. py:method:: compute_roll_radians() Compute roll angle. Uses the ZYX mobile robot convention. :returns: Euler angle in radians. .. py:method:: compute_pitch_radians() Compute pitch angle. Uses the ZYX mobile robot convention. :returns: Euler angle in radians. .. py:method:: compute_yaw_radians() Compute yaw angle. Uses the ZYX mobile robot convention. :returns: Euler angle in radians. .. py:method:: identity() :staticmethod: Returns identity element. :returns: Identity element. .. py:method:: from_matrix(matrix) :staticmethod: Get group member from matrix representation. :param matrix: Matrix representaiton. :returns: Group member. .. py:method:: as_matrix() Get transformation as a matrix. Homogeneous for SE groups. .. py:method:: parameters() Get underlying representation. .. py:method:: apply(target) Applies group action to a point. :param target: Point to transform. :returns: Transformed point. .. py:method:: multiply(other) Composes this transformation with another. :returns: self @ other .. py:method:: exp(tangent) :staticmethod: Computes ``expm(wedge(tangent))``. :param tangent: Tangent vector to take the exponential of. :returns: Output. .. py:method:: log() Computes ``vee(logm(transformation matrix))``. :returns: Output. Shape should be ``(tangent_dim,)``. .. py:method:: adjoint() Computes the adjoint, which transforms tangent vectors between tangent spaces. More precisely, for a transform ``GroupType``\ : .. code-block:: GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames. :returns: Output. Shape should be ``(tangent_dim, tangent_dim)``. .. py:method:: inverse() Computes the inverse of our transform. :returns: Output. .. py:method:: normalize() Normalize/projects values and returns. :returns: *GroupType* -- Normalized group member. .. py:method:: sample_uniform(key) :staticmethod: Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1]. :param key: PRNG key, as returned by ``jax.random.PRNGKey()``. :returns: Sampled group member.