无人机自主探索FUEL:代码阅读1--边界簇检测更新与视点生成

news2024/11/26 12:52:20
~/src/catkin_fuel_refactored/fuel_refactored/fuel_planner/bag

bag中包含三个.sh文件,为rosbag指令,给出了录包指令以及有用话题信息

FIS

1、增量边界检测与聚类

  • 路径:~/fuel_planner/active_perception/src/frontier_finder.cpp

主要函数:寻找并更新边界簇 void FrontierFinder::searchAndAddFrontiers()
使用SDF地图,找到该边界簇的轴对齐包围盒(AABB框) B i B_i Bi,并更新更新的框内的新边界;
增量边界聚类;
创建视点集 V P i VP_i VPi以覆盖簇 F i F_i Fi
进行视点检测与筛选,对视点降序排列;
找不到视点时将边界簇移至休眠列表;
重置边界索引;

    void FrontierFinder::searchAndAddFrontiers() {
        ros::Time t1 = ros::Time::now();
        //---------------   增量边界检测    ---------------------
        // Bounding box of updated region  更新区域的AABB框B_i
        Vector3d update_min, update_max;
        edt_env_->sdf_map_->getUpdatedBox(update_min, update_max, true);
        // ROS_WARN("update_min %lf %lf %lf: ", update_min[0], update_min[1], update_min[2]);
        // ROS_WARN("update_max %lf %lf %lf: ", update_max[0], update_max[1], update_max[2]);

        // Search new frontier within box slightly inflated from updated box
        //从更新的框中搜索稍微膨胀的框内的新边界 
        Vector3d search_min = update_min - Vector3d(1, 1, 0.5);
        Vector3d search_max = update_max + Vector3d(1, 1, 0.5);
        Vector3d box_min, box_max;                              //新的边界
        edt_env_->sdf_map_->getBox(box_min, box_max);
        for (int k = 0; k < 3; ++k) {
            search_min[k] = max(search_min[k], box_min[k]);
            search_max[k] = min(search_max[k], box_max[k]);
        }
        // ROS_WARN("search_min %lf %lf %lf: ", search_min[0], search_min[1], search_min[2]);
        // ROS_WARN("search_max %lf %lf %lf: ", search_max[0], search_max[1], search_max[2]);
        
        Eigen::Vector3i min_id, max_id;
        edt_env_->sdf_map_->posToIndex(search_min, min_id);
        edt_env_->sdf_map_->posToIndex(search_max, max_id);
        ROS_WARN("min_id %lf %lf %lf: ", min_id[0], min_id[1], min_id[2]);
        ROS_WARN("max_id %lf %lf %lf: ", max_id[0], max_id[1], max_id[2]);

        vector<Frontier> tmp_frontiers;                      //当前边界
        for (int x = min_id(0); x <= max_id(0); ++x)
            for (int y = min_id(1); y <= max_id(1); ++y)
                for (int z = min_id(2); z <= max_id(2); ++z) {
                    // Scanning the updated region to find seeds of frontiers
                    Eigen::Vector3i cur(x, y, z);
                    if (!is_in_frontier_[toAddress(cur)] && knownFree(cur) && isNeighborUnknown(cur)) {
                        // Expand from the seed cell to find a complete frontier cluster    //找到完整边界
                        Frontier frontier;
                        if (expandFrontier(cur, frontier)) {          //按距离聚类搜索,检查新的簇的可行性
                            tmp_frontiers.push_back(move(frontier));
                        }
                    }
                }

        //---------------   增量边界聚类   ---------------------
        splitLargeFrontiers(tmp_frontiers);         //递归分割边界簇

        ROS_WARN_THROTTLE(5.0, "Frontier t: %lf", (ros::Time::now() - t1).toSec());

        origin_frontiers_num_ = frontiers_.size();
        int new_num = 0;
        int new_dormant_num = 0;
        //-----------------------  视点生成  ---------------------------
        // Try to find viewpoints for each cluster and categorize them according to viewpoint number
        for (Frontier &tmp_ftr: tmp_frontiers) {
            // Search viewpoints around frontier
            //采样边界平均位置周围的视点,检查边界单元的覆盖率
            sampleViewpoints(tmp_ftr);                                       
            if (!tmp_ftr.viewpoints_.empty()) {
                ++new_num;
                sort(tmp_ftr.viewpoints_.begin(), tmp_ftr.viewpoints_.end(),     //降序排列
                     [](const Viewpoint &v1, const Viewpoint &v2) -> bool {
                         return v1.visible_num_ > v2.visible_num_;
                     });
                frontiers_.insert(frontiers_.end(), tmp_ftr);
            } else {
                // Find no viewpoint, move cluster to dormant list  找不到视点,将边界簇移至休眠列表
                dormant_frontiers_.push_back(tmp_ftr);
                ++new_dormant_num;
            }
        }
        // Reset indices of frontiers   重置边界索引
        int idx = 0;
        for (Frontier &ft: frontiers_) {
            ft.id_ = idx++;
        }
    }

