动态SLAM:基于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):目标检测+语义分割(其实利用的是YOLOv8的实例分割)

针对方法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://xiahunao.cn/news/2803065.html

如若内容造成侵权/违法违规/事实不符,请联系瞎胡闹网进行投诉反馈,一经查实,立即删除!

相关文章

SpringCloud(15)之SpringCloud Gateway

一、Spring Cloud Gateway介绍 Spring Cloud Gateway 是Spring Cloud团队的一个全新项目&#xff0c;基于Spring 5.0、SpringBoot2.0、 Project Reactor 等技术开发的网关。旨在为微服务架构提供一种简单有效统一的API路由管理方式。 Spring Cloud Gateway 作为SpringCloud生态…

WebService学习,wsdl文件详解

目录 第一章、起因1.1&#xff09;学习原因1.2&#xff09;提问的过程&#xff08;逐步提出问题&#xff09;1、&#xff1f;wsdl链接的含义&#xff0c;有什么作用&#xff1f;2、什么是wsdl文档&#xff1f;3、如何阅读wsdl文件&#xff1f;4、wsdl文件有什么作用&#xff1f…

【校招】从容面对笔试面试

笔试面试经验分享 一、笔试二、面试1.自我介绍2. 技术面试 一、笔试 如果是面试研发岗的话一般都是有笔试&#xff0c;难度因公司而异&#xff0c;一般来说越大的公司笔试就越难。对于不同岗位考察的方向也不一样&#xff0c;比如如果岗位是偏通信类的话多一点的话可能就会考一…

【Vuforia+Unity】AR03-圆柱体物体识别(Cylinder Targets)

1.创建数据库模型 这个是让我们把生活中类似圆柱体和圆锥体的物体进行AR识别所选择的模型 Bottom Diameter:底部直径 Top Diameter:顶部直径 Side Length:圆柱侧面长度 请注意&#xff0c;您不必上传所有三个部分的图片&#xff0c;但您需要先为侧面曲面关联一个图像&#…

探索无限:Sora与AI视频模型的技术革命 - 开创未来视觉艺术的新篇章

✨✨ 欢迎大家来访Srlua的博文&#xff08;づ&#xffe3;3&#xffe3;&#xff09;づ╭❤&#xff5e;✨✨ &#x1f31f;&#x1f31f; 欢迎各位亲爱的读者&#xff0c;感谢你们抽出宝贵的时间来阅读我的文章。 我是Srlua&#xff0c;在这里我会分享我的知识和经验。&#x…

同一个包下 golang run时报undefined

问题描述 今天在运行一个项目&#xff0c;一个包下有两个文件&#xff0c;分别是main.go和route&#xff0c;main函数在main.go文件中&#xff0c;main引用了route.go中的两个函数&#xff0c;SetupRoutes和SetupAdminRoutes go build 编译后&#xff0c;直接运行&#xff0c…

算法——模拟

1. 什么是模拟算法&#xff1f; 官方一点来说 模拟算法&#xff08;Simulation Algorithm&#xff09;是一种通过模拟现实或抽象系统的运行过程来研究、分析或解决问题的方法。它通常涉及创建一个模型&#xff0c;模拟系统中的各种事件和过程&#xff0c;以便观察系统的行为&a…

pclpy 可视化点云(多窗口可视化、单窗口多点云可视化)

pclpy 可视化点云&#xff08;多窗口可视化、单窗口多点云可视化&#xff09; 一、算法原理二、代码三、结果1.多窗口可视化结果2.单窗口多点云可视化 四、相关数据五、问题与解决方案1.问题2.解决 一、算法原理 原理看一下代码写的很仔细的。。目前在同一个窗口最多建立2个窗…

PCIE转USB3.0方案(VL805,VL806)

VLI VL806 是一款单芯片 USB 3.0 主机控制器&#xff0c;可使配备 PCI Express 的平台能够具有 USB 超高速 &#xff08;5 Gbps&#xff09;、高速 &#xff08;480 Mbps&#xff09;、全速 &#xff08;12 Mbps&#xff09; 和低速 &#xff08;1.5 Mbps&#xff09; 设备。根…

【力扣hot100】刷题笔记Day10

