ROS合集(七)SVIn2声呐模块分析

image-20250523101940421

文章目录

    • 一、整体思想
    • 二、具体误差建模流程
    • 三、总结明确(预测值与观测值)
    • 四、选点逻辑
    • 五、Sonar 数据处理流水线
      • 1. ROS Launch 配置(imagenex831l.launch)
      • 2. SonarNode 节点(sonar_node.py)
      • 3. Subscriber 订阅与回调(Subscriber.cpp)
      • 4. 后端优化接入(Estimator.cpp)
      • 5. 总结
    • 六、Ceres求解
      • 阶段 1:定义并初始化参数块
      • 阶段 2:构造残差函数(CostFunction)
      • 阶段 3:添加到 Problem(联合注册)
      • 阶段 4:配置 Solver 选项
      • 阶段 5:调用 Solve 执行优化
      • 阶段 6:提取并更新结果

根据论文中给出的DPP-sonar误差计算方法及图示(图6),具体分析声呐误差的计算方式如下:

image-20250523101120306


Here, we assume that the visual-feature based patch is small enough and approximately coplanar with the DPP-sonar point.

在这里,我们假设基于视觉功能的贴片足够小,并且与DPP-Sonar点大约是共面的。

一、整体思想

SVIn2方法使用DPP-sonar声呐传感器来辅助视觉特征,从而提高SLAM的精度和鲁棒性。具体而言:

  • 声呐能够提供对障碍物的距离测量,不受视觉条件(如浑浊水体、光照变化)影响。
  • 声呐的测量点与视觉特征的测量点之间存在一定空间差异,系统通过结合声呐测量点附近的视觉特征(patch)进行误差建模和优化。

二、具体误差建模流程

流程图示如论文图6所示,其中:

  • 蓝色星形:声呐测量点
  • 红色星形:视觉特征点
  • 紫色线段:声呐测量点到视觉特征点群中心(patch)的误差距离
  • 三角形绿色:关键帧(相机位置)
  • 黄色方形:IMU测量位置

具体步骤如下:

image-20250507111132413

image-20250507111154961

image-20250507111207071


三、总结明确(预测值与观测值)

image-20250507111237818

四、选点逻辑

这整个「从声呐量测→世界坐标下的点→在视觉地标里找候选子集」的逻辑,其实就在 Estimator::addStates(...) 里,当你往 OKVIS 后端里挂声呐因子(SonarError)之前。具体是在这段代码里:

// Estimator::addStates(...)
// (前面省略了 IMU、深度、视觉部分)// ———— Sonar ————
if (sonarMeasurements.size() != 0) {auto last_sonarMeasurement_it = sonarMeasurements.rbegin();double range   = last_sonarMeasurement_it->measurement.range;double heading = last_sonarMeasurement_it->measurement.heading;// 1) 把声呐读数〈range, heading〉变成声呐坐标系下的点okvis::kinematics::Transformation sonar_point(Eigen::Vector3d(range * cos(heading),range * sin(heading),0.0),Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0));// 2) 把它从声呐坐标系 T_SSo 換到世界坐标系okvis::kinematics::Transformation T_WSo       = T_WS * params.sonar.T_SSo;okvis::kinematics::Transformation T_WSo_point = T_WSo * sonar_point;Eigen::Vector3d sonar_landmark = T_WSo_point.r();   // ← 这就是“世界系下的声呐点”// 3) 在所有视觉地标里找“x,y,z 三个方向都离它不到 0.1m” 的那些点std::vector<Eigen::Vector3d> landmarkSubset;for (auto rit = landmarksMap_.rbegin(); rit != landmarksMap_.rend(); ++rit) {// 把每个视觉地标从齐次坐标转成 3DEigen::Vector3d visual_landmark =(rit->second.point / rit->second.point[3]).head<3>();if (fabs(sonar_landmark[0] - visual_landmark[0]) < 0.1 &&fabs(sonar_landmark[1] - visual_landmark[1]) < 0.1 &&fabs(sonar_landmark[2] - visual_landmark[2]) < 0.1) {landmarkSubset.push_back(visual_landmark);}}// 4) 如果找到了不止一个,就把它们打包,构造一个 SonarErrorif (!landmarkSubset.empty()) {double information_sonar = 1.0;auto sonarError = std::make_shared<ceres::SonarError>(params, range, heading, information_sonar, landmarkSubset);mapPtr_->addResidualBlock(sonarError, NULL, poseParameterBlock);}
}
  • 构造世界系下的声呐点

    okvis::kinematics::Transformation sonar_point(...);
    T_WSo_point = T_WS * params.sonar.T_SSo * sonar_point;
    Eigen::Vector3d sonar_landmark = T_WSo_point.r();
    
  • 从一个点变成一组候选点
    就是上面对于 landmarksMap_ 的那一小段 for 循环,所有离 sonar_landmark 足够近的视觉地标都被 push 进了 landmarkSubset

