test_ceres_se3.cpp 7.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192
  1. #include <ceres/ceres.h>
  2. #include <iostream>
  3. #include <sophus/se3.hpp>
  4. #include "local_parameterization_se3.hpp"
  5. // Eigen's ostream operator is not compatible with ceres::Jet types.
  6. // In particular, Eigen assumes that the scalar type (here Jet<T,N>) can be
  7. // casted to an arithmetic type, which is not true for ceres::Jet.
  8. // Unfortunately, the ceres::Jet class does not define a conversion
  9. // operator (http://en.cppreference.com/w/cpp/language/cast_operator).
  10. //
  11. // This workaround creates a template specialization for Eigen's cast_impl,
  12. // when casting from a ceres::Jet type. It relies on Eigen's internal API and
  13. // might break with future versions of Eigen.
  14. namespace Eigen {
  15. namespace internal {
  16. template <class T, int N, typename NewType>
  17. struct cast_impl<ceres::Jet<T, N>, NewType> {
  18. EIGEN_DEVICE_FUNC
  19. static inline NewType run(ceres::Jet<T, N> const& x) {
  20. return static_cast<NewType>(x.a);
  21. }
  22. };
  23. } // namespace internal
  24. } // namespace Eigen
  25. struct TestSE3CostFunctor {
  26. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  27. TestSE3CostFunctor(Sophus::SE3d T_aw) : T_aw(T_aw) {}
  28. template <class T>
  29. bool operator()(T const* const sT_wa, T* sResiduals) const {
  30. Eigen::Map<Sophus::SE3<T> const> const T_wa(sT_wa);
  31. Eigen::Map<Eigen::Matrix<T, 6, 1> > residuals(sResiduals);
  32. // We are able to mix Sophus types with doubles and Jet types without
  33. // needing to cast to T.
  34. residuals = (T_aw * T_wa).log();
  35. // Reverse order of multiplication. This forces the compiler to verify that
  36. // (Jet, double) and (double, Jet) SE3 multiplication work correctly.
  37. residuals = (T_wa * T_aw).log();
  38. // Finally, ensure that Jet-to-Jet multiplication works.
  39. residuals = (T_wa * T_aw.cast<T>()).log();
  40. return true;
  41. }
  42. Sophus::SE3d T_aw;
  43. };
  44. struct TestPointCostFunctor {
  45. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  46. TestPointCostFunctor(Sophus::SE3d T_aw, Eigen::Vector3d point_a)
  47. : T_aw(T_aw), point_a(point_a) {}
  48. template <class T>
  49. bool operator()(T const* const sT_wa, T const* const spoint_b,
  50. T* sResiduals) const {
  51. using Vector3T = Eigen::Matrix<T, 3, 1>;
  52. Eigen::Map<Sophus::SE3<T> const> const T_wa(sT_wa);
  53. Eigen::Map<Vector3T const> point_b(spoint_b);
  54. Eigen::Map<Vector3T> residuals(sResiduals);
  55. // Multiply SE3d by Jet Vector3.
  56. Vector3T point_b_prime = T_aw * point_b;
  57. // Ensure Jet SE3 multiplication with Jet Vector3.
  58. point_b_prime = T_aw.cast<T>() * point_b;
  59. // Multiply Jet SE3 with Vector3d.
  60. Vector3T point_a_prime = T_wa * point_a;
  61. // Ensure Jet SE3 multiplication with Jet Vector3.
  62. point_a_prime = T_wa * point_a.cast<T>();
  63. residuals = point_b_prime - point_a_prime;
  64. return true;
  65. }
  66. Sophus::SE3d T_aw;
  67. Eigen::Vector3d point_a;
  68. };
  69. bool test(Sophus::SE3d const& T_w_targ, Sophus::SE3d const& T_w_init,
  70. Sophus::SE3d::Point const& point_a_init,
  71. Sophus::SE3d::Point const& point_b) {
  72. static constexpr int kNumPointParameters = 3;
  73. // Optimisation parameters.
  74. Sophus::SE3d T_wr = T_w_init;
  75. Sophus::SE3d::Point point_a = point_a_init;
  76. // Build the problem.
  77. ceres::Problem problem;
  78. // Specify local update rule for our parameter
  79. problem.AddParameterBlock(T_wr.data(), Sophus::SE3d::num_parameters,
  80. new Sophus::test::LocalParameterizationSE3);
  81. // Create and add cost functions. Derivatives will be evaluated via
  82. // automatic differentiation
  83. ceres::CostFunction* cost_function1 =
  84. new ceres::AutoDiffCostFunction<TestSE3CostFunctor, Sophus::SE3d::DoF,
  85. Sophus::SE3d::num_parameters>(
  86. new TestSE3CostFunctor(T_w_targ.inverse()));
  87. problem.AddResidualBlock(cost_function1, NULL, T_wr.data());
  88. ceres::CostFunction* cost_function2 =
  89. new ceres::AutoDiffCostFunction<TestPointCostFunctor, kNumPointParameters,
  90. Sophus::SE3d::num_parameters,
  91. kNumPointParameters>(
  92. new TestPointCostFunctor(T_w_targ.inverse(), point_b));
  93. problem.AddResidualBlock(cost_function2, NULL, T_wr.data(), point_a.data());
  94. // Set solver options (precision / method)
  95. ceres::Solver::Options options;
  96. options.gradient_tolerance = 0.01 * Sophus::Constants<double>::epsilon();
  97. options.function_tolerance = 0.01 * Sophus::Constants<double>::epsilon();
  98. options.linear_solver_type = ceres::DENSE_QR;
  99. // Solve
  100. ceres::Solver::Summary summary;
  101. Solve(options, &problem, &summary);
  102. std::cout << summary.BriefReport() << std::endl;
  103. // Difference between target and parameter
  104. double const mse = (T_w_targ.inverse() * T_wr).log().squaredNorm();
  105. bool const passed = mse < 10. * Sophus::Constants<double>::epsilon();
  106. return passed;
  107. }
  108. template <typename Scalar>
  109. bool CreateSE3FromMatrix(const Eigen::Matrix<Scalar, 4, 4>& mat) {
  110. Sophus::SE3<Scalar> se3 = Sophus::SE3<Scalar>(mat);
  111. std::cout << se3.translation().x() << std::endl;
  112. return true;
  113. }
  114. int main(int, char**) {
  115. using SE3Type = Sophus::SE3<double>;
  116. using SO3Type = Sophus::SO3<double>;
  117. using Point = SE3Type::Point;
  118. double const kPi = Sophus::Constants<double>::pi();
  119. std::vector<SE3Type> se3_vec;
  120. se3_vec.push_back(
  121. SE3Type(SO3Type::exp(Point(0.2, 0.5, 0.0)), Point(0, 0, 0)));
  122. se3_vec.push_back(
  123. SE3Type(SO3Type::exp(Point(0.2, 0.5, -1.0)), Point(10, 0, 0)));
  124. se3_vec.push_back(SE3Type(SO3Type::exp(Point(0., 0., 0.)), Point(0, 100, 5)));
  125. se3_vec.push_back(
  126. SE3Type(SO3Type::exp(Point(0., 0., 0.00001)), Point(0, 0, 0)));
  127. se3_vec.push_back(SE3Type(SO3Type::exp(Point(0., 0., 0.00001)),
  128. Point(0, -0.00000001, 0.0000000001)));
  129. se3_vec.push_back(
  130. SE3Type(SO3Type::exp(Point(0., 0., 0.00001)), Point(0.01, 0, 0)));
  131. se3_vec.push_back(SE3Type(SO3Type::exp(Point(kPi, 0, 0)), Point(4, -5, 0)));
  132. se3_vec.push_back(
  133. SE3Type(SO3Type::exp(Point(0.2, 0.5, 0.0)), Point(0, 0, 0)) *
  134. SE3Type(SO3Type::exp(Point(kPi, 0, 0)), Point(0, 0, 0)) *
  135. SE3Type(SO3Type::exp(Point(-0.2, -0.5, -0.0)), Point(0, 0, 0)));
  136. se3_vec.push_back(
  137. SE3Type(SO3Type::exp(Point(0.3, 0.5, 0.1)), Point(2, 0, -7)) *
  138. SE3Type(SO3Type::exp(Point(kPi, 0, 0)), Point(0, 0, 0)) *
  139. SE3Type(SO3Type::exp(Point(-0.3, -0.5, -0.1)), Point(0, 6, 0)));
  140. std::vector<Point> point_vec;
  141. point_vec.emplace_back(1.012, 2.73, -1.4);
  142. point_vec.emplace_back(9.2, -7.3, -4.4);
  143. point_vec.emplace_back(2.5, 0.1, 9.1);
  144. point_vec.emplace_back(12.3, 1.9, 3.8);
  145. point_vec.emplace_back(-3.21, 3.42, 2.3);
  146. point_vec.emplace_back(-8.0, 6.1, -1.1);
  147. point_vec.emplace_back(0.0, 2.5, 5.9);
  148. point_vec.emplace_back(7.1, 7.8, -14);
  149. point_vec.emplace_back(5.8, 9.2, 0.0);
  150. for (size_t i = 0; i < se3_vec.size(); ++i) {
  151. const int other_index = (i + 3) % se3_vec.size();
  152. bool const passed = test(se3_vec[i], se3_vec[other_index], point_vec[i],
  153. point_vec[other_index]);
  154. if (!passed) {
  155. std::cerr << "failed!" << std::endl << std::endl;
  156. exit(-1);
  157. }
  158. }
  159. Eigen::Matrix<ceres::Jet<double, 28>, 4, 4> mat;
  160. mat.setIdentity();
  161. std::cout << CreateSE3FromMatrix(mat) << std::endl;
  162. return 0;
  163. }