从零开始搭二维激光SLAM --- Hector论文公式推导与相关代码解析

2023-10-29

这篇文章将带领大家推导一下hector slam论文中的公式.之后再对这部分公式对应的代码进行讲解下.

markdown打公式太费劲了,所以我用手写了.(懒) 然后csdn又限制了图片文件大小,我是照完照片又截图才传上来的,所以图片有点不清晰.

1 高斯牛顿法

首先借用 <视觉SLAM十四讲> 说明一下高斯牛顿法的思路.

高斯牛顿法首先将目标函数进行一阶泰勒展开,再经过公式推导,可以获得最优解的公式为 Δ x = H − 1 ∗ g \Delta x = H^{-1} * g Δx=H1g ,并且hessian矩阵可以通过 H = J T ∗ J H=J^T * J H=JTJ 的形式进行求解,免去了计算hessian矩阵的较大计算量.

请添加图片描述请添加图片描述
以上图片引自 <<视觉SLAM十四讲>> ,如有侵权请联系我进行删除.

2 公式推导

2.1 目标函数推导

目标函数的形式为

ξ ∗ = a r g m i n ( ∑ i = 1 N [ 1 − M ( S i ( ξ ) ) ] 2 ) \xi^*=argmin(\sum_{i=1}^N[1-M( S_i(\xi) ) ]^2) ξ=argmin(i=1N[1M(Si(ξ))]2)

代表当前这帧雷达数据占据地图的概率, M ( S i ( ξ ) ) M( S_i(\xi) ) M(Si(ξ)) 最大为1,最大值不好求,所以通过 1 − M ( S i ( ξ ) ) 1-M( S_i(\xi) ) 1M(Si(ξ)) 的方式求最小值.

首先,通过右加一个小量 Δ ξ \Delta\xi Δξ , 来使得公式趋近于零.

但是由于目标函数是非线性的,不能直接求导,所以根据高斯牛顿法的思路,先进行一阶泰勒展开,然后再进行求导.
在这里插入图片描述之后,进行左右项的变换.求得 Δ ξ = H − 1 ∗ g \Delta\xi = H^{-1} * g Δξ=H1g
在这里插入图片描述

2.2 求解

所以,接下来只需要求出 J ( ξ ) J(\xi) J(ξ) f ( ξ ) f(\xi) f(ξ) 就可以了.

只需分别求出 栅格值 M ( S i ( ξ ) ) M( S_i(\xi)) M(Si(ξ)) , 栅格的导数 ∇ M ( S i ( ξ ) ) \nabla M( S_i(\xi)) M(Si(ξ)), 激光点转换函数的导数 ∇ S i ( ξ ) \nabla S_i(\xi) Si(ξ),即可.

2.2.1 求激光点转换函数的导数

首先求 激光点转换函数的导数.
在这里插入图片描述
激光点转换函数S是个2*1维的矩阵,第一行是x坐标的转换公式,第二行是y坐标的转换公式.

所以求导时候 分别对第一行第二行,对 p x p_x px , p y p_y py , ψ \psi ψ 三个变量进行求导,将得到一个2*3的矩阵.
在这里插入图片描述

2.2.2 求栅格值 M ( S i ( ξ ) ) M( S_i(\xi)) M(Si(ξ))

点(x,y)的栅格值可以通过 这点周围相邻的4个栅格的栅格值 进行插值来表示.

公式是直接从论文里摘下来的,是通过 拉格朗日2次插值 来求的.
在这里插入图片描述

2.2.3 求栅格值的导数 ∇ M ( S i ( ξ ) ) \nabla M( S_i(\xi)) M(Si(ξ))

栅格值的导数是一个1*2的矩阵,是分别对x方向,y方向的导数.

公式是直接从论文里摘下来了,是通过栅格值分别对x与y求偏导得到的。

其中 y1-y0 = x1-x0=1,所以是如下形式。
在这里插入图片描述

2.2.4 求 J ( ξ ) J(\xi) J(ξ) f ( ξ ) f(\xi) f(ξ)

图片里求 J ( ξ ) J(\xi) J(ξ) 的最后一步时,对结果进行转置了, J ( ξ ) J(\xi) J(ξ) 是一个 1*3 的矩阵.
在这里插入图片描述

