GCNv2 VS2017 Win10 部署指南

部署环境

  Windows 10

  VS 2017

  libtorch 1.7 + cu101

Step 1 配置 libtorch 库

版本选择

  在 C++ 中使用torch::jit::load加载模型时,要求.pt模型生成基于的Pytorch版本与环境中的libtorch版本相同,或至少后者要不低于前者。否则在运行加载时就会报错C10::Error

  报错的原因,就我本次部署 GCNv2 的经验而言,是.pt文件中也包含.py代码。因此,如果用不同版本的libtorch,去执行其他版本生成的 Python 代码,那么就很有可能存在语法上的不同而报错。上述报错,在 VS2017 就体现为C10::Error

  例如,GCNv2 的模型文件是基于Pytorch 1.0.1生成的,而我们本次是采用libtorch 1.7.0去加载模型,因此模型文件中的 Python 代码存在不合于libtorch 1.7.0新版本的语法错误,故需要在 Step 2 中对模型代码进行修改。

  我们本次采用libtorch 1.7.0 + cu101,是因为 Gitub 上作者推荐的libtorch 1.0.1版本过于老旧,需要用下述命令下载:

git clone --recursive -b v1.0.1 https://github.com/pytorch/pytorch

  上述方法速度慢暂且不言,关键是其中的第三方库速度过慢,下载不全。类似的问题还存在于 Pangolin 库的配置中,后来我干脆直接自己手动配置 Pangolin 的第三方库了,可以参见我的另一篇博文。

  网上虽然有同仁提供的该版本的网盘下载,但由于是源码,估计还要构建编译,实在麻烦,故此直接采用新版本。若有非要跑该版本的,可以参考博文如右:https://blog.csdn.net/qq_35590091/article/details/103181008

库的下载

  libtorch 1.7.0 + cu101我们直接挪用 Python 环境下的库就可以。首先在命令行中下载该库,命令如下:

pip install torch==1.7.0+cu101 -f  https://download.pytorch.org/whl/torch_stable.html

  然后到 Python 编译器的site-packages目录下,找到torch文件夹,复制其中的lib文件夹以及include的文件夹到新建目录libtorch中,以备后用。

整合至 VS2017 中

  我是将libtorch目录放到了 VS2017 解决方案的3rd文件夹下,所以在项目中新建属性表,其中需要添加的内容是这样的:

VC++目录/包含目录
…\3rd\libtorch\include\torch\csrc\api\include
…\3rd\libtorch\include

VC++目录/库目录:…\external\libjpeg\lib
…\3rd\libtorch\lib

链接器/输入/附加依赖项
asmjit.lib
c10.lib
c10d.lib
c10_cuda.lib
caffe2_detectron_ops_gpu.lib
caffe2_module_test_dynamic.lib
caffe2_nvrtc.lib
caffe2_observers.lib
clog.lib
cpuinfo.lib
dnnl.lib
fbgemm.lib
gloo.lib
gloo_cuda.lib
libprotobuf-lite.lib
libprotobuf.lib
libprotoc.lib
mkldnn.lib
shm.lib
torch.lib
torch_cpu.lib
torch_cuda.lib
torch_python.lib
_C.lib

  注意一:上述lib文件夹内所有*.lib文件名的生成可以采用批处理命令进行,更加快捷。在命令行下进行lib文件夹目录下,执行下述命令:

dir /b *.lib >libs.txt 

  在目录下会生成libs.txt,其中内容就是所有 lib 文件的名称列表。

  注意二:我电脑上的 cuda 版本是 10.1 的,因此我下载的是libtorch 1.7.0 + cu101版本。虽然未曾测试,但我想读者诸君下载的libtorch 1.7.0 + cuxxx 的 cuda 版本,还是与本机相同为好。

  此外,由于我们用到了 cuda,因此尚需在项目属性\链接器\命令行\其他选项中添加如下参数,否则将在加载模型时报错C10::Error

