FPFH特征描述符、对应关系可视化以及ICP配准

一、FPFH特征描述符可视化

C++

#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/search/kdtree.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/normal_3d_omp.h>//使用OMP需要添加的头文件
#include <boost/thread/thread.hpp>
#include <pcl/features/3dsc.h>
#include <pcl/visualization/pcl_plotter.h>// 直方图的可视化 
#include <pcl/visualization/histogram_visualizer.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/features/fpfh_omp.h>
using namespace std;
int main()
{//------------------加载点云数据-----------------pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);if (pcl::io::loadPCDFile<pcl::PointXYZ>("pcd/pig_view1.pcd", *cloud) == -1)//需使用绝对路径{PCL_ERROR("Could not read file\n");}//--------------------计算法线------------------pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::Normal> n;//OMP加速pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);//建立kdtree来进行近邻点集搜索pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);n.setNumberOfThreads(8);//设置openMP的线程数n.setInputCloud(cloud);n.setSearchMethod(tree);n.setKSearch(20);n.compute(*normals);//开始进行法向计算// ------------------FPFH图像计算------------------pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33> f;pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfh_images(new pcl::PointCloud<pcl::FPFHSignature33>());f.setNumberOfThreads(12);f.setInputCloud(cloud);f.setInputNormals(normals);f.setSearchMethod(tree);f.setKSearch(30);f.compute(*fpfh_images);cout << "FPFH图像计算计算完成" << endl;// 显示和检索第一点的自旋图像描述符向量。pcl::FPFHSignature33 first_descriptor = fpfh_images->points[0];cout << first_descriptor << endl;pcl::visualization::PCLPlotter plotter;plotter.addFeatureHistogram(*fpfh_images, 200); //设置的横坐标长度,该值越大,则显示的越细致plotter.setWindowName("FPFH Image");plotter.plot();return 0;
}

关键代码解析:

    pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33> f;pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfh_images(new pcl::PointCloud<pcl::FPFHSignature33>());f.setNumberOfThreads(12);f.setInputCloud(cloud);f.setInputNormals(normals);f.setSearchMethod(tree);f.setKSearch(30);f.compute(*fpfh_images);cout << "FPFH图像计算计算完成" << endl;// 显示和检索第一点的自旋图像描述符向量。pcl::FPFHSignature33 first_descriptor = fpfh_images->points[0];cout << first_descriptor << endl;pcl::visualization::PCLPlotter plotter;plotter.addFeatureHistogram(*fpfh_images, 200); //设置的横坐标长度,该值越大,则显示的越细致plotter.setWindowName("FPFH Image");plotter.plot();

 

  1. pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33> f;

    • 这一行定义了一个FPFH特征估计器对象f,使用了OMP(Open Multi-Processing)进行多线程计算。指定了输入点云类型为pcl::PointXYZ,输入法向量类型为pcl::Normal,以及输出特征类型为pcl::FPFHSignature33
  2. pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfh_images(new pcl::PointCloud<pcl::FPFHSignature33>());

    • 创建一个指向pcl::PointCloud<pcl::FPFHSignature33>类型的智能指针fpfh_images,用于存储计算得到的FPFH特征。
  3. f.setNumberOfThreads(12);

    • 设置用于计算FPFH特征的线程数。这里设置为12,以充分利用多核处理器的性能。线程数的选择应该考虑到计算机的硬件配置,过多的线程可能导致性能下降。
  4. f.setInputCloud(cloud);

    • 将点云数据设置为FPFH估计器的输入。cloud是一个指向pcl::PointCloud<pcl::PointXYZ>类型的指针,表示原始点云数据。
  5. f.setInputNormals(normals);

    • 将法向量数据设置为FPFH估计器的输入。normals是一个指向pcl::PointCloud<pcl::Normal>类型的指针,表示点云中每个点的法向量数据。
  6. f.setSearchMethod(tree);

    • 设置搜索方法。tree是一个用于加速邻域搜索的数据结构,例如kd-tree或octree。这个参数可以根据点云的大小和分布来调整,以获得更好的性能。
  7. f.setKSearch(30);

    • 设置用于计算FPFH特征的近邻点数目。这个参数影响着计算的邻域大小,值越大则考虑的邻域越大,特征描述更全局。
  8. f.compute(*fpfh_images);

    • 运行FPFH特征的计算过程。该方法会根据输入的点云和法向量数据以及设置的搜索参数来计算每个点的FPFH特征,并将结果存储在fpfh_images中。
  9. cout << "FPFH图像计算计算完成" << endl;

    • 打印消息,指示FPFH特征计算完成。
  10. pcl::FPFHSignature33 first_descriptor = fpfh_images->points[0];

    • 提取第一个点的FPFH特征描述符。这里假设点云中至少有一个点。
  11. cout << first_descriptor << endl;

    • 打印第一个点的FPFH特征描述符。
  12. pcl::visualization::PCLPlotter plotter;

    • 创建一个PCL绘图器对象,用于可视化FPFH特征。
  13. plotter.addFeatureHistogram(*fpfh_images, 200);

    • 向绘图器中添加FPFH特征的直方图。第二个参数指定了横坐标的长度,该值越大,显示的越细致。
  14. plotter.setWindowName("FPFH Image");

    • 设置绘图窗口的名称。
  15. plotter.plot();

    • 显示绘图器中的图像。

