基于ORB-SLAM2与YOLOv8剔除动态特征点(三种方法)

基于ORB-SLAM2与YOLOv8剔除动态特征点(三种方法)

写上篇文章时测试过程比较乱,写的时候有些地方有点失误,所以重新写了这篇
本文内容均在RGB-D环境下进行程序测试

本文涉及到的动态特征点剔除速度均是以https://cvg.cit.tum.de/data/datasets/rgbd-dataset/download#freiburg3_walking_xyz数据进行实验

方法1:segment坐标点集合逐一排查剔除

利用YOLOv8的segment获取动态对象(这里指人person)所在区域的坐标点集合segpoints,之后将提取的特征点的坐标逐一与segpoints中的所有坐标作判断,将出现在segpoints中的特征点的坐标改为(-1,-1),然后在畸变校正时会将坐标为(-1,-1)的异常坐标剔除。但是segpoints中的数据量太大,完成一次剔除任务花费的时间太长(基本在40~50ms,这个与动态区域的大小即segpoints中的点数是有关的)。另外,特征点坐标为浮点型,而segpoints中的坐标为整型,其实没必要非用 = 判断,可以判断特征点在获取的动态目标区域坐标的周围1(可以调整,我最终在程序中使用半径为2)个像素就可以了,这已经很接近=了。

下面是部分代码:

std::vector<cv::Point> segpoints;
for (auto& obj:objs_seg) {int idx = obj.label;if (idx == 0){cv::Mat locations;cv::findNonZero(obj.boxMask == 255, locations);for (int i = 0; i < locations.rows; ++i) {cv::Point segpoint = locations.at<cv::Point>(i);segpoint.x += obj.rect.x;segpoint.y += obj.rect.y;segpoints.push_back(segpoint);}}
}
// 动态特征点的判断
for (int k=0; k<mvKeys.size(); ++k){const cv::KeyPoint& kp = mvKeys[k];bool isDynamic = false;for (int kk = 0; kk < segpoints.size(); ++kk) {if (kp.pt.x > segpoints[kk].x-3 && kp.pt.x < segpoints[kk].x+3 && kp.pt.y > segpoints[kk].y-3 && kp.pt.y < segpoints[kk].y+3) {mvKeys[k] = cv::KeyPoint(-1,-1,-1);isDynamic = true;break;}}vbInDynamic_mvKeys.push_back(isDynamic);
}

方法2:利用目标检测框

利用YOLOv8进行目标检测,将检测到的目标分为两类:动态对象和静态对象。
这里仅将person设为动态对象。获取动态对象及静态对象的检测框后判断提取的特征点是否在动态对象检测框内以及是否在静态对象检测框内。

1.特征点在动态对象检测框内而不在静态对象检测框内,则满足剔除条件,将其剔除;
2.其余情况皆不满足剔除条件。

采用这种方法速度提升至0.02~0.03ms.

