test_rxso3.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283
  1. #include <iostream>
  2. #include <sophus/rxso3.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::RxSO3<double>>;
  8. template class Map<Sophus::RxSO3<double> const>;
  9. } // namespace Eigen
  10. namespace Sophus {
  11. template class RxSO3<double, Eigen::AutoAlign>;
  12. template class RxSO3<float, Eigen::DontAlign>;
  13. #if SOPHUS_CERES
  14. template class RxSO3<ceres::Jet<double, 3>>;
  15. #endif
  16. template <class Scalar_>
  17. class Tests {
  18. public:
  19. using Scalar = Scalar_;
  20. using SO3Type = SO3<Scalar>;
  21. using RxSO3Type = RxSO3<Scalar>;
  22. using RotationMatrixType = typename SO3<Scalar>::Transformation;
  23. using Point = typename RxSO3<Scalar>::Point;
  24. using Tangent = typename RxSO3<Scalar>::Tangent;
  25. Scalar const kPi = Constants<Scalar>::pi();
  26. Tests() {
  27. rxso3_vec_.push_back(RxSO3Type::exp(
  28. Tangent(Scalar(0.2), Scalar(0.5), Scalar(0.0), Scalar(1.))));
  29. rxso3_vec_.push_back(RxSO3Type::exp(
  30. Tangent(Scalar(0.2), Scalar(0.5), Scalar(-1.0), Scalar(1.1))));
  31. rxso3_vec_.push_back(RxSO3Type::exp(
  32. Tangent(Scalar(0.), Scalar(0.), Scalar(0.), Scalar(1.1))));
  33. rxso3_vec_.push_back(RxSO3Type::exp(
  34. Tangent(Scalar(0.), Scalar(0.), Scalar(0.00001), Scalar(0.))));
  35. rxso3_vec_.push_back(RxSO3Type::exp(
  36. Tangent(Scalar(0.), Scalar(0.), Scalar(0.00001), Scalar(0.00001))));
  37. rxso3_vec_.push_back(RxSO3Type::exp(
  38. Tangent(Scalar(0.), Scalar(0.), Scalar(0.00001), Scalar(0))));
  39. rxso3_vec_.push_back(
  40. RxSO3Type::exp(Tangent(kPi, Scalar(0), Scalar(0), Scalar(0.9))));
  41. rxso3_vec_.push_back(
  42. RxSO3Type::exp(
  43. Tangent(Scalar(0.2), Scalar(-0.5), Scalar(0), Scalar(0))) *
  44. RxSO3Type::exp(Tangent(kPi, Scalar(0), Scalar(0), Scalar(0))) *
  45. RxSO3Type::exp(
  46. Tangent(-Scalar(0.2), Scalar(-0.5), Scalar(0), Scalar(0))));
  47. rxso3_vec_.push_back(
  48. RxSO3Type::exp(
  49. Tangent(Scalar(0.3), Scalar(0.5), Scalar(0.1), Scalar(0))) *
  50. RxSO3Type::exp(Tangent(kPi, Scalar(0), Scalar(0), Scalar(0))) *
  51. RxSO3Type::exp(
  52. Tangent(Scalar(-0.3), Scalar(-0.5), Scalar(-0.1), Scalar(0))));
  53. Tangent tmp;
  54. tmp << Scalar(0), Scalar(0), Scalar(0), Scalar(0);
  55. tangent_vec_.push_back(tmp);
  56. tmp << Scalar(1), Scalar(0), Scalar(0), Scalar(0);
  57. tangent_vec_.push_back(tmp);
  58. tmp << Scalar(1), Scalar(0), Scalar(0), Scalar(0.1);
  59. tangent_vec_.push_back(tmp);
  60. tmp << Scalar(0), Scalar(1), Scalar(0), Scalar(0.1);
  61. tangent_vec_.push_back(tmp);
  62. tmp << Scalar(0), Scalar(0), Scalar(1), Scalar(-0.1);
  63. tangent_vec_.push_back(tmp);
  64. tmp << Scalar(-1), Scalar(1), Scalar(0), Scalar(-0.1);
  65. tangent_vec_.push_back(tmp);
  66. tmp << Scalar(20), Scalar(-1), Scalar(0), Scalar(2);
  67. tangent_vec_.push_back(tmp);
  68. point_vec_.push_back(Point(Scalar(1), Scalar(2), Scalar(4)));
  69. point_vec_.push_back(Point(Scalar(1), Scalar(-3), Scalar(0.5)));
  70. }
  71. void runAll() {
  72. bool passed = testLieProperties();
  73. passed &= testSaturation();
  74. passed &= testRawDataAcces();
  75. passed &= testConstructors();
  76. passed &= testFit();
  77. processTestResult(passed);
  78. }
  79. private:
  80. bool testLieProperties() {
  81. LieGroupTests<RxSO3Type> tests(rxso3_vec_, tangent_vec_, point_vec_);
  82. return tests.doAllTestsPass();
  83. }
  84. bool testSaturation() {
  85. bool passed = true;
  86. RxSO3Type small1(Constants<Scalar>::epsilon(), SO3Type());
  87. RxSO3Type small2(Constants<Scalar>::epsilon(),
  88. SO3Type::exp(Vector3<Scalar>(Constants<Scalar>::pi(),
  89. Scalar(0), Scalar(0))));
  90. RxSO3Type saturated_product = small1 * small2;
  91. SOPHUS_TEST_APPROX(passed, saturated_product.scale(),
  92. Constants<Scalar>::epsilon(),
  93. Constants<Scalar>::epsilon());
  94. SOPHUS_TEST_APPROX(passed, saturated_product.so3().matrix(),
  95. (small1.so3() * small2.so3()).matrix(),
  96. Constants<Scalar>::epsilon());
  97. return passed;
  98. }
  99. bool testRawDataAcces() {
  100. bool passed = true;
  101. Eigen::Matrix<Scalar, 4, 1> raw = {Scalar(0), Scalar(1), Scalar(0),
  102. Scalar(0)};
  103. Eigen::Map<RxSO3Type const> map_of_const_rxso3(raw.data());
  104. SOPHUS_TEST_APPROX(passed, map_of_const_rxso3.quaternion().coeffs().eval(),
  105. raw, Constants<Scalar>::epsilon());
  106. SOPHUS_TEST_EQUAL(passed, map_of_const_rxso3.quaternion().coeffs().data(),
  107. raw.data());
  108. Eigen::Map<RxSO3Type const> const_shallow_copy = map_of_const_rxso3;
  109. SOPHUS_TEST_EQUAL(passed, const_shallow_copy.quaternion().coeffs().eval(),
  110. map_of_const_rxso3.quaternion().coeffs().eval());
  111. Eigen::Matrix<Scalar, 4, 1> raw2 = {Scalar(1), Scalar(0), Scalar(0),
  112. Scalar(0)};
  113. Eigen::Map<RxSO3Type> map_of_rxso3(raw.data());
  114. Eigen::Quaternion<Scalar> quat;
  115. quat.coeffs() = raw2;
  116. map_of_rxso3.setQuaternion(quat);
  117. SOPHUS_TEST_APPROX(passed, map_of_rxso3.quaternion().coeffs().eval(), raw2,
  118. Constants<Scalar>::epsilon());
  119. SOPHUS_TEST_EQUAL(passed, map_of_rxso3.quaternion().coeffs().data(),
  120. raw.data());
  121. SOPHUS_TEST_NEQ(passed, map_of_rxso3.quaternion().coeffs().data(),
  122. quat.coeffs().data());
  123. Eigen::Map<RxSO3Type> shallow_copy = map_of_rxso3;
  124. SOPHUS_TEST_EQUAL(passed, shallow_copy.quaternion().coeffs().eval(),
  125. map_of_rxso3.quaternion().coeffs().eval());
  126. RxSO3Type const const_so3(quat);
  127. for (int i = 0; i < 4; ++i) {
  128. SOPHUS_TEST_EQUAL(passed, const_so3.data()[i], raw2.data()[i]);
  129. }
  130. RxSO3Type so3(quat);
  131. for (int i = 0; i < 4; ++i) {
  132. so3.data()[i] = raw[i];
  133. }
  134. for (int i = 0; i < 4; ++i) {
  135. SOPHUS_TEST_EQUAL(passed, so3.data()[i], raw.data()[i]);
  136. }
  137. // regression: test that rotationMatrix API doesn't change underlying value
  138. // for non-const-map and compiles at all for const-map
  139. Eigen::Matrix<Scalar, 4, 1> raw3 = {Scalar(2), Scalar(0), Scalar(0),
  140. Scalar(0)};
  141. Eigen::Map<RxSO3Type> map_of_rxso3_3(raw3.data());
  142. Eigen::Map<const RxSO3Type> const_map_of_rxso3_3(raw3.data());
  143. RxSO3Type rxso3_copy3 = map_of_rxso3_3;
  144. const RotationMatrixType r_ref = map_of_rxso3_3.so3().matrix();
  145. const RotationMatrixType r = map_of_rxso3_3.rotationMatrix();
  146. SOPHUS_TEST_APPROX(passed, r_ref, r, Constants<Scalar>::epsilon());
  147. SOPHUS_TEST_APPROX(passed, map_of_rxso3_3.quaternion().coeffs().eval(),
  148. rxso3_copy3.quaternion().coeffs().eval(),
  149. Constants<Scalar>::epsilon());
  150. const RotationMatrixType r_const = const_map_of_rxso3_3.rotationMatrix();
  151. SOPHUS_TEST_APPROX(passed, r_ref, r_const, Constants<Scalar>::epsilon());
  152. SOPHUS_TEST_APPROX(
  153. passed, const_map_of_rxso3_3.quaternion().coeffs().eval(),
  154. rxso3_copy3.quaternion().coeffs().eval(), Constants<Scalar>::epsilon());
  155. Eigen::Matrix<Scalar, 4, 1> data1, data2;
  156. data1 << Scalar(.1), Scalar(.2), Scalar(.3), Scalar(.4);
  157. data2 << Scalar(.5), Scalar(.4), Scalar(.3), Scalar(.2);
  158. Eigen::Map<RxSO3Type> map1(data1.data()), map2(data2.data());
  159. // map -> map assignment
  160. map2 = map1;
  161. SOPHUS_TEST_EQUAL(passed, map1.matrix(), map2.matrix());
  162. // map -> type assignment
  163. RxSO3Type copy;
  164. copy = map1;
  165. SOPHUS_TEST_EQUAL(passed, map1.matrix(), copy.matrix());
  166. // type -> map assignment
  167. copy = RxSO3Type::exp(Tangent(Scalar(0.2), Scalar(0.5),
  168. Scalar(-1.0), Scalar(1.1)));
  169. map1 = copy;
  170. SOPHUS_TEST_EQUAL(passed, map1.matrix(), copy.matrix());
  171. return passed;
  172. }
  173. bool testConstructors() {
  174. bool passed = true;
  175. RxSO3Type rxso3;
  176. Scalar scale(1.2);
  177. rxso3.setScale(scale);
  178. SOPHUS_TEST_APPROX(passed, scale, rxso3.scale(),
  179. Constants<Scalar>::epsilon(), "setScale");
  180. auto so3 = rxso3_vec_[0].so3();
  181. rxso3.setSO3(so3);
  182. SOPHUS_TEST_APPROX(passed, scale, rxso3.scale(),
  183. Constants<Scalar>::epsilon(), "setScale");
  184. SOPHUS_TEST_APPROX(passed, RxSO3Type(scale, so3).matrix(), rxso3.matrix(),
  185. Constants<Scalar>::epsilon(), "RxSO3(scale, SO3)");
  186. SOPHUS_TEST_APPROX(passed, RxSO3Type(scale, so3.matrix()).matrix(),
  187. rxso3.matrix(), Constants<Scalar>::epsilon(),
  188. "RxSO3(scale, SO3)");
  189. Matrix3<Scalar> R =
  190. SO3<Scalar>::exp(Point(Scalar(0.2), Scalar(0.5), Scalar(-1.0)))
  191. .matrix();
  192. Matrix3<Scalar> sR = R * Scalar(1.3);
  193. SOPHUS_TEST_APPROX(passed, RxSO3Type(sR).matrix(), sR,
  194. Constants<Scalar>::epsilon(), "RxSO3(sR)");
  195. rxso3.setScaledRotationMatrix(sR);
  196. SOPHUS_TEST_APPROX(passed, sR, rxso3.matrix(), Constants<Scalar>::epsilon(),
  197. "setScaleRotationMatrix");
  198. rxso3.setScale(scale);
  199. rxso3.setRotationMatrix(R);
  200. SOPHUS_TEST_APPROX(passed, R, rxso3.rotationMatrix(),
  201. Constants<Scalar>::epsilon(), "setRotationMatrix");
  202. SOPHUS_TEST_APPROX(passed, scale, rxso3.scale(),
  203. Constants<Scalar>::epsilon(), "setScale");
  204. return passed;
  205. }
  206. template <class S = Scalar>
  207. enable_if_t<std::is_floating_point<S>::value, bool> testFit() {
  208. bool passed = true;
  209. for (int i = 0; i < 10; ++i) {
  210. Matrix3<Scalar> M = Matrix3<Scalar>::Random();
  211. for (Scalar scale : {Scalar(0.01), Scalar(0.99), Scalar(1), Scalar(10)}) {
  212. Matrix3<Scalar> R = makeRotationMatrix(M);
  213. Matrix3<Scalar> sR = scale * R;
  214. SOPHUS_TEST(passed, isScaledOrthogonalAndPositive(sR),
  215. "isScaledOrthogonalAndPositive(sR): % *\n%", scale, R);
  216. Matrix3<Scalar> sR_cols_swapped;
  217. sR_cols_swapped << sR.col(1), sR.col(0), sR.col(2);
  218. SOPHUS_TEST(passed, !isScaledOrthogonalAndPositive(sR_cols_swapped),
  219. "isScaledOrthogonalAndPositive(-sR): % *\n%", scale, R);
  220. }
  221. }
  222. return passed;
  223. }
  224. template <class S = Scalar>
  225. enable_if_t<!std::is_floating_point<S>::value, bool> testFit() {
  226. return true;
  227. }
  228. std::vector<RxSO3Type, Eigen::aligned_allocator<RxSO3Type>> rxso3_vec_;
  229. std::vector<Tangent, Eigen::aligned_allocator<Tangent>> tangent_vec_;
  230. std::vector<Point, Eigen::aligned_allocator<Point>> point_vec_;
  231. };
  232. int test_rxso3() {
  233. using std::cerr;
  234. using std::endl;
  235. cerr << "Test RxSO3" << endl << endl;
  236. cerr << "Double tests: " << endl;
  237. Tests<double>().runAll();
  238. cerr << "Float tests: " << endl;
  239. Tests<float>().runAll();
  240. #if SOPHUS_CERES
  241. cerr << "ceres::Jet<double, 3> tests: " << endl;
  242. Tests<ceres::Jet<double, 3>>().runAll();
  243. #endif
  244. return 0;
  245. }
  246. } // namespace Sophus
  247. int main() { return Sophus::test_rxso3(); }