- 按距离聚类搜索,检查新的簇的可行性 FrontierFinder::expandFrontier

    bool FrontierFinder::expandFrontier(const Eigen::Vector3i &first, Frontier &frontier) {
        // Data for clustering
        queue<Eigen::Vector3i> cell_queue;
        vector<Eigen::Vector3d> expanded;
        Vector3d pos;

        edt_env_->sdf_map_->indexToPos(first, pos);
        expanded.push_back(pos);
        cell_queue.push(first);
        is_in_frontier_[toAddress(first)] = true;

        // Search frontier cluster based on region growing (distance clustering)  按距离聚类搜索
        while (!cell_queue.empty()) {
            Vector3i cur_cell = cell_queue.front();
            cell_queue.pop();
            vector<Vector3i> neighbors = allNeighbors(cur_cell);
            for (const Vector3i &next_cell: neighbors) {
                // Qualified cell should be inside bounding box and frontier cell not clustered  
                //合格单元格应位于边界框内,且边界单元格不在簇内
                int next_cell_adr = toAddress(next_cell);
                if (is_in_frontier_[next_cell_adr] || !edt_env_->sdf_map_->isInBox(next_cell) ||
                    !(knownFree(next_cell) && isNeighborUnknown(next_cell)))
                    continue;

                edt_env_->sdf_map_->indexToPos(next_cell, pos);
                if (pos[2] < 0.4) continue;  // Remove noise close to ground 消除噪音
                expanded.push_back(pos);
                cell_queue.push(next_cell);
                is_in_frontier_[next_cell_adr] = true;
            }
        }
        if (expanded.size() > cluster_min_) {
            frontier.cells_ = expanded;
            computeFrontierInfo(frontier);
            return true;
        }
        return false;
    }

- 边界簇的分割FrontierFinder::splitLargeFrontiers

void FrontierFinder::searchAndAddFrontiers() 中使用,对每个簇都进行主成分分析,如果最大特征值超过阈值,则将该簇沿第一主轴分成两个均匀的簇。(分割是递归地进行的,因此所有大簇都被分成小簇。)
对应论文 IV.B

    void FrontierFinder::splitLargeFrontiers(vector<Frontier> &frontiers) {
        vector<Frontier> split_frontiers;
        for (Frontier &frontier: frontiers) {
            vector<Frontier> splits;
            if (splitHorizontally(frontier, splits)) {
                split_frontiers.insert(split_frontiers.end(), splits.begin(), splits.end());
            } else
                split_frontiers.emplace_back(move(frontier));
        }
        frontiers = move(split_frontiers);
    }

其中FrontierFinder::splitHorizontally :使用主成分分析,将较大的簇沿第一主轴分成两个均匀的簇 (单个的分割步骤)
在这里插入图片描述

- 视点集 V P i VP_i VPi的采样与覆盖率检测FrontierFinder::sampleViewpoints

void FrontierFinder::searchAndAddFrontiers() 中使用,对应论文 IV.C
对于自由空间内的每个采样点 p \mathbb{p} p,通过一个偏航角优化方法,yaw角 ξ \xi ξ由传感器对簇覆盖的最大角决定;
覆盖度通过符合传感器模型且未被障碍物遮挡的边界单元的数量来估计,
–> 覆盖度超过阈值的视点 将被保留 并按降序排列
–> 保留 V P i VP_i VPi中最多 N v i e w N_{view} Nview个视点,在第二大部分第2步进行局部更新

