symforce.geo.pose3 module#

class Pose3(R=None, t=None)[source]#

Bases: LieGroup

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:
  • R (T.Optional[Rot3]) –

  • t (T.Optional[Vector3]) –

Pose3T = ~Pose3T#
rotation()[source]#

Accessor for the rotation component

Does not make a copy. Also accessible as self.R

Return type:

Rot3

position()[source]#

Accessor for the position component

Does not make a copy. Also accessible as self.t

Return type:

Matrix31

classmethod storage_dim()[source]#

Dimension of underlying storage

Return type:

int

to_storage()[source]#

Flat list representation of the underlying storage, length of storage_dim(). This is used purely for plumbing, it is NOT like a tangent space.

Return type:

List[float]

classmethod from_storage(vec)[source]#

Construct from a flat list representation. Opposite of to_storage().

Parameters:

vec (T.Sequence[T.Scalar]) –

Return type:

Pose3T

classmethod symbolic(name, **kwargs)[source]#

Construct a symbolic element with the given name prefix. Kwargs are forwarded to sf.Symbol (for example, sympy assumptions).

Parameters:
  • name (str) –

  • kwargs (T.Any) –

Return type:

Pose3T

classmethod identity()[source]#

Identity element such that compose(a, identity) = a.

Return type:

Pose3T

compose(other)[source]#

Apply the group operation with other.

Parameters:
  • self (Pose3T) –

  • other (Pose3T) –

Return type:

Pose3T

inverse()[source]#

Group inverse, such that compose(a, inverse(a)) = identity.

Parameters:

self (Pose3T) –

Return type:

Pose3T

classmethod tangent_dim()[source]#

Dimension of the embedded manifold

Return type:

int

classmethod from_tangent(v, epsilon=0.0)[source]#

Mapping from the tangent space vector about identity into a group element.

Parameters:
  • v (T.Sequence[T.Scalar]) –

  • epsilon (T.Scalar) –

Return type:

Pose3T

to_tangent(epsilon=0.0)[source]#

Mapping from this element to the tangent space vector about identity.

Parameters:
  • self (Pose3T) –

  • epsilon (T.Scalar) –

Return type:

T.List[T.Scalar]

storage_D_tangent()[source]#

Note: generated from symforce/notebooks/storage_D_tangent.ipynb

Parameters:

self (Pose3T) –

Return type:

Matrix

tangent_D_storage()[source]#

Note: generated from symforce/notebooks/tangent_D_storage.ipynb

Parameters:

self (Pose3T) –

Return type:

Matrix

retract(vec, epsilon=0.0)[source]#

Applies a tangent space perturbation vec to self. Often used in optimization to update nonlinear values from an update step in the tangent space.

Conceptually represents self + vec if self is a vector.

Implementation retracts the R and t components separately, which is different from compose(self, from_tangent(vec)). See the class docstring for more information.

Parameters:
  • self (Pose3T) –

  • vec (T.Sequence[T.Scalar]) –

  • epsilon (T.Scalar) –

Return type:

Pose3T

local_coordinates(b, epsilon=0.0)[source]#

Computes a tangent space perturbation around self to produce b. Often used in optimization to minimize the distance between two group elements.

Tangent space perturbation that conceptually represents b - self if self is a vector.

Implementation takes local_coordinates of the R and t components separately, which is different from to_tangent(between(self, b)). See the class docstring for more information.

Parameters:
  • self (Pose3T) –

  • b (Pose3T) –

  • epsilon (T.Scalar) –

Return type:

T.List[T.Scalar]

__mul__(right)[source]#

Left-multiply with a compatible quantity.

Parameters:
  • self (Pose3T) –

  • right (T.Union[Pose3T, Vector3]) –

Return type:

T.Union[Pose3T, Vector3]

to_homogenous_matrix()[source]#

4x4 matrix representing this pose transform.

Return type:

Matrix