sym.pose3 module¶
- class Pose3(R=None, t=None)[source]¶
Bases:
object
Autogenerated Python implementation of <class ‘symforce.geo.pose3.Pose3’>.
Group of three-dimensional rigid body transformations - SO(3) x R3.
The storage is a quaternion (x, y, z, w) for rotation followed by position (x, y, z).
The tangent space is 3 elements for rotation followed by 3 elements for translation in the non-rotated frame.
For Lie group enthusiasts: This class is on the PRODUCT manifold. On this class, the group operations (e.g. compose and between) operate as you’d expect for a Pose or SE(3), but the manifold operations (e.g. retract and local_coordinates) operate on the product manifold SO(3) x R3. This means that:
retract(a, vec) != compose(a, from_tangent(vec))
local_coordinates(a, b) != to_tangent(between(a, b))
There is no hat operator, because from_tangent/to_tangent is not the matrix exp/log
If you need a type that has these properties in symbolic expressions, you should use
symforce.geo.unsupported.pose3_se3.Pose3_SE3
. There is no runtime equivalent ofPose3_SE3
, see the docstring on that class for more information.- Parameters:
R (
Optional
[Rot3
]) –t (
Union
[Sequence
[float
],ndarray
,None
]) –
- __init__(R=None, t=None)[source]¶
- Parameters:
R (
Optional
[Rot3
]) –t (
Union
[Sequence
[float
],ndarray
,None
]) –
- data¶
- property t: ndarray¶
Accessor for the position component, equivalent to self.position()
- Return type:
ndarray
- compose_with_point(right)[source]¶
Left-multiply with a compatible quantity.
- Parameters:
right (
Pose3
) –- Return type:
ndarray
- inverse_compose(point)[source]¶
This function was autogenerated from a symbolic function. Do not modify by hand.
Symbolic function: pose3_inverse_compose
- Parameters:
point (
Pose3
) – Matrix31
- Outputs:
res: Matrix31
- Return type:
ndarray
- classmethod from_tangent(vec, epsilon=1e-08)[source]¶
- Parameters:
vec (
ndarray
) –epsilon (
float
) –
- Return type: