Template Class RxSO3Base
Defined in File rxso3.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Derived Type
public Sophus::RxSO3< Scalar, Options >
(Template Class RxSO3)
Class Documentation
-
template<class Derived>
class RxSO3Base 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 forms * R
whereR
is an orthogonal matrix withdet(R)=1
ands > 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 either zero or infinity. Strictly speaking, it must hold that:quaternion().squaredNorm() >= Constants::epsilon()
and1. / 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.
Subclassed by Sophus::RxSO3< Scalar, Options >
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 RxSO3 operations.
-
template<typename OtherDerived>
using RxSO3Product = RxSO3<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.For RxSO(3), it simply returns the rotation matrix corresponding to
A
.
- template<class NewScalarType> inline SOPHUS_FUNC RxSO3< NewScalarType > cast () const
Returns copy of instance casted to NewScalarType.
- inline SOPHUS_FUNC Scalar * data ()
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 SOPHUS_FUNC Scalar const * data () const
Const version of data() above.
- inline SOPHUS_FUNC RxSO3< 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 (scaled rotation matrices) to elements of the tangent space (rotation-vector plus logarithm of scale factor).
To be specific, this function computes
vee(logmat(.))
withlogmat(.)
being the matrix logarithm andvee(.)
the vee-operator of RxSO3.
- inline SOPHUS_FUNC TangentAndTheta logAndTheta () const
As above, but also returns
theta = |omega|
.
- inline SOPHUS_FUNC Transformation matrix () const
Returns 3x3 matrix representation of the instance.
For RxSO3, the matrix representation is an scaled orthogonal matrix
sR
withdet(R)=s^3
, thus a scaled rotation matrixR
with scales
.
- template<class OtherDerived> inline SOPHUS_FUNC RxSO3Base< Derived > & operator= (RxSO3Base< OtherDerived > const &other)
Assignment-like operator from OtherDerived.
- template<typename OtherDerived> inline SOPHUS_FUNC RxSO3Product< OtherDerived > operator* (RxSO3Base< OtherDerived > const &other) const
Group multiplication, which is rotation concatenation and scale multiplication.
Note: This function performs saturation for products close to zero in order to ensure the class invariant.
- 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 a 3 dimensional point
p
by the SO3 elementbar_R_foo
(= rotation matrix) and scales it by the scale factors
:p_bar = s * (bar_R_foo * p_foo)
.
- 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 a parametrized line
l(t) = o + t * d
by the SO3 element and scales it by the scale factor:Origin
o
is rotated and scaled Directiond
is rotated (preserving it’s norm)
- inline SOPHUS_FUNC Hyperplane operator* (Hyperplane const &p) const
Group action on planes.
This function rotates parametrized plane
n.x + d = 0
by the SO3 element and scales it by the scale factor:Normal vector
n
is rotated Offsetd
is scaled
- template<typename OtherDerived, typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type> inline SOPHUS_FUNC RxSO3Base< Derived > & operator*= (RxSO3Base< 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.
Note: This function performs saturation for products close to zero in order to ensure the class invariant.
- inline SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params () const
Returns internal parameters of RxSO(3).
It returns (q.imag[0], q.imag[1], q.imag[2], q.real), with q being the quaternion.
- inline SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quat)
Sets non-zero quaternion
Precondition:
quat
must not be close to either zero or infinity
- inline SOPHUS_FUNC QuaternionType const & quaternion () const
Accessor of quaternion.
- inline SOPHUS_FUNC Transformation rotationMatrix () const
Returns rotation matrix.
- inline SOPHUS_FUNC Scalar scale () const
Returns scale.
- inline SOPHUS_FUNC void setRotationMatrix (Transformation const &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 (Transformation 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 void setSO3 (SO3< Scalar > const &so3)
Setter of SO(3) rotations, leaves scale as is.
- inline SOPHUS_FUNC SO3< Scalar > so3 () const
- inline SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0 () const
Returns derivative of this * RxSO3::exp(x) wrt. 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.
Public Static Attributes
-
static constexpr int DoF = 4
Degrees of freedom of manifold, number of dimensions in tangent space (three for rotation and one for scaling).
-
static constexpr int num_parameters = 4
Number of internal parameters used (quaternion is a 4-tuple).
-
static constexpr int N = 3
Group transformations are 3x3 matrices.
-
static constexpr int Dim = 3
Points are 3-dimensional.
-
struct TangentAndTheta
-
using Line = ParametrizedLine3<Scalar>