Template Class Sim3Base
Defined in File sim3.hpp
Class Documentation
-
template<class Derived>
class Sim3Base 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.
Public Types
-
using Line = ParametrizedLine3<Scalar>
-
using Hyperplane = Hyperplane3<Scalar>
-
template<typename OtherDerived>
using ReturnScalar = typename Eigen::ScalarBinaryOpTraits<Scalar, typename OtherDerived::Scalar>::ReturnType For binary operations the return type is determined with the ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map types, as well as other compatible scalar types such as Ceres::Jet and double scalars with Sim3 operations.
-
template<typename OtherDerived>
using Sim3Product = Sim3<ReturnScalar<OtherDerived>>
-
template<typename PointDerived>
using PointProduct = Vector3<ReturnScalar<PointDerived>>
-
template<typename HPointDerived>
using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>
Public Functions
- inline SOPHUS_FUNC Adjoint Adj () const
Adjoint transformation
This function return the adjoint transformation
Ad
of the group elementA
such that for allx
it holds thathat(Ad_A * x) = A * hat(x) A^{-1}
. See hat-operator below.
- template<class NewScalarType> inline SOPHUS_FUNC Sim3< NewScalarType > cast () const
Returns copy of instance casted to NewScalarType.
- inline SOPHUS_FUNC Sim3< Scalar > inverse () const
Returns group inverse.
- inline SOPHUS_FUNC Tangent log () const
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(.))
withlogmat(.)
being the matrix logarithm andvee(.)
the vee-operator of Sim(3).
- inline SOPHUS_FUNC Transformation matrix () const
Returns 4x4 matrix representation of the instance.
It has the following form:
where| s*R t | | o 1 |
R
is a 3x3 rotation matrix,s
a scale factor,t
a translation 3-vector ando
a 3-column vector of zeros.
- inline SOPHUS_FUNC Matrix< Scalar, 3, 4 > matrix3x4 () const
Returns the significant first three rows of the matrix above.
- template<class OtherDerived> inline SOPHUS_FUNC Sim3Base< Derived > & operator= (Sim3Base< OtherDerived > const &other)
Assignment-like operator from OtherDerived.
- template<typename OtherDerived> inline SOPHUS_FUNC Sim3Product< OtherDerived > operator* (Sim3Base< OtherDerived > const &other) const
Group multiplication, which is rotation plus scaling concatenation.
Note: That scaling is calculated with saturation. See RxSO3 for details.
- template<typename PointDerived, typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 3>::value>::type> inline SOPHUS_FUNC PointProduct< PointDerived > operator* (Eigen::MatrixBase< PointDerived > const &p) const
Group action on 3-points.
This function rotates, scales and translates a three dimensional point
p
by the Sim(3) element(bar_sR_foo, t_bar)
(= similarity transformation):p_bar = bar_sR_foo * p_foo + t_bar
.
- template<typename HPointDerived, typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 4>::value>::type> inline SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
Group action on homogeneous 3-points. See above for more details.
- inline SOPHUS_FUNC Line operator* (Line const &l) const
Group action on lines.
This function rotates, scales and translates a parametrized line
l(t) = o + t * d
by the Sim(3) element:Origin
o
is rotated, scaled and translated Directiond
is rotated
- inline SOPHUS_FUNC Hyperplane operator* (Hyperplane const &p) const
Group action on planes.
This function rotates and translates a plane
n.x + d = 0
by the Sim(3) element:Normal vector
n
is rotated Offsetd
is adjusted for scale and translation
- template<typename OtherDerived, typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> inline SOPHUS_FUNC Sim3Base< Derived > & operator*= (Sim3Base< OtherDerived > const &other)
In-place group multiplication. This method is only valid if the return type of the multiplication is compatible with this SO3’s Scalar type.
- inline SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0 () const
Returns derivative of this * Sim3::exp(x) w.r.t. x at x = 0
- inline SOPHUS_FUNC Matrix< Scalar, DoF, num_parameters > Dx_log_this_inv_by_x_at_this () const
Returns derivative of log(this^{-1} * x) by x at x=this.
- inline SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params () const
Returns internal parameters of Sim(3).
It returns (q.imag[0], q.imag[1], q.imag[2], q.real, t[0], t[1], t[2]), with q being the quaternion, t the translation 3-vector.
- inline SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quat)
Setter of non-zero quaternion.
Precondition:
quat
must not be close to zero.
- inline SOPHUS_FUNC QuaternionType const & quaternion () const
Accessor of quaternion.
- inline SOPHUS_FUNC Matrix3< Scalar > rotationMatrix () const
Returns Rotation matrix
- inline SOPHUS_FUNC RxSO3Type & rxso3 ()
Mutator of SO3 group.
- inline SOPHUS_FUNC RxSO3Type const & rxso3 () const
Accessor of SO3 group.
- inline SOPHUS_FUNC Scalar scale () const
Returns scale.
- inline SOPHUS_FUNC void setRotationMatrix (Matrix3< Scalar > &R)
Setter of quaternion using rotation matrix
R
, leaves scale as is.
- inline SOPHUS_FUNC void setScale (Scalar const &scale)
Sets scale and leaves rotation as is.
Note: This function as a significant computational cost, since it has to call the square root twice.
- inline SOPHUS_FUNC void setScaledRotationMatrix (Matrix3< Scalar > const &sR)
Setter of quaternion using scaled rotation matrix
sR
.Precondition: The 3x3 matrix must be “scaled orthogonal” and have a positive determinant.
- inline SOPHUS_FUNC TranslationType & translation ()
Mutator of translation vector
- inline SOPHUS_FUNC TranslationType const & translation () const
Accessor of translation vector
Public Static Attributes
-
static constexpr int DoF = 7
Degrees of freedom of manifold, number of dimensions in tangent space (three for translation, three for rotation and one for scaling).
-
static constexpr int num_parameters = 7
Number of internal parameters used (4-tuple for quaternion, three for translation).
-
static constexpr int N = 4
Group transformations are 4x4 matrices.
-
static constexpr int Dim = 3
Points are 3-dimensional.
-
using Line = ParametrizedLine3<Scalar>