/INCLUDE:?warp_size@cuda@at@@YAHXZ 

 &esmp;再注意要将项目属性的配置属性\C-C++\常规\SDL检查配置属性\C-C++\语言\符合模式禁止掉,不然在libtorch的源文件中会出现大量,“std”:不明确的的符号问题的报错。

Step 2 代码修改

  由于我们采用的libtorch的版本,与 GCNv2 作者采用的版本不同,因此需要对相关代码进行适应性的修改。我们主要对两方面的代码进行修改,其一是.pt模型中的 Python 代码,其二则是 GCNv2 本身代码的修改。

模型代码修改

  首先,需要找出模型代码中的哪些部分需要修改。启动VS Code,使用安装过libtorch 1.7.0 + cu101的 Python 编译器环境,执行下述代码,加载模型:

import torch

model = torch.jit.load('E:\\Program Files (x86)\\Microsoft Visual Studio\\MyProjects\\GCNv2\\models\\back\\gcn2_320x240.pt')

  然后有报错如下:

在这里插入图片描述
  我们就可以定位到具体错误代码在哪一行:这里可以看到,是在模型文件中的code/gcn.py文件的第六十七行。于是,我们采用WinRAR,打开对应的gcn2_320x240.pt文件,找到其中的gcn.py并打开,如下图所示:

