sym.pose3 module#
- class Pose3(R=None, t=None)[source]#
Bases:
object
Autogenerated Python implementation of
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 (T.Optional[Rot3]) –
t (T.Union[T.Sequence[float], numpy.ndarray, None]) –
- data#
- inverse_compose(point)[source]#
Returns
self.inverse() * point
This is more efficient than calling the generated inverse and compose methods separately, if doing this for one point.