main
wangchongwu 5 months ago
parent e0b3961f04
commit a6a1df2779

@ -40,7 +40,6 @@ public:
virtual SINT32 ReceiveFrame(GD_VIDEO_FRAME_S img, FrameInfo para) = 0;
virtual SINT32 ProcFrame() = 0;
public:
static API_VideoStitch* Create(SINT32 nWidth, SINT32 nHeight);

@ -71,7 +71,7 @@ private:
BA_Task::BA_Task(GeoStitcher * pGeoTrans)
BA_Task::BA_Task(GeoSolver * pGeoTrans)
{
_GeoStitcher = pGeoTrans;
_FeaMatcher = new FeatureMatcher(DetectorType::SIFT, MatcherType::FLANN);

@ -13,7 +13,7 @@
#include "StitchStruct.h"
#include <opencv2/core.hpp>
#include <opencv2/imgproc.hpp>
#include "Arith_GeoStitcher.h"
#include "Arith_GeoSolver.h"
#include "Arith_FeaMatch.h"
using cv::Mat_;
@ -24,7 +24,7 @@ using cv::Mat_;
class BA_Task
{
public:
BA_Task(GeoStitcher* pGeoTrans);
BA_Task(GeoSolver* pGeoTrans);
~BA_Task();
// 加入优化帧
@ -45,7 +45,7 @@ private:
SINT32 CalMatchMat(float fiou_thre);//计算匹配性矩阵(以IOU约束)
private:
GeoStitcher* _GeoStitcher;//外参计算
GeoSolver* _GeoStitcher;//外参计算
FeatureMatcher* _FeaMatcher;//特征匹配
PanInfo _panPara;//全景图配置

@ -1,5 +1,5 @@
#include "Arith_FeaMatch.h"
#include "Arith_GeoStitcher.h"
#include "Arith_GeoSolver.h"
using std::vector;
using cv::KeyPoint;

@ -1,58 +1,28 @@
#include "Arith_GeoStitcher.h"
#include "Arith_GeoSolver.h"
#include "Arith_VideoStitch.h"
#include "Arith_Utils.h"
#include "Arith_CoordModule.h"
#include "Arith_SysStruct.h"
using namespace cv;
GeoStitcher::GeoStitcher()
GeoSolver::GeoSolver()
{
}
GeoStitcher::~GeoStitcher()
GeoSolver::~GeoSolver()
{
}
PanInfo GeoStitcher::InitMap(FrameInfo info)
{
// 设置拼接原点
SetOriginPoint(info);
// 转换关系计算
Proj t_Proj = AnlayseTform(info);
// 帧中心的大地坐标,将其平移到全景图中心
cv::Point2f ct_geo = Trans_uv2Geo(cv::Point2f(info.nWidth / 2, info.nHeight / 2), t_Proj.tf_p2g);
// 全景图初始化
PanInfo panPara = {0};
panPara.m_pan_width = 1000;//全景宽
panPara.m_pan_height = 1000;//全景高
panPara.scale = 0.5;//比例尺,1m = ?pix
// 直接无平移解算
auto cur = Trans_Geo2pan(ct_geo, panPara);
// 计算平移到全景图固定点的平移量,从此处开始拼接
int planX = 200;
int planY = 200;
panPara.map_shiftX = planX - (cur.x);//平移X
panPara.map_shiftY = planY - (cur.y);//平移Y
return panPara;
}
cv::Point2f GeoStitcher::project(cv::Point2f pos_pan, Proj m_Proj, PanInfo pan)
cv::Point2f GeoSolver::project(cv::Point2f pos_pan, Proj m_Proj, PanInfo pan)
{
cv::Point2f pos_geo = Trans_pan2Geo(pos_pan, pan);
cv::Point2f pos_frame = Trans_Geo2uv(pos_geo, m_Proj.tf_g2p);
return pos_frame;
}
cv::Point2f GeoStitcher::back_project(cv::Point2f pos_frame, Proj m_Proj, PanInfo pan)
cv::Point2f GeoSolver::back_project(cv::Point2f pos_frame, Proj m_Proj, PanInfo pan)
{
cv::Point2f pos_geo = Trans_uv2Geo(pos_frame, m_Proj.tf_p2g);
@ -61,12 +31,12 @@ cv::Point2f GeoStitcher::back_project(cv::Point2f pos_frame, Proj m_Proj, PanInf
return pos_pan;
}
void GeoStitcher::SetOriginPoint(FrameInfo info)
void GeoSolver::SetOriginPoint(FrameInfo info)
{
originPoint = getXYZFromBLH(info.craft.stPos);
}
cv::Point2f GeoStitcher::Trans_uv2Geo(cv::Point2f pos_frame, TForm form)
cv::Point2f GeoSolver::Trans_uv2Geo(cv::Point2f pos_frame, TForm form)
{
Mat point = (Mat_<double>(3, 1) << pos_frame.x, pos_frame.y, 1);
Mat result = form.R * point;
@ -80,7 +50,7 @@ cv::Point2f GeoStitcher::Trans_uv2Geo(cv::Point2f pos_frame, TForm form)
return cv::Point2f(warpedX, warpedY);
}
cv::Point2f GeoStitcher::Trans_Geo2uv(cv::Point2f pos_geo, TForm form_inv)
cv::Point2f GeoSolver::Trans_Geo2uv(cv::Point2f pos_geo, TForm form_inv)
{
// 先平移到当前相机位置
cv::Point2f pos_cam = pos_geo;
@ -97,7 +67,7 @@ cv::Point2f GeoStitcher::Trans_Geo2uv(cv::Point2f pos_geo, TForm form_inv)
return cv::Point2f(warpedX, warpedY);
}
cv::Point2f GeoStitcher::Trans_pan2Geo(cv::Point2f pos_pan, PanInfo panPara)
cv::Point2f GeoSolver::Trans_pan2Geo(cv::Point2f pos_pan, PanInfo panPara)
{
double x = (pos_pan.x - panPara.map_shiftX) / panPara.scale;
double y = (panPara.m_pan_height - (pos_pan.y - panPara.map_shiftY)) / panPara.scale;
@ -105,7 +75,7 @@ cv::Point2f GeoStitcher::Trans_pan2Geo(cv::Point2f pos_pan, PanInfo panPara)
return cv::Point2f(x, y);
}
cv::Point2f GeoStitcher::Trans_Geo2pan(cv::Point2f pos_geo, PanInfo panPara)
cv::Point2f GeoSolver::Trans_Geo2pan(cv::Point2f pos_geo, PanInfo panPara)
{
double pan_x = pos_geo.x * panPara.scale + panPara.map_shiftX;
double pan_y = (panPara.m_pan_height - pos_geo.y * panPara.scale) + panPara.map_shiftY;
@ -114,7 +84,7 @@ cv::Point2f GeoStitcher::Trans_Geo2pan(cv::Point2f pos_geo, PanInfo panPara)
Mat GeoStitcher::Mat_TransENGMove(FrameInfo info)
Mat GeoSolver::Mat_TransENGMove(FrameInfo info)
{
PointXYZ ptCurr = getXYZFromBLH(info.craft.stPos);
PointXYZ diff = getNUEXYZFromCGCSXYZ(ptCurr, originPoint);
@ -127,7 +97,7 @@ Mat GeoStitcher::Mat_TransENGMove(FrameInfo info)
return move;
}
Mat GeoStitcher::Mat_TransENG2uv(FrameInfo info)
Mat GeoSolver::Mat_TransENG2uv(FrameInfo info)
{
//从地理坐标系转像素坐标
@ -198,7 +168,7 @@ Mat GeoStitcher::Mat_TransENG2uv(FrameInfo info)
Proj GeoStitcher::AnlayseTform(FrameInfo info)
Proj GeoSolver::AnlayseTform(FrameInfo info)
{
Proj projection;
// 从像方->地理
@ -212,7 +182,7 @@ Proj GeoStitcher::AnlayseTform(FrameInfo info)
return projection;
}
cv::Mat GeoStitcher::findHomography(Proj proj, PanInfo pan)
cv::Mat GeoSolver::findHomography(Proj proj, PanInfo pan)
{
// 同名点计算,从像方到全景
cv::Point2f leftTop_map = back_project(cv::Point2f(0,0), proj, pan);
@ -241,7 +211,7 @@ cv::Mat GeoStitcher::findHomography(Proj proj, PanInfo pan)
return H;
}
cv::Mat GeoStitcher::findHomography(Proj proj)
cv::Mat GeoSolver::findHomography(Proj proj)
{
std::vector<cv::Point2f> srcPoints;
srcPoints.push_back(cv::Point2f(0, 0));

@ -32,15 +32,14 @@ struct Proj
class GeoStitcher
class GeoSolver
{
public:
// 构造函数
GeoStitcher();
~GeoStitcher();
GeoSolver();
~GeoSolver();
// 初始化地理参数和全景图参数
PanInfo InitMap(FrameInfo info);
// 投影:从全景图到帧
cv::Point2f project(cv::Point2f pos_pan, Proj m_Proj, PanInfo pan);
@ -58,9 +57,10 @@ public:
// 建立全景图与归一化地理系的H矩阵
cv::Mat findHomography(Proj proj);
public:
// 设置起始拼接点外参
void SetOriginPoint(FrameInfo info);
public:
// 帧像方-地理坐标
cv::Point2f Trans_uv2Geo(cv::Point2f pos_frame, TForm form);
@ -81,8 +81,7 @@ public:
private:
// 设置起始拼接点外参
void SetOriginPoint(FrameInfo info);
PointXYZ originPoint;//成图初始点的地心地固坐标,作为拼接参考
};

@ -22,7 +22,7 @@ void API_VideoStitch::Destroy(API_VideoStitch * obj)
VideoStitch::VideoStitch(SINT32 nWidth, SINT32 nHeight)
{
_GeoStitcher = new GeoStitcher();
_GeoStitcher = new GeoSolver();
_BATask = new BA_Task(_GeoStitcher);
@ -35,6 +35,38 @@ VideoStitch::~VideoStitch()
}
PanInfo VideoStitch::InitMap(FrameInfo info)
{
// 设置拼接原点
_GeoStitcher->SetOriginPoint(info);
// 转换关系计算
Proj t_Proj = _GeoStitcher->AnlayseTform(info);
// 帧中心的大地坐标,将其平移到全景图中心
cv::Point2f ct_geo = _GeoStitcher->Trans_uv2Geo(cv::Point2f(info.nWidth / 2, info.nHeight / 2), t_Proj.tf_p2g);
// 全景图初始化
PanInfo panPara = { 0 };
panPara.m_pan_width = 1000;//全景宽
panPara.m_pan_height = 1000;//全景高
panPara.scale = 0.5;//比例尺,1m = ?pix
// 直接无平移解算
auto cur = _GeoStitcher->Trans_Geo2pan(ct_geo, panPara);
// 计算平移到全景图固定点的平移量,从此处开始拼接
int planX = 200;
int planY = 200;
panPara.map_shiftX = planX - (cur.x);//平移X
panPara.map_shiftY = planY - (cur.y);//平移Y
return panPara;
}
void VideoStitch::Test()
{
@ -42,7 +74,7 @@ void VideoStitch::Test()
PanInfo VideoStitch::Init(FrameInfo info)
{
_panPara = _GeoStitcher->InitMap(info);
_panPara = InitMap(info);
_BATask->setPanPara(_panPara);
@ -184,32 +216,6 @@ SINT32 VideoStitch::ReceiveFrame(GD_VIDEO_FRAME_S img, FrameInfo para)
return SINT32();
}
SINT32 VideoStitch::ProcFrame()
{
//printf("size:%d\n",_cache->getMemSize());
//std::shared_ptr<FrameCache> loadedFrame1;
// bool bflag1 = _cache->get(30, loadedFrame1);
//std::shared_ptr<FrameCache> loadedFrame2;
//auto bflag2 = _cache->get(40,loadedFrame2);
//if (bflag1 && loadedFrame1->_frame_info.u32Height > 0)
//{
// cv::Mat src1(loadedFrame1->_frame_info.u32Height, loadedFrame1->_frame_info.u32Width, CV_8UC1, loadedFrame1->_data);
// imshow("src30",src1);
// waitKey(1);
//}
//
//if (bflag2 && loadedFrame2->_frame_info.u32Height > 0)
//{
// cv::Mat src2(loadedFrame2->_frame_info.u32Height, loadedFrame2->_frame_info.u32Width, CV_8UC1, loadedFrame2->_data);
// imshow("src40",src2);
// waitKey(0);
//}
return 0;
}

@ -1,6 +1,6 @@
#include "API_VideoStitch.h"
#include "opencv2/opencv.hpp"
#include "Arith_GeoStitcher.h"
#include "Arith_GeoSolver.h"
#include "Arith_FeaMatch.h"
#include "StitchStruct.h"
#include "Arith_BATask.h"
@ -16,6 +16,7 @@ public:
PanInfo Init(FrameInfo info);
PanInfo InitMap(FrameInfo info);
// 接收帧
SINT32 ReceiveFrame(GD_VIDEO_FRAME_S img, FrameInfo para);
@ -27,10 +28,6 @@ public:
SINT32 BAOpt();
// 处理帧
SINT32 ProcFrame();
GD_VIDEO_FRAME_S ExportPanAddr();
private:
@ -39,7 +36,7 @@ private:
private:
GeoStitcher* _GeoStitcher;//外参计算
GeoSolver* _GeoStitcher;//外参计算

Loading…
Cancel
Save