struct DyObject {cv::Rect_<float> rect;int              id = 0;
};std::vector<ORB_SLAM2::DyObject> detect_results;
for (auto& obj:objs_det)
{int class_id = 0;// id为0代表其为静态对象int class_label = obj.label;if (class_label == 0){// 如果是人person则将其id改为1即动态对象class_id = 1;}cv::Rect_<float> bbox;bbox = obj.rect;ORB_SLAM2::DyObject detect_result;detect_result.rect = bbox;detect_result.id = class_id;detect_results.push_back(detect_result);
}
// 判断特征点是否在动态检测框内
bool Frame::isDynamic(const int& i,std::vector<DyObject>& detect_results){const cv::KeyPoint& kp = mvKeys[i];float kp_u  = kp.pt.x;float kp_v = kp.pt.y;bool is_dynamic = false;for(auto& result:detect_results){int idx = result.id;if (idx == 1){double left = result.rect.x;double top = result.rect.y;double right = result.rect.x + result.rect.width;double bottom = result.rect.y + result.rect.height;if(kp_u>left-2 && kp_u<right+2 && kp_v>top-2 && kp_v<bottom-2){// 如果特征点在动态目标检测框内is_dynamic = true;}}}return is_dynamic;
}// 判断特征点是否在静态检测框内
bool Frame::isStatic(const int& i,std::vector<DyObject>& detect_results){const cv::KeyPoint& kp = mvKeys[i];float kp_u  = kp.pt.x;float kp_v = kp.pt.y;bool is_static = false;for(auto& result:detect_results){int idx = result.id;if (idx == 0){double left = result.rect.x;double top = result.rect.y;double right = result.rect.x + result.rect.width;double bottom = result.rect.y + result.rect.height;if(kp_u>left && kp_u<right && kp_v>top && kp_v<bottom){is_static = true;}}}return is_static;}

优化(方法3):目标检测框+实例分割

针对方法1关于速度即处理数据量太大的问题,其实可以将方法1与方法2结合运用,先利用方法2进行判断特征点是否在动态目标的检测框内(不过不需要判断是否在静态目标的检测框内了,方法2中如果在静态目标检测框内就保留该点而不会被剔除,这里舍弃此步骤也是宁缺毋滥的原则),如果判断结果为真的话,则利用方法1将特征点与实例分割的Mask坐标进行判断即可,这样就可以节省很多时间了。

// 动态目标特征点的判断
//先定义一种目标检测的结果结构
struct DyObject {cv::Rect_<float> rect;std::vector<cv::Point> pts;int              id = 0;
};for (auto& obj:objs_seg) {int idx = obj.label;std::vector<cv::Point> segpoints;cv::Mat locations;cv::findNonZero(obj.boxMask == 255, locations);for (int i = 0; i < locations.rows; ++i) {cv::Point segpoint = locations.at<cv::Point>(i);cv::Rect_<float> rect;segpoint.x += obj.rect.x;segpoint.y += obj.rect.y;segpoints.push_back(segpoint);}ORB_SLAM2::DyObject detect_result;detect_result.rect = obj.rect;detect_result.pts = segpoints;detect_result.id = idx;detect_results.push_back(detect_result);
}

速度控制在了25ms以内。

方案1可以被舍弃了,对于方法2与方法3,测试一下二者在精度上的差异,因为从上面的工作中可以看出方法2的速度很快,如果精度差异很小的话为了SLAM实时性还是采用方法2比较好。
TUM提供了SLAM轨迹精度评估工具:
evaluate_ate.py、evaluate_rpe.py、associate.py
具体内容:https://cvg.cit.tum.de/data/datasets/rgbd-dataset/tools
将上面三个代码下载后就可以对TUM数据集的结果轨迹进行精度评估了。

首先是方法2仅利用目标检测框的一个特征点剔除情况:紫色的点就是之后会被剔除的点。

然后是方法3的特征点剔除情况:

上面两张图片的对比可以看出方法2会将一些有用的特征点也标记为动态特征点,而方法3会更精确。关于图片中红色圆圈,是我做的纹理分析,目前还没完全做好所以就先不讲了。

我对ORB-SLAM2与我基于ORB-SLAM2andYOLOv8(方法2与方法3)在数据集rgbd_dataset_freiburg3_walking_xyz的结果轨迹进行了精度评估,结果如下:

精度评估
TUM-freiburg3_walking_xyzORB-SLAM2DWT-SLAM detDWT-SLAM seg
RPE0.5555830.0225210.018761
ATE0.4742760.0173880.014755

方法3利用目标检测框+实例分割的方法的精度是最优的。

下面再测测https://cvg.cit.tum.de/data/datasets/rgbd-dataset/download#freiburg3_walking_rpy

精度评估
TUM-freiburg3_walking_rpyORB-SLAM2DWT-SLAM detDWT-SLAM seg
RPE0.9686050.0358530.035431
ATE0.7880890.0299420.028222

https://cvg.cit.tum.de/data/datasets/rgbd-dataset/download#freiburg3_sitting_halfsphere

精度评估
TUM-freiburg3_walking_halfphereORB-SLAM2DWT-SLAM detDWT-SLAM seg
RPE0.3579840.0452500.029718
ATE0.2940750.0363010.023612

从以上从三个数据集获得的三组精度评估结果来看,方法3的精度最高,25ms的动态特征点处理速度也是可接受的(我的电脑算是比较旧了)。

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

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

相关文章

编写程序,实现shell功能——项目训练——day08

c c今天做了一个实战项目训练&#xff0c;编写一个程序&#xff0c;实现shell功能&#xff0c;我们称之为minishell。 主要是利用Linux中IO接口实现&#xff0c;实现的功能有&#xff1a; 1.ls ls -a ls -l cd cp mv pwd c…

软件License授权原理

软件License授权原理 你知道License是如何防止别人破解的吗&#xff1f;本文将介绍License的生成原理&#xff0c;理解了License的授权原理你不但可以防止别人破解你的License&#xff0c;你甚至可以研究别人的License找到它们的漏洞。喜欢本文的朋友建议收藏关注&#xff0c;…

【Linux】进程状态

进程状态 进程状态的简要介绍运行状态进程排队 阻塞状态挂起状态Linux中的进程状态 进程状态的简要介绍 进程状态指的是一个操作系统中正在运行的进程当前所处的状态。根据不同的操作系统&#xff0c;进程状态可能会有一些细微的差别&#xff0c;但最主要的是以下三种状态 运行…

Java——方法的使用

目录 一.方法的概念及使用 1 什么是方法(method) 2.方法定义 3 方法调用的执行过程 4 实参和形参的关系(重要) 5.没有返回值的方法 二.方法重载 1.为什么需要方法重载 2.方法重载概念 3.方法签名 三.递归 1.递归的概念 2.递归执行过程分析 3. 递归练习 一.方法的…

猫头虎分享已解决Bug || 容器编排问题:OrchestrationFailure, ContainerManagementError

博主猫头虎的技术世界 &#x1f31f; 欢迎来到猫头虎的博客 — 探索技术的无限可能&#xff01; 专栏链接&#xff1a; &#x1f517; 精选专栏&#xff1a; 《面试题大全》 — 面试准备的宝典&#xff01;《IDEA开发秘籍》 — 提升你的IDEA技能&#xff01;《100天精通鸿蒙》 …

【Python】【VS Code】VS Code中python.json和setting.json文件配置说明

目录 1. python.json配置 2. setting.json配置 3. 解决中文乱码 4. 实现效果 1. python.json配置 python.json 获取步骤&#xff1a;文件 -> 首选项 -> 配置用户代码片段 -> python 此为VS Code的头文件设置&#xff0c;复制以下内容到 python.json {"HEADER…

个人做抖店如何能够快速起店?掌握好技巧是关键!建议收藏!

大家好&#xff0c;我是电商小布。 相信我们每个朋友在店铺开通后&#xff0c;最关心的事情就是小店成功起店了。 那么个人做抖店想要快速起店&#xff0c;该怎么来进行操作呢&#xff1f; 接下来&#xff0c;小布重点给大家说三点&#xff1a; 首先来说一下小店的主体类型…

dell r740服务器黄灯闪烁维修现场解决

1&#xff1a;首先看一下这款DELL非常主力的PowerEdge R740服务器长啥样&#xff0c;不得不说就外观来说自从IBM抛弃System X系列服务器后&#xff0c;也就戴尔这个外观看的比较顺眼。 图一&#xff1a;是DELL R740前视图&#xff08;这款是8盘机型&#xff09; 图二&#xff…

QT 数据库的增加操作和画图 Win

第一步、先配置CMakeLists.txt 在CMakeLists.txt中添加 find_package(Qt6 REQUIRED COMPONENTS Sql) find_package(Qt6 REQUIRED COMPONENTS Charts)target_link_libraries(${PROJECT_NAME} PRIVATE Qt6::Sql) target_link_libraries(${PROJECT_NAME} PRIVATE Qt6::Charts)避…

springboot集成JWT实现token权限认证

vuespringboot登录与注册功能的实现 注&#xff1a;对于JWT的学习&#xff0c;首先要完成注册和登录的功能&#xff0c;本篇博客是基于上述博客的进阶学习&#xff0c;代码页也是在原有的基础上进行扩展 ①在pom.xml添加依赖 <!-- JWT --> <dependency><grou…

Linux篇:Shell命令以及运行原理 和 权限

一. Shell命令及原理 Linux操作系统狭义上是Linux内核&#xff0c;广义上是指Linux内核Linux外壳(Shell)和对应的配套程序 Linux外壳&#xff1a;Linux 外壳是用户与内核之间的接口&#xff0c;用户通过外壳与操作系统进行交互和操作。在 Linux 系统中&#xff0c;用户可以选…

pycharm 远程运行报错 Failed to prepare environment

什么也没动的情况下&#xff0c;远程连接后运行是没问题的&#xff0c;突然在运行时就运行不了了&#xff0c;解决方案 清理缓存&#xff1a; 有时候 PyCharm 的内部缓存可能出现问题&#xff0c;可以尝试清除缓存&#xff08;File > Invalidate Caches / Restart&#xff0…

mysql优化指南之原理篇

之前碰到一个线上问题&#xff0c;在接手一个同事的项目后&#xff0c;因为工期比较赶&#xff0c;我还没来得及了解业务背景和大致实现&#xff0c;只是了解了上线发布的顺序和验证方式就进行了上线&#xff0c;在上线进行金丝雀的时候系统还没发生什么异常&#xff0c;于是我…

MySQL数据库进阶第二篇(索引,SQL性能分析,使用规则)

文章目录 一、索引概述二、索引结构三、结构 - B-Tree四、结构 - BTree五、结构 - Hash六、索引分类七、索引语法1.案例代码 八、SQL性能分析1.查看SQl执行频率2.慢查询日志3.PROFILES详情4.EXPLAIN执行计划 九、 索引使用规则十、SQL 提示十一、覆盖索引十二、前缀索引十三、单…

滚动加载react-infinite-scroll-component

react-infinite-scroll-component 当请求数据量过大时&#xff0c;接口返回数据时间会很长&#xff0c;数据回显时间长&#xff0c;Dom 的渲染会有很大的性能压力。 antd的List组件中有提到一个滚动加载的组件库react-infinite-scroll-component 实现滚动加载 Antd&#xff1…

考研高数(高阶导数的计算)

1.归纳法 常见高阶导数 2.泰勒展开式 3.莱布尼兹公式 4.用导数定义证明导函数在某一点连续的例题

【kubernetes】二进制部署k8s集群之cni网络插件flannel和calico工作原理(中)

↑↑↑↑接上一篇继续部署↑↑↑↑ 目录 一、k8s集群的三种接口 二、k8s的三种网络模式 1、pod内容器之间的通信 2、同一个node节点中pod之间通信 3、不同的node节点的pod之间通信 Overlay Network VXLAN 三、flannel网络插件 1、flannel插件模式之UDP模式&#xff0…

2024/2/22

P8680 [蓝桥杯 2019 省 B] 特别数的和 题目描述 小明对数位中含有 2、0、1、9 的数字很感兴趣&#xff08;不包括前导 00&#xff09;&#xff0c;在 1 到 40 中这样的数包括 1、2、9、10 至 32、39 和 40&#xff0c;共28 个&#xff0c;他们的和是574。 请问&#xff0c;在…

【2024软件测试面试必会技能】

Unittest(5)&#xff1a;unittest_忽略用例 忽略用例 在执行测试脚本的时候&#xff0c;可能会有某几条用例本次不想执行&#xff0c;但又不想删也 不想注释&#xff0c;unittest通过忽略部分测试用例不执行的方式&#xff0c;分无条件忽略和有条 件忽略,通过装饰器实现所描述…