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 of Pose3_SE3, see the docstring on that class for more information.

Parameters:
data#
property R: Rot3#

Accessor for the rotation component, equivalent to self.rotation()

property t: ndarray#

Accessor for the position component, equivalent to self.position()

rotation()[source]#
Return type:

Rot3

rotation_storage()[source]#

Returns the rotational component of this pose.

Return type:

ndarray

position()[source]#

Returns the positional component of this pose.

Return type:

ndarray

compose_with_point(right)[source]#

Left-multiply with a compatible quantity.

Parameters:

right (Pose3) –

Return type:

ndarray

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.

Parameters:

point (Pose3) –

Return type:

ndarray

to_homogenous_matrix()[source]#

4x4 matrix representing this pose transform.

Return type:

ndarray

static storage_dim()[source]#
Return type:

int

to_storage()[source]#
Return type:

List[float]

classmethod from_storage(vec)[source]#
Parameters:

vec (Sequence[float]) –

Return type:

Pose3

classmethod identity()[source]#
Return type:

Pose3

inverse()[source]#
Return type:

Pose3

compose(b)[source]#
Parameters:

b (Pose3) –

Return type:

Pose3

between(b)[source]#
Parameters:

b (Pose3) –

Return type:

Pose3

static tangent_dim()[source]#
Return type:

int

classmethod from_tangent(vec, epsilon=1e-08)[source]#
Parameters:
Return type:

Pose3

to_tangent(epsilon=1e-08)[source]#
Parameters:

epsilon (float) –

Return type:

ndarray

retract(vec, epsilon=1e-08)[source]#
Parameters:
Return type:

Pose3

local_coordinates(b, epsilon=1e-08)[source]#
Parameters:
Return type:

ndarray

interpolate(b, alpha, epsilon=1e-08)[source]#
Parameters:
Return type:

Pose3