// Sample viewpoints around frontier's average position, check coverage to the frontier cells
    void FrontierFinder::sampleViewpoints(Frontier &frontier) {
        //通过在原点位于簇中心的柱面坐标系中均匀采样点得到,对应文章fig.4
        // Evaluate sample viewpoints on circles, find ones that cover most cells
        for (double rc = candidate_rmin_, dr = (candidate_rmax_ - candidate_rmin_) / candidate_rnum_;
             rc <= candidate_rmax_ + 1e-3; rc += dr)
            for (double phi = -M_PI; phi < M_PI; phi += candidate_dphi_) {
                const Vector3d sample_pos = frontier.average_ + rc * Vector3d(cos(phi), sin(phi), 0);

                //确认视点在AABB框且在无人机可执行的位置
                // Qualified viewpoint is in bounding box and in safe region 
                if (!edt_env_->sdf_map_->isInBox(sample_pos) ||
                    edt_env_->sdf_map_->getInflateOccupancy(sample_pos) == 1 ||
                    isNearUnknown(sample_pos)) {
                    continue;
                }
                //----------------- 计算视点覆盖度,进行筛选与降序排列 ------------------------
                // Compute average yaw
                const vector<Vector3d> &cells = frontier.filtered_cells_;
                Eigen::Vector3d ref_dir = (cells.front() - sample_pos).normalized();
                double avg_yaw = 0.0;
                for (size_t i = 1; i < cells.size(); ++i) {
                    Eigen::Vector3d dir = (cells[i] - sample_pos).normalized();
                    double yaw = acos(dir.dot(ref_dir));
                    if (ref_dir.cross(dir)[2] < 0) yaw = -yaw;
                    avg_yaw += yaw;
                }
                avg_yaw = avg_yaw / cells.size() + atan2(ref_dir[1], ref_dir[0]);
                wrapYaw(avg_yaw);     //调整yaw角朝向?
                // Compute the fraction of covered and visible cells   计算阈值
                int visible_num = countVisibleCells(sample_pos, avg_yaw, cells);      //计算有效视点
                if (visible_num > min_visible_num_) {               //保留部分视点并在V部分优化
                    Viewpoint vp = {sample_pos, avg_yaw, visible_num};
                    frontier.viewpoints_.push_back(vp);
                }
            }
    }

- 检测视点 x i , j = ( p i , j , ξ i , j ) x_{i,j}=(\mathbb{p}_{i,j},\xi_{i,j}) xi,j=(pi,j,ξi,j)可行性 FrontierFinder::countVisibleCells

FrontierFinder::sampleViewpoints 中使用
检测视点与传感器覆盖角度关系,检测视点未落在障碍物内

 int FrontierFinder::countVisibleCells(const Eigen::Vector3d &pos, const double &yaw,
                                          const vector<Eigen::Vector3d> &cluster) {
        perception_utils_->setPose(pos, yaw);
        int visible_num = 0;
        Eigen::Vector3i idx;
        for (const Vector3d &cell: cluster) {
            if (!perception_utils_->insideFOV(cell)) continue;      //是否超过传感器对簇覆盖的最大角

            // Check if frontier cell is visible (not occluded by obstacles) 检测未落在障碍物内
            ray_caster_->input(cell, pos);
            bool is_visible = true;
            while (ray_caster_->nextId(idx)) {
                if (edt_env_->sdf_map_->getInflateOccupancy(idx) == 1 ||
                    edt_env_->sdf_map_->getOccupancy(idx) == SDFMap::UNKNOWN) {
                    is_visible = false;
                    break;
                }
            }
            if (is_visible) visible_num += 1;
        }
        return visible_num;
    }

在这里插入图片描述

2. 其他函数

  • 移除过时的簇:FrontierFinder::removeOutDatedFrontiers()
    移除改变的簇;移除改变的簇的代价和path;删除已更改的休眠簇

  • 计算每对簇之间的连接代价(F_k1,F_k2) :FrontierFinder::updateFrontierCostMatrix()

  • 检测两个AABB框是否重叠:FrontierFinder::haveOverlap

  • 对簇进行降采样 :FrontierFinder::downSample

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

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