2.2.5 求 H e s s i a n Hessian Hessian矩阵

在这里插入图片描述

3 相关代码讲解

3.1 getCompleteHessianDerivs()

这个函数位于 Creating-2D-laser-slam-from-scratch/lesson4/include/lesson4/hector_mapping/map/OccGridMapUtil.h 内.

代码的实现和公式一模一样,唯一的区别就是公式里的求和符合在代码里变成了累加。

    /**
     * 使用当前pose投影dataPoints到地图,计算出 H 矩阵 b列向量, 理论部分详见Hector论文: 《A Flexible and Scalable SLAM System with Full 3D Motion Estimation》.
     * @param pose    地图系上的位姿
     * @param dataPoints  已转换为地图尺度的激光点数据
     * @param H   需要计算的 H矩阵
     * @param dTr  需要计算的 g列向量
     */
    void getCompleteHessianDerivs(const Eigen::Vector3f &pose,
                                  const DataContainer &dataPoints,
                                  Eigen::Matrix3f &H,
                                  Eigen::Vector3f &dTr)
    {
        int size = dataPoints.getSize();

        // 获取变换矩阵
        Eigen::Affine2f transform(getTransformForState(pose));

        float sinRot = sin(pose[2]);
        float cosRot = cos(pose[2]);

        H = Eigen::Matrix3f::Zero();
        dTr = Eigen::Vector3f::Zero();

        // 按照公式计算H、b
        for (int i = 0; i < size; ++i)
        {
            // 地图尺度下的激光坐标系下的激光点坐标
            const Eigen::Vector2f &currPoint(dataPoints.getVecEntry(i));

            // 将激光点坐标转换到地图系上, 通过双线性插值计算栅格概率
            // transformedPointData[0]--通过插值得到的栅格值
            // transformedPointData[1]--栅格值x方向的梯度
            // transformedPointData[2]--栅格值y方向的梯度
            Eigen::Vector3f transformedPointData(interpMapValueWithDerivatives(transform * currPoint));

            // 目标函数f(x)  (1-M(Pm))
            float funVal = 1.0f - transformedPointData[0];

            // 计算g列向量的 x 与 y 方向的值
            dTr[0] += transformedPointData[1] * funVal;
            dTr[1] += transformedPointData[2] * funVal;

            // 根据公式计算
            float rotDeriv = ((-sinRot * currPoint.x() - cosRot * currPoint.y()) * transformedPointData[1] +
                              (cosRot * currPoint.x() - sinRot * currPoint.y()) * transformedPointData[2]);
            // 计算g列向量的 角度 的值
            dTr[2] += rotDeriv * funVal;

            // 计算 hessian 矩阵
            H(0, 0) += util::sqr(transformedPointData[1]);
            H(1, 1) += util::sqr(transformedPointData[2]);
            H(2, 2) += util::sqr(rotDeriv);

            H(0, 1) += transformedPointData[1] * transformedPointData[2];
            H(0, 2) += transformedPointData[1] * rotDeriv;
            H(1, 2) += transformedPointData[2] * rotDeriv;
        }

        // H是对称矩阵,只算上三角就行, 减少计算量。
        H(1, 0) = H(0, 1);
        H(2, 0) = H(0, 2);
        H(2, 1) = H(1, 2);
    }

3.2 interpMapValueWithDerivatives()

这个函数位于 Creating-2D-laser-slam-from-scratch/lesson4/include/lesson4/hector_mapping/map/OccGridMapUtil.h 内.

