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博客以及本章第一部分已经解释了大部分函数,这里就不赘述了

结果:

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

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

Python一级考试笔记

Python一级考试笔记【源源老师】 前置知识&#xff1a;&#xff08;了解即可&#xff09; Python常见的几种编程环境&#xff1a;IDLE&#xff08;自带&#xff09;、Visual Studio Code、Jupyter、pyCharm&#xff1b; python版本&#xff1a;python3 和 python2&#xff08;…

开源模型应用落地-工具使用篇-向量数据库(三)

一、前言 通过学习"开源模型应用落地"系列文章&#xff0c;我们成功地建立了一个完整可实施的AI交付流程。现在&#xff0c;我们要引入向量数据库&#xff0c;作为我们AI服务的二级缓存。本文将详细介绍如何使用Milvus Lite来为我们的AI服务部署一个前置缓存。 二、术…

论文阅读_用模型模拟记忆过程

英文名称: A generative model of memory construction and consolidation 中文名称: 记忆构建和巩固的生成模型 文章: https://www.nature.com/articles/s41562-023-01799-z 代码: https://github.com/ellie-as/generative-memory 作者: Eleanor Spens, Neil Burgess&#xff…

python+pytest自动化测试函数测试类测试方法的封装

前言 今天呢&#xff0c;笔者想和大家聊聊pythonpytest接口自动化中将代码进行封装&#xff0c;只有将测试代码进行封装&#xff0c;才能被测试框架识别执行。 例如单个接口的请求代码如下&#xff1a; 1 2 3 4 5 6 import requests headers { "user-agent":…

证明之三条看似显然实则需要证明的陈述

三条看似显然实则需要证明的陈述 “表面显然的数学定理&#xff1a;隐藏的证明之谜” 较高等的数学中&#xff0c;有一点让很多人感到费解&#xff1a;其中有一些定理看上去非常显然&#xff0c;简直无须证明。遇到这样的定理时&#xff0c;人们常常会问&#xff1a;“如果这…

海外媒体发稿:掌握这8个东南亚媒体发稿的技巧-华媒舍

在如今的数字化时代&#xff0c;媒体的地位越来越重要&#xff0c;尤其在东南亚地区。了解如何在关键时刻掌握东南亚媒体发稿的技巧是非常重要的。本文将介绍8个在东南亚地区重要的媒体发稿技巧&#xff0c;帮助您更好地传达信息。 1. 熟悉目标媒体 要掌握东南亚媒体发稿的技巧…

如何基于YAML设计接口自动化测试框架?看完秒会!

在设计自动化测试框架的时候&#xff0c;我们会经常将测试数据保存在外部的文件&#xff08;如Excel、YAML、CSV&#xff09;或者数据库中&#xff0c;实现脚本与数据解耦&#xff0c;方便后期维护。目前非常多的自动化测试框架采用通过Excel或者YAML文件直接编写测试用例&…

.NET Core WebAPI中使用Log4net 日志级别分类并记录到数据库

一、效果 记录日志为文档 记录日志到数据库 二、添加NuGet包 三、log4net.config代码配置 <?xml version"1.0" encoding"utf-8" ?> <log4net><!-- Debug日志 --><appender name"RollingFileDebug" type"log4net…

抓包分析 TCP 协议

TCP 协议是在传输层中&#xff0c;一种面向连接的、可靠的、基于字节流的传输层通信协议。 环境准备 对接口测试工具进行分类&#xff0c;可以如下几类&#xff1a; 网络嗅探工具&#xff1a;tcpdump&#xff0c;wireshark 代理工具&#xff1a;fiddler&#xff0c;charles&…

论文阅读-EMS: History-Driven Mutation for Coverage-based Fuzzing(2022)模糊测试

一、背景 本文研究了基于覆盖率的模糊测试中的历史驱动变异技术。之前的研究主要采用自适应变异策略或集成约束求解技术来探索触发独特路径和崩溃的测试用例&#xff0c;但它们缺乏对模糊测试历史的细粒度重用&#xff0c;即它们在不同的模糊测试试验之间很大程度上未能正确利用…

【PyQt】在PyQt5的界面上集成matplotlib绘制的图像

