symforce.geo.unsupported.pose3_se3 module¶
- class Pose3_SE3(R=None, t=None)[source]¶
Bases:
Pose3
Group of three-dimensional rigid body transformations - SE(3).
There is no generated runtime analogue of this class in the
sym
package, which means you cannot use it as an input or output of generated functions or as a variable in an optimized Values. This is intentional - in general, you should use thePose3
class instead of this one, because the generated expressions will be significantly more efficient. If you are sure that you need the different behavior of this class, it’s here for reference or for use in symbolic expressions.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 rotated frame, meaning we interpolate the translation in the tangent of the rotating frame for lie operations. This can be useful but is more expensive than SO(3) x R3 for often no benefit.
- Parameters:
R (T.Optional[Rot3]) –
t (T.Optional[Vector3]) –
- classmethod from_tangent(v, epsilon=0.0)[source]¶
Mapping from the tangent space vector about identity into a group element.
- to_tangent(epsilon=0.0)[source]¶
Mapping from this element to the tangent space vector about identity.
- storage_D_tangent()[source]¶
Note: generated from
symforce/notebooks/storage_D_tangent.ipynb
- Return type:
- tangent_D_storage()[source]¶
Note: generated from
symforce/notebooks/tangent_D_storage.ipynb
- Return type:
- 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.
Implementation is simply
compose(self, from_tangent(vec))
. Conceptually representsself + vec
if self is a vector.
- 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.
Implementation is simply
to_tangent(between(self, b))
. Tangent space perturbation that conceptually representsb - self
if self is a vector.