sym.rot2 module¶
- class Rot2(z=None)[source]¶
Bases:
object
Autogenerated Python implementation of
symforce.geo.rot2.Rot2
.Group of two-dimensional orthogonal matrices with determinant
+1
, representing rotations in 2D space. Backed by a complex number.- Parameters:
z (T.Union[T.Sequence[float], numpy.ndarray, None]) –
- compose_with_point(right)[source]¶
Left-multiplication. Either rotation concatenation or point transform.
- static from_angle(theta)[source]¶
Create a Rot2 from an angle
theta
in radiansThis is equivalent to
from_tangent([theta])
- to_rotation_matrix()[source]¶
A matrix representation of this element in the Euclidean space that contains it.
- Return type:
- static from_rotation_matrix(r)[source]¶
Create a Rot2 from a 2x2 rotation matrix.
Returns the closest Rot2 to the input matrix, by the Frobenius norm. Will be singular when
r[0, 0] == -r[1, 1]
andr[0, 1] == r[1, 0]
are both true.See notebooks/rot2_from_rotation_matrix_derivation.ipynb for the derivation.
- static random_from_uniform_sample(u1)[source]¶
Generate a random element of SO2 from a variable uniformly sampled on [0, 1].