总的来说,这段代码的作用是计算并可视化点云的FPFH特征。参数的设置会直接影响特征的计算和可视化效果,因此需要根据具体的数据和需求进行调整。

结果:

二、FPFH对应关系可视化

C++

#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/normal_3d_omp.h>
#include <pcl/features/fpfh_omp.h>
#include <pcl/registration/correspondence_estimation.h>
#include <boost/thread/thread.hpp>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/registration/transformation_estimation_svd.h> typedef pcl::PointCloud<pcl::PointXYZ> pointcloud;
typedef pcl::PointCloud<pcl::Normal> pointnormal;
typedef pcl::PointCloud<pcl::FPFHSignature33> fpfhFeature;fpfhFeature::Ptr compute_fpfh_feature(pointcloud::Ptr input_cloud, pcl::search::KdTree<pcl::PointXYZ>::Ptr tree)
{pointnormal::Ptr normals(new pointnormal);pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::Normal> n;n.setInputCloud(input_cloud);n.setNumberOfThreads(12);n.setSearchMethod(tree);n.setKSearch(20);n.compute(*normals);fpfhFeature::Ptr fpfh(new fpfhFeature);pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33> f;f.setNumberOfThreads(12);f.setInputCloud(input_cloud);f.setInputNormals(normals);f.setSearchMethod(tree);f.setKSearch(30);f.compute(*fpfh);return fpfh;
}int main(int argc, char** argv)
{pointcloud::Ptr source_cloud(new pointcloud);pointcloud::Ptr target_cloud(new pointcloud);pcl::io::loadPCDFile<pcl::PointXYZ>("pcd/pig_view1.pcd", *source_cloud);pcl::io::loadPCDFile<pcl::PointXYZ>("pcd/pig_view2.pcd", *target_cloud);pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>());fpfhFeature::Ptr source_fpfh = compute_fpfh_feature(source_cloud, tree);fpfhFeature::Ptr target_fpfh = compute_fpfh_feature(target_cloud, tree);pcl::registration::CorrespondenceEstimation<pcl::FPFHSignature33, pcl::FPFHSignature33> crude_cor_est;boost::shared_ptr<pcl::Correspondences> cru_correspondences(new pcl::Correspondences);crude_cor_est.setInputSource(source_fpfh);crude_cor_est.setInputTarget(target_fpfh);crude_cor_est.determineCorrespondences(*cru_correspondences, 0.4);Eigen::Matrix4f Transform = Eigen::Matrix4f::Identity();pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ, float>::Ptr trans(new pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ, float>);trans->estimateRigidTransformation(*source_cloud, *target_cloud, *cru_correspondences, Transform);cout << "变换矩阵为:\n" << Transform << endl;boost::shared_ptr<pcl::visualization::PCLVisualizer>viewer(new pcl::visualization::PCLVisualizer("v"));viewer->setBackgroundColor(0, 0, 0);// 对目标点云着色可视化 (red).pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>target_color(target_cloud, 255, 0, 0);viewer->addPointCloud<pcl::PointXYZ>(target_cloud, target_color, "target cloud");viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "target cloud");// 对源点云着色可视化 (green).pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>input_color(source_cloud, 0, 255, 0);viewer->addPointCloud<pcl::PointXYZ>(source_cloud, input_color, "input cloud");viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "input cloud");//对应关系可视化viewer->addCorrespondences<pcl::PointXYZ>(source_cloud, target_cloud, *cru_correspondences, "correspondence");//viewer->initCameraParameters();while (!viewer->wasStopped()){viewer->spinOnce(100);boost::this_thread::sleep(boost::posix_time::microseconds(100000));}return 0;
}