相关文章

五、模型训练

目录 1. 线性模型1.1 Lasso 回归1.2 Ridge 回归 2. 树模型2.1 随机森林&#xff08;Random Forest&#xff0c;RF&#xff09;2.2 梯度提升树&#xff08;GBDT&#xff09;2.3 XGBoost2.4 LightGBM2.5 CatBoost2.6 模型深入对比 3. 神经网络3.1 多层感知机3.2 卷积神经网络3.3 …

Linux 下 nc 发送接收 udp、tcp数据

nc&#xff0c;全名叫 netcat&#xff0c;它可以用来完成很多的网络功能&#xff0c;譬如端口扫描、建立TCP/UDP连接&#xff0c;数据传输、网络调试等等&#xff0c;因此&#xff0c;它也常被称为网络工具的 瑞士军刀 。 一、只服务端使用nc 备注&#xff1a;这种方式只能发…

【Hive】Centos7安装单机版Hive

Hive依赖MySQL存储元数据信息&#xff0c;安装Hive前需要先安装MySQL 一、安装MySQL 下载mysql安装包 wget http://repo.mysql.com/mysql57-community-release-el7-10.noarch.rpm2. 如果不是root用户需要先切换到root用户&#xff0c;安装第1步下载的rpm包 yum -y install …

MYSQL练习一答案

练习1答案 构建数据库 数据库 数据表 answer开头表为对应题号答案形成的数据表 表结构 表数据 答案&#xff1a; 1、查询商品库存等于50的所有商品&#xff0c;显示商品编号&#xff0c;商 品名称&#xff0c;商品售价&#xff0c;商品库存。 SQL语句 select good_no,good…

数据结构07:查找[C++][B树Btree]

图源&#xff1a;文心一言 考研对于B树的要求重点在推理手算的部分&#xff0c;只参考王道论坛咸鱼老师的视频就可以了&#xff1b;若时间非常充裕的小伙伴&#xff0c;也可以往下滑了解一下代码~&#x1f95d;&#x1f95d; 备注&#xff1a; 这次的代码是从这里复制的&…

nodejs+vue+elementui汽车销售网站

前端技术&#xff1a;nodejsvueelementui,视图层其实质就是vue页面&#xff0c;通过编写vue页面从而展示在浏览器中&#xff0c;编写完成的vue页面要能够和控制器类进行交互&#xff0c;从而使得用户在点击网页进行操作时能够正常。 可以设置中间件来响应 HTTP 请求。 Express …

关于坏点问题的调试总结

1、问题背景&#xff1a; 前段时间调试一个项目&#xff0c;有发现在低照度场景下图上有很多明显的白点&#xff0c;如下图所示。以以往的调试经验来看这就是坏点&#xff0c;可以通过 ISP 中去坏点模块去将其抹掉&#xff0c;但这么多的明显坏点&#xff0c;通过去坏点模块去…

5.1.tensorRT基础(2)-正确导出onnx的介绍,使得onnx问题尽量少

目录 前言1. 正确导出ONNX总结 前言 杜老师推出的 tensorRT从零起步高性能部署 课程&#xff0c;之前有看过一遍&#xff0c;但是没有做笔记&#xff0c;很多东西也忘了。这次重新撸一遍&#xff0c;顺便记记笔记。 本次课程学习 tensorRT 基础-正确导出 onnx 的介绍&#xff0…

【网络安全】DVWA靶场实战BurpSuite内网渗透

BurpSuite 内网渗透 一、 攻击模式介绍1.1 Sniper&#xff08;狙击手&#xff09;1.2 Battering ram&#xff08;攻城锤&#xff09;1.3 Pitchfork&#xff08;草叉&#xff09;1.4 Cluster bomb&#xff08;榴霰弹&#xff09; 二、 DVWA靶场搭建2.1 下载DVWA工程2.2 添加网站…

19 QListWidget控件