五、Sonar 数据处理流水线

1. ROS Launch 配置(imagenex831l.launch)

  • 功能:启动 imagenex831l/sonar_node.py 节点。
  • 关键配置
    • respawn="true":节点意外退出后自动重启。
    • respawn_delay="30":重启前等待 30s。

2. SonarNode 节点(sonar_node.py)

  1. 初始化
    • rospy.init_node('imagenex831l')
    • 发布两个话题:
      • imagenex831l/range(处理后数据,ProcessedRange
      • imagenex831l/range_raw(原始数据,RawRange
    • 启动 dynamic_reconfigure 服务器,支持运行时修改驱动参数。
  2. 参数回调
    • parameters_callback() 中,将 config 下发给驱动并返回更新后的配置。
  3. 主循环 (spin())
    • 按设定频率 poll_frequency 读传感器:
      1. 调用 sensor.send_request()sensor.read_data() 获取原始字节。
      2. 发布 RawRange:填充 headerdata
      3. 调用 sensor.interpret_data() 解析成 ProcessedRange
      4. 发布到 imagenex831l/range
    • 若多次读取异常且超过 RESET_TIMEOUT,调用 rospy.signal_shutdown()
  4. 清理
    • 节点退出前,调用 sensor.close_connection() 关闭串口或网络。

3. Subscriber 订阅与回调(Subscriber.cpp)

  1. setNodeHandle()
    • 订阅 /imagenex831l/rangeProcessedRange)并绑定 sonarCallback()
    • 仅在配置 vioParameters_.sensorList.isSonarUsed == true 时启用。
  2. 回调 sonarCallback(const ProcessedRange::ConstPtr& msg)
    • 量化rangeResolution = msg->max_range / msg->intensity.size()
    • 峰值筛选:在前 size-100 个 bin 中找最大强度 max 及其索引 maxIndex
    • 距离计算range = (maxIndex + 1) * rangeResolutionheading = deg2rad(msg->head_position)
    • 过滤条件range < 4.5mmax > 10
    • 注入后端vioInterface_->addSonarMeasurement(timestamp, range, heading)
  3. 线程同步
    • ThreadedKFVio::startThreads() 中根据 sensorList.isSonarUsed 启动 sonarConsumerThread_
    • sonarConsumerLoop() 中,通过队列 sonarMeasurementsReceived_ 异步消费测量,等待同步器 sonarFrameSynchronizer_ 配合多帧时间戳。

4. 后端优化接入(Estimator.cpp)

  1. 状态添加 (addStates())

    • 取当前 pose T_WS

    • sonarMeasurements 提取最新一条测量 (range, heading)

    • 将测量点转换到世界坐标:

      T_WSo = T_WS * params.sonar.T_SSo;
      point_local = [range*cos(heading), range*sin(heading), 0];
      sonar_landmark = (T_WSo * point_local).r();
      
    • 在视觉地标 landmarksMap_ 中寻找附近(误差 < 0.1m)的关键点集合 landmarkSubset

    • 构建 SonarError 残差块并 mapPtr_->addResidualBlock(sonarError, nullptr, poseBlock)

  2. SonarError 类

    • 保存range_, heading_, 信息矩阵 information_, 以及参考地标 landmarkSubset_

    • Evaluate()

      1. 计算地标几何中心 mean

      2. 预测距离 range_pred = ‖T_WS.r() - mean‖

      3. 残差 e = range_ - range_pred,加权 sqrtInfo * e

      4. 计算雅可比:

        ∂ e / ∂ t = ( T W S . r ( ) − s o n a r _ l a n d m a r k ) / r a n g e \partial e/\partial t = (T_WS.r() - sonar\_landmark)/range e/t=(TWS.r()sonar_landmark)/range


5. 总结

  • 发布层面sonar_node)负责串口/网络 I/O 与格式封装。
  • 订阅层面Subscriber)完成 ROS 消息转换、滤波与后端注入。
  • 后端层面Estimator)将声纳测量融入滑动窗口的非线性优化,通过 SonarError 将声纳对 pose 产生的约束与视觉、IMU 共同优化。

