学习记录-自动驾驶与机器人中的SLAM技术

以下所有内容均为高翔大神所注的《自动驾驶与机器人中的SLAM技术》中的内容

2D SLAM

  • 作者实现了一个2D 的ICP

3D SLAM

ICP

  • 实现了一个并发的ICP配准
  • 实现了点到面的ICP
  • 实现了点到线的ICP
  • 点到线的ICP的结果与点到点的ICP相当,略差于点到面的、在三中算法中,点到面的ICP在精度和效率上都具有一定优势,明显快于PCL的内置版本,单其单次迭代中计算量明显大于原始ICP

NDT

本书各配准算法与PCL的对比

增量式NDT

需要解决两个问题:

  1. 每个体素内的高斯参数如何改变
  2. 如何维护不断增加的体素

高斯分布的增量更新

体素的增量维护

融合导航

1. EKF和优化的关系

2. 组合导航eskf中的预测部分,主要是F矩阵的构建

template <typename S>
bool ESKF<S>::Predict(const IMU& imu) {assert(imu.timestamp_ >= current_time_);double dt = imu.timestamp_ - current_time_;if (dt > (5 * options_.imu_dt_) || dt < 0) {// 时间间隔不对,可能是第一个IMU数据,没有历史信息LOG(INFO) << "skip this imu because dt_ = " << dt;current_time_ = imu.timestamp_;return false;}// nominal state 递推VecT new_p = p_ + v_ * dt + 0.5 * (R_ * (imu.acce_ - ba_)) * dt * dt + 0.5 * g_ * dt * dt;VecT new_v = v_ + R_ * (imu.acce_ - ba_) * dt + g_ * dt;SO3 new_R = R_ * SO3::exp((imu.gyro_ - bg_) * dt);R_ = new_R;v_ = new_v;p_ = new_p;// 其余状态维度不变// error state 递推// 计算运动过程雅可比矩阵 F,见(3.47)// F实际上是稀疏矩阵,也可以不用矩阵形式进行相乘而是写成散装形式,这里为了教学方便,使用矩阵形式Mat18T F = Mat18T::Identity();                                                 // 主对角线F.template block<3, 3>(0, 3) = Mat3T::Identity() * dt;                         // p 对 vF.template block<3, 3>(3, 6) = -R_.matrix() * SO3::hat(imu.acce_ - ba_) * dt;  // v对thetaF.template block<3, 3>(3, 12) = -R_.matrix() * dt;                             // v 对 baF.template block<3, 3>(3, 15) = Mat3T::Identity() * dt;                        // v 对 gF.template block<3, 3>(6, 6) = SO3::exp(-(imu.gyro_ - bg_) * dt).matrix();     // theta 对 thetaF.template block<3, 3>(6, 9) = -Mat3T::Identity() * dt;                        // theta 对 bg// mean and cov predictiondx_ = F * dx_;  // 这行其实没必要算,dx_在重置之后应该为零,因此这步可以跳过,但F需要参与Cov部分计算,所以保留cov_ = F * cov_.eval() * F.transpose() + Q_;current_time_ = imu.timestamp_;return true;
}

3. 以下是速度量测,主要是H矩阵的构建

template <typename S>
bool ESKF<S>::ObserveWheelSpeed(const Odom& odom) {assert(odom.timestamp_ >= current_time_);// odom 修正以及雅可比// 使用三维的轮速观测,H为3x18,大部分为零Eigen::Matrix<S, 3, 18> H = Eigen::Matrix<S, 3, 18>::Zero();H.template block<3, 3>(0, 3) = Mat3T::Identity();// 卡尔曼增益Eigen::Matrix<S, 18, 3> K = cov_ * H.transpose() * (H * cov_ * H.transpose() + odom_noise_).inverse();// velocity obsdouble velo_l = options_.wheel_radius_ * odom.left_pulse_ / options_.circle_pulse_ * 2 * M_PI / options_.odom_span_;double velo_r = options_.wheel_radius_ * odom.right_pulse_ / options_.circle_pulse_ * 2 * M_PI / options_.odom_span_;double average_vel = 0.5 * (velo_l + velo_r);VecT vel_odom(average_vel, 0.0, 0.0);VecT vel_world = R_ * vel_odom;dx_ = K * (vel_world - v_);//v_是状态递推后的速度// update covcov_ = (Mat18T::Identity() - K * H) * cov_;UpdateAndReset();return true;
}

4. 以下是GPS的量测,主要任然是H矩阵的构建

template <typename S>
bool ESKF<S>::ObserveGps(const GNSS& gnss) {/// GNSS 观测的修正assert(gnss.unix_time_ >= current_time_);if (first_gnss_) {R_ = gnss.utm_pose_.so3();p_ = gnss.utm_pose_.translation();first_gnss_ = false;current_time_ = gnss.unix_time_;return true;}assert(gnss.heading_valid_);ObserveSE3(gnss.utm_pose_, options_.gnss_pos_noise_, options_.gnss_ang_noise_);current_time_ = gnss.unix_time_;return true;
}template <typename S>
bool ESKF<S>::ObserveSE3(const SE3& pose, double trans_noise, double ang_noise) {/// 既有旋转,也有平移/// 观测状态变量中的p, R,H为6x18,其余为零Eigen::Matrix<S, 6, 18> H = Eigen::Matrix<S, 6, 18>::Zero();H.template block<3, 3>(0, 0) = Mat3T::Identity();  // P部分H.template block<3, 3>(3, 6) = Mat3T::Identity();  // R部分(3.66)// 卡尔曼增益和更新过程Vec6d noise_vec;noise_vec << trans_noise, trans_noise, trans_noise, ang_noise, ang_noise, ang_noise;Mat6d V = noise_vec.asDiagonal();Eigen::Matrix<S, 18, 6> K = cov_ * H.transpose() * (H * cov_ * H.transpose() + V).inverse();// 更新x和covVec6d innov = Vec6d::Zero();innov.template head<3>() = (pose.translation() - p_);          // 平移部分innov.template tail<3>() = (R_.inverse() * pose.so3()).log();  // 旋转部分(3.67)dx_ = K * innov;cov_ = (Mat18T::Identity() - K * H) * cov_;UpdateAndReset();return true;
}

IMU预积分

  • 书中有IMU预积分所有的公式推导,包括了预积分计算公式,预积分相较于状态量的雅克比矩阵公式,误差传播公式等等

/*** IMU 预积分器** 调用Integrate来插入新的IMU读数,然后通过Get函数得到预积分的值* 雅可比也可以通过本类获得,可用于构建g2o的边类*/
class IMUPreintegration {public:EIGEN_MAKE_ALIGNED_OPERATOR_NEW/// 参数配置项/// 初始的零偏需要设置,其他可以不改struct Options {Options() {}Vec3d init_bg_ = Vec3d::Zero();  // 初始零偏Vec3d init_ba_ = Vec3d::Zero();  // 初始零偏double noise_gyro_ = 1e-2;       // 陀螺噪声,标准差double noise_acce_ = 1e-1;       // 加计噪声,标准差};IMUPreintegration(Options options = Options());/*** 插入新的IMU数据* @param imu   imu 读数* @param dt    时间差*/void Integrate(const IMU &imu, double dt);/*** 从某个起始点开始预测积分之后的状态* @param start 起始时时刻状态* @return  预测的状态*/NavStated Predict(const NavStated &start, const Vec3d &grav = Vec3d(0, 0, -9.81)) const;/// 获取修正之后的观测量,bias可以与预积分时期的不同,会有一阶修正SO3 GetDeltaRotation(const Vec3d &bg);Vec3d GetDeltaVelocity(const Vec3d &bg, const Vec3d &ba);Vec3d GetDeltaPosition(const Vec3d &bg, const Vec3d &ba);public:double dt_ = 0;                          // 整体预积分时间Mat9d cov_ = Mat9d::Zero();              // 累计噪声矩阵Mat6d noise_gyro_acce_ = Mat6d::Zero();  // 测量噪声矩阵// 零偏Vec3d bg_ = Vec3d::Zero();Vec3d ba_ = Vec3d::Zero();// 预积分观测量SO3 dR_;Vec3d dv_ = Vec3d::Zero();Vec3d dp_ = Vec3d::Zero();// 雅可比矩阵Mat3d dR_dbg_ = Mat3d::Zero();Mat3d dV_dbg_ = Mat3d::Zero();Mat3d dV_dba_ = Mat3d::Zero();Mat3d dP_dbg_ = Mat3d::Zero();Mat3d dP_dba_ = Mat3d::Zero();
};

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

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

相关文章

【Proteus仿真】【Arduino单片机】汽车车窗除霜系统设计

文章目录 一、功能简介二、软件设计三、实验现象联系作者 一、功能简介 本项目使用Proteus8仿真Arduino单片机控制器&#xff0c;使用LCD1602显示模块、光线传感器、DS18B20温度传感器、PCF8691 ADC模块、继电器加热模块等。 主要功能&#xff1a; 系统运行后&#xff0c;LCD…

成功 BOM 流程的五个基本要素

您应该以确保 BOM 流程的方式实现和启用它们&#xff1a; 准确的 当前的 完全的 清除 可行的 追求准确性 为下游提供准确数据 制造商使用其 BOM 来通知下游操作他们需要执行什么。不言而喻&#xff0c;向其他团队和员工提供准确的信息至关重要&#xff1b;否则&…

3.日志配置

规范&#xff1a;项目开发不要编写System.out.println()&#xff0c;应该用日志记录信息 先创建项目&#xff1a; 1. 简介 Spring使用commons-logging作为内部日志&#xff0c;但底层日志实现是开放的。可对接其他日志框架。 SpringBoot怎么把日志默认配置好的 1、每个start…

【Spring 篇】深入探索:Spring集成Web环境的奇妙世界

嗨&#xff0c;亲爱的小白们&#xff01;欢迎来到这篇有关Spring集成Web环境的博客。如果你曾对如何在Spring中构建强大的Web应用程序感到好奇&#xff0c;那么这里将为你揭示Web开发的神秘面纱。我们将用情感丰富、语句通顺的文字&#xff0c;以小白友好的方式&#xff0c;一探…

IC验证——perl脚本ccode_standard——c代码寄存器配置标准化

目录 1 脚本名称 2 脚本路径 3 脚本参数说明 4 脚本操作说明 5 脚本代码 1 脚本名称 ccode_standard 2 脚本路径 /scripts/bin/ccode_standard 3 脚本参数说明 次序 参数名 说明 1 address (./rfdig&#xff1b;.&#xff1b;..&#xff1b;./boot) 指定脚本执行路…

SpringBoot集成Minio

pom文件导入依赖 <?xml version"1.0" encoding"UTF-8"?> <project xmlns"http://maven.apache.org/POM/4.0.0" xmlns:xsi"http://www.w3.org/2001/XMLSchema-instance"xsi:schemaLocation"http://maven.apache.org/P…

C盘满了,我用什么思路清理?

20240115 上周六同事传了一个很大的虚拟机给我&#xff0c;C盘就红了 虽然是飞秋选错了存储文件的路径&#xff0c;但后来忘了&#xff0c;就开始毫无目的删除文件&#xff0c;过程中会有没有权限删除的&#xff0c;这样还是没有改善。 咨询了公司IT技术人员&#xff0c; 告…

leetcode-344. 反转字符串、9. 回文数

题目1&#xff1a; 解题方法 直接用reverse()即可 代码&#xff1a; class Solution(object):def reverseString(self, s):""":type s: List[str]:rtype: None Do not return anything, modify s in-place instead."""return s.reverse()如果不…

SpringIOC之support模块GenericXmlApplicationContext

博主介绍&#xff1a;✌全网粉丝5W&#xff0c;全栈开发工程师&#xff0c;从事多年软件开发&#xff0c;在大厂呆过。持有软件中级、六级等证书。可提供微服务项目搭建与毕业项目实战&#xff0c;博主也曾写过优秀论文&#xff0c;查重率极低&#xff0c;在这方面有丰富的经验…

深入理解 Flink(八)Flink Task 部署初始化和启动详解

JobMaster 部署 Task 核心入口&#xff1a; JobMaster.onStart();部署 Task 链条&#xff1a;JobMaster --> DefaultScheduler --> SchedulingStrategy --> ExecutionVertex --> Execution --> RPC请求 --> TaskExecutor TaskExecutor 处理 JobMaster 的 …

服务异步通讯——springcloud

服务异步通讯——springcloud 文章目录 服务异步通讯——springcloud初始MQRabbitMQ快速入门单机部署1.1.下载镜像安装MQ SpringAMQPwork Queue 工作队列Fanout Exchange广播模式DirectExchange路由模式TopicExchange话题模式 消息转换器 初始MQ RabbitMQ快速入门 官网https:/…

Next.js 开发指​南(GitHub 115k star​)

Next.js 是一个构建于 Node.js 之上的开源 Web 开发框架&#xff0c;它扩展了最新的 React 特性&#xff0c;集成了基于 Rust 的 JavaScript 工具&#xff0c;可以帮助你快速创建全栈 Web 应用 &#xff08;full-stack Web applications&#xff09; 。 对于有一定 React 基础…

mesh 如何接线

水星 1900 mg 二手 约 40 一个 参考 https://post.smzdm.com/p/aoozepzr/ https://service.mercurycom.com.cn/article-1565.html

HTML5+CSS3+JS小实例:实时给中文添加拼音

实例:实时给中文添加拼音 技术栈:HTML+CSS+JS 效果: 源码: 【HTML】 <!DOCTYPE html> <html lang="zh-CN"> <head><meta charset="UTF-8"><meta http-equiv="X-UA-Compatible" content="IE=edge"&…

nxp s32k144芯片使用J-LINK程序刷写

1.nxp s32k144 (1)打开软件&#xff1a;J-Flash V6.30j (2)新建工程&#xff1a;file->new project (3)选择芯片型号和 target interface (4)可以保存芯片和接口配置 (5)打开程序&#xff1a;File->open data file &#xff08;6&#xff09;程序刷写&#xff1a;T…

Node cool 跨域问题的解决

1.问题 自己在写后端接口的时候 发现一个接口在抖音小程序上可以调用 浏览器上也可以直接打开 但是在H5 的请求中 一直就是cors error 前端报这个跨域问题 在后端 报not Found 一开始以为是找不到 经过确定 发现是跨域问题 2.解决 在全局 configuration.ts 文件里有个全局…

自动驾驶轨迹规划之碰撞检测(二)

欢迎大家关注我的B站&#xff1a; 偷吃薯片的Zheng同学的个人空间-偷吃薯片的Zheng同学个人主页-哔哩哔哩视频 (bilibili.com) 目录 1.基于凸优化 2.具身足迹 3. ESDF 自动驾驶轨迹规划之碰撞检测&#xff08;一&#xff09;-CSDN博客 大家可以先阅读之前的博客 1.基于…

josef约瑟 电流继电器 DL-13/2 0.5 -1A 1NC, 1NO柜内安装,带附件

系列型号 DL-11电流继电器; DL-12电流继电器; DL-13电流继电器&#xff1b; 一、应用范围 DL-13/2电流继电器 板前接线为电磁式瞬动过电流继电器&#xff0c;它广泛用于电力系统二次回路继电保护装置线路中&#xff0c;作为过电流启动元件。 二、主要技术参数据 动作时间…

普冉32位单片机 PY32C642,M0+内核,1.7 V ~ 5.5 V宽工作电压

PY32C642 单片机采用高性能的 32 位 ARM Cortex-M0内核&#xff0c;宽电压工作范围。嵌入 24Kbytes Flash 和 3 Kbytes SRAM 存储器&#xff0c;最高工作频率 24 MHz。包含多种不同封装类型产品。工作温度范围为-40C ~ 85C&#xff0c;工作电压范围 1.7 V ~ 5.5 V。1 路 12 位A…

【开源】基于JAVA语言的民宿预定管理系统

目录 一、摘要1.1 项目介绍1.2 项目录屏 二、功能模块2.1 用例设计2.2 功能设计2.2.1 租客角色2.2.2 房主角色2.2.3 系统管理员角色 三、系统展示四、核心代码4.1 查询民宿4.2 新增民宿4.3 新增民宿评价4.4 查询留言4.5 新增民宿订单 五、免责说明 一、摘要 1.1 项目介绍 基于…