关键代码解析:

    pcl::registration::CorrespondenceEstimation<pcl::FPFHSignature33, pcl::FPFHSignature33> crude_cor_est;boost::shared_ptr<pcl::Correspondences> cru_correspondences(new pcl::Correspondences);crude_cor_est.setInputSource(source_fpfh);crude_cor_est.setInputTarget(target_fpfh);crude_cor_est.determineCorrespondences(*cru_correspondences, 0.4);Eigen::Matrix4f Transform = Eigen::Matrix4f::Identity();pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ, float>::Ptr trans(new pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ, float>);trans->estimateRigidTransformation(*source_cloud, *target_cloud, *cru_correspondences, Transform);
  1. pcl::registration::CorrespondenceEstimation<pcl::FPFHSignature33, pcl::FPFHSignature33> crude_cor_est;

    • 创建了一个用于估计FPFH特征之间对应关系的对象crude_cor_est。这个对象的类型是pcl::registration::CorrespondenceEstimation,它用于估计两个点云之间的对应关系。
  2. boost::shared_ptr<pcl::Correspondences> cru_correspondences(new pcl::Correspondences);

    • 创建了一个指向pcl::Correspondences类型的智能指针cru_correspondences,用于存储对应关系。
  3. crude_cor_est.setInputSource(source_fpfh);

    • 设置源点云的FPFH特征作为对应关系估计的输入。source_fpfh是指向源点云的FPFH特征的指针。
  4. crude_cor_est.setInputTarget(target_fpfh);

    • 设置目标点云的FPFH特征作为对应关系估计的目标。target_fpfh是指向目标点云的FPFH特征的指针。
  5. crude_cor_est.determineCorrespondences(*cru_correspondences, 0.4);

    • 使用设定的FPFH特征对两个点云之间的对应关系进行估计。第二个参数0.4是一个阈值,用于控制匹配的严格度。更高的值会导致更宽松的匹配。
  6. Eigen::Matrix4f Transform = Eigen::Matrix4f::Identity();

    • 创建一个4x4的单位矩阵,用于存储刚性变换。
  7. pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ, float>::Ptr trans(new pcl::registration::TransformationEstimationSVD<pcl::PointXYZ, pcl::PointXYZ, float>);

    • 创建了一个用于估计刚性变换的对象trans。这里使用了SVD(奇异值分解)方法进行刚性变换的估计。
  8. trans->estimateRigidTransformation(*source_cloud, *target_cloud, *cru_correspondences, Transform);

    • 使用对应关系和源点云以及目标点云之间的FPFH特征,估计两个点云之间的刚性变换。这个变换会被存储在Transform中。

参数的设置会影响配准的结果。例如,对应关系估计的阈值会影响匹配的严格度,而刚性变换的估计方法则会影响配准的准确度和鲁棒性。需要根据具体的应用场景和数据特点来选择合适的参数值

结果:

三、3DSC结合ICP配准  

C++

