test_se2.cpp 9.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260
  1. #include <iostream>
  2. #include <sophus/se2.hpp>
  3. #include <unsupported/Eigen/MatrixFunctions>
  4. #include "tests.hpp"
  5. // Explicit instantiate all class templates so that all member methods
  6. // get compiled and for code coverage analysis.
  7. namespace Eigen {
  8. template class Map<Sophus::SE2<double>>;
  9. template class Map<Sophus::SE2<double> const>;
  10. } // namespace Eigen
  11. namespace Sophus {
  12. template class SE2<double, Eigen::AutoAlign>;
  13. template class SE2<double, Eigen::DontAlign>;
  14. #if SOPHUS_CERES
  15. template class SE2<ceres::Jet<double, 3>>;
  16. #endif
  17. template <class Scalar>
  18. class Tests {
  19. public:
  20. using SE2Type = SE2<Scalar>;
  21. using SO2Type = SO2<Scalar>;
  22. using Point = typename SE2<Scalar>::Point;
  23. using Tangent = typename SE2<Scalar>::Tangent;
  24. Scalar const kPi = Constants<Scalar>::pi();
  25. Tests() {
  26. se2_vec_.push_back(
  27. SE2Type(SO2Type(Scalar(0.0)), Point(Scalar(0), Scalar(0))));
  28. se2_vec_.push_back(
  29. SE2Type(SO2Type(Scalar(0.2)), Point(Scalar(10), Scalar(0))));
  30. se2_vec_.push_back(
  31. SE2Type(SO2Type(Scalar(0.)), Point(Scalar(0), Scalar(100))));
  32. se2_vec_.push_back(
  33. SE2Type(SO2Type(Scalar(-1.)), Point(Scalar(20), -Scalar(1))));
  34. se2_vec_.push_back(
  35. SE2Type(SO2Type(Scalar(0.00001)),
  36. Point(Scalar(-0.00000001), Scalar(0.0000000001))));
  37. se2_vec_.push_back(
  38. SE2Type(SO2Type(Scalar(0.2)), Point(Scalar(0), Scalar(0))) *
  39. SE2Type(SO2Type(kPi), Point(Scalar(0), Scalar(0))) *
  40. SE2Type(SO2Type(Scalar(-0.2)), Point(Scalar(0), Scalar(0))));
  41. se2_vec_.push_back(
  42. SE2Type(SO2Type(Scalar(0.3)), Point(Scalar(2), Scalar(0))) *
  43. SE2Type(SO2Type(kPi), Point(Scalar(0), Scalar(0))) *
  44. SE2Type(SO2Type(Scalar(-0.3)), Point(Scalar(0), Scalar(6))));
  45. Tangent tmp;
  46. tmp << Scalar(0), Scalar(0), Scalar(0);
  47. tangent_vec_.push_back(tmp);
  48. tmp << Scalar(1), Scalar(0), Scalar(0);
  49. tangent_vec_.push_back(tmp);
  50. tmp << Scalar(0), Scalar(1), Scalar(1);
  51. tangent_vec_.push_back(tmp);
  52. tmp << Scalar(-1), Scalar(1), Scalar(0);
  53. tangent_vec_.push_back(tmp);
  54. tmp << Scalar(20), Scalar(-1), Scalar(-1);
  55. tangent_vec_.push_back(tmp);
  56. tmp << Scalar(30), Scalar(5), Scalar(20);
  57. tangent_vec_.push_back(tmp);
  58. point_vec_.push_back(Point(1, 2));
  59. point_vec_.push_back(Point(1, -3));
  60. }
  61. void runAll() {
  62. bool passed = testLieProperties();
  63. passed &= testRawDataAcces();
  64. passed &= testMutatingAccessors();
  65. passed &= testConstructors();
  66. passed &= testFit();
  67. processTestResult(passed);
  68. }
  69. private:
  70. bool testLieProperties() {
  71. LieGroupTests<SE2Type> tests(se2_vec_, tangent_vec_, point_vec_);
  72. return tests.doAllTestsPass();
  73. }
  74. bool testRawDataAcces() {
  75. bool passed = true;
  76. Eigen::Matrix<Scalar, 4, 1> raw;
  77. raw << Scalar(0), Scalar(1), Scalar(0), Scalar(3);
  78. Eigen::Map<SE2Type const> const_se2_map(raw.data());
  79. SOPHUS_TEST_APPROX(passed, const_se2_map.unit_complex().eval(),
  80. raw.template head<2>().eval(),
  81. Constants<Scalar>::epsilon());
  82. SOPHUS_TEST_APPROX(passed, const_se2_map.translation().eval(),
  83. raw.template tail<2>().eval(),
  84. Constants<Scalar>::epsilon());
  85. SOPHUS_TEST_EQUAL(passed, const_se2_map.unit_complex().data(), raw.data());
  86. SOPHUS_TEST_EQUAL(passed, const_se2_map.translation().data(),
  87. raw.data() + 2);
  88. Eigen::Map<SE2Type const> const_shallow_copy = const_se2_map;
  89. SOPHUS_TEST_EQUAL(passed, const_shallow_copy.unit_complex().eval(),
  90. const_se2_map.unit_complex().eval());
  91. SOPHUS_TEST_EQUAL(passed, const_shallow_copy.translation().eval(),
  92. const_se2_map.translation().eval());
  93. Eigen::Matrix<Scalar, 4, 1> raw2;
  94. raw2 << Scalar(1), Scalar(0), Scalar(3), Scalar(1);
  95. Eigen::Map<SE2Type> map_of_se3(raw.data());
  96. map_of_se3.setComplex(raw2.template head<2>());
  97. map_of_se3.translation() = raw2.template tail<2>();
  98. SOPHUS_TEST_APPROX(passed, map_of_se3.unit_complex().eval(),
  99. raw2.template head<2>().eval(),
  100. Constants<Scalar>::epsilon());
  101. SOPHUS_TEST_APPROX(passed, map_of_se3.translation().eval(),
  102. raw2.template tail<2>().eval(),
  103. Constants<Scalar>::epsilon());
  104. SOPHUS_TEST_EQUAL(passed, map_of_se3.unit_complex().data(), raw.data());
  105. SOPHUS_TEST_EQUAL(passed, map_of_se3.translation().data(), raw.data() + 2);
  106. SOPHUS_TEST_NEQ(passed, map_of_se3.unit_complex().data(), raw2.data());
  107. Eigen::Map<SE2Type> shallow_copy = map_of_se3;
  108. SOPHUS_TEST_EQUAL(passed, shallow_copy.unit_complex().eval(),
  109. map_of_se3.unit_complex().eval());
  110. SOPHUS_TEST_EQUAL(passed, shallow_copy.translation().eval(),
  111. map_of_se3.translation().eval());
  112. Eigen::Map<SE2Type> const const_map_of_se2 = map_of_se3;
  113. SOPHUS_TEST_EQUAL(passed, const_map_of_se2.unit_complex().eval(),
  114. map_of_se3.unit_complex().eval());
  115. SOPHUS_TEST_EQUAL(passed, const_map_of_se2.translation().eval(),
  116. map_of_se3.translation().eval());
  117. SE2Type const const_se2(raw2.template head<2>().eval(),
  118. raw2.template tail<2>().eval());
  119. for (int i = 0; i < 4; ++i) {
  120. SOPHUS_TEST_EQUAL(passed, const_se2.data()[i], raw2.data()[i]);
  121. }
  122. SE2Type se2(raw2.template head<2>().eval(), raw2.template tail<2>().eval());
  123. for (int i = 0; i < 4; ++i) {
  124. SOPHUS_TEST_EQUAL(passed, se2.data()[i], raw2.data()[i]);
  125. }
  126. for (int i = 0; i < 4; ++i) {
  127. SOPHUS_TEST_EQUAL(passed, se2.data()[i], raw.data()[i]);
  128. }
  129. SE2Type trans = SE2Type::transX(Scalar(0.2));
  130. SOPHUS_TEST_APPROX(passed, trans.translation().x(), Scalar(0.2),
  131. Constants<Scalar>::epsilon());
  132. trans = SE2Type::transY(Scalar(0.7));
  133. SOPHUS_TEST_APPROX(passed, trans.translation().y(), Scalar(0.7),
  134. Constants<Scalar>::epsilon());
  135. Eigen::Matrix<Scalar, 4, 1> data1, data2;
  136. data1 << Scalar(0), Scalar(1), Scalar(1), Scalar(2);
  137. data1 << Scalar(1), Scalar(0), Scalar(2), Scalar(1);
  138. Eigen::Map<SE2Type> map1(data1.data()), map2(data2.data());
  139. // map -> map assignment
  140. map2 = map1;
  141. SOPHUS_TEST_EQUAL(passed, map1.matrix(), map2.matrix());
  142. // map -> type assignment
  143. SE2Type copy;
  144. copy = map1;
  145. SOPHUS_TEST_EQUAL(passed, map1.matrix(), copy.matrix());
  146. // type -> map assignment
  147. copy = SE2Type::trans(Scalar(4), Scalar(5)) * SE2Type::rot(Scalar(0.5));
  148. map1 = copy;
  149. SOPHUS_TEST_EQUAL(passed, map1.matrix(), copy.matrix());
  150. return passed;
  151. }
  152. bool testMutatingAccessors() {
  153. bool passed = true;
  154. SE2Type se2;
  155. SO2Type R(Scalar(0.2));
  156. se2.setRotationMatrix(R.matrix());
  157. SOPHUS_TEST_APPROX(passed, se2.rotationMatrix(), R.matrix(),
  158. Constants<Scalar>::epsilon());
  159. Eigen::Matrix<Scalar, 4, 1> raw;
  160. raw << Scalar(1), Scalar(0), Scalar(3), Scalar(1);
  161. Eigen::Map<SE2Type> map_of_se2(raw.data());
  162. map_of_se2.setRotationMatrix(R.matrix());
  163. SOPHUS_TEST_APPROX(passed, map_of_se2.rotationMatrix(), R.matrix(),
  164. Constants<Scalar>::epsilon());
  165. return passed;
  166. }
  167. bool testConstructors() {
  168. bool passed = true;
  169. Matrix3<Scalar> I = Matrix3<Scalar>::Identity();
  170. SOPHUS_TEST_EQUAL(passed, SE2Type().matrix(), I);
  171. SE2Type se2 = se2_vec_.front();
  172. Point translation = se2.translation();
  173. SO2Type so2 = se2.so2();
  174. SOPHUS_TEST_APPROX(passed, SE2Type(so2.log(), translation).matrix(),
  175. se2.matrix(), Constants<Scalar>::epsilon());
  176. SOPHUS_TEST_APPROX(passed, SE2Type(so2, translation).matrix(), se2.matrix(),
  177. Constants<Scalar>::epsilon());
  178. SOPHUS_TEST_APPROX(passed, SE2Type(so2.matrix(), translation).matrix(),
  179. se2.matrix(), Constants<Scalar>::epsilon());
  180. SOPHUS_TEST_APPROX(passed,
  181. SE2Type(so2.unit_complex(), translation).matrix(),
  182. se2.matrix(), Constants<Scalar>::epsilon());
  183. SOPHUS_TEST_APPROX(passed, SE2Type(se2.matrix()).matrix(), se2.matrix(),
  184. Constants<Scalar>::epsilon());
  185. return passed;
  186. }
  187. template <class S = Scalar>
  188. enable_if_t<std::is_floating_point<S>::value, bool> testFit() {
  189. bool passed = true;
  190. for (int i = 0; i < 100; ++i) {
  191. Matrix3<Scalar> T = Matrix3<Scalar>::Random();
  192. SE2Type se2 = SE2Type::fitToSE2(T);
  193. SE2Type se2_2 = SE2Type::fitToSE2(se2.matrix());
  194. SOPHUS_TEST_APPROX(passed, se2.matrix(), se2_2.matrix(),
  195. Constants<Scalar>::epsilon());
  196. }
  197. return passed;
  198. }
  199. template <class S = Scalar>
  200. enable_if_t<!std::is_floating_point<S>::value, bool> testFit() {
  201. return true;
  202. }
  203. std::vector<SE2Type, Eigen::aligned_allocator<SE2Type>> se2_vec_;
  204. std::vector<Tangent, Eigen::aligned_allocator<Tangent>> tangent_vec_;
  205. std::vector<Point, Eigen::aligned_allocator<Point>> point_vec_;
  206. };
  207. int test_se2() {
  208. using std::cerr;
  209. using std::endl;
  210. cerr << "Test SE2" << endl << endl;
  211. cerr << "Double tests: " << endl;
  212. Tests<double>().runAll();
  213. cerr << "Float tests: " << endl;
  214. Tests<float>().runAll();
  215. #if SOPHUS_CERES
  216. cerr << "ceres::Jet<double, 3> tests: " << endl;
  217. Tests<ceres::Jet<double, 3>>().runAll();
  218. #endif
  219. return 0;
  220. }
  221. } // namespace Sophus
  222. int main() { return Sophus::test_se2(); }