1 Star 1 Fork 1

zl_vslam/slam_optimizer

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
文件
克隆/下载
pose_estimation_3d2d.cpp 7.88 KB
一键复制 编辑 原始数据 按行查看 历史
zl_vslam 提交于 2025-11-16 21:42 +08:00 . zl: dev optimize
#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <chrono>
#include <vector>
#include <ceres/ceres.h>
#include "PnPSolver.h"
#include "VerifyReprojectionJacobian.h"
using namespace std;
using namespace cv;
using namespace Eigen;
static double fx_, fy_, cx_, cy_;
template<typename T>
Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> cvMatToEigen(const cv::Mat& cv_mat) {
Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> eigen_mat;
eigen_mat.resize(cv_mat.rows, cv_mat.cols);
for (int i = 0; i < cv_mat.rows; ++i) {
for (int j = 0; j < cv_mat.cols; ++j) {
eigen_mat(i, j) = cv_mat.at<T>(i, j);
}
}
return eigen_mat;
}
void find_feature_matches (
const Mat& img_1, const Mat& img_2,
std::vector<KeyPoint>& keypoints_1,
std::vector<KeyPoint>& keypoints_2,
std::vector< DMatch >& matches );
// 像素坐标转相机归一化坐标
Point2d pixel2cam ( const Point2d& p, const Mat& K );
// 在优化后添加详细的结果分析
void AnalyzeResults(vector<Eigen::Vector3d> landmarks,
vector<Eigen::Vector2d> bearings,
const Eigen::Vector3d& estimated_translation,
const Eigen::Quaterniond& estimated_rotation) {
std::cout << "\n=== Detailed Result Analysis ===" << std::endl;
// 重投影误差分析
double total_reprojection_error = 0.0;
int point_count = landmarks.size();
for (int i = 0; i < point_count; ++i) {
Eigen::Vector3d p_c = estimated_rotation * landmarks[i] + estimated_translation;
double u_pred = fx_ * (p_c[0] / p_c[2]) + cx_;
double v_pred = fy_ * (p_c[1] / p_c[2]) + cy_;
double error = std::sqrt(std::pow(u_pred - bearings[i][0], 2) +
std::pow(v_pred - bearings[i][1], 2));
total_reprojection_error += error;
}
double avg_reprojection_error = total_reprojection_error / point_count;
std::cout << "Average reprojection error: " << avg_reprojection_error << " pixels" << std::endl;
}
int main ( int argc, char** argv )
{
//-- 读取图像
Mat img_1 = imread ( "../1.png", 1 );
Mat img_2 = imread ( "../2.png", 1 );
vector<KeyPoint> keypoints_1, keypoints_2;
vector<DMatch> matches;
find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches );
cout<<"一共找到了"<<matches.size() <<"组匹配点"<<endl;
// 建立3D点
Mat d1 = imread ( "../1_depth.png", 1 ); // 深度图为16位无符号数,单通道图像
Mat K = ( Mat_<double> ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );
fx_ = 520.9;
fy_ = 521.0;
cx_ = 325.1;
cy_ = 249.7;
vector<Point3f> pts_3d;
vector<Point2f> pts_2d;
for ( DMatch m:matches )
{
ushort d = d1.ptr<unsigned short> (int ( keypoints_1[m.queryIdx].pt.y )) [ int ( keypoints_1[m.queryIdx].pt.x ) ];
if ( d == 0 ) // bad depth
continue;
float dd = d/5000.0;
Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );
pts_3d.push_back ( Point3f ( p1.x*dd, p1.y*dd, dd ) );
pts_2d.push_back ( keypoints_2[m.trainIdx].pt );
}
cout<<"3d-2d pairs: "<<pts_3d.size() <<endl;
Mat r, t;
solvePnP ( pts_3d, pts_2d, K, Mat(), r, t, false, SOLVEPNP_EPNP); // 调用OpenCV 的 PnP 求解,可选择EPNP,DLS等方法
// solvePnP ( pts_3d, pts_2d, K, Mat(), r, t, false ); // 调用OpenCV 的 PnP 求解,可选择EPNP,DLS等方法
Mat R;
cv::Rodrigues ( r, R ); // r为旋转向量形式,用Rodrigues公式转换为矩阵
cout<<"R="<<endl<<R<<endl;
cout<<"t="<<endl<<t<<endl;
vector<Eigen::Vector3d> landmarks;
vector<Eigen::Vector2d> bearings;
// 添加一些测试点
for (int i = 0; i < pts_3d.size(); ++i) {
landmarks.push_back(Eigen::Vector3d(pts_3d[i].x, pts_3d[i].y, pts_3d[i].z));
Point2d points_2d = ( Point2d(pts_2d[i].x, pts_2d[i].y) );
bearings.push_back(Eigen::Vector2d(points_2d.x, points_2d.y));
}
Vector3d eigen_translate = cvMatToEigen<double>(t);
Matrix3d eigen_rotation_mat = cvMatToEigen<double>(R);
// 初始位姿估计
Eigen::Quaterniond initial_rotation(eigen_rotation_mat);
Vector3d initial_translation(eigen_translate);
if (!landmarks.empty()) {
JacobianVerifier::VerifyReprojectionJacobian(
landmarks[0], bearings[0], initial_translation, initial_rotation, fx_, fy_, cx_, cy_);
}
std::cout << " Initial translation ======== : " << initial_translation.transpose() << std::endl;
std::cout << " Initial quaternion: " << initial_rotation.coeffs().transpose() << std::endl;
// 创建求解器并求解
PnPSolver solver(fx_, fy_, cx_, cy_);
bool success = solver.Solve(landmarks, bearings, initial_translation, initial_rotation);
if (success) {
std::cout << "\n=== Optimization Result ===" << std::endl;
std::cout << "Final translation: " << initial_translation.transpose() << std::endl;
std::cout << "Final quaternion: " << initial_rotation.coeffs().transpose() << std::endl;
AnalyzeResults(landmarks, bearings, initial_translation, initial_rotation);
} else {
std::cerr << "Optimization failed!" << std::endl;
return -1;
}
}
void find_feature_matches ( const Mat& img_1, const Mat& img_2,
std::vector<KeyPoint>& keypoints_1,
std::vector<KeyPoint>& keypoints_2,
std::vector< DMatch >& matches )
{
//-- 初始化
Mat descriptors_1, descriptors_2;
// used in OpenCV3
Ptr<FeatureDetector> detector = ORB::create();
Ptr<DescriptorExtractor> descriptor = ORB::create();
// use this if you are in OpenCV2
// Ptr<FeatureDetector> detector = FeatureDetector::create ( "ORB" );
// Ptr<DescriptorExtractor> descriptor = DescriptorExtractor::create ( "ORB" );
Ptr<DescriptorMatcher> matcher = DescriptorMatcher::create ( "BruteForce-Hamming" );
//-- 第一步:检测 Oriented FAST 角点位置
detector->detect ( img_1,keypoints_1 );
detector->detect ( img_2,keypoints_2 );
//-- 第二步:根据角点位置计算 BRIEF 描述子
descriptor->compute ( img_1, keypoints_1, descriptors_1 );
descriptor->compute ( img_2, keypoints_2, descriptors_2 );
//-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
vector<DMatch> match;
// BFMatcher matcher ( NORM_HAMMING );
matcher->match ( descriptors_1, descriptors_2, match );
//-- 第四步:匹配点对筛选
double min_dist=10000, max_dist=0;
//找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离
for ( int i = 0; i < descriptors_1.rows; i++ )
{
double dist = match[i].distance;
if ( dist < min_dist ) min_dist = dist;
if ( dist > max_dist ) max_dist = dist;
}
printf ( "-- Max dist : %f \n", max_dist );
printf ( "-- Min dist : %f \n", min_dist );
//当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限.
for ( int i = 0; i < descriptors_1.rows; i++ )
{
if ( match[i].distance <= max ( 2*min_dist, 30.0 ) )
{
matches.push_back ( match[i] );
}
}
Mat img_matches;
drawMatches( img_1, keypoints_1, img_2, keypoints_2, matches, img_matches );
imshow("ORB Matches", img_matches);
waitKey(0);
}
Point2d pixel2cam ( const Point2d& p, const Mat& K )
{
return Point2d
(
( p.x - K.at<double> ( 0,2 ) ) / K.at<double> ( 0,0 ),
( p.y - K.at<double> ( 1,2 ) ) / K.at<double> ( 1,1 )
);
}
Loading...
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
1
https://gitee.com/zl_vslam/slam_optimizer.git
git@gitee.com:zl_vslam/slam_optimizer.git
zl_vslam
slam_optimizer
slam_optimizer
master

搜索帮助