有效提取激光雷达点云平面点
有效地面点云的提取和平面点的识别是通过一系列步骤实现的。以下是主要步骤:
-
高度过滤:
- 首先,根据激光雷达传感器的安装高度,对当前帧扫描得到的点云进行高度过滤,以初步分割出地面点云。假设第 k k k 帧的点云为 { P 0 , P 1 , P 2 , ⋯ P n } k \left\{P_{0}, P_{1}, P_{2},\cdots P_{n}\right\}_{k} {P0,P1,P2,⋯Pn}k,传感器离地面的安装高度为 s _ H s\_H s_H,高度过滤阈值为 t h _ H t h\_H th_H,则地面点云可以通过以下公式初步提取:
{ P G 0 , P G 1 , … P G m } k for P G i . z ∈ [ s − H − t h − H , s − H + t h − H 2 ] \left\{P_{G 0}, P_{G 1},\ldots P_{G m}\right\}_k \text{ for } P_{G i}.z \in \left[s_{-} H - t h_{-} H, s_{-} H + \frac{t h_{-} H}{2}\right] {PG0,PG1,…PGm}k for PGi.z∈[s−H−th−H,s−H+2th−H] - 这一步通过设定高度范围来初步筛选出可能的地面点。
- 首先,根据激光雷达传感器的安装高度,对当前帧扫描得到的点云进行高度过滤,以初步分割出地面点云。假设第 k k k 帧的点云为 { P 0 , P 1 , P 2 , ⋯ P n } k \left\{P_{0}, P_{1}, P_{2},\cdots P_{n}\right\}_{k} {P0,P1,P2,⋯Pn}k,传感器离地面的安装高度为 s _ H s\_H s_H,高度过滤阈值为 t h _ H t h\_H th_H,则地面点云可以通过以下公式初步提取:
-
法向量过滤:
- 在初步提取的地面点云中,仍然可能存在一些非地面点。为了进一步精炼地面点云,使用局部法向量过滤。假设以查询点 P G i P_{G i} PGi 为中心,通过KD-Tree搜索得到局部点集 { P G i , P G i + 1 , ⋯ , P G n } \left\{P_{G i}, P_{G i+1},\cdots, P_{G n}\right\} {PGi,PGi+1,⋯,PGn}。
- 对局部点集进行主成分分析(PCA),计算协方差矩阵并求解最小特征值对应的特征向量,该特征向量即为局部平面的法向量。
- 计算局部平面法向量与先验地面法向量之间的夹角余弦值,保留夹角小于设定阈值的点集,从而实现法向量过滤。
-
RANSAC算法拟合平面系数:
- 在经过法向量过滤后,使用RANSAC算法对地面点云进行平面系数的拟合。RANSAC算法通过随机选择几个点计算平面方程 A x + B y + C z + D = 0 A x + B y + C z + D = 0 Ax+By+Cz+D=0,然后计算所有点到平面的距离,选择距离小于阈值的点作为内点,否则为外点。
- 通过多次迭代选择最佳拟合参数,从而有效地减少异常值对平面方程系数拟合的影响。
通过这些步骤,能够有效地提取和识别地面点云,并计算出准确的地面平面系数。
#include <iostream>
#include <fstream>
#include <string>
#include <sstream>
#include <iomanip>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/ModelCoefficients.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>#include <pcl/common/transforms.h>
#include <pcl/features/normal_3d.h>
#include <pcl/search/impl/search.hpp>
#include <pcl/filters/impl/plane_clipper3D.hpp>
#include <pcl/filters/extract_indices.h>
#include <pcl/sample_consensus/ransac.h>
#include <pcl/sample_consensus/sac_model_plane.h>typedef pcl::PointXYZ PointT;
double sensor_height = 0.2;
double normal_filter_thresh = 20.0;
double height_clip_range = 0.5;
double floor_normal_thresh = 10.0;
double tilt_deg = 0.0;
bool use_normal_filtering = true;/*** @brief plane_clip* @param src_cloud* @param plane* @param negative* @return*/pcl::PointCloud<PointT>::Ptr plane_clip(const pcl::PointCloud<PointT>::Ptr& src_cloud, const Eigen::Vector4f& plane, bool negative) {pcl::PlaneClipper3D<PointT> clipper(plane);pcl::PointIndices::Ptr indices(new pcl::PointIndices);clipper.clipPointCloud3D(*src_cloud, indices->indices);std::cout << " src_cloud's points num is "<< src_cloud->size() <<std::endl;pcl::PointCloud<PointT>::Ptr dst_cloud(new pcl::PointCloud<PointT>);pcl::ExtractIndices<PointT> extract;extract.setInputCloud(src_cloud);extract.setIndices(indices);extract.setNegative(negative);extract.filter(*dst_cloud);std::cout << " dst_cloud's points num is "<< dst_cloud->size() <<std::endl;return dst_cloud;}/*** @brief filter points with non-vertical normals* @param cloud input cloud* @return filtered cloud* 函数广泛应用于需要根据点云中的几何特征进行筛选的场景,例如在室外环境中区分水平地面与其他垂直结构,通过法线过滤可以提取具有特定性质的点*/pcl::PointCloud<PointT>::Ptr normal_filtering(const pcl::PointCloud<PointT>::Ptr& cloud) {// 创建一个法线估计对象,指定输入和输出的数据类型(PointT 为输入点类型,pcl::Normal 为输出法线类型)pcl::NormalEstimation<PointT, pcl::Normal> ne;// 设置输入点云,指定要计算法线的点云ne.setInputCloud(cloud);std::cout << " normal_filtering's cloud point number is " << cloud->size() <<std::endl;// 创建一个 kd-tree 用于邻域查找pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);// 设置搜索方法,即使用 kd-tree 来加速近邻搜索ne.setSearchMethod(tree);// 用于存储计算得到的法线pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);// 设置 k-邻域搜索的邻居数目,使用10个邻居来估计法线ne.setKSearch(10);// 设置视点位置,用于确定法线的方向(这里假设传感器高度为 sensor_height)ne.setViewPoint(0.0f, 0.0f, sensor_height);// 计算法线,以以上参数进行估计并存储结果在 normals 中ne.compute(*normals);// 创建一个新的点云,用于存储过滤后的点pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>);// 预先分配足够的内存以容纳原点云大小(提高效率)filtered->reserve(cloud->size());// 遍历输入点云中的所有点for(int i = 0; i < cloud->size(); i++) {// 获取第 i 个点的法向量并归一化,然后计算它与全局 Z 轴的点积(夹角的余弦值)float dot = normals->at(i).getNormalVector3fMap().normalized().dot(Eigen::Vector3f::UnitZ());// 若点积的绝对值大于给定的余弦阈值,则保留该点(意味着与Z轴夹角较小)if(std::abs(dot) > std::cos(normal_filter_thresh * M_PI / 180.0)) {filtered->push_back(cloud->at(i)); // 将满足条件的点加入新的点云中}}// 设置过滤后点云的属性filtered->width = filtered->size(); // 宽度为点的数量filtered->height = 1; // 高度为1,这通常意味着这是一个平面而非三维数组filtered->is_dense = false; // 设置点云为非稠密,意味着可能存在无效/NaN点std::cout << "run normal_filtering() end" <<std::endl;// 返回过滤后的点云return filtered;}/*** @brief detect the floor plane from a point cloud* @param cloud input cloud* @return detected floor plane coefficients*/
Eigen::Vector4f detect(const std::string& file_path) {pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);if (pcl::io::loadPCDFile<PointT>(file_path, *cloud) == -1 || cloud->empty()) {PCL_ERROR("Couldn't read file %s\n", file_path.c_str());exit(-1);}//打印点云的数量std::cout << "Cloud size: " << cloud->size() << std::endl;// compensate the tilt rotationEigen::Matrix4f tilt_matrix = Eigen::Matrix4f::Identity();tilt_matrix.topLeftCorner(3, 3) = Eigen::AngleAxisf(tilt_deg * M_PI / 180.0f, Eigen::Vector3f::UnitY()).toRotationMatrix();// filtering before RANSAC (height and normal filtering)pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>);pcl::transformPointCloud(*cloud, *filtered, tilt_matrix);filtered = plane_clip(filtered, Eigen::Vector4f(0.0f, 0.0f, 1.0f, sensor_height + height_clip_range), false);filtered = plane_clip(filtered, Eigen::Vector4f(0.0f, 0.0f, 1.0f, sensor_height - height_clip_range), true);if(use_normal_filtering) {//函数广泛应用于需要根据点云中的几何特征进行筛选的场景,例如在室外环境中区分水平地面与其他垂直结构,//通过法线过滤可以提取具有特定性质的点filtered = normal_filtering(filtered);}//打印std::cout << "Filtered size: " << filtered->size() << std::endl;pcl::transformPointCloud(*filtered, *filtered, static_cast<Eigen::Matrix4f>(tilt_matrix.inverse()));// too few points for RANSACif(filtered->size() < 1024) {return Eigen::Vector4f(0,0,0,0);}// RANSAC//建立平面模型,然后使用 RANSAC 算法从点云中估计平面模型的参数pcl::SampleConsensusModelPlane<PointT>::Ptr model_p(new pcl::SampleConsensusModelPlane<PointT>(filtered));pcl::RandomSampleConsensus<PointT> ransac(model_p);ransac.setDistanceThreshold(0.05);//设置距离阈值,即点到平面的距离小于该值的点被认为是内点ransac.computeModel();//计算平面模型参数//提取内点pcl::PointIndices::Ptr inliers(new pcl::PointIndices);ransac.getInliers(inliers->indices);// too few inliers 检查内点数量是否足够if(inliers->indices.size() < 1024) {return Eigen::Vector4f(0,0,0,0);}//打印内点数量std::cout << "Inliers size: " << inliers->indices.size() << std::endl;// verticality check of the detected floor's normal// 检测平面法线是否垂直于全局 Z 轴Eigen::Vector4f reference = tilt_matrix.inverse() * Eigen::Vector4f::UnitZ();//估计模型系数Eigen::VectorXf coeffs;ransac.getModelCoefficients(coeffs);//检查法线coeffs.head<3>()与参考向量的夹角,通过计算点积来验证法线是否垂直于全局 Z 轴double dot = coeffs.head<3>().dot(reference.head<3>());if(std::abs(dot) < std::cos(floor_normal_thresh * M_PI / 180.0)) {// the normal is not verticalreturn Eigen::Vector4f(0,0,0,0);}// make the normal upward//调整法线方向,使其指向上方if(coeffs.head<3>().dot(Eigen::Vector3f::UnitZ()) < 0.0f) {coeffs *= -1.0f;}//打印// std::cout << "Plane coefficients: " << coeffs.transpose() << std::endl;//保存平面点云到文件pcl::PointCloud<PointT>::Ptr plane_cloud(new pcl::PointCloud<PointT>);pcl::copyPointCloud(*filtered, inliers->indices, *plane_cloud);pcl::io::savePCDFileBinary("plane.pcd", *plane_cloud);return Eigen::Vector4f(coeffs);}int main() {std::string pcdDirectory = "../cloud.pcd";Eigen::Vector4f planeCoefficients = detect(pcdDirectory);//打印平面参数std::cout << "Plane coefficients: " << planeCoefficients.transpose() << std::endl;return 0;
}
cmake_minimum_required(VERSION 3.10)
project(PlaneOptimization)# 设置C++标准
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)# 查找PCL库
find_package(PCL 1.8 REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})# 查找GTSAM库
# find_package(GTSAM REQUIRED)
# include_directories(${GTSAM_INCLUDE_DIR})# 添加可执行目标
add_executable(PlaneOptimization ground_extraction.cpp)# 链接库
# target_link_libraries(PlaneOptimization ${PCL_LIBRARIES} gtsam)
相关文章:
有效提取激光雷达点云平面点
有效地面点云的提取和平面点的识别是通过一系列步骤实现的。以下是主要步骤: 高度过滤: 首先,根据激光雷达传感器的安装高度,对当前帧扫描得到的点云进行高度过滤,以初步分割出地面点云。假设第 k k k 帧的点云为 { …...
Vulnhub DC-8靶机攻击实战(一)
导语 Vulnhub DC-8靶机教程来了,好久没有更新打靶的教程了,这次我们在来更新一期关于Vulnhub DC-8的打靶训练,如下所示。 安装并且启动靶机 安装并且启动靶机,如下所示。 开始信息采集 进入到Kali中,通过如下的命令来查找到靶机的IP地址。 arp-scan -l根据上面的结…...
基于PHP的校园新闻发布管理
摘要 近年来,随着互联网技术的迅速发展,人们获取新闻的渠道也变得越来越多样化,已经不再拘束于传统的报纸、期刊、杂志等纸质化的方式,而是通过网络满足了人们获得第一手新闻的愿望,这样更加有助于实现新闻的规范化管…...
LabVIEW时域近场天线测试
随着通信技术的飞速发展,特别是在5G及未来通信技术中,天线性能的测试需求日益增加。对于短脉冲天线和宽带天线的时域特性测试,传统的频域测试方法已无法满足其需求。时域测试方法在这些应用中具有明显优势,可以提供更快速和精准的…...
组播PIM-原理介绍+报文分析+配置示例
个人认为,理解报文就理解了协议。通过报文中的字段可以理解协议在交互过程中相关传递的信息,更加便于理解协议。 因此本文将在PIMv2协议报文的基础上进行介绍,以详细介绍组播协议PIM。 这里需要说明的是,以下内容都针对的是ASM&a…...
规避路由冲突
路由冲突是指在网络中存在两个或多个路由器在进行路由选择时出现矛盾,导致网络数据包无法正确传输,影响网络的正常运行。为了规避路由冲突,可以采取以下措施: 一、合理规划IP地址 分配唯一IP:确保每个设备在网络中都有…...
Asp .Net Core 实现微服务:集成 Ocelot+Nacos+Swagger+Cors实现网关、服务注册、服务发现
什么是 Ocelot ? Ocelot是一个开源的ASP.NET Core微服务网关,它提供了API网关所需的所有功能,如路由、认证、限流、监控等。 Ocelot是一个简单、灵活且功能强大的API网关,它可以与现有的服务集成,并帮助您保护、监控和扩展您的…...
【C++】非类型模板参数 || 类模板的特化
目录 1. 非类型模板参数 2. 模板特化 3. 类模板特化 3.1.全特化 3.2 部分特化 3.3 参数更进一步限制 3.4 类模板应用 1. 非类型模板参数 模板参数分类类型形参与非类型形参。类型形参即:出现在模板参数列表中,跟在class或者typename之类的参数类型…...
Python基本概念与实践
Python语言,总给我一种“嗯?还能这么玩儿?”的感觉 Python像一个二三十岁的年轻人,自由、年轻、又灵活 欢迎一起进入Python的世界~ 本人工作中经常使用Python,针对一些常用的语法概念进行持续记录。 一、类与常见数据结…...
SQL Prompt 插件
SQL Prompt 插件 注:SQL Prompt插件提供智能代码补全、SQL格式化、代码自动提示和快捷输入等功能,非常方便,可以自行去尝试体会。 1、问题 SSMS(SQL Server Management Studio)是SQL Server自带的管理工具,…...
1.6 从 GPT-1 到 GPT-3.5:一路的风云变幻
从 GPT-1 到 GPT-3.5:一路的风云变幻 人工智能的进步一直是科技领域的一个重要话题,而在自然语言处理(NLP)领域,GPT(Generative Pre-trained Transformer)系列模型的发布,标志着一个又一个技术突破。从2018年发布的 GPT-1 到2022年推出的 GPT-3.5,OpenAI 的每一次更新…...
centos 7 Mysql服务
将此服务器配置为 MySQL 服务器,创建数据库为 hubeidatabase,将登录的root密码设置为Qwer1234。在库中创建表为 mytable,在表中创建 2 个用户,分别为(xiaoming,2010-4-1,女,male&…...
参数校验 Spring Validation框架
后端参数校验 解决:校验前端传入的参数是否符合预期 1、引入依赖 使用Spring Validation框架 <!-- validation参数校验框架--><dependency><groupId>org.springframework.boot</groupId><artifactId>spring-boot-starter-validatio…...
sunrays-framework 微调
文章目录 1.common-log4j2-starter 动态获取并打印日志存储的根目录的绝对路径以及应用的访问地址1.目录2.log4j2.xml 配置LOG_HOME3.LogHomePrinter.java 配置监听器4.spring.factories 注册监听器5.测试1.common-log4j2-starter-demo 配置2.启动测试 2.common-minio-starter …...
Java正则转带中划线或下划线属性名为驼峰命名
Java正则转带中划线或下划线属性名为驼峰命名。 利用Java正则分组匹配的方式,将属性名中 -(_) 后接的字母,匹配上了去掉当前 -(_),将后接的字母转为大写,再追加拼接起来,就完成了驼峰命名。 String lineToHump(Strin…...
WebSocket实现分布式的不同方案对比
引言 随着实时通信需求的日益增长,WebSocket作为一种基于TCP的全双工通信协议,在实时聊天、在线游戏、数据推送等场景中得到了广泛应用。然而,在分布式环境下,如何实现WebSocket的连接管理和消息推送成为了一个挑战。本文将对比几…...
Linux下的dev,sys和proc(TODO)
(TODO) 还有一个sysfs 在 Linux 系统中,/dev、/sys 和 /proc 是三个特殊的虚拟文件系统目录,它们各自有特定的用途,主要用于与设备和内核交互。以下是它们的详细区别和功能说明: 1. /dev(Devi…...
JavaScript系列(32)-- WebAssembly集成详解
JavaScript WebAssembly集成详解 🚀 今天,让我们深入了解JavaScript与WebAssembly的集成,这是一项能够显著提升Web应用性能的关键技术。 WebAssembly基础概念 🌟 💡 小知识:WebAssembly(简称W…...
通过外部链接启动 Flutter App(详细介绍及示例)
通过外部链接启动 Flutter App(firebase_dynamic_links 和 app_links) 详细介绍 通过外部链接启动flutter App 的使用及示例 在我们的APP中,经常有点击链接启动并进入APP的需求(如果未安装跳转到应用商店)。Android通…...
计算机视觉模型的未来:视觉语言模型
一、视觉语言模型 人工智能已经从识别数据中的简单模式跃升为理解复杂的多模态数据。该领域的发展之一是视觉语言模型 (VLM) 的兴起。这类模型将视觉和文本之间联系起来,改变了我们理解视觉数据并与之交互的方式。随着 VLM 的不断发展,它们正在为计算机视觉设定一个新的水平…...
CTK插件框架学习-源码下载编译(01)
1、编译环境 window11、vs17、Qt5.14.0、cmake3.27.4 2、下载链接 cmake:Index of /files/v3.20 qt:Index of / vs22以前的版本需要登录下载:Visual Studio 较旧的下载 - 2019、2017、2015 和以前的版本 vs22下载:下载 Visu…...
Python 字符串分割时 spilt 和 re 效率对比
假设 有一些文件名是 数字_文档名 的格式,如何用python将数字提取出来? 可以使用 Python 的正则表达式模块 re 提取文件名中的数字部分。以下是实现代码: 示例代码: import re# 示例文件名列表 file_names ["1_file1.txt…...
AUTOSAR通信篇 - PDU和收发数据
点击订阅专栏不迷路 文章目录 一、概述二、OSI模型与AUTOSAR层级关系三、I-PDU、N-PDU、L-PDU及其关系3.1. L-PDU3.2. N-PDU3.3. I-PDU 四、数据流4.1. 普通数据流4.2. 诊断数据流4.3. 动态PDU数据流4.4. 安全通信数据流4.5. XCP数据流 返回总目录 一、概述 在学习Autosar通信…...
wps数据分析000002
目录 一、快速定位技巧 二、快速选中技巧 全选 选中部分区域 选中部分区域(升级版) 三、快速移动技巧 四、快速录入技巧 五、总结 一、快速定位技巧 ctrl→(上下左右)快速定位光标对准单元格的上下部分双击名称单元格中…...
【C++基础】enum,union,uint8_t,static
enum 所以有时候使用 Enum 的目的,不是为了自定义一种数据类型,而是为了声明一组常量。 from: https://github.com/wangdoc/clang-tutorial/blob/main/docs/enum.md union C 语言提供了 Union 结构,用来自定义可以灵活变更的数据结构。它内部…...
node.js的进程保活
nodejs的进程保活其实用PM2应该更好用些,不过由于原理其实并不复杂,我们可以自己手写一个服务来干这个工作。 假设我们有一个服务,可以这样来定义下它的相关信息: const svcs[ {"sid":"apl","name"…...
css中的阴影详解
在 CSS 中,阴影效果通常使用 box-shadow 和 text-shadow 来实现,它们分别适用于元素的框和文本。阴影是提升页面设计感和层次感的重要工具。下面,我会详细讲解这两个属性,并结合代码示例说明。 目录 1. box-shadow示例 2. text-sh…...
AI刷题-饭馆菜品选择问题、构造回文字符串问题
目录 一、饭馆菜品选择问题 问题描述 测试样例 解题思路: 问题理解 数据结构选择 算法步骤 最终代码: 运行结果: 二、构造回文字符串问题 问题描述 测试样例 解题思路: 解题思路 具体步骤 最终代码:…...
时间序列分析ARIMA(AutoRegressive Integrated Moving Average,自回归积分滑动平均)模型:中英双语
ARIMA模型:时间序列分析中的强大工具 在时间序列分析中,ARIMA(AutoRegressive Integrated Moving Average,自回归积分滑动平均)模型是一种广泛使用的模型。它通过结合自回归、差分和滑动平均三种方法来对时间序列进行…...
青少年编程与数学 02-007 PostgreSQL数据库应用 02课题、PostgreSQL数据库安装
青少年编程与数学 02-007 PostgreSQL数据库应用 02课题、PostgreSQL数据库安装 一、安装Windows系统安装PostgreSQL 17Linux系统安装PostgreSQL 17 二、配置Windows系统Linux系统 三、启动(一)Windows系统使用服务管理器(services.msc&#x…...
群发邮件适合外贸行业吗
一、群发邮件契合外贸行业的市场拓展需求 外贸业务的本质在于跨越地域限制,与全球各地的潜在客户建立联系。群发邮件能够突破时空限制,瞬间将产品或服务信息传递到世界各地。通过精准的市场调研与客户数据整理,企业可以针对不同国家和地区的…...
面试之《new关键字》
一问:new关键字做了什么操作,手写一个new方法,实现new关键字的作用 二问: // 第一题 / function Test(){this.name 1;return {name: 2} } const a new Test(); console.log(a.name) // 打印什么/// 第二题 / function Test2()…...
《机器学习》——SVD(奇异分解)降维
文章目录 SVD基本定义SVD降维的步骤SVD降维使用场景SVD 降维的优缺点SVD降维实例导入所需库定义SVD降维函数导入图像处理图像处理图像打印降维结果并显示处理后两个图像的对比图 SVD基本定义 简单来说就是,通过SVD(奇异值分解)对矩阵数据进行…...
【MySQL实战】mysql_exporter+Prometheus+Grafana
要在Prometheus和Grafana中监控MySQL数据库,如下图: 可以使用mysql_exporter。 以下是一些步骤来设置和配置这个监控环境: 1. 安装和配置Prometheus: - 下载和安装Prometheus。 - 在prometheus.yml中配置MySQL通过添加以下内…...
业务架构、数据架构、应用架构和技术架构
TOGAF(The Open Group Architecture Framework)是一个广泛应用的企业架构框架,旨在帮助组织高效地进行架构设计和管理。 TOGAF 的核心就是由我们熟知的四大架构领域组成:业务架构、数据架构、应用架构和技术架构。 企业数字化架构设计中的最常见要素是4A 架构。 4…...
mysql-5.7.18保姆级详细安装教程
本文主要讲解如何安装mysql-5.7.18数据库: 将绿色版安装包mysql-5.7.18-winx64解压后目录中内容如下图,该例是安装在D盘根目录。 在mysql安装目录中新建my.ini文件,文件内容及各配置项内容如下图,需要先将配置项【skip-grant-tab…...
Linux测试处理fps为30、1920*1080、一分钟的视频性能
前置条件 模拟fps为30、1920*1080、一分钟的视频 项目CMakeLists.txt cmake_minimum_required(VERSION 3.30) project(testOpenGl)set(CMAKE_CXX_STANDARD 11)add_executable(testOpenGl main.cpptestOpenCl.cpptestOpenCl.hTestCpp.cppTestCpp.hTestCppThread.cppTestCppTh…...
kubeneters-循序渐进Ingress
文章目录 overviewIngress 是什么?为什么使用 Ingress?我们会在这里做些什么?HTTP 服务器(Nginx)还能做什么?Kubernetes 中的简单示例:A) 使用 Service ClusterIPB) 手动配置 Nginx 服务作为代理…...
Shell控监Kafka积压
1、获取Kafka消息堆积情况 vi check-kafka-lag.sh #!/bin/bashTOPIC"total_random" GROUP_ID"etl-dw" BOOTSTRAP_SERVER"node-01:9092,node-02:9092,node-03:9092"# 检查第一个参数是否为数字 if ! [[ $1 ~ ^[0-9]$ ]]; thenecho &…...
USB3020任意波形发生器4路16位同步模拟量输出卡1MS/s频率 阿尔泰科技
信息社会的发展,在很大程度上取决于信息与信号处理技术的先进性。数字信号处理技术的出现改变了信息 与信号处理技术的整个面貌,而数据采集作为数字信号处理的必不可少的前期工作在整个数字系统中起到关键 性、乃至决定性的作用,其应用已经深…...
MongoDB 学习指南与资料分享
MongoDB学习资料 MongoDB学习资料 MongoDB学习资料 在数据爆炸的当下,MongoDB 作为非关系型数据库的佼佼者,以其独特优势在各领域发光发热。无论是海量数据的存储,还是复杂数据结构的处理,MongoDB 都能轻松应对。接下来…...
Web端实时播放RTSP视频流(监控)
一、安装ffmpeg: 1、官网下载FFmpeg: Download FFmpeg 2、点击Windows图标,选第一个:Windows builds from gyan.dev 3、跳转到下载页面: 4、下载后放到合适的位置,不用安装,解压即可: 5、配置path 复制解压后的\bin路径,配置环境变量如图: <...
23- TIME-LLM: TIME SERIES FORECASTING BY REPRO- GRAMMING LARGE LANGUAGE MODELS
解决问题 用LLM来解决时序预测问题,并且能够将时序数据映射(reprogramming)为NLP token,并且保持backbone的大模型是不变的。解决了时序序列数据用于大模型训练数据稀疏性的问题。 方法 Input Embedding 输入: X …...
【Go】Go数据类型详解—数组与切片
1. 前言 今天需要学习的是Go语言当中的数组与切片数据类型。很多编程语言当中都有数组这样的数据类型,Go当中的切片类型本质上也是对 数组的引用。但是在了解如何定义使用数组与切片之前,我们需要思考为什么要引入数组这样的数据结构。 1.1 为什么需要…...
微服务中引入消息队列的利弊
微服务中引入消息队列的利弊 1、微服务架构中引入消息队列(Message Queue)的主要优势: 1.1 解耦(Decoupling) 服务之间不需要直接调用,通过消息队列实现松耦合 生产者和消费者可以独立扩展和维护 降低系统间的依赖性 1.2 异步处理(Asynchronous Proc…...
如何使用策略模式并让spring管理
1、策略模式公共接口类 BankFileStrategy public interface BankFileStrategy {String getBankFile(String bankType) throws Exception; } 2、策略模式业务实现类 Slf4j Component public class ConcreteStrategy implements BankFileStrategy {Overridepublic String ge…...
骑砍2霸主MOD开发(11)-可编程渲染管线Shader编程
一.固定渲染管线&可编程渲染管线 固定渲染管线:GPU常规渲染算法,将3D模型经过四大变换计算得到2D屏幕图像 可编程渲染管线:定制化GPU渲染算法,需要提交Shader至GPU中,GPU根据定制化算法得到2D屏幕图像 二.CoreShader&TerrainShader CoreShader:游戏中使用的静态shader…...
【PowerQuery专栏】PowerQuery 函数之CSV文件处理函数
CSV.Document 函数是进行CSV文件解析功能的函数,函数目前包含4个参数: 参数1为文件的数据源,数据类型为二进制类型,值为需要读取的文本数据参数2为列名称,数据类型为字符串类型,值为分割后的列名称参数3为分隔符,数据类型为任意类型,值为分割数据的分隔符参数4为文件编…...
【FAQ】HarmonyOS SDK 闭源开放能力 —Map Kit(4)
1.问题描述: 添加了很多的marker点,每个marker点都设置了customInfoWindow,但是每次只能显示一个customInfoWindow吗? 解决方案: Marker的InfoWindow每次只能显示一个。 2.问题描述: 在地图选型中&…...
通过ffmpeg将FLV文件转换为MP4
使用 ffmpeg 将 FLV 文件转换为 MP4 文件是一个常见的操作。ffmpeg 是一个强大的多媒体处理工具,支持多种格式的转换、剪辑、合并等操作。以下是详细的步骤和命令示例,帮助你完成这一任务。 安装 FFmpeg 如果你还没有安装 ffmpeg,可以根据你…...