#include <sim3.hpp>
Public Types | |
using | Adjoint = Matrix< Scalar, DoF, DoF > |
using | HomogeneousPoint = Vector4< Scalar > |
template<typename HPointDerived > | |
using | HomogeneousPointProduct = Vector4< ReturnScalar< HPointDerived > > |
using | Line = ParametrizedLine3< Scalar > |
using | Point = Vector3< Scalar > |
template<typename PointDerived > | |
using | PointProduct = Vector3< ReturnScalar< PointDerived > > |
using | QuaternionType = typename RxSO3Type::QuaternionType |
template<typename OtherDerived > | |
using | ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType |
using | RxSO3Type = typename Eigen::internal::traits< Derived >::RxSO3Type |
using | Scalar = typename Eigen::internal::traits< Derived >::Scalar |
template<typename OtherDerived > | |
using | Sim3Product = Sim3< ReturnScalar< OtherDerived > > |
using | Tangent = Vector< Scalar, DoF > |
using | Transformation = Matrix< Scalar, N, N > |
using | TranslationType = typename Eigen::internal::traits< Derived >::TranslationType |
Public Member Functions | |
SOPHUS_FUNC Adjoint | Adj () const |
template<class NewScalarType > | |
SOPHUS_FUNC Sim3< NewScalarType > | cast () const |
SOPHUS_FUNC Sim3< Scalar > | inverse () const |
SOPHUS_FUNC Tangent | log () const |
SOPHUS_FUNC Transformation | matrix () const |
SOPHUS_FUNC Matrix< Scalar, 3, 4 > | matrix3x4 () const |
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 Sim3Product< OtherDerived > | operator* (Sim3Base< OtherDerived > const &other) const |
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> | |
SOPHUS_FUNC Sim3Base< Derived > & | operator*= (Sim3Base< OtherDerived > const &other) |
SOPHUS_FUNC Sim3Base & | operator= (Sim3Base const &other)=default |
template<class OtherDerived > | |
SOPHUS_FUNC Sim3Base< Derived > & | operator= (Sim3Base< OtherDerived > const &other) |
SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > | params () const |
SOPHUS_FUNC QuaternionType const & | quaternion () const |
SOPHUS_FUNC Matrix3< Scalar > | rotationMatrix () const |
SOPHUS_FUNC RxSO3Type & | rxso3 () |
SOPHUS_FUNC RxSO3Type const & | rxso3 () const |
SOPHUS_FUNC Scalar | scale () const |
SOPHUS_FUNC void | setQuaternion (Eigen::Quaternion< Scalar > const &quat) |
SOPHUS_FUNC void | setRotationMatrix (Matrix3< Scalar > &R) |
SOPHUS_FUNC void | setScale (Scalar const &scale) |
SOPHUS_FUNC void | setScaledRotationMatrix (Matrix3< Scalar > const &sR) |
SOPHUS_FUNC TranslationType & | translation () |
SOPHUS_FUNC TranslationType const & | translation () const |
Static Public Attributes | |
static constexpr int | DoF = 7 |
static constexpr int | N = 4 |
Group transformations are 4x4 matrices. More... | |
static constexpr int | num_parameters = 7 |
Sim3 base type - implements Sim3 class but is storage agnostic.
Sim(3) is the group of rotations and translation and scaling in 3d. It is the semi-direct product of R+xSO(3) and the 3d Euclidean vector space. The class is represented using a composition of RxSO3 for scaling plus rotation and a 3-vector for translation.
Sim(3) is neither compact, nor a commutative group.
See RxSO3 for more details of the scaling + rotation representation in 3d.
using Sophus::Sim3Base< Derived >::HomogeneousPoint = Vector4<Scalar> |
using Sophus::Sim3Base< Derived >::HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived> > |
using Sophus::Sim3Base< Derived >::Line = ParametrizedLine3<Scalar> |
using Sophus::Sim3Base< Derived >::Point = Vector3<Scalar> |
using Sophus::Sim3Base< Derived >::PointProduct = Vector3<ReturnScalar<PointDerived> > |
using Sophus::Sim3Base< Derived >::QuaternionType = typename RxSO3Type::QuaternionType |
using Sophus::Sim3Base< Derived >::ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar>::ReturnType |
using Sophus::Sim3Base< Derived >::RxSO3Type = typename Eigen::internal::traits<Derived>::RxSO3Type |
using Sophus::Sim3Base< Derived >::Scalar = typename Eigen::internal::traits<Derived>::Scalar |
using Sophus::Sim3Base< Derived >::Sim3Product = Sim3<ReturnScalar<OtherDerived> > |
using Sophus::Sim3Base< Derived >::Tangent = Vector<Scalar, DoF> |
using Sophus::Sim3Base< Derived >::Transformation = Matrix<Scalar, N, N> |
using Sophus::Sim3Base< Derived >::TranslationType = typename Eigen::internal::traits<Derived>::TranslationType |
|
inline |
|
inline |
|
inline |
|
inline |
Logarithmic map
Computes the logarithm, the inverse of the group exponential which maps element of the group (rigid body transformations) to elements of the tangent space (twist).
To be specific, this function computes vee(logmat(.))
with logmat(.)
being the matrix logarithm and vee(.)
the vee-operator of Sim(3).
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
default |
Assignment operator.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |