Program Listing for File SO3_base.h¶
↰ Return to documentation for file (manif/impl/so3/SO3_base.h
)
#ifndef _MANIF_MANIF_SO3_BASE_H_
#define _MANIF_MANIF_SO3_BASE_H_
#include "manif/impl/so3/SO3_properties.h"
#include "manif/impl/lie_group_base.h"
#include "manif/impl/utils.h"
namespace manif {
//
// LieGroup
//
template <typename _Derived>
struct SO3Base : LieGroupBase<_Derived>
{
private:
using Base = LieGroupBase<_Derived>;
using Type = SO3Base<_Derived>;
public:
MANIF_GROUP_TYPEDEF
MANIF_INHERIT_GROUP_AUTO_API
MANIF_INHERIT_GROUP_OPERATOR
using Base::coeffs;
using Rotation = typename internal::traits<_Derived>::Rotation;
using Transformation = typename internal::traits<_Derived>::Transformation;
using QuaternionDataType = Eigen::Quaternion<Scalar>;
protected:
using Base::derived;
MANIF_DEFAULT_CONSTRUCTOR(SO3Base)
public:
MANIF_GROUP_ML_ASSIGN_OP(SO3Base)
// LieGroup common API
LieGroup inverse(OptJacobianRef J_minv_m = {}) const;
Tangent log(OptJacobianRef J_t_m = {}) const;
MANIF_DEPRECATED
Tangent lift(OptJacobianRef J_t_m = {}) const;
template <typename _DerivedOther>
LieGroup compose(const LieGroupBase<_DerivedOther>& m,
OptJacobianRef J_mc_ma = {},
OptJacobianRef J_mc_mb = {}) const;
template <typename _EigenDerived>
Eigen::Matrix<Scalar, 3, 1>
act(const Eigen::MatrixBase<_EigenDerived> &v,
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>>> J_vout_m = {},
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>>> J_vout_v = {}) const;
Jacobian adj() const;
// SO3 specific functions
Transformation transform() const;
Rotation rotation() const;
Scalar x() const;
Scalar y() const;
Scalar z() const;
Scalar w() const;
QuaternionDataType quat() const;
void normalize();
void quat(const QuaternionDataType& quaternion);
template <typename _EigenDerived>
void quat(const Eigen::MatrixBase<_EigenDerived>& quaternion);
};
template <typename _Derived>
typename SO3Base<_Derived>::Transformation
SO3Base<_Derived>::transform() const
{
Transformation T = Transformation::Identity();
T.template topLeftCorner<3,3>() = rotation();
return T;
}
template <typename _Derived>
typename SO3Base<_Derived>::Rotation
SO3Base<_Derived>::rotation() const
{
return quat().matrix();
}
template <typename _Derived>
typename SO3Base<_Derived>::LieGroup
SO3Base<_Derived>::inverse(OptJacobianRef J_minv_m) const
{
if (J_minv_m)
{
*J_minv_m = -rotation();
}
return LieGroup(quat().conjugate());
}
template <typename _Derived>
typename SO3Base<_Derived>::Tangent
SO3Base<_Derived>::log(OptJacobianRef J_t_m) const
{
using std::sqrt;
using std::atan2;
Tangent tan;
Scalar log_coeff;
const Scalar sin_angle_squared = coeffs().template head<3>().squaredNorm();
if (sin_angle_squared > Constants<Scalar>::eps)
{
const Scalar sin_angle = sqrt(sin_angle_squared);
const Scalar cos_angle = w();
const Scalar two_angle = Scalar(2.0) * ((cos_angle < Scalar(0.0)) ?
Scalar(atan2(-sin_angle, -cos_angle)) :
Scalar(atan2( sin_angle, cos_angle)));
log_coeff = two_angle / sin_angle;
}
else
{
// small-angle approximation
log_coeff = Scalar(2.0);
}
tan = Tangent(coeffs().template head<3>() * log_coeff);
// using std::atan2;
// Scalar n = coeffs().template head<3>().norm();
// Scalar angle(0);
// typename Tangent::DataType axis(1,0,0);
// if (n<Constants<Scalar>::eps)
// n = coeffs().template head<3>().stableNorm();
// if (n > Scalar(0))
// {
// angle = Scalar(2)*atan2(n, w());
// axis = coeffs().template head<3>() / n;
// }
// tan = Tangent(axis*angle);
if (J_t_m)
{
J_t_m->setIdentity();
J_t_m->noalias() += Scalar(0.5) * tan.hat();
Scalar theta2 = tan.coeffs().squaredNorm();
if (theta2 > Constants<Scalar>::eps)
{
Scalar theta = sqrt(theta2); // rotation angle
J_t_m->noalias() +=
(Scalar(1) / theta2 - (Scalar(1) + cos(theta)) / (Scalar(2) * theta * sin(theta))) *
tan.hat() * tan.hat();
}
}
return tan;
}
template <typename _Derived>
typename SO3Base<_Derived>::Tangent
SO3Base<_Derived>::lift(OptJacobianRef J_t_m) const
{
return log(J_t_m);
}
template <typename _Derived>
template <typename _DerivedOther>
typename SO3Base<_Derived>::LieGroup
SO3Base<_Derived>::compose(
const LieGroupBase<_DerivedOther>& m,
OptJacobianRef J_mc_ma,
OptJacobianRef J_mc_mb) const
{
using std::abs;
static_assert(
std::is_base_of<SO3Base<_DerivedOther>, _DerivedOther>::value,
"Argument does not inherit from S03Base !");
const auto& m_SO3 = static_cast<const SO3Base<_DerivedOther>&>(m);
if (J_mc_ma)
{
*J_mc_ma = m_SO3.rotation().transpose();
}
if (J_mc_mb)
J_mc_mb->setIdentity();
QuaternionDataType ret_q = quat() * m_SO3.quat();
const Scalar ret_sqnorm = ret_q.squaredNorm();
if (abs(ret_sqnorm-Scalar(1)) > Constants<Scalar>::eps)
{
ret_q.coeffs() *= approxSqrtInv(ret_sqnorm);
}
return LieGroup(ret_q);
}
template <typename _Derived>
template <typename _EigenDerived>
Eigen::Matrix<typename SO3Base<_Derived>::Scalar, 3, 1>
SO3Base<_Derived>::act(const Eigen::MatrixBase<_EigenDerived> &v,
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>>> J_vout_m,
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>>> J_vout_v) const
{
assert_vector_dim(v, 3);
const Rotation R(rotation());
if (J_vout_m)
{
J_vout_m->noalias() = -R * skew(v);
}
if (J_vout_v)
{
(*J_vout_v) = R;
}
return R * v;
}
template <typename _Derived>
typename SO3Base<_Derived>::Jacobian
SO3Base<_Derived>::adj() const
{
return rotation();
}
// SO3 specific
template <typename _Derived>
typename SO3Base<_Derived>::Scalar
SO3Base<_Derived>::x() const
{
return coeffs().x();
}
template <typename _Derived>
typename SO3Base<_Derived>::Scalar
SO3Base<_Derived>::y() const
{
return coeffs().y();
}
template <typename _Derived>
typename SO3Base<_Derived>::Scalar
SO3Base<_Derived>::z() const
{
return coeffs().z();
}
template <typename _Derived>
typename SO3Base<_Derived>::Scalar
SO3Base<_Derived>::w() const
{
return coeffs().w();
}
template <typename _Derived>
typename SO3Base<_Derived>::QuaternionDataType
SO3Base<_Derived>::quat() const
{
return QuaternionDataType(coeffs());
}
template <typename _Derived>
void SO3Base<_Derived>::normalize()
{
coeffs().normalize();
}
template <typename _Derived>
void SO3Base<_Derived>::quat(const QuaternionDataType& quaternion)
{
quat(quaternion.coeffs());
}
template <typename _Derived>
template <typename _EigenDerived>
void SO3Base<_Derived>::quat(const Eigen::MatrixBase<_EigenDerived>& quaternion)
{
using std::abs;
assert_vector_dim(quaternion, 4);
MANIF_ASSERT(abs(quaternion.norm()-Scalar(1)) <
Constants<Scalar>::eps,
"The quaternion is not normalized !",
invalid_argument);
coeffs() = quaternion;
}
namespace internal {
template <typename Derived>
struct RandomEvaluatorImpl<SO3Base<Derived>>
{
template <typename T>
static void run(T& m)
{
using Scalar = typename SO3Base<Derived>::Scalar;
using LieGroup = typename SO3Base<Derived>::LieGroup;
m = LieGroup(randQuat<Scalar>());
}
};
template <typename Derived>
struct AssignmentEvaluatorImpl<SO3Base<Derived>>
{
template <typename T>
static void run_impl(const T& data)
{
using std::abs;
MANIF_ASSERT(
abs(data.norm()-typename SO3Base<Derived>::Scalar(1)) <
Constants<typename SO3Base<Derived>::Scalar>::eps,
"SO3 assigned data not normalized !",
manif::invalid_argument
);
MANIF_UNUSED_VARIABLE(data);
}
};
template <typename Derived, typename NewScalar>
struct CastEvaluatorImpl<SO3Base<Derived>, NewScalar> {
template <typename T>
static auto run(const T& o) -> typename Derived::template LieGroupTemplate<NewScalar> {
const typename SO3Base<Derived>::QuaternionDataType q = o.quat();
return typename Derived::template LieGroupTemplate<NewScalar>(
q.template cast<NewScalar>().normalized()
);
}
};
} /* namespace internal */
} /* namespace manif */
#endif /* _MANIF_MANIF_SO3_BASE_H_ */