取相邻4点的栅格值时用了一个cache函数,这块感觉实现的不好,可能这里就是导致地图变大时hector计算时间变长的原因。

    /**
     * 双线性插值计算网格中任一点的得分(占据概率)以及该点处的梯度
     * @param coords  激光点地图坐标
     * @return ret(0) 是网格值 , ret(1) 是栅格值在x方向的导数 , ret(2)是栅格值在y方向的导数
     */
    Eigen::Vector3f interpMapValueWithDerivatives(const Eigen::Vector2f &coords)
    {
        // 检查coords坐标是否是在地图坐标范围内
        if (concreteGridMap->pointOutOfMapBounds(coords))
        {
            return Eigen::Vector3f(0.0f, 0.0f, 0.0f);
        }

        // 对坐标进行向下取整,即得到坐标(x0,y0)
        Eigen::Vector2i indMin(coords.cast<int>());

        // 得到双线性插值的因子
        // | x |   | x0 |   | x-x0 |
        // |   | - |    | = |      |
        // | y |   | y0 |   | y-y0 |
        Eigen::Vector2f factors(coords - indMin.cast<float>());

        // 获得地图的X方向最大边界
        int sizeX = concreteGridMap->getSizeX();

        // 计算(x0, y0)点的网格索引值
        int index = indMin[1] * sizeX + indMin[0]; 

        // 下边这取4个点的栅格值,感觉就是导致hector大地图后计算变慢的原因

        /** 首先判断cache中该地图点在本次scan中是否被访问过,若有则直接取值;没有则立马计算概率值并更新到cache **/
        /** 这个cache的作用是,避免单次scan重复访问同一网格时带来的重复概率计算。地图更新后,网格logocc改变,cache数据就会无效。 **/
        /** 但是这种方式内存开销太大..相当于同时维护两份地图,使用 hash map 是不是会更合适些 **/
        if (!cacheMethod.containsCachedData(index, intensities[0]))
        {
            intensities[0] = getUnfilteredGridPoint(index); // 得到M(P00),P00(x0,y0)
            cacheMethod.cacheData(index, intensities[0]);
        }

        ++index;
        if (!cacheMethod.containsCachedData(index, intensities[1]))
        {
            intensities[1] = getUnfilteredGridPoint(index);
            cacheMethod.cacheData(index, intensities[1]);
        }

        index += sizeX - 1;
        if (!cacheMethod.containsCachedData(index, intensities[2]))
        {
            intensities[2] = getUnfilteredGridPoint(index);
            cacheMethod.cacheData(index, intensities[2]);
        }

        ++index;
        if (!cacheMethod.containsCachedData(index, intensities[3]))
        {
            intensities[3] = getUnfilteredGridPoint(index);
            cacheMethod.cacheData(index, intensities[3]);
        }

        float dx1 = intensities[0] - intensities[1]; // 求得(M(P00) - M(P10))的值
        float dx2 = intensities[2] - intensities[3]; // 求得(M(P01) - M(P11))的值

        float dy1 = intensities[0] - intensities[2]; // 求得(M(P00) - M(P01))的值
        float dy2 = intensities[1] - intensities[3]; // 求得(M(P10) - M(P11))的值

        // 得到双线性插值的因子,注意x0+1=x1,y0+1=y1,则
        //     | x-x0 |   | 1-x+x0 |   | x1-x |
        // 1 - |      | = |        | = |      |
        //     | y-y0 |   | 1-y+y0 |   | y1-x |
        float xFacInv = (1.0f - factors[0]); // 求得(x1-x)的值
        float yFacInv = (1.0f - factors[1]); // 求得(y1-y)的值

        //         y-y0 | x-x0            x1-x        |    y1-y | x-x0            x1-x        |
        // M(Pm) = ------|------ M(P11) + ------ M(P01)| + ------|------ M(P10) + ------ M(P00)|
        //         y1-y0| x1-x0           x1-x0       |    y1-y0| x1-x0           x1-x0       |
        // 注意:此处y1-y0=x1-x0=1,那么对应函数返回值,可以写成
        // M(Pm) = (M(P00) * (x1-x) + M(P10) * (x-x0)) * (y1-y) + (M(P01) * (x1-x) + M(P11) * (x-x0)) * (y-y0)

        // d(M(Pm))     y-y0 |                |    y1-y |                |
        // ---------- = ------| M(P11) - M(P01)| + ------| M(P10) - M(P00)|
        //    dx        y1-y0|                |    y1-y0|                |
        // 同理,化简可得 d(M(Pm))/dx = -((M(P00) - M(P10)) * (y1-y) + (M(P01) - M(P11)) * (y-y0))
        // 同样地,也有   d(M(Pm))/dy = -((M(P00) - M(P01)) * (x1-x) + (M(P10) - M(P11)) * (x-x0))

        // 计算网格值,计算梯度 --- 原版这里的dx、dy的计算有错误,已经改过来了
        return Eigen::Vector3f(
            ((intensities[0] * xFacInv + intensities[1] * factors[0]) * (yFacInv)) +
                ((intensities[2] * xFacInv + intensities[3] * factors[0]) * (factors[1])),
            -((dx1 * yFacInv) + (dx2 * factors[1])),
            -((dy1 * xFacInv) + (dy2 * factors[0]))
            // -((dx1 * xFacInv) + (dx2 * factors[0])), // 应该为: -((dx1 * yFacInv) + (dx2 * factors[1]))
            // -((dy1 * yFacInv) + (dy2 * factors[1]))  // 应该为: -((dy1 * xFacInv) + (dy2 * factors[0]))
        );
    }