Tips: 对于列表式数据可以使用QStringList进行左移一块输入。 代码&#xff1a; //listWidget使用 // QListWidgetItem * item new QListWidgetItem("锄禾日当午"); // QListWidgetItem * item2 new QListWidgetItem("汗滴禾下土"); // ui->…

vue前端打包优化

建议&#xff0c;使用pnpn代替原生的npm 具体操作如下&#xff1a; pnpm安装&#xff0c;如果是linux&#xff0c;需要把npm和pnpm设置为环境变量## 安装pnpm npm install -g pnpm5.15.0 --registryhttps://registry.npm.taobao.org ## 设置淘宝镜像pnpm config set registry…

Vue3+vite实现组件上传npm并应用

场景&#xff1a;就是A项目的组件需要在B项目中使用 下面举例的是把a项目pagination分页组件上传到npm&#xff0c;在b项目使用 采坑日记&#xff1a;封装的组件一定要起name要不调用不成功 1.1 配置打包 1.1 首先在公用组件components文件夹下创建index.js文件&#xff0c…

JavaSwing+MySQL的小区物业管理系统

点击以下链接获取源码&#xff1a; https://download.csdn.net/download/qq_64505944/88071096 JDK1.8、MySQL5.7 《数据库原理课程设计》课程设计任务书 题 目&#xff1a; 小区物业管理系统 学生姓名&#xff1a; xxxxxx 班 级&#xff1a; xx 级软件工程 x 班 学 号&#…

虚继承是如何解决二义性和数据的冗余的

我们知道面向对象的三大特性分别为封装,继承,多态。在继承中&#xff0c;我们知道一个类可以继承另一个类&#xff0c;这样的关系被叫做子类&#xff08;派生类&#xff09;继承父类&#xff08;基类&#xff09;&#xff0c;并且子类可以使用到父类的接口。但是在C中还被设计了…

ElasticSearch学习--数据聚合

介绍 数据聚合可以帮助我们对海量的数据进行统计分析&#xff0c;如果结合kibana&#xff0c;我们还能形成可视化的图形报表。自动补全可以根据用户输入的部分关键字去自动补全和提示。数据同步可以帮助我们解决es和mysql的数据一致性问题。集群可以帮助我们了解结构和不同节点…

Pytorch个人学习记录总结 08

目录 神经网络-搭建小实战和Sequential的使用 版本1——未用Sequential 版本2——用Sequential 神经网络-搭建小实战和Sequential的使用 torch.nn.Sequential的官方文档地址&#xff0c;模块将按照它们在构造函数中传递的顺序添加。代码实现的是下图&#xff1a; 版本1—…

BeanFactory容器的构建和使用示例

BeanFactory容器的实现流程&#xff1a; BeanFactory是Spring框架中的一部分&#xff0c;它提供了IoC&#xff08;控制反转&#xff09;的实现机制。下面是BeanFactory的IoC实现过程&#xff1a; 定义Bean定义&#xff1a;首先&#xff0c;我们需要在配置文件中定义Bean的定义…

[数据结构]顺序表和ArrayList

顺序表的介绍 在了解顺序表之前先了解一下什么叫做线性表&#xff1a; 线性表&#xff08;linear list&#xff09;&#xff1a;是n个具有相同特性的数据元素的有限序列。 线性表是一种在实际中广泛使用的数据结构。 常见的线性表&#xff1a;顺序表、链表、栈、队列… 线性…

数学建模入门-如何从0开始,掌握数学建模的基本技能

一、前言 本文主要面向没有了解过数学建模的同学&#xff0c;帮助同学们如何快速地进行数学建模的入门并且尽快地在各类赛事中获奖&#xff0c;或者写出优秀的数学建模论文。 在本文中&#xff0c;我将从什么是数学建模、数学建模的应用领域、数学建模的基本步骤、数学建模的技…

两天学会用Webpack打包前端代码-day01

(创作不易&#xff0c;感谢有你&#xff0c;你的支持&#xff0c;就是我前行的最大动力&#xff0c;如果看完对你有帮助&#xff0c;请留下您的足迹&#xff09; 目录 什么是 Webpack&#xff1f; 使用 Webpack 体验webpack打包过程 修改 Webpack 打包入口和出口 入口 出…