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

本文介绍了三种在RGB-D环境中剔除ORB-SLAM2中动态特征点的方法,包括基于YOLOv8的segment和目标检测,以及结合目标检测与实例分割的优化策略。实验结果显示,结合目标检测与实例分割的方法在速度和精度上表现最优。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

基于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坐标进行判断即可,这样就可以节省很多时间了。

速度控制在了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的动态特征点处理速度也是可接受的(我的电脑算是比较旧了)。

### YOLOSLAM3集成及其在计算机视觉项目中的应用 YOLO (You Only Look Once) 是一种高效的实时目标检测算法,而 SLAM (Simultaneous Localization And Mapping, 同步定位地图构建) 技术则用于机器人或设备在未知环境中移动的同时创建环境的地图并确定自己的位置。当提到 SLAM3 时,通常是指第三代或是更先进的 SLAM技术实现。 #### 集成背景 为了增强机器人的感知能力,在实际应用场景中常常会将这两种技术结合起来使用。通过融合来自摄像头的数据和其他传感器的信息,可以实现在复杂环境下更加精准的目标识别和导航功能[^1]。 #### 实现方式 对于YOLOSLAM 的集成主要体现在以下几个方面: - **数据共享**:利用同一套相机输入源供两者处理,减少硬件成本; - **特征关联**:基于YOLO 提取到的对象边界框作为先验信息辅助 SLAM 进行地标匹配; - **语义分割**:不仅限于矩形区域内的物体标记,还可以进一步做像素级别的分类来帮助理解场景结构; - **动态障碍物规避**:借助 YOLO 对运动物体的快速响应特性及时调整路径规划策略以避开潜在危险。 ```python import cv2 from yolov5 import detect_objects # 假设这是调用YOLOv5的一个接口函数 from slam_system import update_map_and_localize # 调用SLAM系统的更新函数 def integrate_yolo_slam(image_frame): detected_items = detect_objects(image_frame) for item in detected_items: bounding_box = item['bbox'] label = item['label'] # 将YOLO的结果传递给SLAM模块 update_map_and_localize(bounding_box=bounding_box, object_label=label) cap = cv2.VideoCapture(0) while True: ret, frame = cap.read() if not ret: break integrate_yolo_slam(frame) cv2.imshow('frame', frame) if cv2.waitKey(1) & 0xFF == ord('q'): break cv2.destroyAllWindows() ``` 上述代码展示了如何在一个简单的循环里读取视频流,并将其送入 `integrate_yolo_slam` 函数中进行处理。该函数内部实现了YOLO对象检测以及向SLAM系统提供这些检测结果的过程。
评论 30
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

笨小古

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值