4 实验

将 2.2 节中的 cacheMethod 相关语句都注释掉,发现同样跑完数据包时,注释掉 cacheMethod 后最终 odom_hector 的频率是9.249hz ,而没有注释时最终 odom_hector 的频率是8.571hz ,可见这块确实会导致时间增长.

原因猜测是本来只需要计算4次网格值就行了,现在还有在cache中进行查找,如果数据量太大的情况下查找的时间将比直接计算4次网格值的时间要大.

虽然频率确实下降的少了,但是还是下降了,应该是还有别的原因导致计算时间变长.

5 总结与思考

5.1 总结

通过三篇文章对hector进行了讲解。

第一篇文章讲了hector的地图是如何构建的,第二篇文章讲了hector是如何进行slam的,第三篇文章讲了hector论文的公式推导以及公式对应的代码的讲解。

虽然成功的构建出了地图,但是还是有几点不足的。

  • 首先就是hector的计算太慢了,只进行扫描匹配的操作就要花费大概0.1秒钟,这就导致即使雷达频率再高,hector也处理不过来
  • 还有就是hector的地图不能自动更改大小,地图的大小在初始化之后始终是固定的
  • hector中获取栅格点时使用了cache,这块实现的不是特别好
  • hector中维护的始终是一张地图,有时会出现地图被错误更新之后再也恢复不了的情况

5.2 思考

gmapping与hector维护地图的方式不同.

gmapping的维护地图是通过保存下来的位姿与相应的雷达数据,每次发布的地图都是新生成的地图,将所有的保存的雷达数据写成地图。

hector的维护地图是在初始化阶段时只初始化一张地图,然后使用新的雷达数据对这张地图进行更新与维护。

这就导致,如果某时刻的雷达点出现了偏差,将未知区域更新成空闲区域了,而如果之后不出现偏差的话,这块空闲地图再也不会被更新了,也不会变成未知区域了。

也就是上一篇地图中走廊两边的墙内区域还有一些白色区域,这块的白色区域就不会被更新,也就是不会消失,不会再变成未知区域。

这点就是始终维护一张地图不好的地方。但是,如果这帧偏离的激光数据被gmapping保存下来了,那接下来gmapping生成的地图也始终会存在这一块区域。

6 NEXT

hector其实还可以做很多改进,如将里程计或者imu加进来做位姿预测,地图大小可以动态更新,计算地图这可以使用ceres库等等。

github上有人对hector的高斯牛顿这的代码做了改进,使用ceres库进行计算,感兴趣的可以在github上搜索 hector_slam_Ceres 查看代码。

由于后边还有karto与cartographer这些更优秀的项目等着我,所以我就不对hector再进行研究了。

接下来的文章将开始使用里程计,首先简单讲解下里程计,之后对激光雷达数据进行畸变校正处理。

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

