|  | 
| SOPHUS_FUNC Adjoint | Adj () const | 
|  | Adjoint transformation.  More... 
 | 
|  | 
| template<class S  = Scalar> | 
| SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > | angleX () const | 
|  | 
| template<class S  = Scalar> | 
| SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > | angleY () const | 
|  | 
| template<class S  = Scalar> | 
| SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > | angleZ () const | 
|  | 
| template<class NewScalarType > | 
| SOPHUS_FUNC SO3< NewScalarType > | cast () const | 
|  | 
| SOPHUS_FUNC Scalar * | data () | 
|  | 
| SOPHUS_FUNC Scalar const  * | data () const | 
|  | 
| SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > | Dx_this_mul_exp_x_at_0 () const | 
|  | 
| SOPHUS_FUNC SO3< Scalar > | inverse () const | 
|  | 
| SOPHUS_FUNC Tangent | log () const | 
|  | 
| SOPHUS_FUNC TangentAndTheta | logAndTheta () const | 
|  | 
| SOPHUS_FUNC Transformation | matrix () const | 
|  | 
| SOPHUS_FUNC void | normalize () | 
|  | 
| template<typename HPointDerived , typename  = typename std::enable_if<                IsFixedSizeVector<HPointDerived, 4>::value>::type> | 
| SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > | operator* (Eigen::MatrixBase< HPointDerived > const &p) const | 
|  | Group action on homogeneous 3-points. See above for more details.  More... 
 | 
|  | 
| template<typename PointDerived , typename  = typename std::enable_if<                IsFixedSizeVector<PointDerived, 3>::value>::type> | 
| SOPHUS_FUNC PointProduct< PointDerived > | operator* (Eigen::MatrixBase< PointDerived > const &p) const | 
|  | 
| SOPHUS_FUNC Line | operator* (Line const &l) const | 
|  | 
| template<typename OtherDerived > | 
| SOPHUS_FUNC SO3Product< OtherDerived > | operator* (SO3Base< OtherDerived > const &other) const | 
|  | 
| template<typename OtherDerived , typename  = typename std::enable_if<                std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> | 
| SOPHUS_FUNC SO3Base< Derived > & | operator*= (SO3Base< OtherDerived > const &other) | 
|  | 
| SOPHUS_FUNC SO3Base & | operator= (SO3Base const &other)=default | 
|  | 
| template<class OtherDerived > | 
| SOPHUS_FUNC SO3Base< Derived > & | operator= (SO3Base< OtherDerived > const &other) | 
|  | 
| SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > | params () const | 
|  | 
| SOPHUS_FUNC void | setQuaternion (Eigen::Quaternion< Scalar > const &quaternion) | 
|  | 
| SOPHUS_FUNC QuaternionType const  & | unit_quaternion () const | 
|  | 
template<class Derived>
class Sophus::SO3Base< Derived >
SO3 base type - implements SO3 class but is storage agnostic.
SO(3) is the group of rotations in 3d. As a matrix group, it is the set of matrices which are orthogonal such that R * R' = I (with R' being the transpose of R) and have a positive determinant. In particular, the determinant is 1. Internally, the group is represented as a unit quaternion. Unit quaternion can be seen as members of the special unitary group SU(2). SU(2) is a double cover of SO(3). Hence, for every rotation matrix R, there exist two unit quaternions: (r, v) and (-r, -v), with r the real part and v being the imaginary 3-vector part of the quaternion.
SO(3) is a compact, but non-commutative group. First it is compact since the set of rotation matrices is a closed and bounded set. Second it is non-commutative since the equation R_1 * R_2 = R_2 * R_1 does not hold in general. For example rotating an object by some degrees about its x-axis and then by some degrees about its y axis, does not lead to the same orientation when rotation first about y and then about x.
Class invariant: The 2-norm of unit_quaternion must be close to 1. Technically speaking, it must hold that:
|unit_quaternion().squaredNorm() - 1| <= Constants::epsilon(). 
Definition at line 74 of file so3.hpp.
template<class Derived > 
template<typename PointDerived , typename  = typename std::enable_if<                IsFixedSizeVector<PointDerived, 3>::value>::type> 
 
Group action on 3-points.
This function rotates a 3 dimensional point p by the SO3 element bar_R_foo (= rotation matrix): p_bar = bar_R_foo * p_foo.
Since SO3 is internally represented by a unit quaternion q, it is implemented as p_bar = q * p_foo * q^{*} with q^{*} being the quaternion conjugate of q.
Geometrically, p is rotated by angle |omega| around the axis omega/|omega| with omega := vee(log(bar_R_foo)).
For vee-operator, see below. 
NOTE: We cannot use Eigen's Quaternion transformVector because it always returns a Vector3 of the same Scalar as this quaternion, so it is not able to be applied to Jets and doubles correctly.
Definition at line 357 of file so3.hpp.