diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 6e31bd9f1b4a81175e4277663009aed3b17eb4a5..33aac84a31c11d37bd295f8f91567c47751313f9 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -190,6 +190,8 @@ SET(HDRS_BASE constraint_analytic.h constraint_autodiff.h constraint_base.h + eigen_assert.h + eigen_predicates.h factory.h feature_base.h feature_match.h diff --git a/src/eigen_assert.h b/src/eigen_assert.h new file mode 100644 index 0000000000000000000000000000000000000000..5c079da7aab383eed93578869b219c65854419d4 --- /dev/null +++ b/src/eigen_assert.h @@ -0,0 +1,89 @@ +#ifndef _WOLF_EIGEN_ASSERT_H_ +#define _WOLF_EIGEN_ASSERT_H_ + +#include <Eigen/Dense> + +namespace Eigen { + +////////////////////////////////////////////////////////// +/** Check Eigen Matrix sizes, both statically and dynamically + * + * Help: + * + * The WOLF project implements many template functions using Eigen Matrix and Quaternions, in different versions + * (Static size, Dynamic size, Map, Matrix expression). + * + * Eigen provides some macros for STATIC assert of matrix sizes, the most common of them are (see Eigen's StaticAssert.h): + * + * EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE + * EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE + * EIGEN_STATIC_ASSERT_VECTOR_ONLY + * + * but they do not work if the evaluated types are of dynamic size. + * + * In order to achieve full templatization over both dynamic and static sizes, we use extensively a prototype of this kind: + * + * template<typename Derived> + * inline Eigen::Matrix<typename Derived::Scalar, 3, 3> function(const Eigen::MatrixBase<Derived>& _v){ + * + * MatrixSizeCheck<3,1>::check(_v); /// We check here the size of the input parameter + * + * typedef typename Derived::Scalar T; + * + * ... code ... + * + * return M; + * } + * + * The function : MatrixSizeCheck <Rows, Cols>::check(M) checks that the Matrix M is of size ( Rows x Cols ). + * This check is performed statically or dynamically, depending on the type of argument provided. + */ +template<int Size, int DesiredSize> +struct StaticDimCheck +{ + template<typename T> + StaticDimCheck(const T&) + { + static_assert(Size == DesiredSize, "Size of static Vector or Matrix does not match"); + } +}; + +template<int DesiredSize> +struct StaticDimCheck<Eigen::Dynamic, DesiredSize> +{ + template<typename T> + StaticDimCheck(const T& t) + { + if (t != DesiredSize) std::cerr << "t : " << t << " != DesiredSize : " << DesiredSize << std::endl; + assert(t == DesiredSize && "Size of dynamic Vector or Matrix does not match"); + } +}; + +template<int DesiredR, int DesiredC> +struct MatrixSizeCheck +{ + /** \brief Assert matrix size dynamically or statically + * + * @param t the variable for which we wish to assert the size. + * + * Usage: to assert that t is size (Rows x Cols) + * + * MatrixSizeCheck<Rows, Cols>::check(t); + */ + template<typename T> + static void check(const Eigen::MatrixBase<T>& t) + { + StaticDimCheck<Eigen::MatrixBase<T>::RowsAtCompileTime, DesiredR>(t.rows()); + StaticDimCheck<Eigen::MatrixBase<T>::ColsAtCompileTime, DesiredC>(t.cols()); + } +}; + +template <int Dim> +using VectorSizeCheck = MatrixSizeCheck<Dim, 1>; + +template <int Dim> +using RowVectorSizeCheck = MatrixSizeCheck<1, Dim>; + +} /* namespace Eigen */ + +#endif /* _WOLF_EIGEN_ASSERT_H_ */ diff --git a/src/eigen_predicates.h b/src/eigen_predicates.h new file mode 100644 index 0000000000000000000000000000000000000000..65e737b1b328d2dc546ab4a1bddc1783dcef1db5 --- /dev/null +++ b/src/eigen_predicates.h @@ -0,0 +1,101 @@ +/** + * \file eigen_predicates.h + * \brief Some utils for comparing Eigen types + * \author Jeremie Deray + * Created on: 24/10/2017 + */ + +#ifndef _WOLF_EIGEN_PREDICATES_H_ +#define _WOLF_EIGEN_PREDICATES_H_ + +#include "rotations.h" + +namespace wolf { + +/// @brief check that each Matrix/Vector elem is approx equal to value +- precision +/// +/// @note we overload this rather than using Eigen::Matrix::isConstant() since it is +/// defined as : +/// abs(x - y) <= (min)(abs(x), abs(y)) * prec +/// which does not play nice with y = 0 +auto is_constant = [](const Eigen::MatrixXs& lhs, const Scalar val, const Scalar precision) + { + for (Eigen::MatrixXs::Index j = 0; j < lhs.cols(); ++j) + for (Eigen::MatrixXs::Index i = 0; i < lhs.rows(); ++i) + if (std::abs(lhs.coeff(i, j) - val) > precision) + return false; + return true; + }; + +/// @brief check that each element of the Matrix/Vector difference +/// is approx 0 +- precision +auto pred_zero = [](const Eigen::MatrixXs& lhs, const Scalar precision) + { return is_constant(lhs, 0, precision); }; + +/// @brief check that each element of the Matrix/Vector difference +/// is approx 0 +- precision +auto pred_diff_zero = [](const Eigen::MatrixXs& lhs, const Eigen::MatrixXs& rhs, const Scalar precision) + { return pred_zero(lhs - rhs, precision); }; + +/// @brief check that the Matrix/Vector difference norm is approx 0 +- precision +auto pred_diff_norm_zero = [](const Eigen::MatrixXs& lhs, const Eigen::MatrixXs& rhs, const Scalar precision) + { return std::abs((lhs - rhs).norm()) <= std::abs(precision); }; + +/// @brief check that the lhs Matrix/Vector is elem-wise approx the rhs +-precision +auto pred_is_approx = [](const Eigen::MatrixXs& lhs, const Eigen::MatrixXs& rhs, const Scalar precision) + { return lhs.isApprox(rhs, precision); }; + +/// @brief check that angle θ of rotation required to get from lhs quaternion to rhs +/// is <= precision +auto pred_quat_is_approx = [](const Eigen::Quaternions& lhs, const Eigen::Quaternions& rhs, const Scalar precision) + { return pred_zero( log_q(rhs * lhs.inverse()), precision ); }; + +/// @brief check that angle θ of rotation required to get from lhs quaternion to identity +/// is <= precision +auto pred_quat_identity = [](const Eigen::Quaternions& lhs, const Scalar precision) + { return pred_quat_is_approx(lhs, Eigen::Quaternions::Identity(), precision); }; + +/// @brief check that rotation angle to get from lhs angle to rhs is <= precision +auto pred_angle_is_approx = [](const Scalar lhs, const Scalar rhs, const Scalar precision) + { return std::abs(pi2pi(lhs - rhs)) <= std::abs(precision); }; + +/// @brief check that rotation angle to get from lhs angle to 0 is <= precision +auto pred_angle_zero = [](const Scalar lhs, const Scalar precision) + { return pred_angle_is_approx(lhs, 0, precision); }; + +/// @brief check that the lhs pose is approx rhs +- precision +/// +/// @note +/// Comparison is : +/// d = inv(lhs) * rhs +/// d.translation().elem_wise() ~ 0 (+- precision) +/// +/// if pose 3d : +/// d.rotation_as_quaternion() ~ quaternion.getIdentity (+- precision) +/// +/// else if pose 2d: +/// d.rotation_angle() ~ 0 (+- precision) +/// +/// else throw std::runtime +/// +/// @see pred_zero for translation comparison +/// @see pred_quat_identity for 3d rotation comparison +/// @see pred_angle_zero for 2d rotation comparison +//auto pred_pose_is_approx = [](const Eigen::MatrixXs lhs, const Eigen::MatrixXs rhs, const Scalar precision) +// { +// const Eigen::MatrixXs d = lhs.inverse() * rhs; +// const bool tok = pred_zero(d.rightCols(1), precision); + +// const bool qok = (lhs.rows() == 3)? +// pred_quat_identity(Eigen::Quaternions(d.block(0,0,3,1)), +// precision) +// : (lhs.rows() == 2)? pred_angle_zero(getYaw(d), precision) +// : throw std::runtime_error("Canno't compare pose in Dim > 3 !"); + +// return tok && qok; +// }; + +} // namespace wolf + + +#endif /* _WOLF_EIGEN_PREDICATES_H_ */ diff --git a/src/rotations.h b/src/rotations.h index a5fc57e566d1bec2b0077a37fb35dfb67f026515..caa57f0d442e7a0c3afc66b1315a16a6ba8aebe0 100644 --- a/src/rotations.h +++ b/src/rotations.h @@ -23,8 +23,10 @@ namespace wolf * @return formatted angle */ template<typename T> -inline T pi2pi(T angle) +inline T pi2pi(const T angle) { + using std::fmod; + return (angle > (T)0 ? fmod(angle + (T)M_PI, (T)(2*M_PI)) - (T)M_PI : fmod(angle - (T)M_PI, (T)(2*M_PI)) + (T)M_PI); @@ -36,7 +38,7 @@ inline T pi2pi(T angle) * @return angle in radians */ template<typename T> -inline T toRad(const T& deg) +inline T toRad(const T deg) { return (T)M_TORAD * deg; } @@ -47,7 +49,7 @@ inline T toRad(const T& deg) * @return angle in degrees */ template<typename T> -inline T toDeg(const T& rad) +inline T toDeg(const T rad) { return (T)M_TODEG * rad; } @@ -102,6 +104,10 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 1> vee(const Eigen::MatrixBase template<typename Derived> inline Eigen::Quaternion<typename Derived::Scalar> exp_q(const Eigen::MatrixBase<Derived>& _v) { + using std::sqrt; + using std::cos; + using std::sin; + MatrixSizeCheck<3,1>::check(_v); typedef typename Derived::Scalar T; @@ -132,6 +138,8 @@ inline Eigen::Quaternion<typename Derived::Scalar> exp_q(const Eigen::MatrixBase template<typename Derived> inline Eigen::Matrix<typename Derived::Scalar, 3, 1> log_q(const Eigen::QuaternionBase<Derived>& _q) { + using std::sqrt; + typedef typename Derived::Scalar T; Eigen::Matrix<T, 3, 1> vec = _q.vec(); @@ -157,6 +165,8 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 1> log_q(const Eigen::Quaterni template<typename Derived> inline Eigen::Matrix<typename Derived::Scalar, 3, 3> exp_R(const Eigen::MatrixBase<Derived>& _v) { + using std::sqrt; + MatrixSizeCheck<3, 1>::check(_v); typedef typename Derived::Scalar T; @@ -291,6 +301,10 @@ inline Eigen::Quaternion<typename Derived::Scalar> R2q(const Eigen::MatrixBase<D template<typename Derived> inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_right(const Eigen::MatrixBase<Derived>& _theta) { + using std::sqrt; + using std::cos; + using std::sin; + MatrixSizeCheck<3, 1>::check(_theta); typedef typename Derived::Scalar T; @@ -326,6 +340,10 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_right(const Eigen:: template<typename Derived> inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_right_inv(const Eigen::MatrixBase<Derived>& _theta) { + using std::sqrt; + using std::cos; + using std::sin; + MatrixSizeCheck<3, 1>::check(_theta); typedef typename Derived::Scalar T; @@ -334,7 +352,7 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_right_inv(const Eig Eigen::Matrix<T, 3, 3> W(skew(_theta)); if (theta2 <= Constants::EPS_SMALL) return Eigen::Matrix<T, 3, 3>::Identity() + (T)0.5 * W; // Small angle approximation - T theta = std::sqrt(theta2); // rotation angle + T theta = sqrt(theta2); // rotation angle Eigen::Matrix<T, 3, 3> M; M.noalias() = ((T)1 / theta2 - (1 + cos(theta)) / ((T)2 * theta * sin(theta))) * (W * W); return Eigen::Matrix<T, 3, 3>::Identity() + (T)0.5 * W + M; //is this really more optimized? @@ -356,6 +374,10 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_right_inv(const Eig template<typename Derived> inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_left(const Eigen::MatrixBase<Derived>& _theta) { + using std::sqrt; + using std::cos; + using std::sin; + MatrixSizeCheck<3, 1>::check(_theta); typedef typename Derived::Scalar T; @@ -390,6 +412,10 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_left(const Eigen::M template<typename Derived> inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_left_inv(const Eigen::MatrixBase<Derived>& _theta) { + using std::sqrt; + using std::cos; + using std::sin; + MatrixSizeCheck<3, 1>::check(_theta); typedef typename Derived::Scalar T; @@ -398,7 +424,7 @@ inline Eigen::Matrix<typename Derived::Scalar, 3, 3> jac_SO3_left_inv(const Eige Eigen::Matrix<T, 3, 3> W(skew(_theta)); if (theta2 <= Constants::EPS_SMALL) return Eigen::Matrix<T, 3, 3>::Identity() + (T)0.5 * W; // Small angle approximation - T theta = std::sqrt(theta2); // rotation angle + T theta = sqrt(theta2); // rotation angle Eigen::Matrix<T, 3, 3> M; M.noalias() = ((T)1 / theta2 - (1 + cos(theta)) / ((T)2 * theta * sin(theta))) * (W * W); return Eigen::Matrix<T, 3, 3>::Identity() - (T)0.5 * W + M; //is this really more optimized? @@ -416,6 +442,13 @@ inline Eigen::Matrix<T, 3, 3> matrixRollPitchYaw(const T roll, return (az * ay * ax).toRotationMatrix().matrix(); } +template <typename Derived> +inline typename Eigen::MatrixBase<Derived>::Scalar +getYaw(const Eigen::MatrixBase<Derived>& r) +{ + using std::atan2; + return atan2( r(1, 0), r(0, 0) ); +} } // namespace wolf diff --git a/src/test/CMakeLists.txt b/src/test/CMakeLists.txt index 6200ebc3af36d86dea01c639f926007a20728982..d2e015c98754b08e3242868ba1ffce5f6c14250d 100644 --- a/src/test/CMakeLists.txt +++ b/src/test/CMakeLists.txt @@ -48,6 +48,10 @@ target_link_libraries(gtest_capture_base ${PROJECT_NAME}) #wolf_add_gtest(gtest_constraint_sparse gtest_constraint_sparse.cpp) #target_link_libraries(gtest_constraint_sparse ${PROJECT_NAME}) +# FeatureBase classes test +wolf_add_gtest(gtest_eigen_predicates gtest_eigen_predicates.cpp) +target_link_libraries(gtest_eigen_predicates ${PROJECT_NAME}) + # FeatureBase classes test wolf_add_gtest(gtest_feature_base gtest_feature_base.cpp) target_link_libraries(gtest_feature_base ${PROJECT_NAME}) diff --git a/src/test/gtest_eigen_predicates.cpp b/src/test/gtest_eigen_predicates.cpp new file mode 100644 index 0000000000000000000000000000000000000000..6f32d00e438f71e98b3785f4471ac850f5e0ba19 --- /dev/null +++ b/src/test/gtest_eigen_predicates.cpp @@ -0,0 +1,178 @@ +#include "utils_gtest.h" + +#include "../eigen_predicates.h" + +TEST(TestEigenPredicates, TestEigenDynPredZero) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::MatrixXs::Zero(4,4); + B = Eigen::MatrixXs::Random(4,4); + C = Eigen::MatrixXs::Ones(4,4) * (wolf::Constants::EPS/2.); + + EXPECT_TRUE(wolf::pred_zero(A, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_zero(B, wolf::Constants::EPS)); + EXPECT_TRUE(wolf::pred_zero(C, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenFixPredZero) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::Matrix4s::Zero(); + B = Eigen::Matrix4s::Random(); + C = Eigen::Matrix4s::Ones() * (wolf::Constants::EPS/2.); + + EXPECT_TRUE(wolf::pred_zero(A, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_zero(B, wolf::Constants::EPS)); + EXPECT_TRUE(wolf::pred_zero(C, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenDynPredDiffZero) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::MatrixXs::Random(4,4); + B = Eigen::MatrixXs::Random(4,4); + C = A; + + EXPECT_TRUE(wolf::pred_diff_zero(A, C, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_diff_zero(A, B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenFixPredDiffZero) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::Matrix4s::Random(); + B = Eigen::Matrix4s::Random(); + C = A; + + EXPECT_TRUE(wolf::pred_diff_zero(A, C, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_diff_zero(A, B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenDynPredDiffNorm) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::MatrixXs::Random(4,4); + B = Eigen::MatrixXs::Random(4,4); + C = A; + + EXPECT_TRUE(wolf::pred_diff_norm_zero(A, C, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_diff_norm_zero(A, B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenFixPredDiffNorm) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::Matrix4s::Random(); + B = Eigen::Matrix4s::Random(); + C = A; + + EXPECT_TRUE(wolf::pred_diff_norm_zero(A, C, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_diff_norm_zero(A, B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenDynPredIsApprox) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::MatrixXs::Random(4,4); + B = Eigen::MatrixXs::Random(4,4); + C = A; + + EXPECT_TRUE(wolf::pred_is_approx(A, C, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_is_approx(A, B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenFixPredIsApprox) +{ + Eigen::MatrixXs A, B, C; + + A = Eigen::Matrix4s::Random(); + B = Eigen::Matrix4s::Random(); + C = A; + + EXPECT_TRUE(wolf::pred_is_approx(A, C, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_is_approx(A, B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenPredQuatIsApprox) +{ + Eigen::Quaternions A, B, C; + + /// @todo which version of Eigen provides this ? +// A = Eigen::Quaternions::UnitRandom(); + + A.coeffs() = Eigen::Vector4s::Random().normalized(); + B.coeffs() = Eigen::Vector4s::Random().normalized(); + C = A; + + EXPECT_TRUE(wolf::pred_quat_is_approx(A, C, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_quat_is_approx(A, B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenPredQuatIsIdentity) +{ + Eigen::Quaternions A, B; + + A = Eigen::Quaternions::Identity(); + B.coeffs() = Eigen::Vector4s::Random().normalized(); + + EXPECT_TRUE(wolf::pred_quat_identity(A, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_quat_identity(B, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenPredAngleIsApprox) +{ + wolf::Scalar a = M_PI; + wolf::Scalar b = -M_PI; + wolf::Scalar c = 0; + + EXPECT_TRUE(wolf::pred_angle_is_approx(a, b, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_angle_is_approx(a, c, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +TEST(TestEigenPredicates, TestEigenPredAngleIsZero) +{ + wolf::Scalar a = 0; + wolf::Scalar b = M_PI; + wolf::Scalar c = 2.*M_PI; + + EXPECT_TRUE(wolf::pred_angle_zero(a, wolf::Constants::EPS)); + EXPECT_FALSE(wolf::pred_angle_zero(b, wolf::Constants::EPS)); + EXPECT_TRUE(wolf::pred_angle_zero(c, wolf::Constants::EPS)); + + PRINT_TEST_FINISHED; +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/src/test/utils_gtest.h b/src/test/utils_gtest.h index 21648221f5dfc59b5e0c608e2106f95c4daba241..0883d86ff494abe6f89e7bc53a35c1b0ab556c9a 100644 --- a/src/test/utils_gtest.h +++ b/src/test/utils_gtest.h @@ -71,6 +71,14 @@ extern void ColoredPrintf(GTestColor color, const char* fmt, ...); testing::internal::ColoredPrintf(testing::internal::COLOR_YELLOW, __VA_ARGS__); } \ while(0) +#define PRINT_TEST_FINISHED \ +{ \ + const ::testing::TestInfo* const test_info = \ + ::testing::UnitTest::GetInstance()->current_test_info(); \ + PRINTF(std::string("Finished test case ").append(test_info->test_case_name()).\ + append(" of test ").append(test_info->name()).append(".\n").c_str()); \ +} + // C++ stream interface class TestCout : public std::stringstream {