#include <rxso3.hpp>
Classes | |
struct | TangentAndTheta |
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 Eigen::internal::traits< Derived >::QuaternionType |
template<typename OtherDerived > | |
using | ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType |
template<typename OtherDerived > | |
using | RxSO3Product = RxSO3< ReturnScalar< OtherDerived > > |
using | Scalar = typename Eigen::internal::traits< Derived >::Scalar |
using | Tangent = Vector< Scalar, DoF > |
using | Transformation = Matrix< Scalar, N, N > |
Public Member Functions | |
SOPHUS_FUNC Adjoint | Adj () const |
template<class NewScalarType > | |
SOPHUS_FUNC RxSO3< NewScalarType > | cast () const |
SOPHUS_FUNC Scalar * | data () |
SOPHUS_FUNC Scalar const * | data () const |
SOPHUS_FUNC RxSO3< Scalar > | inverse () const |
SOPHUS_FUNC Tangent | log () const |
SOPHUS_FUNC TangentAndTheta | logAndTheta () const |
SOPHUS_FUNC Transformation | matrix () 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 RxSO3Product< OtherDerived > | operator* (RxSO3Base< OtherDerived > const &other) const |
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> | |
SOPHUS_FUNC RxSO3Base< Derived > & | operator*= (RxSO3Base< OtherDerived > const &other) |
SOPHUS_FUNC RxSO3Base & | operator= (RxSO3Base const &other)=default |
template<class OtherDerived > | |
SOPHUS_FUNC RxSO3Base< Derived > & | operator= (RxSO3Base< OtherDerived > const &other) |
SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > | params () const |
SOPHUS_FUNC QuaternionType const & | quaternion () const |
SOPHUS_FUNC Transformation | rotationMatrix () const |
SOPHUS_FUNC Scalar | scale () const |
SOPHUS_FUNC void | setQuaternion (Eigen::Quaternion< Scalar > const &quat) |
SOPHUS_FUNC void | setRotationMatrix (Transformation const &R) |
SOPHUS_FUNC void | setScale (Scalar const &scale) |
SOPHUS_FUNC void | setScaledRotationMatrix (Transformation const &sR) |
SOPHUS_FUNC void | setSO3 (SO3< Scalar > const &so3) |
SOPHUS_FUNC SO3< Scalar > | so3 () const |
Static Public Attributes | |
static constexpr int | DoF = 4 |
static constexpr int | N = 3 |
Group transformations are 3x3 matrices. More... | |
static constexpr int | num_parameters = 4 |
Number of internal parameters used (quaternion is a 4-tuple). More... | |
Protected Member Functions | |
SOPHUS_FUNC QuaternionType & | quaternion_nonconst () |
RxSO3 base type - implements RxSO3 class but is storage agnostic
This class implements the group R+ x SO(3)
, the direct product of the group of positive scalar 3x3 matrices (= isomorph to the positive real numbers) and the three-dimensional special orthogonal group SO(3). Geometrically, it is the group of rotation and scaling in three dimensions. As a matrix groups, RxSO3 consists of matrices of the form s * R
where R
is an orthogonal matrix with det(R)=1
and s > 0
being a positive real number.
Internally, RxSO3 is represented by the group of non-zero quaternions. In particular, the scale equals the squared(!) norm of the quaternion q
, s = |q|^2
. This is a most compact representation since the degrees of freedom (DoF) of RxSO3 (=4) equals the number of internal parameters (=4).
This class has the explicit class invariant that the scale s
is not too close to zero. Strictly speaking, it must hold that:
quaternion().squaredNorm() >= Constants::epsilon()
.
In order to obey this condition, group multiplication is implemented with saturation such that a product always has a scale which is equal or greater this threshold.
using Sophus::RxSO3Base< Derived >::HomogeneousPoint = Vector4<Scalar> |
using Sophus::RxSO3Base< Derived >::HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived> > |
using Sophus::RxSO3Base< Derived >::Line = ParametrizedLine3<Scalar> |
using Sophus::RxSO3Base< Derived >::Point = Vector3<Scalar> |
using Sophus::RxSO3Base< Derived >::PointProduct = Vector3<ReturnScalar<PointDerived> > |
using Sophus::RxSO3Base< Derived >::QuaternionType = typename Eigen::internal::traits<Derived>::QuaternionType |
using Sophus::RxSO3Base< Derived >::ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar>::ReturnType |
using Sophus::RxSO3Base< Derived >::RxSO3Product = RxSO3<ReturnScalar<OtherDerived> > |
using Sophus::RxSO3Base< Derived >::Scalar = typename Eigen::internal::traits<Derived>::Scalar |
using Sophus::RxSO3Base< Derived >::Tangent = Vector<Scalar, DoF> |
using Sophus::RxSO3Base< Derived >::Transformation = Matrix<Scalar, N, N> |
|
inline |
Adjoint transformation
This function return the adjoint transformation Ad
of the group element A
such that for all x
it holds that hat(Ad_A * x) = A * hat(x) A^{-1}
. See hat-operator below.
For RxSO(3), it simply returns the rotation matrix corresponding to A
.
|
inline |
|
inline |
This provides unsafe read/write access to internal data. RxSO(3) is represented by an Eigen::Quaternion (four parameters). When using direct write access, the user needs to take care of that the quaternion is not set close to zero.
Note: The first three Scalars represent the imaginary parts, while the forth Scalar represent the real part.
|
inline |
|
inline |
|
inline |
Logarithmic map
Computes the logarithm, the inverse of the group exponential which maps element of the group (scaled rotation matrices) to elements of the tangent space (rotation-vector plus logarithm of scale factor).
To be specific, this function computes vee(logmat(.))
with logmat(.)
being the matrix logarithm and vee(.)
the vee-operator of RxSO3.
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
default |
Assignment operator.
|
inline |
|
inline |
|
inline |
|
inlineprotected |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |