反光板导航SLAM(二)VEnus代码浅析

2023-05-16

上一章简单介绍了VEnus中几个主要函数的作用,这里详细展开看一下每个函数的具体思路,通过研究具体的代码我们可以简单了解VEnus中对于反光柱定位的具体流程。

1、IntensityExtraction::Extract

IntensityExtraction::Extract(VEnus::Sensor::IntensityRange2D &cloud,
                                  VEnus::Sensor::IntensityRange2D &candidate_cloud)

Extract函数的主要作用是从激光点云中提取出高反点,然后存储到对应的容器中。输入的数据类型为

VEnus::Sensor::IntensityRange2D 

IntensityRange2D数据类型是定义在sensor/proto/sensor.proto文件内

message IntensityRange2D
{
    int64 timestamp = 1;
    string frame_id = 2;
    repeated IntensityPoint2D points = 3;
}

IntensityPoint2D的数据格式如下:

message IntensityPoint2D
{
    float x = 1;
    float y = 2;
    float intensity = 3;
}

repeated 类似于std的vector,可以用来存放N个相同类型的内容。所以这个函数的输入cloud是一系列带有强度信息的2D坐标点。函数的candidate_cloud代表的是匹配到的可能的反光柱点。所以它们数据结构是一样的。

然后是函数实现,这个函数其实很简单,它只是对整个点云进行了一次遍历,取连续的n个点,这个由一个参数intensity_median_filter_param决定,如果反光柱粗一点的或者激光分辨率高一点的话可以设置大一点,否则的话可以设置小一点,例如3。然后对这些点进行判断,只要其中有一半的点云强度超过阈值intensity_threshold则认为这里存在一个反光柱,将其中的点云强度处于中间值的那个点存入到容器candidate_cloud。

2、DBscanAssociation::Association

DBscanAssociation::Association(VEnus::Sensor::IntensityRange2D& candidate_cloud,
                                    VEnus::Sensor::Feature2DList& feature_list)

前面我们提取出了反光柱的中心点,但是这里的点云中可能会出现很多个点代表同一个反光柱的情况。所以这个函数即是对刚才的这些点进行一次类似于聚类的操作。candidate_cloud为第一步中选出来的高反点。feature_list为可能的反光柱中心。然后我们具体看一下函数实现:

Association的第一部分主要是遍历了所有点,通过调用expand_cluster函数进行一个分类:

  for (; iter < dataset.end(); ++iter) {
    if (iter->status == UNCLASSIFIED) {
      //聚类,将所有高反点根据相互之间距离分类,分类完成的点status为CLASSIFIED,同时处于同一类的点ID一致。
      if (expand_cluster(iter, cluster_id)) {
        cluster_id++;
      }
    }
  }

dataset里面存储的就是当前帧的高反点,来自于candidate_cloud,数据类型为:

PointDBSCAN(double px, double py) {
      x = px;
      y = py;
      status = UNCLASSIFIED;
      id = 0;
    }

可以看到对于每一个高反点,都有坐标x/y、状态status以及id等几个属性。初始状态下状态都为UNCLASSIFIED未区分,id都为0。然后函数对于每个点调用expand_cluster函数。这个函数的作用是:对于每一个candidate_cloud,找到所有candidate_cloud中的点与其接近的点(两者间距离小于一定阈值)这些点的status都会被设置为CLASSIFIED防止重复判断。id都会被设置为相同代表同一个反光柱。通过这种方式可以将所有点都划分成一个个点的区域,每个区域代表了一个反光柱。

在划分完成后,当然是要对每个区域做处理:

//按照ID将所有点放到map容器中
  unordered_map<int, vector<int> > feature_dict;
  iter = dataset.begin();
  for (; iter < dataset.end(); ++iter) {
    if (iter->status == CLASSIFIED) {
      feature_dict[iter->id].push_back(iter - dataset.begin());
    }
  }
  //找到每一组点的中心点的坐标,存放到tmp_res里面
  vector<pair<double, double> > tmp_res;
  for (auto pr : feature_dict) {
    double center_x = 0;
    double center_y = 0;
    for (int idx : pr.second) {
      center_x += dataset.at(idx).x;
      center_y += dataset.at(idx).y;
    }
    int sz = pr.second.size();
    //ROS_INFO("center point,x = %f,y = %f",center_x / double(sz),center_y / double(sz));
    tmp_res.push_back(std::make_pair(center_x / double(sz), center_y / double(sz)));
  }
  //判断每个中心点之间的距离,将距离过近的中心点视为代表同一个反光柱,更新容器中反光柱中心点坐标
  merge_cluster(tmp_res);

首先这里通过map维护了每一个待选的反光柱信息,所有的同一个反光柱的信息放到一起。进行一个划分,然后对每一类点集调用merge_cluster进行一个中心点的求取。求取的方式其实很简单就是简单相加求平均。这样子就可以知道了所有反光柱中心点所在的位置。

3、CartoMapping::InsertFeatureList

这个函数的功能还是挺多的,包括匹配,位姿估计,位姿优化等一系列其实都是在这个函数中实现的。详细看一下这个函数具体情况:

3.1、初始化

InsertFeatureList函数的第一步判断了feature_points容器是否为空,这里面存储的是全局坐标下的反光柱。这个容器为空说明目前没有已经确定的反光柱。则进行初始化。

if (feature_points.empty())

初始化的方式比较简单,将第一帧的反光柱坐标存储到feature_points中作为初始状态下反光柱的中心坐标,然后更新FeatureGraph。注意到这里的函数:InsertToFeatureGraph,这个函数的意义是对于每一个待插入的点(反光柱),计算它与周围反光柱之间的距离,然后存储到feature_graph中。注意到feature_graph的数据类型<int, std::unordered_map<int, double>>。第一个int为对应的feature_points的ID,第二个std::unordered_map<int, double>中的int为与这个feature_points相互关联的反光柱点的ID,后面的double类型数据为两个点之间的距离。

3.2、特征点匹配

SiftNewFeaturePoints(input_fpts, hit_id_pair, wait_insert);

在确认初始化完成的情况下,调用SiftNewFeaturePoints函数进行反光柱的匹配。这个函数有三个参数:input_fpts为前面识别出来的反光柱坐标,hit_id_pair为当前帧反光柱与世界坐标系下的反光柱匹配上的ID,wait_insert为当前帧中没能跟世界坐标系下反光柱所匹配上的点的ID。函数主要执行了以下工作:

首先,对于所有当前点,建立一个局部的local_feature_graph,记录当前点与点之间的距离。

然后,对于每一个当前帧的点,使用其局部local_feature_graph与全局点进行匹配。注意这里不是点与点的匹配而是类似于线与线的匹配,如果一个点到其他点的距离与全局点中某个点到其周围点的距离基本一致,则认为这两个点是匹配上了的,这时候会把这一对ID存放到hit_id_pair中。这个方式其实应该是有问题的,如果两个点到周围点的距离都很接近,就可能发生误匹配。

最后,对于input_fpts中剩下没有匹配到的点,则会将其存放到wait_insert中,这个数据代表这里检测出一个反光柱但是在全局中没有,后面需要另外处理。

3.3、初始位姿估计

ComputeCurrentPose(localization_hit, pose)

这个函数emmm其实我没看,因为似乎它基本就没有正确计算出来过。不过也不要紧,直接看下一步

3.4、位姿优化

OptimizeCurrentPose(localization_hit, pose);

OptimizeCurrentPose中需要输入两个变量:localization_hit里面存放的是当前帧下匹配点全局点之间的坐标。pose是机器人当前初步估计下的位姿,按照逻辑它应该会来自于步骤3,但是由于3总是出问题所以大部分情况下它来自于上一次估计出来的位姿。

然后根据输入的约束关系localization_hit以及初始位姿pose,调用ceres优化得到一个新的位姿:

  ceres::Problem problem;
  double pose[3] = {robot_pose.x(), robot_pose.y(), robot_pose.theta()};

  for (auto fpt_pair : match_result) {
    problem.AddResidualBlock(new ceres::AutoDiffCostFunction<FeaturePairCost, 2, 3>(
                                 new FeaturePairCost(fpt_pair.second, fpt_pair.first)),
                             new ceres::CauchyLoss(0.2), pose);
  }

  ceres::Solver::Options options;
  options.linear_solver_type = ceres::DENSE_QR;
  options.minimizer_progress_to_stdout = false;

  ceres::Solver::Summary summary;
  ceres::Solve(options, &problem, &summary);

最后这里输出得到的是一个新的优化后的位姿pose

3.5、更新反光柱信息

注意到前面3.2中还有一个东西没有处理,就是返回的wait_insert容器。这个里面存放的是当时检测到的反光柱但是这个反光柱没能与地图上其他地方的反光柱相匹配上,说明它可能是一个新的反光柱,对于这些信息我们要将其更新到最新的反光柱信息中:

  Eigen::Isometry2d matrixT = Eigen::Isometry2d::Identity();
  matrixT.pretranslate(Eigen::Vector2d(pose.x(), pose.y()));
  matrixT.rotate(pose.theta());
  //   Eigen::Isometry2d matrixTinv = matrixT.inverse();

  vector<pair<double, double> > new_fpt_wait_insert;
  vector<int> new_fpt_assigned_id;
  for (auto unhit : wait_insert) {
    Eigen::Vector3d local_fpt(unhit.first, unhit.second, 1.0);
    auto global_fpt = matrixT * local_fpt;

    auto new_fpt = make_pair(global_fpt[0], global_fpt[1]);
    feature_points[feature_point_cnt] = new_fpt;
    new_fpt_wait_insert.push_back(new_fpt);
    new_fpt_assigned_id.push_back(feature_point_cnt);
    feature_point_cnt++;
  }

首先是通过矩阵matrixT将这些反光柱点转到世界坐标系下,然后再根据初始化时候的方式一样更新feature_points容器,存储新的反光柱信息。当然最后还要调用:

InsertToFeatureGraph(new_fpt_wait_insert, new_fpt_assigned_id);

来更新feature_graph,也就是反光柱之间的距离信息。

通过以上一系列步骤我们就可以得到一个连续的基于反光柱匹配的位姿估计算法。当然这个算法还有一点小问题,比如线匹配意味着每一个反光柱到周围反光柱之间的距离都要独一无二,否则就可能出现误匹配的问题。匹配阈值也不能设计的太大,否则也会发生匹配错误,但是设计的太小就可能导致本来是一个地方的反光柱没有成功匹配上,最后该位置会生成出很多个反光柱,类似于这样:

在这里插入图片描述
这里先介绍完代码思路,具体的代码实现以及优化过程下一章单独展开介绍。

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

反光板导航SLAM(二)VEnus代码浅析 的相关文章

  • go语言值变量命名规范,定义变量,数据类型,常量,函数基础,函数高级

    这里写目录标题 一 昨日回顾二 今日内容1 变量命名规范2 变量代码演示 3 类型代码演示 4 常量5 函数基础6 函数高级 一 昨日回顾 span class token number 1 span redis高级 span class
  • 串口接收一帧数据及解析

    3 xff0e 下位机中的数据接收和协议解析 下位机接收数据也有两种方式 xff0c 一 等待接收 xff0c 处理器一直查询串口状态 xff0c 来判断是否接收到数据 二 中断接收 两种方法的优缺点在此前的一篇关于串口通信的文章中详细讨论
  • <string>库常用的函数

    include lt string h gt 库包含字符串处理函数 xff0c 常用的有strcpy strcat strcmp strchr等 1 strcpy是字符串赋值函数 char strcpy char target char s
  • APM(Ardupilot)——电机输出流程图

    电机类声明 xff1a system cpp void Copter allocate motors void switch AP Motors motor frame class g2 frame class get if FRAME C
  • C++中的三个特殊宏:__FILE__,__FUNCTION__和__LINE__

    C 43 43 中的三个特殊宏 xff1a FILE xff0c FUNCTION 和 LINE 1 FILE 宏 FILE 宏用于检查当前文件名 xff0c 例如 xff1a include lt cstdio gt using name
  • GD32F10x外部晶振配置108MHz系统时钟

    嵌入式 GD32F10x外部晶振配置108MHz系统时钟 文章目录 嵌入式 GD32F10x外部晶振配置108MHz系统时钟前言一 时钟树与配置思路二 时钟配置过程三 晶振故障排查总结 前言 由于公司更改硬件设计选择使用新的型号兆易创新国产
  • Keil MDK C (error: #29: expected an expression) 错误的解决

    今天 xff0c 自己建了一个EFM32工程模版 xff0c 调试代码时显示 App Panel main c 119 error 29 expected an expression 仔细的检查了半个小时 xff0c 最后解决了 xff01
  • HTTP协议之报文详解

    学习WEB开发需要对HTTP协议熟悉 xff0c 下面直接进入主题 一 什么是报文 报文 xff0c 是网络中交换和传输的数据单元 xff0c 即站点一次性要发送的数据块 报文包含了将要发送的完整的数据信息 xff0c 其长短很不一致 xf
  • linux发送tcp/udp请求

    本文章介绍下通过nc工具 iperf工具和python脚本 xff0c 实现发送tcp udp请求 一 nc工具 xff08 netcat工具 xff09 这个工具linux系统默认是自带的 xff0c 以下是命令的常用参数 1 1 发送t
  • 第一次网页前端培训笔记(HBuilderX)

    一 安装HBuilderX 官网 xff1a HBuilderX 高效极客技巧 dcloud io 二 了解HBuilderX lt DOCTYPE html gt lt html gt lt head gt lt meta charset
  • 第二次网页前端培训笔记(HBuilderX)

    常用标签 一 表单 form标签 xff1a 表单标签 xff0c 块级元素 xff0c 会自动换行 xff1b 将数据传输给服务器 常用属性 xff1a action 表单提交的地址url id 唯一标识 name 名称 target 表
  • 前端第7次培训

    对象 一对象的创建 1 字面量形式创建对象 var对象名 61 xff1b var对象名 61 键 xff1a 值 2 通过new Object创建 var对象名 61 new Object xff08 xff09 3 通过Object对象
  • MPU6050的再次深度学习与实操遇到问题

    数据的处理与实现 xff1a MPU6050芯片提供的数据夹杂有较严重的噪音 xff0c 在芯片处理静止状态时数据摆动都可能超过2 除了噪音 xff0c 各项数据还会有偏移的现象 xff0c 也就是说数据并不是围绕静止工作点摆动 xff0c
  • moderlarts第一次作业

    一 物体检测模型 以口罩检测为例 1 下载OBS 2 打开华为云 xff0c 找到modelarts控制台 xff0c 鼠标移到用户名上 xff0c 点击我的凭证 3 点击访问密钥 gt 新增访问密钥 xff0c 下载 xff0c 然后登陆
  • 培训modelarts 二

    一 进行声音分类 1 下载数据包 xff0c 导入OBS 2 创建声音分类项目 3 标签分类 4 开始训练 5 部署模型 6 预测结果 二 AI gallery 1 下载数据集 2 创建数据集 xff0c 导入外卖评论 3 进行创建文本分类
  • Jetson Xavier NX 配置(七)—— 数据传输之socket文件传输 & usb摄像头RTSP视频推流

    目录 1 Python socket 文件传输 xff08 1 xff09 发送单个文件 xff08 一次性 xff09 xff08 2 xff09 发送一个文件夹下的所有文件 xff08 一次性 xff09 xff08 3 xff09 发
  • 使用plist文件进行ipa的安装

    前提 将html 用户扫码 地址访问 ipa和plist放在https的远程服务器上 编写html文件 内容如下 lt DOCTYPE html PUBLIC W3C DTD XHTML 1 0 Transitional EN http w
  • 关于U盘变成RAW格式 windows无法格式化的解决方法

    网上有很多人说是U盘坏了 xff0c 其实不是这样 这个问题是可以解决的 xff0c 解决方法也是在网上搜索到的 xff0c 到这里同大家分享下 本人昨天使用U盘的时候就碰到了U盘变成RAW格式 xff0c 系统可以读出盘符 xff0c 但
  • Xcode11.6编写C++项目出现报错:vector or iostream file not found

    解决办法 xff1a
  • iPhone设备型号代码(iPhone 4s - iPhone 14)

    lt string gt iPhone15 3 lt string gt iPhone 14 Pro Max lt string gt iPhone15 2 lt string gt iPhone 14 Pro lt string gt i

随机推荐

  • [Linux] Vim 撤销 回退 操作

    在vi中按u可以撤销一次操作 u 撤销上一步的操作 Ctrl 43 r 恢复上一步被撤销的操作 注意 xff1a 如果你输入 u 两次 xff0c 你的文本恢复原样 xff0c 那应该是你的Vim被配置在Vi兼容模式了 重做 如果你撤销得太
  • 为什么系统进入到Checking Media Presence

    你按联想热启键来开机 xff0c 也就是那个还原键来开机 然后你选择BIOS Setup回车 选择Boot这项的boot mode把UEFI改成legacy support和boot priority把UEFI改成legacy 然后保存退出
  • MacBook Air响一声白屏故障情况说明及解决

    情况说明 xff1a 2013款的MacBook Air安装Windows 7系统 xff0c 结果导致开机响一声就白屏 xff0c 按option无选项出现 xff0c 其他各种组合按键尝试都无效 百度搜索 xff0c 有人说是屏幕故障
  • 如何在Eclipse中打开现有项目(高手免入)

    如果我们现在已经有了Java项目 xff08 网上下载的或者从别的电脑上拷贝过来的 xff09 xff0c 我们都知道 xff0c Eclipse和其他的编程软件不一样 xff0c 不能够通过直接双击某个文件的方式来打开 xff0c 那么我
  • svn is not a working copy 怎么解决

    确定当目录下是否含有 svn文件夹 如果没有就重新啊checkout xff0c 或者在上一层目录或下一层目录查找 xff0c 有则可执行 svn commit m 34 更新部分代码 34
  • CSS3设置Border边框是内边框还是外边框

    CSS3可以设置边框是向内还是向外 xff0c 如果要设置为内边框使用 1 box sizing border box 外边框 1 box sizing content box
  • If this view is optional add '@Nullable' (fields) or '@Optional' (methods) ...

    lt 在出错的activity中 xff0c 对应布局文件中加入 gt lt 不能缺少 xff0c 缺少后出现If this view is optional add 39 64 Nullable 39 fields or 39 64 Op
  • MTK Camera(OV13850) 驱动移植

    一 驱动源码包结构 拿到的驱动源码包解压后得到hal和kernel两个目录文件 xff0c 源码目录结构如下所示 13850 6592 driver 10 28 7z hal camera AE PLineTable ov13850mipi
  • 查看路由器WAN口IP是否为公网ip指南

    查看路由器WAN口IP是否为公网ip指南 吴捷 一 xff0e 公网ip和私网ip ip地址分类中常用的有A B C类 xff0c 每类IP中都规划了一段私网IP xff0c 除了这些私网外的IP都是公网IP 分类IP地址范围适用用户A1
  • [iOS] WKWebView 于JavaScript传值

    如果在项目中采用WKWebView的方法加载网页 OC向JS传值方法总结 xff1a 1 OC gt JS 传数组的方法 xff1a NSString arrStr 61 self arr componentsJoinedByString
  • iOS日历中的日程生成VCalendar 2.0(.vcs)格式的字符串和解析

    获取 VCalendar2 0 的格式字符串 43 NSString getVCalendar20StrWithEvents NSArray lt EKEvent gt events NSString vcalendar 61 NSStri
  • 数传电台术语详解

    数传电台 xff08 data radio xff09 是指借助DSP 技术和无线电技术实现的高性能专业数据传输电台 数传电台的使用从最早的按键电码 电报 模拟电台加无线MODEM xff0c 发展到目前的数字电台和DSP 软件无线电 xf
  • 无线数传电台的发展趋势

    摘自 专业无线通信 传媒 无线数传电台作为一种最简洁的通行方式 xff0c 具有很长的历史 xff0c 其基本的特征是通联方便 简捷 xff0c 同时也存在着封闭性强的特点 xff0c 正是由于上述原因 xff0c 无线数传电台产品的生命期
  • wget 提交post请求

    格式 xff1a wget post data 34 item1 61 value1 amp item2 61 value2 34 http xxx xxx com 示例 xff1a wget post data 34 username 6
  • 欧拉角、轴角与四元数

    1 欧拉角 欧拉角使用最简单的x y z值来分别表示在x xff0c y xff0c z轴上的旋转角度 xff0c 其取值为0 360 或者0 2pi xff09 xff0c 一般使用roll xff0c pitch xff0c yaw来表
  • Linux 系统投屏显示

    最近使用电脑跑Linux时需要用到显示器投屏 xff0c 于是快乐的拿上我的笔记本连上了投影仪 emmm 然鹅并没有什么卵用 果断问度娘 xff0c 看到好多人说使用xrandr命令设置 xff0c 于是便上手试了下 xff0c 看到我运行
  • C++ 判断一个 int 型整数是否为 2 的 N 次方(幂次)

    判断一个整数是否为2的幂次方法有以下几种 xff1a 1 循环除2 这是最简单最好理解的方式 对于一个数如果是2的幂次 xff0c 则其肯定可以被2一直整除直到其值为1 所以可以通过一个while循环判断 xff1a void judge
  • Dijkstra算法图文详解

    Dijkstra算法算是贪心思想实现的 xff0c 首先把起点到所有点的距离存下来找个最短的 xff0c 然后松弛一次再找出最短的 xff0c 所谓的松弛操作就是 xff0c 遍历一遍看通过刚刚找到的距离最短的点作为中转站会不会更近 xff
  • 需求中如何画用例图

    UML用例图 用例图主要用来图示化系统的主事件流程 xff0c 它主要用来描述客户的需求 xff0c 即用户希望系统具备的完成一定功能的动作 xff0c 通俗地理解用例就是软件的功能模块 xff0c 所以是设计系统分析阶段的起点 xff0c
  • 反光板导航SLAM(二)VEnus代码浅析

    上一章简单介绍了VEnus中几个主要函数的作用 xff0c 这里详细展开看一下每个函数的具体思路 xff0c 通过研究具体的代码我们可以简单了解VEnus中对于反光柱定位的具体流程 1 IntensityExtraction Extract