在这里插入图片描述
  定位到错误发生的第六十七行:

  _32 = torch.squeeze(torch.grid_sampler(input, grid, 0, 0))

  参照之前的报错信息,我们可以知晓是torch.grid_sampler函数缺少了一个align_corners参数。我们参照另一位同仁的博文(https://blog.csdn.net/weixin_45650404/article/details/106085719),将函数最后的一个参数添加为True如下:

  _32 = torch.squeeze(torch.grid_sampler(input, grid, 0, 0, True))

  再度加载模型,报错消失。至此,模型代码修改完毕。

GCNv2 代码修改

  代码的修改主要针对GCNextractor.ccGCNextractor.h两个文件,如下所述:

  首先,在GCNextractor.h文件中,将GCNextractor类中protected成员module进行修改。代码原本是:

    std::shared_ptr<torch::jit::script::Module> module;

  修改为:

	torch::jit::Module module;
	// std::shared_ptr<torch::jit::script::Module> module;

  其次,在GCNextractor.cc文件中,修改构造函数中加载模型的部分代码。代码原本是:

    const char *net_fn = getenv("GCN_PATH");
    net_fn = (net_fn == nullptr) ? "gcn2.pt" : net_fn;
    module = torch::jit::load(net_fn);

  修改为:

	const char *net_fn = "D:\\gcn2_320x240.pt";
    module = torch::jit::load(net_fn);

  同时,在重载的括号运算符中,将模型推导的下述代码:

    auto output = module->forward(inputs).toTuple();

  修改为:

    auto output = module.forward(inputs).toTuple();

  仍然有两点需要注意,其一,GCNv2 的作者,在最新版的代码中,特地增加了对于libtorch较新版本的适配,重载的括号运算符中相关代码如下:

    #if defined(TORCH_NEW_API)
        std::vector<int64_t> dims = {1, img_height, img_width, 1};
        auto img_var = torch::from_blob(img.data, dims, torch::kFloat32).to(device);	
        img_var = img_var.permute({0,3,1,2});	
    #else 
        auto img_tensor = torch::CPU(torch::kFloat32).tensorFromBlob(img.data, {1, img_height, img_width, 1});
        img_tensor = img_tensor.permute({0,3,1,2});
        auto img_var = torch::autograd::make_variable(img_tensor, false).to(device);
    #endif

  可见,我们需要在项目属性中预处理器设置里,额外增加一个TORCH_NEW_API的定义。

  其二,注意根据输入图像的大小,对代码进行一些修改。在相同的函数中,有下述代码:


    int img_width = 320;
    int img_height = 240;

    int border = 8;
    int dist_thresh = 4;

    if (getenv("FULL_RESOLUTION") != nullptr)
    {
        img_width = 640;
        img_height = 480;

        border = 16;
        dist_thresh = 8;
    }

  可见,输入图像默认的大小是320×240,刚好是 TUM 数据集图像大小的一半。这里的图像大小,需要根据模型的不同,加以修改。由于我们测试的模型是gcn2_320x240.pt,大小于此相同,因此也就不改了。不过读者如果要用gcn2_640x480.pt模型进行测试,则务必修改。修改代码可以参照如下:


    int img_width = 320;
    int img_height = 240;

    int border = 8;
    int dist_thresh = 4;
	
	bool fullResolution = true;

    if (getenv("FULL_RESOLUTION") != nullptr || fullResolution)			
    {
        img_width = 640;
        img_height = 480;

        border = 16;
        dist_thresh = 8;
    }

Step 3 运行测试

  新建 VS2017 项目,将GCNextractor.hGCNextractor.cc择出来,编写示例代码如下,进行测试:

#include <iostream>
#include <opencv2\opencv.hpp>
#include "GCNextractor.h"

using namespace std;
using namespace GCN;

int main()
{
	GCNextractor* mpGCNextractor;

	int nFeatures = 1200;
	float fScaleFactor = 1.2;
	int nLevels = 8;
	int fIniThFAST = 20;
	int fMinThFAST = 7;

	mpGCNextractor = new GCNextractor(nFeatures, fScaleFactor, nLevels, fIniThFAST, fMinThFAST);

	std::cout << "loaded deep model" << std::endl;

	cv::Mat frame1 = cv::imread("D:\\before.png", cv::IMREAD_GRAYSCALE);
	cv::Mat frame2 = cv::imread("D:\\after.png", cv::IMREAD_GRAYSCALE);

	cv::resize(frame1, frame1, cv::Size(640, 480));
	cv::resize(frame2, frame2, cv::Size(640, 480));

	std::vector<cv::KeyPoint> mvKeys, mvKeys2;
	cv::Mat mDescriptors, mDescriptors2;

#ifdef ORB_USE

	cv::Ptr<cv::ORB> detector = cv::ORB::create();
	
	detector->detectAndCompute(frame1, cv::Mat(), mvKeys, mDescriptors);
	detector->detectAndCompute(frame2, cv::Mat(), mvKeys2, mDescriptors2);
	
#else

	(*mpGCNextractor)(frame1, cv::Mat(), mvKeys, mDescriptors);
	(*mpGCNextractor)(frame2, cv::Mat(), mvKeys2, mDescriptors2);
	
#endif


	cv::Mat outImg;
	cv::drawKeypoints(frame1, mvKeys, outImg, cv::Scalar::all(-1), cv::DrawMatchesFlags::DEFAULT);

	std::vector<cv::DMatch> matches;
	cv::BFMatcher matcher(cv::NORM_HAMMING);
	matcher.match(mDescriptors, mDescriptors2, matches, cv::Mat());

	double min_dist = 10000, max_dist = 0;
	for (int i = 0; i < mDescriptors.rows; i++) {
		double dist = matches[i].distance;
		if (dist < min_dist) min_dist = dist;
		if (dist > max_dist) max_dist = dist;
	}
	std::vector<cv::DMatch> goodMatches;
	for (int i = 0; i < mDescriptors.rows; i++) {
		if (matches[i].distance <= max(2 * min_dist, 30.0))
			goodMatches.push_back(matches[i]);
	}

	cv::Mat matchesImage2;
	cv::drawMatches(frame1, mvKeys, frame2, mvKeys2, goodMatches, matchesImage2);
	cv::imshow("curr-prev", matchesImage2);
	cv::waitKey(1);
	cv::imshow("kp", outImg);
	cv::waitKey(0);
	
	return 0;
}

  可以通过预定义宏ORB_USE来对 ORB 和 GCNv2 进行比对测试,结果如下:

  ORB:

在这里插入图片描述
  GCNv2:

在这里插入图片描述
  可见,就这两张图片而言,匹配效果要更好一些。

  • 0
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值