sym.pose2 module¶
- class Pose2(R=None, t=None)[source]¶
Bases:
object
Autogenerated Python implementation of
symforce.geo.pose2.Pose2
.Group of two-dimensional rigid body transformations - R2 x SO(2).
The storage space is a complex (real, imag) for rotation followed by a position (x, y).
The tangent space is one angle for rotation followed by two 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(2), but the manifold operations (e.g. retract and local_coordinates) operate on the product manifold SO(2) x R2. 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.pose2_se2.Pose2_SE2
. There is no runtime equivalent ofPose2_SE2
, see the docstring on that class for more information.- Parameters:
R (T.Optional[Rot2]) –
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.
- to_homogenous_matrix()[source]¶
A matrix representation of this element in the Euclidean space that contains it.
- Returns:
3x3 Matrix
- Return type: