test_se3.cpp 10.0 KB

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