main
wangchongwu 2 weeks ago
parent 797811e204
commit 5540528a1d

@ -83,9 +83,9 @@ struct HomographyResidual
// 约束投影位置不变
residual[2] = (P_r1 - pS1_E).squaredNorm();
residual[3] = (P_r2 - pS2_E).squaredNorm();
residual[4] = (P_r3 - pS3_E).squaredNorm();
residual[1] = (P_r1 - pS1_E).squaredNorm();
residual[2] = (P_r2 - pS2_E).squaredNorm();
residual[3] = (P_r3 - pS3_E).squaredNorm();
return true;
@ -298,15 +298,17 @@ void BA_Task::OptFrame(vector<KeyType> frameInd,cv::Mat H_map, std::unordered_ma
{
_MatchMat.at<int>(i, j) = matches.size();
_MatchMat.at<int>(j, i) = matches.size();
#ifdef SHOW_MATCH
// 绘制匹配结果
drawMatch(i, j, matches, H_map);
#endif
}
else
{
continue;
}
#ifdef SHOW_MATCH
// 绘制匹配结果
drawMatch(i, j, matches, H_map);
#endif
// 添加匹配点对的残差块
for (int m = 0; m < matches.size(); m++)
@ -333,7 +335,7 @@ void BA_Task::OptFrame(vector<KeyType> frameInd,cv::Mat H_map, std::unordered_ma
ceres::CostFunction* cost_function =
new ceres::AutoDiffCostFunction<HomographyResidual, 4, 8, 8>(
new HomographyResidual(keypoint_i, keypoint_j, Hi0, Hj0));
problemH2.AddResidualBlock(cost_function, scale_loss, h_list[i], h_list[j]);
problemH2.AddResidualBlock(cost_function, nullptr, h_list[i], h_list[j]);
#endif
#ifdef OPT_SE3
@ -352,13 +354,13 @@ void BA_Task::OptFrame(vector<KeyType> frameInd,cv::Mat H_map, std::unordered_ma
// 配置求解器
ceres::Solver::Options options;
options.max_num_iterations = 10; // 增加最大迭代次数
options.max_num_iterations = 5; // 增加最大迭代次数
options.function_tolerance = 1e-15; // 设置更严格的函数值容忍度
options.gradient_tolerance = 1e-15; // 设置更严格的梯度容忍度
options.parameter_tolerance = 1e-15; // 设置更严格的参数容忍度
options.minimizer_progress_to_stdout = true;
//options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY; // 使用稀疏求解器
options.num_threads = 8; // 使用多线程
options.num_threads = 12; // 使用多线程
ceres::Solver::Summary summary;

@ -18,8 +18,8 @@
//#define SHOW_MATCH
//#define OPT_H
#define OPT_SE3
#define OPT_H
//#define OPT_SE3
class BA_Task
{

@ -257,7 +257,7 @@ void MapBlend::BatchMapWithH(const vector<KeyType> frameInd, const cv::Mat mapH,
// 读1帧取出常规信息宽高等
_cache->get(frameInd[0], _t_frame_cache);
//#pragma omp parallel for
for (int i = 0; i < frameInd.size(); i++)
{
KeyType key = frameInd[i];
@ -284,7 +284,6 @@ void MapBlend::BatchMapWithH(const vector<KeyType> frameInd, const cv::Mat mapH,
{
continue; // 完全在外面,直接跳过
}
//帧在视场内,读取文件缓存
if (!_cache->get(key, _t_frame_cache))

@ -51,7 +51,7 @@ UnderStitch::UnderStitch(std::string cachedir)
_cacheDir = cachedir;
// 创建缓存对象
_cache = new FileCache<FrameCache>(100, cachedir);
_cache = new FileCache<FrameCache>(500, cachedir);
_GeoSolver = new GeoSolver();
@ -237,8 +237,8 @@ UPanInfo UnderStitch::InitMap_SCAN(FrameInfo para, float ptRange)
float min_y = min(min(ct_geo_left.y, ct_geo_right.y), min(ct_geo_left_fly.y, ct_geo_right_fly.y));
float max_y = max(max(ct_geo_left.y, ct_geo_right.y), max(ct_geo_left_fly.y, ct_geo_right_fly.y));
float E_range = (max_x - min_x) * 1.2;
float N_range = (max_y - min_y) * 1.2;
float E_range = (max_x - min_x) * 1.3;
float N_range = (max_y - min_y) * 1.3;
// 不损失分辨率的全景图尺寸
panPara.m_pan_width = E_range / scale_max;
@ -381,7 +381,7 @@ UPanInfo UnderStitch::Init(FrameInfo info)
// 摆扫45度初始化地图尺寸
#ifdef SCAN_MODE
_panPara = InitMap_SCAN(info,45);
_panPara = InitMap_SCAN(info,42);
#else
// 常规初始化全景图(基于内存限制)
_panPara = InitMap(info);
@ -399,6 +399,9 @@ UPanInfo UnderStitch::Init(FrameInfo info)
_config.bUseBA = false;
_config.bOutFrameTile = false;
//
infoLast = info;
LOG_INFO("Init success");
return _panPara;
}
@ -443,12 +446,43 @@ bool UnderStitch::isFrameInPanView(const cv::Size& frameSize, const cv::Mat& H,
return false; // 需要触发处理
}
cv::Mat gammaCorrect(const cv::Mat& src, double gamma)
{
cv::Mat lut(1, 256, CV_8U);
for (int i = 0; i < 256; i++)
lut.at<uchar>(i) = pow(i / 255.0, gamma) * 255.0;
cv::Mat dst;
cv::LUT(src, lut, dst);
return dst.clone();
}
SINT32 UnderStitch::Run(GD_VIDEO_FRAME_S frame, FrameInfo para)
{
stopWatch sw;
LOG_INFO("Run Frame {}", para.nFrmID);
TransPitch(para);
run_test(para);
LOG_INFO("B:{} L:{} H:{} Yaw:{} Pitch:{} Roll:{},fAz:{} fPt:{},camf:{},camPixel:{}",
para.craft.stPos.B, para.craft.stPos.L, para.craft.stPos.H, para.craft.stAtt.fYaw, para.craft.stAtt.fPitch, para.craft.stAtt.fRoll,
para.servoInfo.fServoAz, para.servoInfo.fServoPt,para.camInfo.nFocus,para.camInfo.fPixelSize);
//run_test(para);
// 统计扫描方向
int dir = StatScanDir(para);
if (dir == 1)
{
printf("++++++++++++++++++++\n");
}
else
{
printf("--------------------\n");
}
//// 视频帧筛选
if (!FilterFrame(para))
@ -473,6 +507,20 @@ SINT32 UnderStitch::Run(GD_VIDEO_FRAME_S frame, FrameInfo para)
cv::Size(_panPara.m_pan_width, _panPara.m_pan_height)))
{
//cv::Mat pan_ds;
// Mat pan_rgb_ds(cv::Size(panImage.cols / 2, panImage.rows / 2),CV_8UC3);
// cv::resize(panImage, pan_ds, cv::Size(panImage.cols / 2, panImage.rows / 2));
// cv::cvtColor(pan_ds, pan_rgb_ds, cv::COLOR_BGRA2BGR);
// imwrite(_outDir + "/" + _filename + std::to_string(_lastFrameKey) + "_z" + "_pan.png", pan_rgb_ds);
//OptAndOutCurrPan(_baCurrViewKey);
// cv::resize(panImage, pan_ds, cv::Size(panImage.cols / 2, panImage.rows / 2));
//cv::cvtColor(pan_ds, pan_rgb_ds, cv::COLOR_BGRA2BGR);
// imwrite(_outDir + "/" + _filename + std::to_string(_lastFrameKey) + "_z" + "_pan_AFTER.png", pan_rgb_ds);
LOG_INFO("Frame {} is out of pan view, reinitializing projection parameters", para.nFrmID);
// 输出当前所有瓦片,再不输出就会丢失当前全景中的瓦片
@ -486,6 +534,8 @@ SINT32 UnderStitch::Run(GD_VIDEO_FRAME_S frame, FrameInfo para)
_googleProduct.ExportTileSet(mat_pan, mat_mask, tilesvec, outdirpath, filename);
}, "ExportTileSet");
// _googleProduct.ExportTileSet(panImage, panMask, _taskTilesVec, _outDir, _filename + std::to_string(_lastFrameKey));
// 重新初始化投影参数
@ -514,9 +564,24 @@ SINT32 UnderStitch::Run(GD_VIDEO_FRAME_S frame, FrameInfo para)
return 0;
}
//if (dir == -1)
//{
// cv::Mat src1(frame.u32Height, frame.u32Width, CV_8UC3, (void*)frame.u64VirAddr[0]);
// src1 = src1 + cv::Scalar(30, 30, 30);
//}
//if (dir == 1 && para.servoInfo.fServoPt < 0)
//{
// int delta = ABS(para.servoInfo.fServoPt);
// cv::Mat src1(frame.u32Height, frame.u32Width, CV_8UC3, (void*)frame.u64VirAddr[0]);
// src1 = src1 + cv::Scalar(delta, delta, delta);
//}
// 获取RGBA图像
cv::Mat src = getRGBAMatFromGDFrame(frame, frame.u64VirAddr[0]);
// 输出单帧谷歌瓦片
if (_config.bOutFrameTile)
{
@ -534,16 +599,19 @@ SINT32 UnderStitch::Run(GD_VIDEO_FRAME_S frame, FrameInfo para)
if (_config.bUseBA && TriggerBA(para))
{
// 异步执行BA优化
_threadPool.commit(
[this]() {
OptAndOutCurrPan(_baWindowKey);
},
"BA_Optimization"
);
// 异步执行BA优化
_threadPool.commit(
[this]() {
OptAndOutCurrPan(_baWindowKey);
},
"BA_Optimization"
);
}
LOG_INFO("stitch total times:{}", sw.elapsed_ms());
return 0;
}
@ -580,7 +648,7 @@ SINT32 UnderStitch::OptAndOutCurrPan(vector<KeyType> workFrame)
// 输出当前所有瓦片
LOG_INFO("ExportTileSet");
_googleProduct.ExportTileSet(_MapBlender->getPanImageMat(), _MapBlender->getPanMaskMat(),
_taskTilesVec, _outDir, _filename + std::to_string(_lastFrameKey));
_taskTilesVec, _outDir, _filename + std::to_string(_lastFrameKey),false);
return workFrame.size();
}
@ -608,7 +676,13 @@ bool UnderStitch::FilterFrame(FrameInfo para)
}
// 扫描角过大,跳过
if (ABS(para.servoInfo.fServoPt) > 45)
if (ABS(para.servoInfo.fServoPt) > 37)
{
return false;
}
// 姿态不稳定,跳过
if(ABS(para.craft.stAtt.fRoll) > 5)
{
return false;
}
@ -1030,6 +1104,24 @@ void UnderStitch::TransPitch(FrameInfo& info)
info.servoInfo.fServoPt += 90;
}
int UnderStitch::StatScanDir(FrameInfo& para)
{
double d = para.servoInfo.fServoPt - infoLast.servoInfo.fServoPt;
infoLast = para;
// 指数平滑趋势
ScanTrend = 0.2 * ScanTrend + 0.8 * d;
int dir = 0;
if (ScanTrend > 0.2)
dir = 1;
else if (ScanTrend < -0.2)
dir = -1;
return dir;
}
cv::Mat UnderStitch::getAffineFromGeo2Pan(UPanInfo _pan)