六、Ceres求解

阶段 1:定义并初始化参数块

主要内容

  • 把所有待估计量(相机位姿、IMU 速度-偏置、3D 地标……)封装成 Ceres 的 ParameterBlock。
  • 为每种变量选择合适的参数化:四元数形式的位姿、齐次坐标形式的地标等。

方法论

  • 调用对应的 ParameterBlock 构造函数(如 PoseParameterBlockHomogeneousPointParameterBlock)。
  • mapPtr_->addParameterBlock(...) 将它们注册到统一的 Ceres Problem(OKVIS 封装在 mapPtr_ 中)。

目的

  • 将所有待优化的自由变量集中管理,Ceres 才能在同一次求解中联合调整它们。

对应代码段

// 1. 添加相机位姿 ParameterBlock(6DoF Pose)
auto posePB = std::make_shared<okvis::ceres::PoseParameterBlock>(T_WS,    // 初始世界到载体位姿poseId,  // 唯一 IDtimestamp);
mapPtr_->addParameterBlock(posePB, okvis::ceres::Map::Pose6d);// 2. 添加齐次坐标地标 ParameterBlock (4D homogeneous point)
Eigen::Vector4d lm4d(lx, ly, lz, 1.0);
auto lmPB = std::make_shared<okvis::ceres::HomogeneousPointParameterBlock>(lm4d,    // [x,y,z,1]lmId);   // 唯一 ID
mapPtr_->addParameterBlock(lmPB, okvis::ceres::Map::HomogeneousPoint);

阶段 2:构造残差函数(CostFunction)

主要内容

  • 针对每种传感器观测(视觉重投影、IMU 预积分、Sonar 距离、Depth 深度…)实现一个残差模型:误差值和雅可比。

方法论

  • 自定义或继承 Ceres 的 SizedCostFunctionAnalyticCostFunction,在 Evaluate()(或 operator()) 中完成残差计算和对依赖参数的导数计算。

目的

  • 把测量值和当前变量估计联系起来,以残差形式告诉优化器“该如何调整参数来减小测量误差”。

对应代码段

// 视觉重投影残差
auto reprojError = std::make_shared<okvis::ceres::ReprojectionError>(cameraModel, keypoint, intrinsics, extrinsics);// IMU 预积分残差
auto imuError = std::make_shared<okvis::ceres::ImuError>(imuMeasurements, imuParams, priorState);// Sonar 距离残差
double info = 1.0;
auto sonarError = std::make_shared<okvis::ceres::SonarError>(params, range, heading, info, landmarkSubset);

阶段 3:添加到 Problem(联合注册)

主要内容

  • 将所有 ParameterBlock 和 CostFunction(ResidualBlock)绑定到同一个 Ceres Problem 中(OKVIS 用 mapPtr_ 封装)。
  • 指定每个残差块依赖哪些参数块,Ceres 内部自动构建稀疏雅可比结构。

方法论

  • 调用 mapPtr_->addResidualBlock(residual, lossFunction, parameterBlockIds...),将观测残差和对应变量挂钩。

目的

  • 构建完整的非线性最小二乘问题,让优化器在所有约束下同时调整所有自由变量。

对应代码段

// 视觉重投影:优化 pose 和 landmark
mapPtr_->addResidualBlock(reprojError,          // 残差模型lossFunctionPtr,      // 可选的 robust lossposePB->id(),         // 依赖的参数块 IDlmPB->id());// IMU 预积分:连接前后两帧的 pose+bias
mapPtr_->addResidualBlock(imuError,nullptr,              // 不使用 robust lossprevPosePB->id(), prevBiasPB->id(),currPosePB->id(), currBiasPB->id());// Sonar 距离:只优化当前帧位姿
mapPtr_->addResidualBlock(sonarError,nullptr,posePB->id());

阶段 4:配置 Solver 选项

主要内容

  • 设定线性求解器类型(如 SPARSE_SCHUR)、信赖域策略(DOGLEG / Levenberg–Marquardt)、最大迭代次数、并行线程数、日志输出等。

方法论

  • 通过 mapPtr_->options 修改 ceres::Solver::Options

目的

  • 根据问题规模和实时性要求,选择最合适的求解策略以保证性能和收敛性。

对应代码段

mapPtr_->options.linear_solver_type           = ceres::SPARSE_SCHUR;
mapPtr_->options.trust_region_strategy_type   = ceres::DOGLEG;
mapPtr_->options.max_num_iterations           = 20;
mapPtr_->options.num_threads                  = 4;
mapPtr_->options.minimizer_progress_to_stdout = false;

阶段 5:调用 Solve 执行优化

主要内容

  • 触发底层 Problem::Solve(options, &summary),Ceres 会迭代地最小化所有残差平方和。

方法论

  • OKVIS 封装了一个 Estimator::optimize(...) 接口,内部调用 mapPtr_->solve()

目的

  • 联合优化所有 ParameterBlock 中的变量,实现多源信息融合的非线性最小二乘解。

对应代码段

void Estimator::optimize(size_t numIter, size_t numThreads, bool verbose) {// 设置并行线程数和迭代次数mapPtr_->options.num_threads           = numThreads;mapPtr_->options.max_num_iterations    = numIter;mapPtr_->options.minimizer_progress_to_stdout = verbose;// 真正调用 Ceres solvermapPtr_->solve();
}

阶段 6:提取并更新结果

主要内容

  • 优化完成后,从每个 ParameterBlock 中读取 .estimate(),并将结果回写到 SLAM / VIO 的状态中(位姿、速度-偏置、地图点等)。

方法论

  • 对 PoseParameterBlock,调用 OKVIS 的 estimator_.get_T_WS(...)
  • 对地标,通过 HomogeneousPointParameterBlock->estimate() 拿到最新坐标。

目的

  • 将优化后的值推送到系统其他模块(里程计输出、地图维护、回环检测、可视化等),完成一次优化闭环。

对应代码段

// 1. 更新当前帧位姿
okvis::kinematics::Transformation T_WS_opt;
estimator_.get_T_WS(frameId, T_WS_opt);// 2. 更新所有地图点
for (auto &kv : landmarksMap_) {uint64_t lmId = kv.first;auto pb = std::static_pointer_cast<okvis::ceres::HomogeneousPointParameterBlock>(mapPtr_->parameterBlockPtr(lmId));kv.second.point = pb->estimate();  // 新的 [x,y,z,1]
}

image-20250523101925044

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

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

相关文章

Python爬虫实战:研究PySpider框架相关技术

1. 引言 1.1 研究背景与意义 网络爬虫作为互联网数据采集的重要工具,在信息检索、舆情分析、市场调研等领域发挥着重要作用。随着互联网信息的爆炸式增长,如何高效、稳定地获取所需数据成为了一个关键挑战。PySpider 作为一款功能强大的 Python 爬虫框架,提供了丰富的功能…

《大模型开源与闭源的深度博弈:科技新生态下的权衡与抉择》

开源智能体大模型的核心魅力&#xff0c;在于它构建起了一个全球开发者共同参与的超级协作网络。想象一下&#xff0c;来自世界各个角落的开发者、研究者&#xff0c;无论身处繁华都市还是偏远小镇&#xff0c;只要心怀对技术的热爱与追求&#xff0c;就能加入到这场技术狂欢中…

大数据模型对陌生场景图像的识别能力研究 —— 以 DEEPSEEK 私有化部署模型为例

摘要 本研究聚焦于已训练的大数据模型能否识别未包含在样本数据集中的陌生场景图像这一问题&#xff0c;以 DEEPSEEK 私有化部署模型为研究对象&#xff0c;结合机器学习理论&#xff0c;分析模型识别陌生场景图像的影响因素&#xff0c;并通过理论探讨与实际应用场景分析&…

STM32——从点灯到传感器控制

STM32基础外设开发&#xff1a;从点灯到传感器控制 一、前言 本篇文章总结STM32F10x系列基础外设开发实例&#xff0c;涵盖GPIO控制、按键检测、传感器应用等。所有代码基于标准库开发&#xff0c;适合STM32初学者参考。 二、硬件准备 STM32F10x系列开发板LED模块有源蜂鸣器…

[特殊字符] 使用增量同步+MQ机制将用户数据同步到Elasticsearch

在开发用户搜索功能时&#xff0c;我们通常会将用户信息存储到 Elasticsearch&#xff08;简称 ES&#xff09; 中&#xff0c;以提高搜索效率。本篇文章将详细介绍我们是如何实现 MySQL 到 Elasticsearch 的增量同步&#xff0c;以及如何通过 MQ 消息队列实现用户信息实时更新…

MyBatis缓存机制全解析

在MyBatis中&#xff0c;缓存分为一级缓存和二级缓存&#xff0c;它们的主要目的是减少数据库的访问次数&#xff0c;提高查询效率。下面简述这两种缓存的工作原理&#xff1a; 一、 一级缓存&#xff08;SqlSession级别的缓存&#xff09; 一级缓存是MyBatis默认开启的缓存机…

【短距离通信】【WiFi】WiFi7关键技术之4096-QAM、MRU

目录 3. 4096-QAM 3.1 4096-QAM 3.2 QAM 的阶数越高越好吗&#xff1f; 4. MRU 4.1 OFDMA 和 RU 4.2 MRU 资源分配 3. 4096-QAM 摘要 本章主要介绍了Wi-Fi 7引入的4096-QAM对数据传输速率的提升。 3.1 4096-QAM 对速率的提升 Wi-Fi 标准一直致力于提升数据传输速率&a…

【二刷力扣】【力扣热题100】今天的题目是:283.移动零

题目&#xff1a; 给定一个数组 nums&#xff0c;编写一个函数将所有 0 移动到数组的末尾&#xff0c;同时保持非零元素的相对顺序。 请注意 &#xff0c;必须在不复制数组的情况下原地对数组进行操作。 示例 1: 输入: nums [0,1,0,3,12] 输出: [1,3,12,0,0] 示例 2: 输…

机器学习中的多GPU训练模式

文章目录 一、数据并行&#xff08;Data Parallelism&#xff09;二、模型并行&#xff08;Model Parallelism&#xff09;1. 模型并行2. 张量并行&#xff08;Tensor Parallelism&#xff09; 三、流水线并行&#xff08;Pipeline Parallelism&#xff09;四、混合并行&#x…

《JavaScript 性能优化:从原理到实战的全面指南》

《JavaScript 性能优化&#xff1a;从原理到实战的全面指南》 一、JavaScript 性能优化基础理论 在深入探讨 JavaScript 性能优化技术之前&#xff0c;我们需要明白JavaScript 的执行机制和性能瓶颈产生的根本原因。JavaScript 是一种单线程、非阻塞的脚本语言&#xff0c;其…

选择合适的Azure数据库监控工具

Azure云为组织提供了众多服务&#xff0c;使其能够无缝运行应用程序、Web服务和服务器部署&#xff0c;其中包括云端数据库部署。Azure数据库能够与云应用程序实现无缝集成&#xff0c;具备可靠、易扩展和易管理的特性&#xff0c;不仅能提升数据库可用性与性能&#xff0c;同时…

9.4在 VS Code 中配置 Maven

在 VS Code 中配置 Maven 需要完成 Maven 环境安装 一、安装 Maven&#xff08;如果未安装&#xff09; 下载 Maven 访问 Apache Maven 官网&#xff0c;下载最新版本的 Maven&#xff08;如apache-maven-3.9.9-bin.zip&#xff09;。 解压文件 将下载的 ZIP 文件解压到本地目…

影刀自动化流程复用技巧:流程复用

草莓时刻会创建一个新的空白流程。但是很多时候需要复用过往基础流程&#xff0c;在此基础上进行修改即可。而而不是重新创建基础流程。 为了解决这个问题&#xff0c;我们需要了解一下影刀流程的基础结构。 影刀流程基础结构概览 影刀自动化流程的基础结构主要包括几个关键组…

理论篇六:如何在Webpack中实现持久化缓存?

在 Webpack 中实现持久化缓存可以显著提升构建速度,尤其是在大型项目中。以下是 7 种核心策略 及其详细配置方法: 一、文件哈希命名(Content Hash) 确保文件内容变化时哈希值才改变,利用浏览器缓存。 // webpack.config.js output: {filename: [name].[contenthash:8].j…

C++单例模式与线程安全

C单例模式的线程安全实践与优化-CSDN博客 https://www.zhihu.com/question/56527586/answer/2344903391 C11中的单例模式 在C11及更高版本中&#xff0c;可以使用std::call_once和std::once_flag来确保单例实例的线程安全初始化。这种方法不需要显式地使用互斥锁&#xff0c…

UE5 图片导入,拖到UI上变色

UE5会自动把蓝色的图片当成法线贴图处理&#xff0c;非常傻逼 双击出问题的图片&#xff0c;右侧面板将压缩设置从法线改回默认

服务器安装xfce桌面环境并通过浏览器操控

最近需要运行某个浏览器的脚本&#xff0c;但是服务器没有桌面环境&#xff0c;无法使用&#xff0c;遂找到了KasmVNC&#xff0c;并配合xfce实现低占用的桌面环境&#xff0c;可以直接使用浏览器进行操作 本文基于雨云——新一代云服务提供商的Debian11服务器操作&#xff0c;…

Python函数全面解析:从基础到高级特性

文章目录 Python函数全面解析&#xff1a;从基础到高级特性一、函数基础概念1. 什么是函数&#xff1f;2. 函数的组成部分 二、函数的参数传递1. 参数类型对比2. 参数传递示例 三、函数的作用域作用域示例global和nonlocal关键字 四、函数的属性和方法1. 函数的特殊属性2. 函数…

Ubuntu20.04的安装(VMware)

1.Ubuntu20.04.iso文件下载 下载网址&#xff1a;ubuntu-releases-20.04安装包下载_开源镜像站-阿里云 2.创建虚拟环境 2.1打开VMware与创建新虚拟机 点击创建新虚拟机 如果没下好可以点击稍后安装操作系统 选择linux版本选择Ubuntu 64位然后点击下一步。 注意这里需要选择一…

Kafka 的日志清理策略:delete 和 compact

Kafka delete 日志清理策略&#xff08;日志删除&#xff09; 原理&#xff1a;按照一定保留策略&#xff0c;直接删除不符合条件的日志分段。Kafka 把 topic 的一个 partition 大文件分成多个小文件段&#xff0c;通过这种方式&#xff0c;能方便地定期清除或删除已消费完的文…