test_calibration_hand_eye.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759
  1. // This file is part of OpenCV project.
  2. // It is subject to the license terms in the LICENSE file found in the top-level directory
  3. // of this distribution and at http://opencv.org/license.html.
  4. #include "test_precomp.hpp"
  5. #include "opencv2/calib3d.hpp"
  6. namespace opencv_test { namespace {
  7. static void generatePose(RNG& rng, double min_theta, double max_theta,
  8. double min_tx, double max_tx,
  9. double min_ty, double max_ty,
  10. double min_tz, double max_tz,
  11. Mat& R, Mat& tvec,
  12. bool random_sign)
  13. {
  14. Mat axis(3, 1, CV_64FC1);
  15. for (int i = 0; i < 3; i++)
  16. {
  17. axis.at<double>(i,0) = rng.uniform(-1.0, 1.0);
  18. }
  19. double theta = rng.uniform(min_theta, max_theta);
  20. if (random_sign)
  21. {
  22. theta *= std::copysign(1.0, rng.uniform(-1.0, 1.0));
  23. }
  24. Mat rvec(3, 1, CV_64FC1);
  25. rvec.at<double>(0,0) = theta*axis.at<double>(0,0);
  26. rvec.at<double>(1,0) = theta*axis.at<double>(1,0);
  27. rvec.at<double>(2,0) = theta*axis.at<double>(2,0);
  28. tvec.create(3, 1, CV_64FC1);
  29. tvec.at<double>(0,0) = rng.uniform(min_tx, max_tx);
  30. tvec.at<double>(1,0) = rng.uniform(min_ty, max_ty);
  31. tvec.at<double>(2,0) = rng.uniform(min_tz, max_tz);
  32. if (random_sign)
  33. {
  34. tvec.at<double>(0,0) *= std::copysign(1.0, rng.uniform(-1.0, 1.0));
  35. tvec.at<double>(1,0) *= std::copysign(1.0, rng.uniform(-1.0, 1.0));
  36. tvec.at<double>(2,0) *= std::copysign(1.0, rng.uniform(-1.0, 1.0));
  37. }
  38. cv::Rodrigues(rvec, R);
  39. }
  40. static Mat homogeneousInverse(const Mat& T)
  41. {
  42. CV_Assert( T.rows == 4 && T.cols == 4 );
  43. Mat R = T(Rect(0, 0, 3, 3));
  44. Mat t = T(Rect(3, 0, 1, 3));
  45. Mat Rt = R.t();
  46. Mat tinv = -Rt * t;
  47. Mat Tinv = Mat::eye(4, 4, T.type());
  48. Rt.copyTo(Tinv(Rect(0, 0, 3, 3)));
  49. tinv.copyTo(Tinv(Rect(3, 0, 1, 3)));
  50. return Tinv;
  51. }
  52. static void simulateDataEyeInHand(RNG& rng, int nPoses,
  53. std::vector<Mat> &R_gripper2base, std::vector<Mat> &t_gripper2base,
  54. std::vector<Mat> &R_target2cam, std::vector<Mat> &t_target2cam,
  55. bool noise, Mat& R_cam2gripper, Mat& t_cam2gripper)
  56. {
  57. //to avoid generating values close to zero,
  58. //we use positive range values and randomize the sign
  59. const bool random_sign = true;
  60. generatePose(rng, 10.0*CV_PI/180.0, 50.0*CV_PI/180.0,
  61. 0.05, 0.5, 0.05, 0.5, 0.05, 0.5,
  62. R_cam2gripper, t_cam2gripper, random_sign);
  63. Mat R_target2base, t_target2base;
  64. generatePose(rng, 5.0*CV_PI/180.0, 85.0*CV_PI/180.0,
  65. 0.5, 3.5, 0.5, 3.5, 0.5, 3.5,
  66. R_target2base, t_target2base, random_sign);
  67. for (int i = 0; i < nPoses; i++)
  68. {
  69. Mat R_gripper2base_, t_gripper2base_;
  70. generatePose(rng, 5.0*CV_PI/180.0, 45.0*CV_PI/180.0,
  71. 0.5, 1.5, 0.5, 1.5, 0.5, 1.5,
  72. R_gripper2base_, t_gripper2base_, random_sign);
  73. R_gripper2base.push_back(R_gripper2base_);
  74. t_gripper2base.push_back(t_gripper2base_);
  75. Mat T_cam2gripper = Mat::eye(4, 4, CV_64FC1);
  76. R_cam2gripper.copyTo(T_cam2gripper(Rect(0, 0, 3, 3)));
  77. t_cam2gripper.copyTo(T_cam2gripper(Rect(3, 0, 1, 3)));
  78. Mat T_gripper2base = Mat::eye(4, 4, CV_64FC1);
  79. R_gripper2base_.copyTo(T_gripper2base(Rect(0, 0, 3, 3)));
  80. t_gripper2base_.copyTo(T_gripper2base(Rect(3, 0, 1, 3)));
  81. Mat T_base2cam = homogeneousInverse(T_cam2gripper) * homogeneousInverse(T_gripper2base);
  82. Mat T_target2base = Mat::eye(4, 4, CV_64FC1);
  83. R_target2base.copyTo(T_target2base(Rect(0, 0, 3, 3)));
  84. t_target2base.copyTo(T_target2base(Rect(3, 0, 1, 3)));
  85. Mat T_target2cam = T_base2cam * T_target2base;
  86. if (noise)
  87. {
  88. //Add some noise for the transformation between the target and the camera
  89. Mat R_target2cam_noise = T_target2cam(Rect(0, 0, 3, 3));
  90. Mat rvec_target2cam_noise;
  91. cv::Rodrigues(R_target2cam_noise, rvec_target2cam_noise);
  92. rvec_target2cam_noise.at<double>(0,0) += rng.gaussian(0.002);
  93. rvec_target2cam_noise.at<double>(1,0) += rng.gaussian(0.002);
  94. rvec_target2cam_noise.at<double>(2,0) += rng.gaussian(0.002);
  95. cv::Rodrigues(rvec_target2cam_noise, R_target2cam_noise);
  96. Mat t_target2cam_noise = T_target2cam(Rect(3, 0, 1, 3));
  97. t_target2cam_noise.at<double>(0,0) += rng.gaussian(0.005);
  98. t_target2cam_noise.at<double>(1,0) += rng.gaussian(0.005);
  99. t_target2cam_noise.at<double>(2,0) += rng.gaussian(0.005);
  100. //Add some noise for the transformation between the gripper and the robot base
  101. Mat R_gripper2base_noise = T_gripper2base(Rect(0, 0, 3, 3));
  102. Mat rvec_gripper2base_noise;
  103. cv::Rodrigues(R_gripper2base_noise, rvec_gripper2base_noise);
  104. rvec_gripper2base_noise.at<double>(0,0) += rng.gaussian(0.001);
  105. rvec_gripper2base_noise.at<double>(1,0) += rng.gaussian(0.001);
  106. rvec_gripper2base_noise.at<double>(2,0) += rng.gaussian(0.001);
  107. cv::Rodrigues(rvec_gripper2base_noise, R_gripper2base_noise);
  108. Mat t_gripper2base_noise = T_gripper2base(Rect(3, 0, 1, 3));
  109. t_gripper2base_noise.at<double>(0,0) += rng.gaussian(0.001);
  110. t_gripper2base_noise.at<double>(1,0) += rng.gaussian(0.001);
  111. t_gripper2base_noise.at<double>(2,0) += rng.gaussian(0.001);
  112. }
  113. //Test rvec representation
  114. Mat rvec_target2cam;
  115. cv::Rodrigues(T_target2cam(Rect(0, 0, 3, 3)), rvec_target2cam);
  116. R_target2cam.push_back(rvec_target2cam);
  117. t_target2cam.push_back(T_target2cam(Rect(3, 0, 1, 3)));
  118. }
  119. }
  120. static void simulateDataEyeToHand(RNG& rng, int nPoses,
  121. std::vector<Mat> &R_base2gripper, std::vector<Mat> &t_base2gripper,
  122. std::vector<Mat> &R_target2cam, std::vector<Mat> &t_target2cam,
  123. bool noise, Mat& R_cam2base, Mat& t_cam2base)
  124. {
  125. //to avoid generating values close to zero,
  126. //we use positive range values and randomize the sign
  127. const bool random_sign = true;
  128. generatePose(rng, 10.0*CV_PI/180.0, 50.0*CV_PI/180.0,
  129. 0.5, 3.5, 0.5, 3.5, 0.5, 3.5,
  130. R_cam2base, t_cam2base, random_sign);
  131. Mat R_target2gripper, t_target2gripper;
  132. generatePose(rng, 5.0*CV_PI/180.0, 85.0*CV_PI/180.0,
  133. 0.05, 0.5, 0.05, 0.5, 0.05, 0.5,
  134. R_target2gripper, t_target2gripper, random_sign);
  135. Mat T_target2gripper = Mat::eye(4, 4, CV_64FC1);
  136. R_target2gripper.copyTo(T_target2gripper(Rect(0, 0, 3, 3)));
  137. t_target2gripper.copyTo(T_target2gripper(Rect(3, 0, 1, 3)));
  138. for (int i = 0; i < nPoses; i++)
  139. {
  140. Mat R_gripper2base_, t_gripper2base_;
  141. generatePose(rng, 5.0*CV_PI/180.0, 45.0*CV_PI/180.0,
  142. 0.5, 1.5, 0.5, 1.5, 0.5, 1.5,
  143. R_gripper2base_, t_gripper2base_, random_sign);
  144. Mat R_base2gripper_ = R_gripper2base_.t();
  145. Mat t_base2gripper_ = -R_base2gripper_ * t_gripper2base_;
  146. Mat T_gripper2base = Mat::eye(4, 4, CV_64FC1);
  147. R_gripper2base_.copyTo(T_gripper2base(Rect(0, 0, 3, 3)));
  148. t_gripper2base_.copyTo(T_gripper2base(Rect(3, 0, 1, 3)));
  149. Mat T_cam2base = Mat::eye(4, 4, CV_64FC1);
  150. R_cam2base.copyTo(T_cam2base(Rect(0, 0, 3, 3)));
  151. t_cam2base.copyTo(T_cam2base(Rect(3, 0, 1, 3)));
  152. Mat T_target2cam = homogeneousInverse(T_cam2base) * T_gripper2base * T_target2gripper;
  153. if (noise)
  154. {
  155. //Add some noise for the transformation between the target and the camera
  156. Mat R_target2cam_noise = T_target2cam(Rect(0, 0, 3, 3));
  157. Mat rvec_target2cam_noise;
  158. cv::Rodrigues(R_target2cam_noise, rvec_target2cam_noise);
  159. rvec_target2cam_noise.at<double>(0,0) += rng.gaussian(0.002);
  160. rvec_target2cam_noise.at<double>(1,0) += rng.gaussian(0.002);
  161. rvec_target2cam_noise.at<double>(2,0) += rng.gaussian(0.002);
  162. cv::Rodrigues(rvec_target2cam_noise, R_target2cam_noise);
  163. Mat t_target2cam_noise = T_target2cam(Rect(3, 0, 1, 3));
  164. t_target2cam_noise.at<double>(0,0) += rng.gaussian(0.005);
  165. t_target2cam_noise.at<double>(1,0) += rng.gaussian(0.005);
  166. t_target2cam_noise.at<double>(2,0) += rng.gaussian(0.005);
  167. //Add some noise for the transformation between the robot base and the gripper
  168. Mat rvec_base2gripper_noise;
  169. cv::Rodrigues(R_base2gripper_, rvec_base2gripper_noise);
  170. rvec_base2gripper_noise.at<double>(0,0) += rng.gaussian(0.001);
  171. rvec_base2gripper_noise.at<double>(1,0) += rng.gaussian(0.001);
  172. rvec_base2gripper_noise.at<double>(2,0) += rng.gaussian(0.001);
  173. cv::Rodrigues(rvec_base2gripper_noise, R_base2gripper_);
  174. t_base2gripper_.at<double>(0,0) += rng.gaussian(0.001);
  175. t_base2gripper_.at<double>(1,0) += rng.gaussian(0.001);
  176. t_base2gripper_.at<double>(2,0) += rng.gaussian(0.001);
  177. }
  178. R_base2gripper.push_back(R_base2gripper_);
  179. t_base2gripper.push_back(t_base2gripper_);
  180. //Test rvec representation
  181. Mat rvec_target2cam;
  182. cv::Rodrigues(T_target2cam(Rect(0, 0, 3, 3)), rvec_target2cam);
  183. R_target2cam.push_back(rvec_target2cam);
  184. t_target2cam.push_back(T_target2cam(Rect(3, 0, 1, 3)));
  185. }
  186. }
  187. static std::string getMethodName(HandEyeCalibrationMethod method)
  188. {
  189. std::string method_name = "";
  190. switch (method)
  191. {
  192. case CALIB_HAND_EYE_TSAI:
  193. method_name = "Tsai";
  194. break;
  195. case CALIB_HAND_EYE_PARK:
  196. method_name = "Park";
  197. break;
  198. case CALIB_HAND_EYE_HORAUD:
  199. method_name = "Horaud";
  200. break;
  201. case CALIB_HAND_EYE_ANDREFF:
  202. method_name = "Andreff";
  203. break;
  204. case CALIB_HAND_EYE_DANIILIDIS:
  205. method_name = "Daniilidis";
  206. break;
  207. default:
  208. break;
  209. }
  210. return method_name;
  211. }
  212. static std::string getMethodName(RobotWorldHandEyeCalibrationMethod method)
  213. {
  214. std::string method_name = "";
  215. switch (method)
  216. {
  217. case CALIB_ROBOT_WORLD_HAND_EYE_SHAH:
  218. method_name = "Shah";
  219. break;
  220. case CALIB_ROBOT_WORLD_HAND_EYE_LI:
  221. method_name = "Li";
  222. break;
  223. default:
  224. break;
  225. }
  226. return method_name;
  227. }
  228. static void printStats(const std::string& methodName, const std::vector<double>& rvec_diff, const std::vector<double>& tvec_diff)
  229. {
  230. double max_rvec_diff = *std::max_element(rvec_diff.begin(), rvec_diff.end());
  231. double mean_rvec_diff = std::accumulate(rvec_diff.begin(),
  232. rvec_diff.end(), 0.0) / rvec_diff.size();
  233. double sq_sum_rvec_diff = std::inner_product(rvec_diff.begin(), rvec_diff.end(),
  234. rvec_diff.begin(), 0.0);
  235. double std_rvec_diff = std::sqrt(sq_sum_rvec_diff / rvec_diff.size() - mean_rvec_diff * mean_rvec_diff);
  236. double max_tvec_diff = *std::max_element(tvec_diff.begin(), tvec_diff.end());
  237. double mean_tvec_diff = std::accumulate(tvec_diff.begin(),
  238. tvec_diff.end(), 0.0) / tvec_diff.size();
  239. double sq_sum_tvec_diff = std::inner_product(tvec_diff.begin(), tvec_diff.end(),
  240. tvec_diff.begin(), 0.0);
  241. double std_tvec_diff = std::sqrt(sq_sum_tvec_diff / tvec_diff.size() - mean_tvec_diff * mean_tvec_diff);
  242. std::cout << "Method " << methodName << ":\n"
  243. << "Max rvec error: " << max_rvec_diff << ", Mean rvec error: " << mean_rvec_diff
  244. << ", Std rvec error: " << std_rvec_diff << "\n"
  245. << "Max tvec error: " << max_tvec_diff << ", Mean tvec error: " << mean_tvec_diff
  246. << ", Std tvec error: " << std_tvec_diff << std::endl;
  247. }
  248. static void loadDataset(std::vector<Mat>& R_target2cam, std::vector<Mat>& t_target2cam,
  249. std::vector<Mat>& R_base2gripper, std::vector<Mat>& t_base2gripper)
  250. {
  251. const std::string camera_poses_filename = findDataFile("cv/robot_world_hand_eye_calibration/cali.txt");
  252. const std::string end_effector_poses = findDataFile("cv/robot_world_hand_eye_calibration/robot_cali.txt");
  253. // Parse camera poses, the pose of the chessboard in the camera frame
  254. {
  255. std::ifstream file(camera_poses_filename);
  256. ASSERT_TRUE(file.is_open());
  257. int ndata = 0;
  258. file >> ndata;
  259. R_target2cam.reserve(ndata);
  260. t_target2cam.reserve(ndata);
  261. std::string image_name;
  262. Matx33d cameraMatrix;
  263. Matx33d R;
  264. Matx31d t;
  265. Matx16d distCoeffs;
  266. Matx13d distCoeffs2;
  267. while (file >> image_name >>
  268. cameraMatrix(0,0) >> cameraMatrix(0,1) >> cameraMatrix(0,2) >>
  269. cameraMatrix(1,0) >> cameraMatrix(1,1) >> cameraMatrix(1,2) >>
  270. cameraMatrix(2,0) >> cameraMatrix(2,1) >> cameraMatrix(2,2) >>
  271. R(0,0) >> R(0,1) >> R(0,2) >>
  272. R(1,0) >> R(1,1) >> R(1,2) >>
  273. R(2,0) >> R(2,1) >> R(2,2) >>
  274. t(0) >> t(1) >> t(2) >>
  275. distCoeffs(0) >> distCoeffs(1) >> distCoeffs(2) >> distCoeffs(3) >> distCoeffs(4) >>
  276. distCoeffs2(0) >> distCoeffs2(1) >> distCoeffs2(2)) {
  277. R_target2cam.push_back(Mat(R));
  278. t_target2cam.push_back(Mat(t));
  279. }
  280. }
  281. // Parse robot poses, the pose of the robot base in the robot hand frame
  282. {
  283. std::ifstream file(end_effector_poses);
  284. ASSERT_TRUE(file.is_open());
  285. int ndata = 0;
  286. file >> ndata;
  287. R_base2gripper.reserve(ndata);
  288. t_base2gripper.reserve(ndata);
  289. Matx33d R;
  290. Matx31d t;
  291. Matx14d last_row;
  292. while (file >>
  293. R(0,0) >> R(0,1) >> R(0,2) >> t(0) >>
  294. R(1,0) >> R(1,1) >> R(1,2) >> t(1) >>
  295. R(2,0) >> R(2,1) >> R(2,2) >> t(2) >>
  296. last_row(0) >> last_row(1) >> last_row(2) >> last_row(3)) {
  297. R_base2gripper.push_back(Mat(R));
  298. t_base2gripper.push_back(Mat(t));
  299. }
  300. }
  301. }
  302. static void loadResults(Matx33d& wRb, Matx31d& wtb, Matx33d& cRg, Matx31d& ctg)
  303. {
  304. const std::string transformations_filename = findDataFile("cv/robot_world_hand_eye_calibration/rwhe_AA_RPI/transformations.txt");
  305. std::ifstream file(transformations_filename);
  306. ASSERT_TRUE(file.is_open());
  307. std::string str;
  308. //Parse X
  309. file >> str;
  310. Matx44d wTb;
  311. for (int i = 0; i < 4; i++)
  312. {
  313. for (int j = 0; j < 4; j++)
  314. {
  315. file >> wTb(i,j);
  316. }
  317. }
  318. //Parse Z
  319. file >> str;
  320. int cam_num = 0;
  321. //Parse camera number
  322. file >> cam_num;
  323. Matx44d cTg;
  324. for (int i = 0; i < 4; i++)
  325. {
  326. for (int j = 0; j < 4; j++)
  327. {
  328. file >> cTg(i,j);
  329. }
  330. }
  331. for (int i = 0; i < 3; i++)
  332. {
  333. for (int j = 0; j < 3; j++)
  334. {
  335. wRb(i,j) = wTb(i,j);
  336. cRg(i,j) = cTg(i,j);
  337. }
  338. wtb(i) = wTb(i,3);
  339. ctg(i) = cTg(i,3);
  340. }
  341. }
  342. class CV_CalibrateHandEyeTest : public cvtest::BaseTest
  343. {
  344. public:
  345. CV_CalibrateHandEyeTest(bool eyeToHand) : eyeToHandConfig(eyeToHand) {
  346. eps_rvec[CALIB_HAND_EYE_TSAI] = 1.0e-8;
  347. eps_rvec[CALIB_HAND_EYE_PARK] = 1.0e-8;
  348. eps_rvec[CALIB_HAND_EYE_HORAUD] = 1.0e-8;
  349. eps_rvec[CALIB_HAND_EYE_ANDREFF] = 1.0e-8;
  350. eps_rvec[CALIB_HAND_EYE_DANIILIDIS] = 1.0e-8;
  351. eps_tvec[CALIB_HAND_EYE_TSAI] = 1.0e-8;
  352. eps_tvec[CALIB_HAND_EYE_PARK] = 1.0e-8;
  353. eps_tvec[CALIB_HAND_EYE_HORAUD] = 1.0e-8;
  354. eps_tvec[CALIB_HAND_EYE_ANDREFF] = 1.0e-8;
  355. eps_tvec[CALIB_HAND_EYE_DANIILIDIS] = 1.0e-8;
  356. eps_rvec_noise[CALIB_HAND_EYE_TSAI] = 2.0e-2;
  357. eps_rvec_noise[CALIB_HAND_EYE_PARK] = 2.0e-2;
  358. eps_rvec_noise[CALIB_HAND_EYE_HORAUD] = 2.0e-2;
  359. eps_rvec_noise[CALIB_HAND_EYE_ANDREFF] = 1.0e-2;
  360. eps_rvec_noise[CALIB_HAND_EYE_DANIILIDIS] = 1.0e-2;
  361. eps_tvec_noise[CALIB_HAND_EYE_TSAI] = 5.0e-2;
  362. eps_tvec_noise[CALIB_HAND_EYE_PARK] = 5.0e-2;
  363. eps_tvec_noise[CALIB_HAND_EYE_HORAUD] = 5.0e-2;
  364. if (eyeToHandConfig)
  365. {
  366. eps_tvec_noise[CALIB_HAND_EYE_ANDREFF] = 7.0e-2;
  367. }
  368. else
  369. {
  370. eps_tvec_noise[CALIB_HAND_EYE_ANDREFF] = 5.0e-2;
  371. }
  372. eps_tvec_noise[CALIB_HAND_EYE_DANIILIDIS] = 5.0e-2;
  373. }
  374. protected:
  375. virtual void run(int);
  376. bool eyeToHandConfig;
  377. double eps_rvec[5];
  378. double eps_tvec[5];
  379. double eps_rvec_noise[5];
  380. double eps_tvec_noise[5];
  381. };
  382. void CV_CalibrateHandEyeTest::run(int)
  383. {
  384. ts->set_failed_test_info(cvtest::TS::OK);
  385. RNG& rng = ts->get_rng();
  386. std::vector<std::vector<double> > vec_rvec_diff(5);
  387. std::vector<std::vector<double> > vec_tvec_diff(5);
  388. std::vector<std::vector<double> > vec_rvec_diff_noise(5);
  389. std::vector<std::vector<double> > vec_tvec_diff_noise(5);
  390. std::vector<HandEyeCalibrationMethod> methods;
  391. methods.push_back(CALIB_HAND_EYE_TSAI);
  392. methods.push_back(CALIB_HAND_EYE_PARK);
  393. methods.push_back(CALIB_HAND_EYE_HORAUD);
  394. methods.push_back(CALIB_HAND_EYE_ANDREFF);
  395. methods.push_back(CALIB_HAND_EYE_DANIILIDIS);
  396. const int nTests = 100;
  397. for (int i = 0; i < nTests; i++)
  398. {
  399. const int nPoses = 10;
  400. if (eyeToHandConfig)
  401. {
  402. {
  403. //No noise
  404. std::vector<Mat> R_base2gripper, t_base2gripper;
  405. std::vector<Mat> R_target2cam, t_target2cam;
  406. Mat R_cam2base_true, t_cam2base_true;
  407. const bool noise = false;
  408. simulateDataEyeToHand(rng, nPoses, R_base2gripper, t_base2gripper, R_target2cam, t_target2cam, noise,
  409. R_cam2base_true, t_cam2base_true);
  410. for (size_t idx = 0; idx < methods.size(); idx++)
  411. {
  412. Mat rvec_cam2base_true;
  413. cv::Rodrigues(R_cam2base_true, rvec_cam2base_true);
  414. Mat R_cam2base_est, t_cam2base_est;
  415. calibrateHandEye(R_base2gripper, t_base2gripper, R_target2cam, t_target2cam, R_cam2base_est, t_cam2base_est, methods[idx]);
  416. Mat rvec_cam2base_est;
  417. cv::Rodrigues(R_cam2base_est, rvec_cam2base_est);
  418. double rvecDiff = cvtest::norm(rvec_cam2base_true, rvec_cam2base_est, NORM_L2);
  419. double tvecDiff = cvtest::norm(t_cam2base_true, t_cam2base_est, NORM_L2);
  420. vec_rvec_diff[idx].push_back(rvecDiff);
  421. vec_tvec_diff[idx].push_back(tvecDiff);
  422. const double epsilon_rvec = eps_rvec[idx];
  423. const double epsilon_tvec = eps_tvec[idx];
  424. //Maybe a better accuracy test would be to compare the mean and std errors with some thresholds?
  425. if (rvecDiff > epsilon_rvec || tvecDiff > epsilon_tvec)
  426. {
  427. ts->printf(cvtest::TS::LOG, "Invalid accuracy (no noise) for method: %s, rvecDiff: %f, epsilon_rvec: %f, tvecDiff: %f, epsilon_tvec: %f\n",
  428. getMethodName(methods[idx]).c_str(), rvecDiff, epsilon_rvec, tvecDiff, epsilon_tvec);
  429. ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
  430. }
  431. }
  432. }
  433. {
  434. //Gaussian noise on transformations between calibration target frame and camera frame and between robot base and gripper frames
  435. std::vector<Mat> R_base2gripper, t_base2gripper;
  436. std::vector<Mat> R_target2cam, t_target2cam;
  437. Mat R_cam2base_true, t_cam2base_true;
  438. const bool noise = true;
  439. simulateDataEyeToHand(rng, nPoses, R_base2gripper, t_base2gripper, R_target2cam, t_target2cam, noise,
  440. R_cam2base_true, t_cam2base_true);
  441. for (size_t idx = 0; idx < methods.size(); idx++)
  442. {
  443. Mat rvec_cam2base_true;
  444. cv::Rodrigues(R_cam2base_true, rvec_cam2base_true);
  445. Mat R_cam2base_est, t_cam2base_est;
  446. calibrateHandEye(R_base2gripper, t_base2gripper, R_target2cam, t_target2cam, R_cam2base_est, t_cam2base_est, methods[idx]);
  447. Mat rvec_cam2base_est;
  448. cv::Rodrigues(R_cam2base_est, rvec_cam2base_est);
  449. double rvecDiff = cvtest::norm(rvec_cam2base_true, rvec_cam2base_est, NORM_L2);
  450. double tvecDiff = cvtest::norm(t_cam2base_true, t_cam2base_est, NORM_L2);
  451. vec_rvec_diff_noise[idx].push_back(rvecDiff);
  452. vec_tvec_diff_noise[idx].push_back(tvecDiff);
  453. const double epsilon_rvec = eps_rvec_noise[idx];
  454. const double epsilon_tvec = eps_tvec_noise[idx];
  455. //Maybe a better accuracy test would be to compare the mean and std errors with some thresholds?
  456. if (rvecDiff > epsilon_rvec || tvecDiff > epsilon_tvec)
  457. {
  458. ts->printf(cvtest::TS::LOG, "Invalid accuracy (noise) for method: %s, rvecDiff: %f, epsilon_rvec: %f, tvecDiff: %f, epsilon_tvec: %f\n",
  459. getMethodName(methods[idx]).c_str(), rvecDiff, epsilon_rvec, tvecDiff, epsilon_tvec);
  460. ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
  461. }
  462. }
  463. }
  464. }
  465. else
  466. {
  467. {
  468. //No noise
  469. std::vector<Mat> R_gripper2base, t_gripper2base;
  470. std::vector<Mat> R_target2cam, t_target2cam;
  471. Mat R_cam2gripper_true, t_cam2gripper_true;
  472. const bool noise = false;
  473. simulateDataEyeInHand(rng, nPoses, R_gripper2base, t_gripper2base, R_target2cam, t_target2cam, noise,
  474. R_cam2gripper_true, t_cam2gripper_true);
  475. for (size_t idx = 0; idx < methods.size(); idx++)
  476. {
  477. Mat rvec_cam2gripper_true;
  478. cv::Rodrigues(R_cam2gripper_true, rvec_cam2gripper_true);
  479. Mat R_cam2gripper_est, t_cam2gripper_est;
  480. calibrateHandEye(R_gripper2base, t_gripper2base, R_target2cam, t_target2cam, R_cam2gripper_est, t_cam2gripper_est, methods[idx]);
  481. Mat rvec_cam2gripper_est;
  482. cv::Rodrigues(R_cam2gripper_est, rvec_cam2gripper_est);
  483. double rvecDiff = cvtest::norm(rvec_cam2gripper_true, rvec_cam2gripper_est, NORM_L2);
  484. double tvecDiff = cvtest::norm(t_cam2gripper_true, t_cam2gripper_est, NORM_L2);
  485. vec_rvec_diff[idx].push_back(rvecDiff);
  486. vec_tvec_diff[idx].push_back(tvecDiff);
  487. const double epsilon_rvec = eps_rvec[idx];
  488. const double epsilon_tvec = eps_tvec[idx];
  489. //Maybe a better accuracy test would be to compare the mean and std errors with some thresholds?
  490. if (rvecDiff > epsilon_rvec || tvecDiff > epsilon_tvec)
  491. {
  492. ts->printf(cvtest::TS::LOG, "Invalid accuracy (no noise) for method: %s, rvecDiff: %f, epsilon_rvec: %f, tvecDiff: %f, epsilon_tvec: %f\n",
  493. getMethodName(methods[idx]).c_str(), rvecDiff, epsilon_rvec, tvecDiff, epsilon_tvec);
  494. ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
  495. }
  496. }
  497. }
  498. {
  499. //Gaussian noise on transformations between calibration target frame and camera frame and between gripper and robot base frames
  500. std::vector<Mat> R_gripper2base, t_gripper2base;
  501. std::vector<Mat> R_target2cam, t_target2cam;
  502. Mat R_cam2gripper_true, t_cam2gripper_true;
  503. const bool noise = true;
  504. simulateDataEyeInHand(rng, nPoses, R_gripper2base, t_gripper2base, R_target2cam, t_target2cam, noise,
  505. R_cam2gripper_true, t_cam2gripper_true);
  506. for (size_t idx = 0; idx < methods.size(); idx++)
  507. {
  508. Mat rvec_cam2gripper_true;
  509. cv::Rodrigues(R_cam2gripper_true, rvec_cam2gripper_true);
  510. Mat R_cam2gripper_est, t_cam2gripper_est;
  511. calibrateHandEye(R_gripper2base, t_gripper2base, R_target2cam, t_target2cam, R_cam2gripper_est, t_cam2gripper_est, methods[idx]);
  512. Mat rvec_cam2gripper_est;
  513. cv::Rodrigues(R_cam2gripper_est, rvec_cam2gripper_est);
  514. double rvecDiff = cvtest::norm(rvec_cam2gripper_true, rvec_cam2gripper_est, NORM_L2);
  515. double tvecDiff = cvtest::norm(t_cam2gripper_true, t_cam2gripper_est, NORM_L2);
  516. vec_rvec_diff_noise[idx].push_back(rvecDiff);
  517. vec_tvec_diff_noise[idx].push_back(tvecDiff);
  518. const double epsilon_rvec = eps_rvec_noise[idx];
  519. const double epsilon_tvec = eps_tvec_noise[idx];
  520. //Maybe a better accuracy test would be to compare the mean and std errors with some thresholds?
  521. if (rvecDiff > epsilon_rvec || tvecDiff > epsilon_tvec)
  522. {
  523. ts->printf(cvtest::TS::LOG, "Invalid accuracy (noise) for method: %s, rvecDiff: %f, epsilon_rvec: %f, tvecDiff: %f, epsilon_tvec: %f\n",
  524. getMethodName(methods[idx]).c_str(), rvecDiff, epsilon_rvec, tvecDiff, epsilon_tvec);
  525. ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
  526. }
  527. }
  528. }
  529. }
  530. }
  531. for (size_t idx = 0; idx < methods.size(); idx++)
  532. {
  533. std::cout << std::endl;
  534. printStats(getMethodName(methods[idx]), vec_rvec_diff[idx], vec_tvec_diff[idx]);
  535. printStats("(noise) " + getMethodName(methods[idx]), vec_rvec_diff_noise[idx], vec_tvec_diff_noise[idx]);
  536. }
  537. }
  538. ///////////////////////////////////////////////////////////////////////////////////////////////////
  539. TEST(Calib3d_CalibrateHandEye, regression_eye_in_hand)
  540. {
  541. //Eye-in-Hand configuration (camera mounted on the robot end-effector observing a static calibration pattern)
  542. const bool eyeToHand = false;
  543. CV_CalibrateHandEyeTest test(eyeToHand);
  544. test.safe_run();
  545. }
  546. TEST(Calib3d_CalibrateHandEye, regression_eye_to_hand)
  547. {
  548. //Eye-to-Hand configuration (static camera observing a calibration pattern mounted on the robot end-effector)
  549. const bool eyeToHand = true;
  550. CV_CalibrateHandEyeTest test(eyeToHand);
  551. test.safe_run();
  552. }
  553. TEST(Calib3d_CalibrateHandEye, regression_17986)
  554. {
  555. std::vector<Mat> R_target2cam, t_target2cam;
  556. // Dataset contains transformation from base to gripper frame since it contains data for AX = ZB calibration problem
  557. std::vector<Mat> R_base2gripper, t_base2gripper;
  558. loadDataset(R_target2cam, t_target2cam, R_base2gripper, t_base2gripper);
  559. std::vector<HandEyeCalibrationMethod> methods = {CALIB_HAND_EYE_TSAI,
  560. CALIB_HAND_EYE_PARK,
  561. CALIB_HAND_EYE_HORAUD,
  562. CALIB_HAND_EYE_ANDREFF,
  563. CALIB_HAND_EYE_DANIILIDIS};
  564. for (auto method : methods) {
  565. SCOPED_TRACE(cv::format("method=%s", getMethodName(method).c_str()));
  566. Matx33d R_cam2base_est;
  567. Matx31d t_cam2base_est;
  568. calibrateHandEye(R_base2gripper, t_base2gripper, R_target2cam, t_target2cam, R_cam2base_est, t_cam2base_est, method);
  569. EXPECT_TRUE(checkRange(R_cam2base_est));
  570. EXPECT_TRUE(checkRange(t_cam2base_est));
  571. }
  572. }
  573. TEST(Calib3d_CalibrateRobotWorldHandEye, regression)
  574. {
  575. std::vector<Mat> R_world2cam, t_worldt2cam;
  576. std::vector<Mat> R_base2gripper, t_base2gripper;
  577. loadDataset(R_world2cam, t_worldt2cam, R_base2gripper, t_base2gripper);
  578. std::vector<Mat> rvec_R_world2cam;
  579. rvec_R_world2cam.reserve(R_world2cam.size());
  580. for (size_t i = 0; i < R_world2cam.size(); i++)
  581. {
  582. Mat rvec;
  583. cv::Rodrigues(R_world2cam[i], rvec);
  584. rvec_R_world2cam.push_back(rvec);
  585. }
  586. std::vector<RobotWorldHandEyeCalibrationMethod> methods = {CALIB_ROBOT_WORLD_HAND_EYE_SHAH,
  587. CALIB_ROBOT_WORLD_HAND_EYE_LI};
  588. Matx33d wRb, cRg;
  589. Matx31d wtb, ctg;
  590. loadResults(wRb, wtb, cRg, ctg);
  591. for (auto method : methods) {
  592. SCOPED_TRACE(cv::format("method=%s", getMethodName(method).c_str()));
  593. Matx33d wRb_est, cRg_est;
  594. Matx31d wtb_est, ctg_est;
  595. calibrateRobotWorldHandEye(rvec_R_world2cam, t_worldt2cam, R_base2gripper, t_base2gripper,
  596. wRb_est, wtb_est, cRg_est, ctg_est, method);
  597. EXPECT_TRUE(checkRange(wRb_est));
  598. EXPECT_TRUE(checkRange(wtb_est));
  599. EXPECT_TRUE(checkRange(cRg_est));
  600. EXPECT_TRUE(checkRange(ctg_est));
  601. //Arbitrary thresholds
  602. const double rotation_threshold = 1.0; //1deg
  603. const double translation_threshold = 50.0; //5cm
  604. //X
  605. //rotation error
  606. Matx33d wRw_est = wRb * wRb_est.t();
  607. Matx31d rvec_wRw_est;
  608. cv::Rodrigues(wRw_est, rvec_wRw_est);
  609. double X_rotation_error = cv::norm(rvec_wRw_est)*180/CV_PI;
  610. //translation error
  611. double X_t_error = cv::norm(wtb_est - wtb);
  612. SCOPED_TRACE(cv::format("X rotation error=%f", X_rotation_error));
  613. SCOPED_TRACE(cv::format("X translation error=%f", X_t_error));
  614. EXPECT_TRUE(X_rotation_error < rotation_threshold);
  615. EXPECT_TRUE(X_t_error < translation_threshold);
  616. //Z
  617. //rotation error
  618. Matx33d cRc_est = cRg * cRg_est.t();
  619. Matx31d rvec_cMc_est;
  620. cv::Rodrigues(cRc_est, rvec_cMc_est);
  621. double Z_rotation_error = cv::norm(rvec_cMc_est)*180/CV_PI;
  622. //translation error
  623. double Z_t_error = cv::norm(ctg_est - ctg);
  624. SCOPED_TRACE(cv::format("Z rotation error=%f", Z_rotation_error));
  625. SCOPED_TRACE(cv::format("Z translation error=%f", Z_t_error));
  626. EXPECT_TRUE(Z_rotation_error < rotation_threshold);
  627. EXPECT_TRUE(Z_t_error < translation_threshold);
  628. }
  629. }
  630. }} // namespace