#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/features/normal_3d_omp.h>
#include <pcl/features/spin_image.h>
#include <pcl/registration/icp.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <boost/thread/thread.hpp>
#include <pcl/keypoints/iss_3d.h>
#include <pcl/registration/ia_ransac.h>
#include <pcl/visualization/pcl_plotter.h>
#include <pcl/features/fpfh_omp.h>
typedef pcl::PointXYZ PointT;
typedef pcl::PointCloud<PointT> PointCloud;
typedef pcl::FPFHSignature33 FPFHT;
typedef pcl::PointCloud<FPFHT> PointCloudfpfh;
typedef pcl::search::KdTree<PointT> Tree;// 关键点提取
void extract_keypoint(PointCloud::Ptr& cloud, PointCloud::Ptr& keypoint, Tree::Ptr& tree)
{pcl::ISSKeypoint3D<PointT, PointT> iss;iss.setInputCloud(cloud);iss.setSearchMethod(tree);iss.setNumberOfThreads(8);     //初始化调度器并设置要使用的线程数iss.setSalientRadius(5);  // 设置用于计算协方差矩阵的球邻域半径iss.setNonMaxRadius(5);   // 设置非极大值抑制应用算法的半径iss.setThreshold21(0.95);     // 设定第二个和第一个特征值之比的上限iss.setThreshold32(0.95);     // 设定第三个和第二个特征值之比的上限iss.setMinNeighbors(6);       // 在应用非极大值抑制算法时,设置必须找到的最小邻居数iss.compute(*keypoint);
}
// 法线计算和 计算特征点的Spinimage描述子
void computeKeyPointsFPFH(PointCloud::Ptr& cloud_in, PointCloud::Ptr& key_cloud, PointCloudfpfh::Ptr& dsc, Tree::Ptr& tree)
{pcl::NormalEstimationOMP<PointT, pcl::Normal> n;//OMP加速pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);n.setNumberOfThreads(6);//设置openMP的线程数n.setInputCloud(key_cloud);n.setSearchSurface(cloud_in);n.setSearchMethod(tree);//n.setKSearch(10);n.setRadiusSearch(0.3);n.compute(*normals);pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33> f;f.setNumberOfThreads(12);f.setInputCloud(key_cloud);f.setInputNormals(normals);f.setSearchMethod(tree);f.setKSearch(30);f.compute(*dsc);}// 点云可视化
void visualize_pcd(PointCloud::Ptr icp_result, PointCloud::Ptr cloud_target)
{//创建初始化目标pcl::visualization::PCLVisualizer viewer("registration Viewer");pcl::visualization::PointCloudColorHandlerCustom<PointT> final_h(icp_result, 0, 255, 0);pcl::visualization::PointCloudColorHandlerCustom<PointT> tgt_h(cloud_target, 255, 0, 0);viewer.setBackgroundColor(0, 0, 0);viewer.addPointCloud(cloud_target, tgt_h, "tgt cloud");viewer.addPointCloud(icp_result, final_h, "final cloud");while (!viewer.wasStopped()){viewer.spinOnce(100);boost::this_thread::sleep(boost::posix_time::microseconds(100000));}
}int main()
{// 加载源点云和目标点云PointCloud::Ptr cloud(new PointCloud);PointCloud::Ptr cloud_target(new PointCloud);if (pcl::io::loadPCDFile<pcl::PointXYZ>("pcd/pig_view1.pcd", *cloud) == -1){PCL_ERROR("加载点云失败\n");}if (pcl::io::loadPCDFile<pcl::PointXYZ>("pcd/pig_view2.pcd", *cloud_target) == -1){PCL_ERROR("加载点云失败\n");}visualize_pcd(cloud, cloud_target);//关键点pcl::PointCloud<PointT>::Ptr keypoints1(new pcl::PointCloud<pcl::PointXYZ>);pcl::PointCloud<PointT>::Ptr keypoints2(new pcl::PointCloud<pcl::PointXYZ>);Tree::Ptr tree(new Tree);extract_keypoint(cloud, keypoints1, tree);extract_keypoint(cloud_target, keypoints2, tree);cout << "iss完成!" << endl;cout << "cloud的关键点的个数:" << keypoints1->size() << endl;cout << "cloud_target的关键点的个数:" << keypoints2->size() << endl;// 使用SpinImage描述符计算特征PointCloudfpfh::Ptr source_features(new PointCloudfpfh);PointCloudfpfh::Ptr target_features(new PointCloudfpfh);computeKeyPointsFPFH(cloud, keypoints1, source_features, tree);computeKeyPointsFPFH(cloud_target, keypoints2, target_features, tree);cout << "FPFH完成!" << endl;//SAC配准pcl::SampleConsensusInitialAlignment<PointT, PointT, FPFHT> scia;scia.setInputSource(keypoints1);scia.setInputTarget(keypoints2);scia.setSourceFeatures(source_features);scia.setTargetFeatures(target_features);scia.setMinSampleDistance(7);     // 设置样本之间的最小距离scia.setNumberOfSamples(100);       // 设置每次迭代计算中使用的样本数量(可省),可节省时间scia.setCorrespondenceRandomness(6);// 在选择随机特征对应时,设置要使用的邻居的数量;PointCloud::Ptr sac_result(new PointCloud);scia.align(*sac_result);Eigen::Matrix4f sac_trans;sac_trans = scia.getFinalTransformation();cout << "SAC配准完成!" << endl;//icp配准PointCloud::Ptr icp_result(new PointCloud);pcl::IterativeClosestPoint<PointT, PointT> icp;icp.setInputSource(keypoints1);icp.setInputTarget(keypoints2);icp.setMaxCorrespondenceDistance(20);icp.setMaximumIterations(35);        // 最大迭代次数icp.setTransformationEpsilon(1e-10); // 两次变化矩阵之间的差值icp.setEuclideanFitnessEpsilon(0.01);// 均方误差icp.align(*icp_result, sac_trans);cout << "ICP配准完成!" << endl;// 输出配准结果std::cout << "ICP converged: " << icp.hasConverged() << std::endl;std::cout << "Transformation matrix:\n" << icp.getFinalTransformation() << std::endl;Eigen::Matrix4f icp_trans;icp_trans = icp.getFinalTransformation();cout << icp_trans << endl;使用创建的变换对未过滤的输入点云进行变换pcl::transformPointCloud(*cloud, *icp_result, icp_trans);visualize_pcd(icp_result, cloud_target);return 0;
}

关键代码解析:

我之前在iss关键点检测以及SAC-IA粗配准-CSDN博客

和Spin Image自旋图像描述符可视化以及ICP配准-CSDN博客以及本章第一部分已经解释了大部分函数,这里就不赘述了

结果:

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.hqwc.cn/news/475786.html

如若内容造成侵权/违法违规/事实不符,请联系编程知识网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

Midjourney绘图欣赏系列(五)

Midjourney介绍 Midjourney 是生成式人工智能的一个很好的例子&#xff0c;它根据文本提示创建图像。它与 Dall-E 和 Stable Diffusion 一起成为最流行的 AI 艺术创作工具之一。与竞争对手不同&#xff0c;Midjourney 是自筹资金且闭源的&#xff0c;因此确切了解其幕后内容尚不…

如何系统地学习Python

建议系统学习Python的途径遵循理论与实践相结合的教学方法。以下是一个分阶段的学习计划&#xff1a; 阶段一&#xff1a;基础知识 理解Python的特点&#xff1a; 认识Python的历史与设计哲学。学习Python的基本语法和运行环境。 安装Python&#xff1a; 学习如何在不同操作系…

芯片的分类

目录 通用处理器数字信号处理器专用处理器 通用处理器 我们常听说的中央处理器CPU就是一种典型的通用处理器&#xff08;GPP&#xff09;。这种处理器多使用片上系统&#xff08;SoC&#xff09;的设计理念&#xff0c;在处理器上集成各种功能模块&#xff0c;每一种功能都是用…

【JavaEE】_多线程Thread类及其常用方法

目录 1. Thread类常用构造方法 2. Thread类的几个常见属性 3. 启动一个线程 4. 中断一个线程 4.1 方法1&#xff1a;手动设置标志位 4.2 方法2&#xff1a;使用Thread内置的标志位 5. 等待一个线程 6. 获取当前线程引用 7. 休眠当前线程 1. Thread类常用构造方法 方法…

【开源】SpringBoot框架开发食品生产管理系统

目录 一、摘要1.1 项目介绍1.2 项目录屏 二、功能模块2.1 加工厂管理模块2.2 客户管理模块2.3 食品管理模块2.4 生产销售订单管理模块2.5 系统管理模块2.6 其他管理模块 三、系统展示四、核心代码4.1 查询食品4.2 查询加工厂4.3 新增生产订单4.4 新增销售订单4.5 查询客户 五、…

Java面向对象案例之设计用户去ATM机存款取款(三)

需求及思路分析 业务代码需求&#xff1a; 某公司要开发“银行管理系统”&#xff0c;请使用面向对象的思想&#xff0c;设计银行的储户信息&#xff0c;描述存款、取款业务。 储户类的思路分析&#xff1a; 属性&#xff1a;用户姓名、密码、身份证号、账号、帐户余额 方法&a…

【开源】JAVA+Vue.js实现城市桥梁道路管理系统

目录 一、摘要1.1 项目介绍1.2 项目录屏 二、功能模块三、系统展示四、核心代码4.1 查询城市桥梁4.2 新增城市桥梁4.3 编辑城市桥梁4.4 删除城市桥梁4.5 查询单个城市桥梁 五、免责说明 一、摘要 1.1 项目介绍 基于VueSpringBootMySQL的城市桥梁道路管理系统&#xff0c;支持…

大数据,对于生活的改变

谷歌通过对于疾病的查询量可以预测一个个h1n1病毒的大爆发&#xff0c; 大数据时代对于人的考验 用户的搜索记录就是一种信息&#xff0c;这种信息会满足其基础相关的词条与其有关的词条&#xff08;最为原始的搜索机制&#xff0c;国内的搜索引擎都是采用这种基础原理。&…

Java并发之死锁详解

(/≧▽≦)/~┴┴ 嗨~我叫小奥 ✨✨✨ &#x1f440;&#x1f440;&#x1f440; 个人博客&#xff1a;小奥的博客 &#x1f44d;&#x1f44d;&#x1f44d;&#xff1a;个人CSDN ⭐️⭐️⭐️&#xff1a;传送门 &#x1f379; 本人24应届生一枚&#xff0c;技术和水平有限&am…

论文精读--对比学习论文综述

InstDisc 提出了个体判别任务&#xff0c;而且利用这个代理任务与NCE Loss去做对比学习从而得到了不错的无监督表征学习的结果&#xff1b;同时提出了别的数据结构——Memory Bank来存储大量负样本&#xff1b;解决如何对特征进行动量式的更新 翻译&#xff1a; 有监督学习的…

线程池再思考(业务学习)

1.为什么要用线程池&#xff1f; **1.降低资源消耗&#xff0c;**复用已创建的线程来降低创建和销毁线程的消耗。 2.提高响应速度&#xff0c;任务到达时&#xff0c;可以不需要等待线程的创建立即执行。 3.提高线程的可管理性&#xff0c;使用线程池能够统一的分配、调优和监…

字符设备驱动分步注册过程实现LED驱动的编写,编写应用程序测试

头文件&#xff01;&#xff01;&#xff01;&#xff01; #ifndef __HEAD_H__ #define __HEAD_H__ typedef struct{unsigned int MODER;unsigned int OTYPER;unsigned int OSPEEDR;unsigned int PUPDR;unsigned int IDR;unsigned int ODR; }gpio_t; #define PHY_LED1_ADDR 0…