从零开始搭二维激光SLAM --- Hector论文公式推导与相关代码解析 的相关文章

  • 微信小程序SLAM AR零基础入门教程

    鬼灭之刃花街篇 开播在即 今天带大家零基础使用Kivicube制作一个炭治郎的SLAM AR云手办 可以通过微信小程序将AR版的炭治郎放置在家中 提前感受鬼灭的氛围 先上个GIF大家看看动态的展示效果 在这里先科普一下本次教程使用到的AR技
  • No rule to make target

    No rule to make target 引言 解决方法 引言 报错 No rule to make target Thirdparty g2o lib libg2o so needed by lib libygz SLAM so 停止
  • ubuntu系统下配置vscode编译cmake

    文章目录 一 配置vs code运行c 代码 三个关键文件介绍 1 tasks json run helloworld cpp 1 1 打开cpp文件 使其成为活动文件 1 2 按编辑器右上角的播放按钮 1 3生成task文件 1 4 此时
  • 各向异性(anisotropic)浅提

    文章目录 各向异性 anisotropic 定义 哪种物体具有各向异性反射 什么导致各向异性反射 总结 各向异性 anisotropic 定义 它指一种存在方向依赖性 这意味着在不同的方向不同的特性 相对于该属性各向同性 当沿不同轴测量时
  • 速腾聚创雷达最新驱动安装(包含ring和timestamp)运行lio-sam

    记录一下搞slam的过程 ring和timestamp 最近想跑lio sam 需要用到ring和timestamp两个参数 lio sam作者用的velodyne雷达是带这两个参数的 但是rs雷达的老版驱动录制的点云包没有这两个参数 在g
  • [SLAM四元数基础系列一] 四元数定义 Hamilton vs JPL

    四元数定义 Hamilton vs JPL 简介 四种区分方式 Hamilton vs JPL 引用 不管是卡尔曼滤波或者BA优化形式的SLAM或者VIO系统中 都需要用到单位四元数 Quaternion 来表示旋转 主要是单位四元数表示旋
  • ORB-SLAM2:基于可识别特征的自主导航与地图构建

    目录 ORB SLAM2 基于可识别特征的自主导航与地图构建 简介 地图 A 地图特征点或3D ORB B 关键帧 C 可视化图像 位置识别 A 图像识别数据库 B 高效优化的ORB匹配 C 视觉一致性 自主导航追踪 A ORB特征获取 B
  • docker dbus-x11

    本来想用terminator启动nvidia docker 显示出图形界面的 结果发现启动的时候出问题了 terminator 1 dbind WARNING 07 31 53 725 Couldn t connect to accessi
  • 舒尔补-边际概率-条件概率

    margin求边际概率的时候喜欢通过舒尔补的形式去操作信息矩阵 如p b c 求积分p a b c da 从上图可知 边缘概率直接看协方差矩阵比较方便 边际概率的方差就是取对应联合分布中相应的协方差块 信息矩阵是由舒尔补的形式计算 此形式也
  • Ubuntu18.04安装pcl(过程/坑记录式教程)

    Ubuntu18 04安装pcl 1 下载pcl 2 安装依赖项 3 编译 4 安装 5 网上教程说要安装QT5和VTK 但按照本文的 本文记录了安装时出现的问题 出错的安装命令也记录了 建议浏览一遍再参考 不要错用了错误的指令 1 下载p
  • ORB-SLAM2:基于可识别特征的自主导航与地图构建

    ORB SLAM2 基于可识别特征的自主导航与地图构建 ORB SLAM Tracking and Mapping Recognizable Features 转自 http blog csdn net cicibabe article d
  • BLAM跑自己的数据包无法显示全局点云地图解决(速腾聚创RS-LiDAR-16 雷达 )-SLAM不学无术小问题

    BLAM算法跑自己的数据包无法显示全局点云地图解决 适配速腾聚创RS LiDAR 16 雷达 提示 本文笔者使用环境Ubuntu18 04 ROS melodic版本 首先放一个效果链接 由b站up VladimirDuan上传 非官方 官
  • SLAM练习题(十一)—— G2O实战

    SLAM 学习笔记 写在前面的话 算是一点小小的感悟吧 估计位姿的方法有线性方法和非线性方法 线性方法就是特征点法中的2D 2D的对极约束 3D 2D的PnP问题 非线性方法有BA优化 它将位姿的估计问题转换成了一个误差关于优化量的最小二乘
  • Ubuntu18.04安装Autoware1.15(解决Openplanner无法绕障的问题:Openplanner2.5)

    文章目录 一 下载Autoware1 15源码 二 安装依赖 三 修改CUDA版本 四 编译以及报错解决 编译 1 报 undefined reference to cv Mat Mat 的错就按照下面方式改相应包 2 遇到OpenCV的C
  • 什么是深度学习的无监督学习与有监督学习

    无监督学习 深度学习中的无监督学习方法是一种训练算法 它在没有标注输出的情况下从输入数据中学习模式和特征 这种方法的核心是探索和理解数据的内在结构和分布 而不是通过已知的输出来指导学习过程 无监督学习在深度学习领域有许多不同的形式和应用 以
  • 高翔博士Faster-LIO论文和算法解析

    说明 题目 Faster LIO 快速激光IMU里程计 参考链接 Faster LIO 快速激光IMU里程计 iVox Faster Lio 智行者高博团队开源的增量式稀疏体素结构 Faster Lio是高翔博士在Fast系列的新作 对标基
  • Hector 是否提供 API 来支持复合密钥?

    现在 我必须通过将子项格式化在一起来手动生成复合键 它很丑陋而且效率低下 我想知道 Hector 是否提供了这样一组 API 来以更体面的方式处理复合键 是的 它确实 您可以查看 DynamicCompositeTest 的示例 https
  • 针对单个客户端请求并行多个数据库查询

    为了完成用户的某些请求 在我的应用程序中 我从单个方法发出多个数据库查询 但它们当前正在按顺序执行 因此应用程序被阻止 直到它收到前一个查询的响应 数据 然后继续下一个查询 这不是我很喜欢的事情 我想发出并行查询 另外 在发出查询之后 我想
  • 如何从 Cassandra 获取排序计数器

    我有一排计数器 我想让它的列按值排序 有什么策略或数据模型吗 恐怕没有办法让 Cassandra 为你做这件事 您需要从 Cassandra 获取整行 对大行进行分页 并在客户端中对其进行排序 如果您的解决方案可以处理非最新结果 您可以使用
  • Hector (Cassandra) 删除异常

    当我尝试删除时使用 hector cassandra 客户端 它会删除列 但将行键留在后面 有谁知道为什么 以及如何删除该行键 使用 Cassandra 时这是预期的 由于它通过写入逻辑删除来删除 因此数据仍然存在 直到下一次压缩 最终它会