@ -59,6 +59,9 @@ public:
private:
// 俯仰零位转换
void TransPitch(FrameInfo& para);
// 扫描方向判别
int StatScanDir(FrameInfo& para);
// 判断帧是否在全景图视场内
bool isFrameInPanView(const cv::Size& frameSize, const cv::Mat& H, const cv::Size& panSize);
@ -155,4 +158,8 @@ private:
std::threadpool _threadPool; // 线程池
SINT32 scanDir; //扫描方向
FrameInfo infoLast;//上一帧
FLOAT32 ScanTrend;
};

@ -118,7 +118,7 @@ void FileCache<T>::evictIfNeeded()
lru_list_.pop_back();
cache_.erase(oldest);
std::cout << "Evicted cache from memory for key: " << oldest << std::endl;
std::cout << "cache_size:"<< cache_.size() << "Evicted cache from memory for key: " << oldest << std::endl;
}
template <typename T>

@ -47,7 +47,7 @@ void googleTile::ExportGeoPng(cv::Mat _pan, TileInfo info, std::string dir)
}
#include "Log/Logger.h"
#include "utils/Arith_timer.h"
void googleTile::ExportTileSet(cv::Mat _pan, cv::Mat _panMask, vector<TileInfo> taskTilesVec, std::string dir,std::string fileString)
void googleTile::ExportTileSet(cv::Mat _pan, cv::Mat _panMask, vector<TileInfo> taskTilesVec, std::string dir,std::string fileString, bool bKml)
{
stopWatch sw;
int panWidth = _pan.cols;
@ -120,8 +120,11 @@ void googleTile::ExportTileSet(cv::Mat _pan, cv::Mat _panMask, vector<TileInfo>
}
// 输出KML
WriteKml(vaildTilesVec,dir + "/" + fileString + "_z" + std::to_string(zoom) + ".kml");
if (bKml)
{
// 输出KML
WriteKml(vaildTilesVec,dir + "/" + fileString + "_z" + std::to_string(zoom) + ".kml");
}
LOG_INFO("ExportTileSet TIME:{}", sw.elapsed_ms());

@ -51,7 +51,7 @@ public:
void ExportGeoPng(cv::Mat _pan, TileInfo info, std::string dir);
// 输出tile组
void ExportTileSet(cv::Mat _pan, cv::Mat _panMask, vector<TileInfo> taskTilesVec, std::string dir, std::string fileString);
void ExportTileSet(cv::Mat _pan, cv::Mat _panMask, vector<TileInfo> taskTilesVec, std::string dir, std::string fileString, bool bKml = true);
// 输出单个tile
void ExportOneTile(cv::Mat _pan, TileInfo tile, std::string dir, std::string fileString);

@ -2,5 +2,5 @@
#pragma once
#include <string>
std::string BUILD_TIME = "BUILD_TIME 2025_11_20-13.13.47";
std::string BUILD_TIME = "BUILD_TIME 2025_11_24-10.08.46";
std::string VERSION = "BUILD_VERSION 1.0.1";

@ -196,7 +196,7 @@ void DecodeData::Init()
m_frontStitcher = API_FrontStitch::Create();
m_underStitcher = API_UnderStitch::Create("d:/google_tiles/cache");
m_underStitcher = API_UnderStitch::Create("D:/google_tiles/cache");
}
void DecodeData::UnInit()
@ -681,7 +681,7 @@ int DecodeData::DecodeRGBImageAndPara(unsigned char *RGBBuffer, H264SEI_Para_732
m_underStitcher->SetConfig(cfg);
m_underStitcher->SetOutput("baotou", "E:/google_tiles");
m_underStitcher->SetOutput("baotou", "D:/google_tiles");
}
else
{

@ -13,7 +13,7 @@ using namespace std;
void ProcessVL(string filePath)
{
auto stitcher = API_UnderStitch::Create("D:/cache");
auto stitcher = API_UnderStitch::Create("/home/wang/cache");
stitcher->SetOutput("BT", "google_tiles");
@ -24,6 +24,8 @@ void ProcessVL(string filePath)
FILE* file = fopen(filePath.c_str(), "rb");
cv::VideoWriter output;
@ -40,9 +42,9 @@ void ProcessVL(string filePath)
const int delayFrames = 5; // 假设延迟3帧
std::deque<cv::Mat> MatBuffer;
const int matdelayFrames = 2; // 假设延迟3帧
const int matdelayFrames = 1; // 假设延迟3帧
fseek(file, nVLFrameSize * 80, SEEK_SET);
fseek(file, nVLFrameSize * 5, SEEK_SET);
while (!feof(file))
{
@ -66,7 +68,7 @@ void ProcessVL(string filePath)
info_rev.craft.stPos.L = Paras_VL.trackInputPara.stAirCraftInfo.stPos.L;
info_rev.craft.stPos.H = Paras_VL.trackInputPara.stAirCraftInfo.stPos.H;
info_rev.nEvHeight = info_rev.craft.stPos.H - 1200;
info_rev.nEvHeight = info_rev.craft.stPos.H - 1250;
info_rev.servoInfo.fServoAz = Paras_VL.trackInputPara.stServoInfo.fServoAz;
info_rev.servoInfo.fServoPt = Paras_VL.trackInputPara.stServoInfo.fServoPt;
@ -81,21 +83,21 @@ void ProcessVL(string filePath)
cv::cvtColor(mat_src, IMG, cv::COLOR_YUV2GRAY_NV21);
cv::Mat f;
IMG.convertTo(f, CV_32F, 1.0 / 255.0);
cv::pow(f, 0.8, f); // gamma < 1 => 变亮
cv::Mat bright;
f.convertTo(bright, CV_8U, 255.0);
cv::cvtColor(bright, bright, cv::COLOR_GRAY2BGR);
//cv::Mat f;
//IMG.convertTo(f, CV_32F, 1.0 / 255.0);
//cv::pow(f, 0.8, f); // gamma < 1 => 变亮
//cv::Mat bright;
//f.convertTo(bright, CV_8U, 255.0);
//cv::cvtColor(bright, bright, cv::COLOR_GRAY2BGR);
cv::cvtColor(IMG, IMG, cv::COLOR_GRAY2BGR);
cv::namedWindow("IMG_show", cv::WINDOW_NORMAL);
imshow("IMG_show", IMG);
MatBuffer.push_back(bright.clone());
MatBuffer.push_back(IMG.clone());
if (MatBuffer.size() < matdelayFrames)
{
@ -121,19 +123,19 @@ void ProcessVL(string filePath)
stitcher->Init(info);
UPanConfig cfg = { 0 };
cfg.bOutGoogleTile = 0;
cfg.bOutGoogleTile = 1;
cfg.bOutFrameTile = 0;
cfg.bUseBA = 0;
cfg.bUseBA = 1;
stitcher->SetConfig(cfg);
stitcher->SetOutput("baotou","F:/google_tiles");
stitcher->SetOutput("baotou","/home/wang/google_tiles");
pan = stitcher->ExportPanAddr();
mat_pan = cv::Mat(pan.u32Height, pan.u32Width, CV_8UC4, pan.u64VirAddr[0]);
output.open("output.mp4", VideoWriter::fourcc('M', 'P', '4', 'V'), 50, Size(pan.u32Width / 8, pan.u32Height / 8), true);
output.open("output.mp4", VideoWriter::fourcc('M', 'P', '4', 'V'), 50, Size(pan.u32Width / 10, pan.u32Height / 10), true);
if (!output.isOpened())
{
cout << "打开视频失败" << endl;
@ -157,9 +159,10 @@ void ProcessVL(string filePath)
cout << "time:" << tm.getTimeMilli() << endl;
}
Mat pan_ds;
Mat pan_rgb_ds(cv::Size(mat_pan.cols / 8, mat_pan.rows / 8),CV_8UC3);
cv::resize(mat_pan, pan_ds, cv::Size(mat_pan.cols / 8, mat_pan.rows / 8));
Mat pan_rgb_ds(cv::Size(mat_pan.cols / 10, mat_pan.rows / 10),CV_8UC3);
cv::resize(mat_pan, pan_ds, cv::Size(mat_pan.cols / 10, mat_pan.rows / 10));
cv::cvtColor(pan_ds, pan_rgb_ds, cv::COLOR_BGRA2BGR);
@ -184,7 +187,7 @@ void ProcessVL(string filePath)
//cv::TickMeter tm;
//tm.start();
//// 处理帧
//stitcher->OptAndOutCurrPan();
stitcher->OptAndOutCurrPan();
//tm.stop();
@ -203,7 +206,7 @@ void ProcessVL(string filePath)
int main()
{
ProcessVL("/media/wang/think/S732/扫描视频/20251116_091223317_10.yuv");
ProcessVL("/media/wang/data/包头/20251121/20251121_155930045_16.yuv");
return 0;
}

@ -5,12 +5,12 @@ int main(int argc, char* argv[])
{
DecodeData* m_DecodeData = new DecodeData();
std::string filestr = "D:/Project/S732/1101VL.dat";
std::string filestr = "F:/包头/S732显控/1101VL.dat";
//std::string filestr = "E:/03855jcw/S732/H265data/1080ir2.dat";
m_DecodeData->m_CurrentVideo = 1;//0:红外1可见光
m_DecodeData->m_LocalHeight = 1365;// 本地海拔
m_DecodeData->m_LocalHeight = 1200;// 本地海拔
m_DecodeData->Init();
m_DecodeData->processFileInChunks(filestr, 6 * 1024);

Loading…
Cancel
Save