前言 一鼓作气把链表给刷完&#xff01;&#xff01;中等题困难题冲冲冲啊啊啊&#xff01; 25. K 个一组翻转链表 - 力扣&#xff08;LeetCode&#xff09; 模拟 class Solution:def reverseKGroup(self, head: Optional[ListNode], k: int) -> Optional[ListNode]:# 翻转…

使用 JMeter 生成测试数据对 MySQL 进行压力测试

博主历时三年精心创作的《大数据平台架构与原型实现&#xff1a;数据中台建设实战》一书现已由知名IT图书品牌电子工业出版社博文视点出版发行&#xff0c;点击《重磅推荐&#xff1a;建大数据平台太难了&#xff01;给我发个工程原型吧&#xff01;》了解图书详情&#xff0c;…

小程序-上拉触底

1.概念 2.使用与监听 3.配置距离

GEE数据集——30 米全球年度烧毁面积地图 (GABAM)(更新)

30 米全球年度烧毁面积地图 (GABAM) 迄今为止&#xff0c;全球烧毁面积&#xff08;BA&#xff09;产品只有较高的空间分辨率&#xff0c;因为目前大多数全球烧毁面积产品都是在主动火灾探测或密集时间序列变化分析的帮助下生成的&#xff0c;这需要非常高的时间分辨率。不过&a…

备战蓝桥杯---基础算法刷题1

最近在忙学校官网上的题&#xff0c;就借此记录分享一下有价值的题&#xff1a; 1.注意枚举角度 如果我们就对于不同的k常规的枚举&#xff0c;复杂度直接炸了。 于是我们考虑换一个角度&#xff0c;我们不妨从1开始枚举因子&#xff0c;我们记录下他的倍数的个数sum个&#…

ES6 | (一)ES6 新特性(上) | 尚硅谷Web前端ES6教程

文章目录 &#x1f4da;ES6新特性&#x1f4da;let关键字&#x1f4da;const关键字&#x1f4da;变量的解构赋值&#x1f4da;模板字符串&#x1f4da;简化对象写法&#x1f4da;箭头函数&#x1f4da;函数参数默认值设定&#x1f4da;rest参数&#x1f4da;spread扩展运算符&a…

【行业科普】5个应用趋势说明为什么“云-边协同”越来越重要!

在上一篇科普中分析了云计算和边缘计算哪个更强&#xff1f;&#xff08;【干货分享】云计算和边缘计算哪个强&#xff1f;谁更具优势&#xff1f;一次说清&#xff01;&#xff09; 我们都知道云计算和边缘计算的关系&#xff1a;边缘计算是对云计算的一种补充和优化&#xf…

每日五道java面试题之spring篇(三)

目录&#xff1a; 第一题 ApplicationContext和BeanFactory有什么区别&#xff1f;第二题 Spring中的事务是如何实现的&#xff1f;第三题 Spring中什么时候Transactional会失效&#xff1f;第四题 Spring容器启动流程是怎样的&#xff1f;第五题 Spring Boot、Spring MVC 和 S…

企微hook框架

https://wwm.lanzoum.com/ipUTp1ot1twh 密码:hvev 免费的企微框架 支持文本消息&#xff0c;图片消息&#xff0c;视频消息&#xff0c;文件消息。 其他可自行下载测试。 有兴趣可以进群交流。720192224 BOOL WxWorkSendData(string data) { WX_GETOBJDATA ob…

网络电视盒子哪个品牌好?达人强推口碑电视盒子推荐

电视盒子使用时容易卡顿、死机&#xff0c;广告植入过多&#xff0c;系统操作复杂&#xff0c;散热差&#xff0c;这是很多电视盒子都存在的问题&#xff0c;网络电视盒子哪个品牌好是大家都在讨论的话题&#xff0c;我这次要分享的是用户评价最好的五款电视盒子推荐给不懂如何…

Gitea提交代码自动触发Jenkins构建版本

提交代码自动触发Jenkins构建版本 1. 下载Generic Webhook Trigger 2. 配置Generic Webhook Trigger http://JENKINS_URL/generic-webhook-trigger/invoke?tokenruoyi-ui-8978456465 http://192.168.0.136:8090 为jenkisn地址&#xff0c;/generic-webhook-trigger/invoke?…