文章目录 0 前期教程1 概述2 matplotlib2.1 库导入2.2 图片的各个部分解释2.3 代码风格2.4 后端 3 集成matplotlib图像到pyqt界面中3.1 使用到的模块3.2 理解Qt Designer中的“控件提升”3.3 界面与逻辑分离的思路3.4 扩展 0 前期教程 【PyQt】PyQt5进阶——串口上位机及实时数…

Android稳定性相关知识

关于作者&#xff1a;CSDN内容合伙人、技术专家&#xff0c; 从零开始做日活千万级APP。 专注于分享各领域原创系列文章 &#xff0c;擅长java后端、移动开发、商业变现、人工智能等&#xff0c;希望大家多多支持。 目录 一、导读二、概览三、相关方法论3.1 crash3.2 性能3.3 高…

一,STM32cubeMX配置FreeRTOS工程

从这篇文章开始&#xff0c;大家就进入到了FreeRTOS的学习之路。 那么&#xff0c;从这里开启学习的第一课如何使用cubeMX配置FreeRTOS工程 文章目录 前言一、使用 cubeMX 配置 FreeRTOS二、CMSIS 接口总结 前言 一、使用 cubeMX 配置 FreeRTOS 选择 stm32 芯片。 选择外部晶振…

【Linux】简单的网络计算器的实现(自定义协议,序列化,反序列化)

文章目录 前言一、 服务端1.ServerCal.cc&#xff08;服务器主文件&#xff09;2.ServerCal.hpp3.Sock.hpp(套接字封装)4.TcpServer.hpp(服务器)5.Protocol&#xff08;自定义协议&#xff09; 二、用户端1.ClientCal 三、Log.hpp&#xff08;日志&#xff09;四、makefile 前言…

洛谷 P8627 [蓝桥杯 2015 省 A] 饮料换购

参考代码and代码解读 #include <bits/stdc.h> using namespace std; int main() { int n; scanf("%d", &n); int dr;//drdrink; dr n;//把drink赋值于n; while (n > 2) {//剩余的总瓶盖数要大于二,才能换得下一瓶饮料; dr n…

C语言系列-带有副作用的宏参数#和##命名约定宏替换的规则

&#x1f308;个人主页: 会编辑的果子君 &#x1f4ab;个人格言:“成为自己未来的主人~” 目录 带有副作用的宏参数 宏替换的规则 宏函数的对比 #和## #运算符 ##运算符 命名约定 #undef 带有副作用的宏参数 当宏参数在宏的定义中出现超过一次的时候&#xff0c;如果…

树莓派登录方式

目录 1.串口登录树莓派 1.1 USB-TTL连接树莓派串口 1.2 修改系统配置&#xff0c;启用串口登录树莓派 1.3 启动树莓派 2.网络方式登录树莓派 2.1 使树莓派接入网络 2.2 网络SSH 方式登录树莓派 2.2.1 打开ssh功能&#xff0c; 输入命令&#xff1a; 1.串口登录树莓派 1…

MOS管故障排查(G极电阻篇)

我们经常看到&#xff0c;在电源电路中&#xff0c;功率MOS管的G极经常会串联一个小电阻&#xff0c;几欧姆到几十欧姆不等&#xff0c;那么这个电阻用什么作用呢&#xff1f; 如上图开关电源&#xff0c;G串联电阻R13这个电阻的作用有2个作用&#xff1a;限制G极电流&#x…

2024最新软件测试八股文(答案+文档)

&#x1f345; 视频学习&#xff1a;文末有免费的配套视频可观看 &#x1f345; 关注公众号【互联网杂货铺】&#xff0c;回复 1 &#xff0c;免费获取软件测试全套资料&#xff0c;资料在手&#xff0c;涨薪更快 1、B/S架构和C/S架构区别 B/S 只需要有操作系统和浏览器就行&a…

SD-WAN稳定性如何?

随着网络技术的不断发展&#xff0c;软件定义广域网&#xff08;SDWAN&#xff09;作为一种新兴的网络架构&#xff0c;受到了越来越多企业的青睐。然而&#xff0c;对于许多人来说&#xff0c;关于SDWAN最关键的问题之一就是它的稳定性。本文将探讨SDWAN的稳定性表现&#xff…