|  | 
| SOPHUS_FUNC Adjoint | Adj () const | 
|  | 
| Scalar | angleX () const | 
|  | 
| Scalar | angleY () const | 
|  | 
| Scalar | angleZ () const | 
|  | 
| template<class NewScalarType > | 
| SOPHUS_FUNC SE3< NewScalarType > | cast () const | 
|  | 
| SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > | Dx_this_mul_exp_x_at_0 () const | 
|  | 
| SOPHUS_FUNC SE3< Scalar > | inverse () const | 
|  | 
| SOPHUS_FUNC Tangent | log () const | 
|  | 
| SOPHUS_FUNC Transformation | matrix () const | 
|  | 
| SOPHUS_FUNC Matrix< Scalar, 3, 4 > | matrix3x4 () 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 | 
|  | 
| 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 SE3Product< OtherDerived > | operator* (SE3Base< OtherDerived > const &other) const | 
|  | 
| template<typename OtherDerived , typename  = typename std::enable_if<                std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> | 
| SOPHUS_FUNC SE3Base< Derived > & | operator*= (SE3Base< OtherDerived > const &other) | 
|  | 
| SOPHUS_FUNC SE3Base & | operator= (SE3Base const &other)=default | 
|  | 
| template<class OtherDerived > | 
| SOPHUS_FUNC SE3Base< Derived > & | operator= (SE3Base< OtherDerived > const &other) | 
|  | 
| SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > | params () const | 
|  | 
| SOPHUS_FUNC Matrix3< Scalar > | rotationMatrix () const | 
|  | 
| SOPHUS_FUNC void | setQuaternion (Eigen::Quaternion< Scalar > const &quat) | 
|  | 
| SOPHUS_FUNC void | setRotationMatrix (Matrix3< Scalar > const &R) | 
|  | 
| SOPHUS_FUNC SO3Type & | so3 () | 
|  | 
| SOPHUS_FUNC SO3Type const  & | so3 () const | 
|  | 
| SOPHUS_FUNC TranslationType & | translation () | 
|  | 
| SOPHUS_FUNC TranslationType const  & | translation () const | 
|  | 
| SOPHUS_FUNC QuaternionType const  & | unit_quaternion () const | 
|  | 
template<class Derived>
class Sophus::SE3Base< Derived >
SE3 base type - implements SE3 class but is storage agnostic.
SE(3) is the group of rotations and translation in 3d. It is the semi-direct product of SO(3) and the 3d Euclidean vector space. The class is represented using a composition of SO3 for rotation and a one 3-vector for translation.
SE(3) is neither compact, nor a commutative group.
See SO3 for more details of the rotation representation in 3d. 
Definition at line 58 of file se3.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 and translates a three dimensional point p by the SE(3) element bar_T_foo = (bar_R_foo, t_bar) (= rigid body transformation):
p_bar = bar_R_foo * p_foo + t_bar. 
Definition at line 325 of file se3.hpp.
 
 
Returns internal parameters of SE(3).
It returns (q.imag[0], q.imag[1], q.imag[2], q.real, t[0], t[1], t[2]), with q being the unit quaternion, t the translation 3-vector. 
Definition at line 403 of file se3.hpp.