pose_estimation_3d2d.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290
  1. #include <iostream>
  2. #include <opencv2/core/core.hpp>
  3. #include <opencv2/features2d/features2d.hpp>
  4. #include <opencv2/highgui/highgui.hpp>
  5. #include <opencv2/calib3d/calib3d.hpp>
  6. /*#include <Eigen/Core>
  7. #include <Eigen/Geometry>
  8. #include <g2o/core/base_vertex.h>
  9. #include <g2o/core/base_unary_edge.h>
  10. #include <g2o/core/block_solver.h>
  11. #include <g2o/core/optimization_algorithm_levenberg.h>
  12. #include <g2o/solvers/csparse/linear_solver_csparse.h>
  13. #include <g2o/types/sba/types_six_dof_expmap.h>*/
  14. #include <chrono>
  15. #include "pnp.h"
  16. #include "../Steger.h"
  17. using namespace std;
  18. using namespace cv;
  19. void find_feature_matches (
  20. const Mat& img_1, const Mat& img_2,
  21. std::vector<KeyPoint>& keypoints_1,
  22. std::vector<KeyPoint>& keypoints_2,
  23. std::vector< DMatch >& matches );
  24. void bundleAdjustment (
  25. const vector<Point3f> points_3d,
  26. const vector<Point2f> points_2d,
  27. const Mat& K,
  28. Mat& R, Mat& t
  29. );
  30. void verify_result(Mat R,Mat t,vector<Point2f> pts_2d,Mat K,vector<Point3f> pts_3d)
  31. {
  32. if(pts_2d.size()!=pts_3d.size())
  33. {
  34. printf(" pts_2d.size()!=pts_3d.size() \n");
  35. return;
  36. }
  37. Mat RINV=R.inv();
  38. for(int i=0;i<pts_3d.size();++i)
  39. {
  40. float dx=pts_3d[i].x+t.at<double>(0,0);
  41. float dy=pts_3d[i].y+t.at<double>(1,0);
  42. float dz=pts_3d[i].z+t.at<double>(2,0);
  43. float distance=sqrt(dx*dx+dy*dy+dz*dz);
  44. Point2d p1 = pixel2cam ( pts_2d[i], K );
  45. Point3f pose3d ( Point3f ( p1.x*distance, p1.y*distance, distance ) );
  46. Mat pose3d_m=Mat::zeros(3,1,R.type());
  47. pose3d_m.at<double>(0,0)=pose3d.x-t.at<double>(0,0);
  48. pose3d_m.at<double>(1,0)=pose3d.y-t.at<double>(1,0);
  49. pose3d_m.at<double>(2,0)=pose3d.z-t.at<double>(2,0);
  50. Mat o_pose=RINV*pose3d_m;
  51. printf(" cal :%f, %f, %f org:%f, %f, %f\n",o_pose.at<double>(0,0),o_pose.at<double>(1,0),o_pose.at<double>(2,0),
  52. pts_3d[i].x,pts_3d[i].y,pts_3d[i].z);
  53. }
  54. }
  55. void test_pnp(){
  56. Mat K = ( Mat_<double> ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );
  57. cv::Mat R=(Mat_<double> ( 3,3 ) <<0.9979193252225095, -0.05138618904650328, 0.03894200717385427,
  58. 0.05033852907733768, 0.9983556574295407, 0.02742286944795593,
  59. -0.04028712992732941, -0.02540552801471822, 0.998865109165653);
  60. cv::Mat T=(Mat_<double>(3,1)<<-0.1255867099750184,-0.007363525258815341,0.0609992658867812);
  61. P3d2d p3d2d(K);
  62. p3d2d.R_=R;
  63. p3d2d.t_=T;
  64. cv::Mat src = cv::imread("../images/3.bmp", 0);
  65. cv::Mat image = src(cv::Rect(0, 0, src.cols, src.rows)).clone();
  66. for (int i = 0; i < image.rows; i++)
  67. {
  68. for (int j = 0; j < image.cols; j++)
  69. {
  70. if (image.at<uchar>(i, j) < 20)
  71. image.at<uchar>(i, j) = 0;
  72. }
  73. }
  74. cv::Mat out= cv::Mat::zeros(image.size(), CV_8UC1);
  75. CSteger steger;
  76. cv::GaussianBlur(image, image, cv::Size(3, 3), 3, 3);
  77. std::vector<cv::Point2d> points = steger.StripCenter(image);
  78. auto t1=std::chrono::steady_clock::now();
  79. p3d2d.execute(points);
  80. auto t2=std::chrono::steady_clock::now();
  81. double ms=std::chrono::duration<double,std::milli>(t2-t1).count();
  82. printf("points :%d time :%lf\n",points.size(),ms);
  83. }
  84. int main ( int argc, char** argv )
  85. {
  86. test_pnp();
  87. return 0;
  88. if ( argc != 4 )
  89. {
  90. cout<<"usage: pose_estimation_3d2d img1 img2 depth1"<<endl;
  91. return 1;
  92. }
  93. //-- 读取图像
  94. Mat img_1 = imread ( argv[1], CV_LOAD_IMAGE_COLOR );
  95. Mat img_2 = imread ( argv[2], CV_LOAD_IMAGE_COLOR );
  96. vector<KeyPoint> keypoints_1, keypoints_2;
  97. vector<DMatch> matches;
  98. find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches );
  99. cout<<"一共找到了"<<matches.size() <<"组匹配点"<<endl;
  100. // 建立3D点
  101. Mat d1 = imread ( argv[3], CV_LOAD_IMAGE_UNCHANGED ); // 深度图为16位无符号数,单通道图像
  102. Mat K = ( Mat_<double> ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );
  103. vector<Point3f> pts_3d;
  104. vector<Point2f> pts_2d;
  105. for ( DMatch m:matches )
  106. {
  107. ushort d = d1.ptr<unsigned short> (int ( keypoints_1[m.queryIdx].pt.y )) [ int ( keypoints_1[m.queryIdx].pt.x ) ];
  108. if ( d == 0 ) // bad depth
  109. continue;
  110. float dd = d/5000.0;
  111. Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );
  112. pts_3d.push_back ( Point3f ( p1.x*dd, p1.y*dd, dd ) );
  113. pts_2d.push_back ( keypoints_2[m.trainIdx].pt );
  114. printf("image1 key 3d :%f, %f, %f image2 key 2d:%f, %f\n",p1.x*dd, p1.y*dd, dd ,
  115. keypoints_2[m.trainIdx].pt.x,keypoints_2[m.trainIdx].pt.y);
  116. }
  117. cout<<"3d-2d pairs: "<<pts_3d.size() <<endl;
  118. Mat r, t;
  119. solvePnP ( pts_3d, pts_2d, K, Mat(), r, t, false ); // 调用OpenCV 的 PnP 求解,可选择EPNP,DLS等方法
  120. Mat R;
  121. cv::Rodrigues ( r, R ); // r为旋转向量形式,用Rodrigues公式转换为矩阵
  122. cout<<"R="<<endl<<R<<endl;
  123. cout<<"t="<<endl<<t<<endl;
  124. verify_result(R,t,pts_2d,K,pts_3d);
  125. cout<<"calling bundle adjustment"<<endl;
  126. //bundleAdjustment ( pts_3d, pts_2d, K, R, t );
  127. }
  128. void find_feature_matches ( const Mat& img_1, const Mat& img_2,
  129. std::vector<KeyPoint>& keypoints_1,
  130. std::vector<KeyPoint>& keypoints_2,
  131. std::vector< DMatch >& matches )
  132. {
  133. //-- 初始化
  134. Mat descriptors_1, descriptors_2;
  135. // used in OpenCV3
  136. Ptr<FeatureDetector> detector = ORB::create();
  137. Ptr<DescriptorExtractor> descriptor = ORB::create();
  138. // use this if you are in OpenCV2
  139. // Ptr<FeatureDetector> detector = FeatureDetector::create ( "ORB" );
  140. // Ptr<DescriptorExtractor> descriptor = DescriptorExtractor::create ( "ORB" );
  141. Ptr<DescriptorMatcher> matcher = DescriptorMatcher::create ( "BruteForce-Hamming" );
  142. //-- 第一步:检测 Oriented FAST 角点位置
  143. detector->detect ( img_1,keypoints_1 );
  144. detector->detect ( img_2,keypoints_2 );
  145. //-- 第二步:根据角点位置计算 BRIEF 描述子
  146. descriptor->compute ( img_1, keypoints_1, descriptors_1 );
  147. descriptor->compute ( img_2, keypoints_2, descriptors_2 );
  148. //-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
  149. vector<DMatch> match;
  150. // BFMatcher matcher ( NORM_HAMMING );
  151. matcher->match ( descriptors_1, descriptors_2, match );
  152. //-- 第四步:匹配点对筛选
  153. double min_dist=10000, max_dist=0;
  154. //找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离
  155. for ( int i = 0; i < descriptors_1.rows; i++ )
  156. {
  157. double dist = match[i].distance;
  158. if ( dist < min_dist ) min_dist = dist;
  159. if ( dist > max_dist ) max_dist = dist;
  160. }
  161. printf ( "-- Max dist : %f \n", max_dist );
  162. printf ( "-- Min dist : %f \n", min_dist );
  163. //当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限.
  164. for ( int i = 0; i < descriptors_1.rows; i++ )
  165. {
  166. if ( match[i].distance <= max ( 2*min_dist, 30.0 ) )
  167. {
  168. matches.push_back ( match[i] );
  169. }
  170. }
  171. }
  172. void bundleAdjustment (
  173. const vector< Point3f > points_3d,
  174. const vector< Point2f > points_2d,
  175. const Mat& K,
  176. Mat& R, Mat& t )
  177. {
  178. // 初始化g2o
  179. /*typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block; // pose 维度为 6, landmark 维度为 3
  180. Block::LinearSolverType* linearSolver = new g2o::LinearSolverCSparse<Block::PoseMatrixType>(); // 线性方程求解器
  181. Block* solver_ptr = new Block ( linearSolver ); // 矩阵块求解器
  182. g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( solver_ptr );
  183. g2o::SparseOptimizer optimizer;
  184. optimizer.setAlgorithm ( solver );
  185. // vertex
  186. g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); // camera pose
  187. Eigen::Matrix3d R_mat;
  188. R_mat <<
  189. R.at<double> ( 0,0 ), R.at<double> ( 0,1 ), R.at<double> ( 0,2 ),
  190. R.at<double> ( 1,0 ), R.at<double> ( 1,1 ), R.at<double> ( 1,2 ),
  191. R.at<double> ( 2,0 ), R.at<double> ( 2,1 ), R.at<double> ( 2,2 );
  192. pose->setId ( 0 );
  193. pose->setEstimate ( g2o::SE3Quat (
  194. R_mat,
  195. Eigen::Vector3d ( t.at<double> ( 0,0 ), t.at<double> ( 1,0 ), t.at<double> ( 2,0 ) )
  196. ) );
  197. optimizer.addVertex ( pose );
  198. int index = 1;
  199. for ( const Point3f p:points_3d ) // landmarks
  200. {
  201. g2o::VertexSBAPointXYZ* point = new g2o::VertexSBAPointXYZ();
  202. point->setId ( index++ );
  203. point->setEstimate ( Eigen::Vector3d ( p.x, p.y, p.z ) );
  204. point->setMarginalized ( true ); // g2o 中必须设置 marg 参见第十讲内容
  205. optimizer.addVertex ( point );
  206. }
  207. // parameter: camera intrinsics
  208. g2o::CameraParameters* camera = new g2o::CameraParameters (
  209. K.at<double> ( 0,0 ), Eigen::Vector2d ( K.at<double> ( 0,2 ), K.at<double> ( 1,2 ) ), 0
  210. );
  211. camera->setId ( 0 );
  212. optimizer.addParameter ( camera );
  213. // edges
  214. index = 1;
  215. for ( const Point2f p:points_2d )
  216. {
  217. g2o::EdgeProjectXYZ2UV* edge = new g2o::EdgeProjectXYZ2UV();
  218. edge->setId ( index );
  219. edge->setVertex ( 0, dynamic_cast<g2o::VertexSBAPointXYZ*> ( optimizer.vertex ( index ) ) );
  220. edge->setVertex ( 1, pose );
  221. edge->setMeasurement ( Eigen::Vector2d ( p.x, p.y ) );
  222. edge->setParameterId ( 0,0 );
  223. edge->setInformation ( Eigen::Matrix2d::Identity() );
  224. optimizer.addEdge ( edge );
  225. index++;
  226. }
  227. chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
  228. optimizer.setVerbose ( true );
  229. optimizer.initializeOptimization();
  230. optimizer.optimize ( 100 );
  231. chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
  232. chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>> ( t2-t1 );
  233. cout<<"optimization costs time: "<<time_used.count() <<" seconds."<<endl;
  234. cout<<endl<<"after optimization:"<<endl;
  235. cout<<"T="<<endl<<Eigen::Isometry3d ( pose->estimate() ).matrix() <<endl;*/
  236. }