/// @file /// Common type aliases. #ifndef SOPHUS_TYPES_HPP #define SOPHUS_TYPES_HPP #include #include "common.hpp" namespace Sophus { template using Vector = Eigen::Matrix; template using Vector2 = Vector; using Vector2f = Vector2; using Vector2d = Vector2; template using Vector3 = Vector; using Vector3f = Vector3; using Vector3d = Vector3; template using Vector4 = Vector; using Vector4f = Vector4; using Vector4d = Vector4; template using Vector6 = Vector; using Vector6f = Vector6; using Vector6d = Vector6; template using Vector7 = Vector; using Vector7f = Vector7; using Vector7d = Vector7; template using Matrix = Eigen::Matrix; template using Matrix2 = Matrix; using Matrix2f = Matrix2; using Matrix2d = Matrix2; template using Matrix3 = Matrix; using Matrix3f = Matrix3; using Matrix3d = Matrix3; template using Matrix4 = Matrix; using Matrix4f = Matrix4; using Matrix4d = Matrix4; template using Matrix6 = Matrix; using Matrix6f = Matrix6; using Matrix6d = Matrix6; template using Matrix7 = Matrix; using Matrix7f = Matrix7; using Matrix7d = Matrix7; template using ParametrizedLine = Eigen::ParametrizedLine; template using ParametrizedLine3 = ParametrizedLine; using ParametrizedLine3f = ParametrizedLine3; using ParametrizedLine3d = ParametrizedLine3; template using ParametrizedLine2 = ParametrizedLine; using ParametrizedLine2f = ParametrizedLine2; using ParametrizedLine2d = ParametrizedLine2; namespace details { template class MaxMetric { public: static Scalar impl(Scalar s0, Scalar s1) { using std::abs; return abs(s0 - s1); } }; template class MaxMetric> { public: static Scalar impl(Matrix const& p0, Matrix const& p1) { return (p0 - p1).template lpNorm(); } }; template class SetToZero { public: static void impl(Scalar& s) { s = Scalar(0); } }; template class SetToZero> { public: static void impl(Matrix& v) { v.setZero(); } }; template class SetElementAt; template class SetElementAt { public: static void impl(Scalar& s, Scalar value, int at) { SOPHUS_ENSURE(at == 0, "is %", at); s = value; } }; template class SetElementAt, Scalar> { public: static void impl(Vector& v, Scalar value, int at) { SOPHUS_ENSURE(at >= 0 && at < N, "is %", at); v[at] = value; } }; template class SquaredNorm { public: static Scalar impl(Scalar const& s) { return s * s; } }; template class SquaredNorm> { public: static Scalar impl(Matrix const& s) { return s.squaredNorm(); } }; template class Transpose { public: static Scalar impl(Scalar const& s) { return s; } }; template class Transpose> { public: static Matrix impl(Matrix const& s) { return s.transpose(); } }; } // namespace details /// Returns maximum metric between two points ``p0`` and ``p1``, with ``p0, p1`` /// being matrices or a scalars. /// template auto maxMetric(T const& p0, T const& p1) -> decltype(details::MaxMetric::impl(p0, p1)) { return details::MaxMetric::impl(p0, p1); } /// Sets point ``p`` to zero, with ``p`` being a matrix or a scalar. /// template void setToZero(T& p) { return details::SetToZero::impl(p); } /// Sets ``i``th component of ``p`` to ``value``, with ``p`` being a /// matrix or a scalar. If ``p`` is a scalar, ``i`` must be ``0``. /// template void setElementAt(T& p, Scalar value, int i) { return details::SetElementAt::impl(p, value, i); } /// Returns the squared 2-norm of ``p``, with ``p`` being a vector or a scalar. /// template auto squaredNorm(T const& p) -> decltype(details::SquaredNorm::impl(p)) { return details::SquaredNorm::impl(p); } /// Returns ``p.transpose()`` if ``p`` is a matrix, and simply ``p`` if m is a /// scalar. /// template auto transpose(T const& p) -> decltype(details::Transpose::impl(T())) { return details::Transpose::impl(p); } template struct IsFloatingPoint { static bool const value = std::is_floating_point::value; }; template struct IsFloatingPoint> { static bool const value = std::is_floating_point::value; }; template struct GetScalar { using Scalar = Scalar_; }; template struct GetScalar> { using Scalar = Scalar_; }; /// If the Vector type is of fixed size, then IsFixedSizeVector::value will be /// true. template ::type> struct IsFixedSizeVector : std::true_type {}; /// Planes in 3d are hyperplanes. template using Plane3 = Eigen::Hyperplane; using Plane3d = Plane3; using Plane3f = Plane3; /// Lines in 2d are hyperplanes. template using Line2 = Eigen::Hyperplane; using Line2d = Line2; using Line2f = Line2; } // namespace Sophus #endif // SOPHUS_TYPES_HPP