随机推荐

  • HTML——列表标签

    使用场景 在网页中按照行展示关联性的内容 如 新闻列表 排行榜 账单等 特点 按照行的方式 整齐显示内容 种类 无序列表 有序列表 自定义列表 1 无序列表 ul 标签表示 HTML 页面中项目的无序列表 一般会以项目符号呈现列表项 而列表
  • Matlab实现支持向量机算法(附上多个完整仿真源码)

    支持向量机是一种常见的机器学习算法 它可以用于分类和回归问题 在Matlab中使用支持向量机 可以方便地构建和训练模型 并进行预测和评估 本文将介绍Matlab支持向量机的基本原理以及一个简单的分类案例 文章目录 1 支持向量机的基本原理
  • 华为网络工程师虚拟服务器软件,软考网络工程师华为、思科指令大全

    原标题 软考网络工程师华为 思科指令大全 华为命令大全 一 配置交换机的名称和密文密码 用户视图 system view 进入系统视图配置 Huawei 系统视图 Huawei quit 或 return 退出系统视图模式 Huawei s
  • 如何在完成css路由跳转动画样式的同时完成umi路由鉴权?

    具体解决步骤 1 在src的目录下 和page同级 新建一个wrappers文件夹 这个名称是固定的 在文件夹下新建 Auth tsx文件 2 在文件里面的写入以下内容 import Redirect from umi export def
  • SpringBoot 中 @SpringBootApplication注解背后的三体结构探秘

    概 述 SpringBoot 约定大于配置 的功力让我们如沐春风 在我之前写的文章 从SpringBoot到SpringMVC 也对比过 SpringBoot 和 SpringMVC 这两个框架 不过最终 SpringBoot 以超高的代码
  • 计算机网络 : 综合实验

    打算稍微做一下实验课程的回顾 话不多说 正文开始 期末周的好同志就是这么单刀直入 综合实验 实验目的和要求 实验图 实验原理 实验仪器设备 实验步骤 过程数据记录 实验结果分析与总结 实验目的和要求 了解路由协议的作用 学习动态路由协议的工
  • c++语言所有函数都是外部函数.,简单讲解C++的内部和外部函数以及宏的定义

    C 内部函数和外部函数 函数本质上是全局的 因为一个函数要被另外的函数调用 但是 也可以指定函数只能被本文件调用 而不能被其他文件调用 根据函数能否被其他源文件调用 将函数区分为内部函数和外部函数 内部函数 如果一个函数只能被本文件中其他函
  • Servlet容器(Web容器)是什么

    Servlet 容器就是 Servlet 代码的运行环境 实现 Servlet 规范定义的各种接口和类 因为是基于 Java 语言的 运行必然少不了 JRE 的支持 这样的能运行Servlet 代码的就是Servlet容器 tomcat容器
  • jmeter基础使用方法

    文章目录 一 配置环境变量 二 Jmeter默认语言设置 三 启动 线程组的创建 发送http请求 数据报告 一 配置环境变量 设置JMETER HOME 及jemeter解压目录 设置CLASSPATH 此处分别配置ApacheJMete
  • 【一文清晰】单元测试到底是什么?应该怎么做?

    我是java程序员出身 后来因为工作原因转到到了测试开发岗位 测试开发工作很多年后 现在是一名自由职业者 1 什么是单元测试 2 该怎么做单元测试 一 什么是单元测试 单元测试 unit testing 是指对软件中的最小可测试单元进行检查
  • 网络工程师(中级)知识点记录

    软考中级网络工程师大纲地址 链接 https pan baidu com s 1vqKdtA9CeMxozXwLetQp8A 提取码 pbb6 内容还挺全的 可以拿来当做学习知识点用 1 现代的计算机网络是从 1969年美国国防部的ARPA
  • sql 统计查询(按月统计)

    String 类型 转化为 年月日 yyyy mm dd to date substr t submit time 1 10 如果统计一年 需要用 left join select level mymonth from dualconnec
  • opencv报错【warn】 global....... imread(

    检查你的输入依赖 debug用带d结尾的lib release用不带d的 把多余的删掉即可
  • C语言小游戏:猜数字小游戏(猜1-100的数字)

    初学c语言循环部分的萌新可以看看 内含有详细讲解 试着自己去理解会有很大帮助 include
  • 基于MATLAB的指纹识别算法仿真实现

    FPGA教程目录 MATLAB教程目录 目录 一 理论基础 二 核心程序 三 测试结果 一 理论基础 在指纹图像预处理部分 论文对预处理的各个步骤包括规格化 图像分割 中值滤波 二值化 细化等以及各个步骤的方法进行了深入的分析和研究 选择了
  • MySQL数据库实现本地数据库和远程服务器数据库数据同步

    项目中有两个数据库 本地数据库和远程服务器数据库 数据要在本地经过数据洗涤后才传上服务器数据库 之前用的Navicat工具 但是速度慢 且无法设置定时同步 后来改用Datax 它的效率真的非常高 DataX 是阿里巴巴集团内被广泛使用的离线
  • 大语言模型未来会是数据工程吗

    作者 养生的控制人 整理 NewBeeNLP https zhuanlan zhihu com p 654959483 大家好 这里是 NewBeeNLP 分享符尧博士关于大语言模型的数据工程方面的一些见解 原文链接 1 take home
  • Docker基础篇6:Dockerfile指令(1)

    1 Dockerfile指令 1 FROM指令 构建的新镜像是基于那个镜像 例如 FROM centos 7 2 MAINTAINER指令 镜像维护者姓名或者邮件地址 3 RUN指令 构建镜像时运行的shell命令 写法一 RUN yum
  • vue 获取 指定元素的高度宽度等(使用vue中的 ref 获取到的是 dom 元素高度或者宽度)

    使用 vue 的时候 想要获得一个指定的元素的高度时 可以使用 vue 中的 ref 当 ref 加在普通的元素上 使用 this ref name 获取到的是 dom 元素 示例 写在 页面 html 部分的 div div 写在 页面
  • 从零开始搭二维激光SLAM --- Hector论文公式推导与相关代码解析

    这篇文章将带领大家推导一下hector slam论文中的公式 之后再对这部分公式对应的代码进行讲解下 markdown打公式太费劲了 所以我用手写了 懒 然后csdn又限制了图片文件大小 我是照完照片又截图才传上来的 所以图片有点不清晰 1