《视觉 SLAM 十四讲》V2 第 10 讲 后端优化2 简化BA 【位姿图】

news2024/12/23 2:02:59

在这里插入图片描述

文章目录

  • 第10讲 后端2
    • 10.1 滑动窗口滤波 和 优化
      • 10.1.2 滑动窗口法
    • 10.2 位姿图
    • 10.3 实践: 位姿图优化
          • 本讲 CMakeLists.txt
      • 10.3.1 g2o 原生位姿图 【Code】
      • 10.3.2 李代数上的位姿优化 【Code】
    • 习题10
      • 题1 【没推完】
    • LaTex

第10讲 后端2

滑动窗口优化
位姿图优化【简化的BA】
带IMU 紧耦合 的优化
g2o 的位姿图

第9讲 以BA为主的图优化。
BA能精确地优化每个相机位姿与特征点位置。
在大场景中,大量特征点 会严重降低计算效率,计算量越来越大 ——> 无法实时化。
改进: 简化BA 【位姿图】

10.1 滑动窗口滤波 和 优化

BA:带有相机位姿和空间点的图优化。

控制 BA 规模:仅保留 离当前时刻最近的 N 个关键帧。【滑动窗口法】

ORB-SLAM2 :
共视图(Covisibility graph) : 与现在的相机 存在共同观测的关键帧构成的图。

10.1.2 滑动窗口法

在这里插入图片描述
在这里插入图片描述
在这里插入图片描述
滑动窗口法 比较适合VO系统,不适合大规模建图系统。

10.2 位姿图

在这里插入图片描述

10.3 实践: 位姿图优化

本讲 CMakeLists.txt
cmake_minimum_required(VERSION 2.8)
project(pose_graph)

set(CMAKE_BUILD_TYPE "Release")
set(CMAKE_CXX_FLAGS "-std=c++17 -O2")

list(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)

# Eigen
include_directories("/usr/include/eigen3")


# sophus 
find_package(Sophus REQUIRED)
include_directories(${Sophus_INCLUDE_DIRS})


# g2o 
find_package(G2O REQUIRED)
include_directories(${G2O_INCLUDE_DIRS})

add_executable(pose_graph_g2o_SE3 pose_graph_g2o_SE3.cpp)
target_link_libraries(pose_graph_g2o_SE3
        g2o_core g2o_stuff g2o_types_slam3d ${CHOLMOD_LIBRARIES}
        )

SET(G2O_LIBS g2o_csparse_extension g2o_stuff g2o_core cxsparse)

add_executable(pose_graph_g2o_lie pose_graph_g2o_lie_algebra.cpp)
target_link_libraries(pose_graph_g2o_lie
        ${G2O_LIBS}
        ${CHOLMOD_LIBRARIES}
        ${Sophus_LIBRARIES})

——————————
改动1:
SE3d 和 SO3d 去掉d

改动2:
CMakeLists.txt 加这一句 使满足 C++17标准, 最新版 g2o 需要

改动3: CMakeLists.txt 添加 csparse 相关的链接库

在这里插入图片描述

    std::unique_ptr<g2o::BlockSolverX::LinearSolverType> linearSolver (new g2o::LinearSolverEigen<g2o::BlockSolverX::PoseMatrixType>()); // 这里直接用 前面提到的Eigen 线性方程求解库 也可以

    std::unique_ptr<g2o::BlockSolverX> solver_ptr (new g2o::BlockSolverX(std::move(linearSolver)));
    g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(solver_ptr));

10.3.1 g2o 原生位姿图 【Code】

查看待优化的位姿图。注意在文件sphere.g2o所在文件夹打开命令行窗口。

g2o_viewer sphere.g2o   

在这里插入图片描述

mkdir build && cd build
cmake ..
make 
./pose_graph_g2o_SE3 ../sphere.g2o
g2o_viewer result.g2o

在这里插入图片描述
在这里插入图片描述
pose_graph_g2o_SE3.cpp

#include <iostream>
#include <fstream>
#include <string>

#include <g2o/types/slam3d/types_slam3d.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/optimization_algorithm_levenberg.h>
#include <g2o/solvers/eigen/linear_solver_eigen.h>

using namespace std;

/************************************************
 * 本程序演示如何用g2o solver进行位姿图优化
 * sphere.g2o是人工生成的一个Pose graph,我们来优化它。
 * 尽管可以直接通过load函数读取整个图,但我们还是自己来实现读取代码,以期获得更深刻的理解
 * 这里使用g2o/types/slam3d/中的SE3表示位姿,它实质上是四元数而非李代数.
 * **********************************************/

int main(int argc, char **argv) {
    if (argc != 2) {
        cout << "Usage: pose_graph_g2o_SE3 sphere.g2o" << endl;
        return 1;
    }
    ifstream fin(argv[1]);
    if (!fin) {
        cout << "file " << argv[1] << " does not exist." << endl;
        return 1;
    }

    // 设定g2o
   /*typedef g2o::BlockSolver<g2o::BlockSolverTraits<6, 6>> BlockSolverType;
    typedef g2o::LinearSolverEigen<BlockSolverType::PoseMatrixType> LinearSolverType;
    auto solver = new g2o::OptimizationAlgorithmLevenberg(
        g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));
*/ 
    std::unique_ptr<g2o::BlockSolverX::LinearSolverType> linearSolver (new g2o::LinearSolverEigen<g2o::BlockSolverX::PoseMatrixType>());

    std::unique_ptr<g2o::BlockSolverX> solver_ptr (new g2o::BlockSolverX(std::move(linearSolver)));
    g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(solver_ptr));

    g2o::SparseOptimizer optimizer;     // 图模型
    optimizer.setAlgorithm(solver);   // 设置求解器
    optimizer.setVerbose(true);       // 打开调试输出

    int vertexCnt = 0, edgeCnt = 0; // 顶点和边的数量
    while (!fin.eof()) {
        string name;
        fin >> name;
        if (name == "VERTEX_SE3:QUAT") {
            // SE3 顶点
            g2o::VertexSE3 *v = new g2o::VertexSE3();
            int index = 0;
            fin >> index;
            v->setId(index);
            v->read(fin);
            optimizer.addVertex(v);
            vertexCnt++;
            if (index == 0)
                v->setFixed(true);
        } else if (name == "EDGE_SE3:QUAT") {
            // SE3-SE3 边
            g2o::EdgeSE3 *e = new g2o::EdgeSE3();
            int idx1, idx2;     // 关联的两个顶点
            fin >> idx1 >> idx2;
            e->setId(edgeCnt++);
            e->setVertex(0, optimizer.vertices()[idx1]);
            e->setVertex(1, optimizer.vertices()[idx2]);
            e->read(fin);
            optimizer.addEdge(e);
        }
        if (!fin.good()) break;
    }

    cout << "read total " << vertexCnt << " vertices, " << edgeCnt << " edges." << endl;

    cout << "optimizing ..." << endl;
    optimizer.initializeOptimization();
    optimizer.optimize(30);

    cout << "saving optimization results ..." << endl;
    optimizer.save("result.g2o");

    return 0;
}

10.3.2 李代数上的位姿优化 【Code】

前端和后端 分开: 跟踪和建图

报错:

xixi@ubuntu:~/Downloads/slambook2-master/ch10/build$ ./pose_graph_g2o_lie ../sphere.g2o
Segmentation fault

在这里插入图片描述

./pose_graph_g2o_lie ../sphere.g2o
g2o_viewer result.g2o

在这里插入图片描述

pose_graph_g2o_lie_algebra.cpp

#include <iostream>
#include <fstream>
#include <string>
#include <Eigen/Core>

#include <g2o/core/base_vertex.h>
#include <g2o/core/base_binary_edge.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/optimization_algorithm_levenberg.h>
#include <g2o/solvers/eigen/linear_solver_eigen.h>

#include <sophus/se3.h>

using namespace std;
using namespace Eigen;
using Sophus::SE3;
using Sophus::SO3;

/************************************************
 * 本程序演示如何用g2o solver进行位姿图优化
 * sphere.g2o是人工生成的一个Pose graph,我们来优化它。
 * 尽管可以直接通过load函数读取整个图,但我们还是自己来实现读取代码,以期获得更深刻的理解
 * 本节使用李代数表达位姿图,节点和边的方式为自定义
 * **********************************************/

typedef Matrix<double, 6, 6> Matrix6d;

// 给定误差求J_R^{-1}的近似
Matrix6d JRInv(const SE3 &e) {
    Matrix6d J;
    J.block(0, 0, 3, 3) = SO3::hat(e.so3().log());
    J.block(0, 3, 3, 3) = SO3::hat(e.translation());
    J.block(3, 0, 3, 3) = Matrix3d::Zero(3, 3);
    J.block(3, 3, 3, 3) = SO3::hat(e.so3().log());
    // J = J * 0.5 + Matrix6d::Identity();
    J = Matrix6d::Identity();    // try Identity if you want
    return J;
}

// 李代数顶点
typedef Matrix<double, 6, 1> Vector6d;

class VertexSE3LieAlgebra : public g2o::BaseVertex<6, SE3> {
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW

    virtual bool read(istream &is) override {
        double data[7];
        for (int i = 0; i < 7; i++)
            is >> data[i];
        setEstimate(SE3(
            Quaterniond(data[6], data[3], data[4], data[5]),
            Vector3d(data[0], data[1], data[2])
        ));
        return true;
    }

    virtual bool write(ostream &os) const override {
        os << id() << " ";
        Quaterniond q = _estimate.unit_quaternion();
        os << _estimate.translation().transpose() << " ";
        os << q.coeffs()[0] << " " << q.coeffs()[1] << " " << q.coeffs()[2] << " " << q.coeffs()[3] << endl;
        return true;
    }

    virtual void setToOriginImpl() override {
        _estimate = SE3();
    }

    // 左乘更新
    virtual void oplusImpl(const double *update) override {
        Vector6d upd;
        upd << update[0], update[1], update[2], update[3], update[4], update[5];
        _estimate = SE3::exp(upd) * _estimate;
    }
};

// 两个李代数节点之边
class EdgeSE3LieAlgebra : public g2o::BaseBinaryEdge<6, SE3, VertexSE3LieAlgebra, VertexSE3LieAlgebra> {
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW

    virtual bool read(istream &is) override {
        double data[7];
        for (int i = 0; i < 7; i++)
            is >> data[i];
        Quaterniond q(data[6], data[3], data[4], data[5]);
        q.normalize();
        setMeasurement(SE3(q, Vector3d(data[0], data[1], data[2])));
        for (int i = 0; i < information().rows() && is.good(); i++)
            for (int j = i; j < information().cols() && is.good(); j++) {
                is >> information()(i, j);
                if (i != j)
                    information()(j, i) = information()(i, j);
            }
        return true;
    }

    virtual bool write(ostream &os) const override {
        VertexSE3LieAlgebra *v1 = static_cast<VertexSE3LieAlgebra *> (_vertices[0]);
        VertexSE3LieAlgebra *v2 = static_cast<VertexSE3LieAlgebra *> (_vertices[1]);
        os << v1->id() << " " << v2->id() << " ";
        SE3 m = _measurement;
        Eigen::Quaterniond q = m.unit_quaternion();
        os << m.translation().transpose() << " ";
        os << q.coeffs()[0] << " " << q.coeffs()[1] << " " << q.coeffs()[2] << " " << q.coeffs()[3] << " ";

        // information matrix 
        for (int i = 0; i < information().rows(); i++)
            for (int j = i; j < information().cols(); j++) {
                os << information()(i, j) << " ";
            }
        os << endl;
        return true;
    }

    // 误差计算与书中推导一致
    virtual void computeError() override {
        SE3 v1 = (static_cast<VertexSE3LieAlgebra *> (_vertices[0]))->estimate();
        SE3 v2 = (static_cast<VertexSE3LieAlgebra *> (_vertices[1]))->estimate();
        _error = (_measurement.inverse() * v1.inverse() * v2).log();
    }

    // 雅可比计算
    virtual void linearizeOplus() override {
        SE3 v1 = (static_cast<VertexSE3LieAlgebra *> (_vertices[0]))->estimate();
        SE3 v2 = (static_cast<VertexSE3LieAlgebra *> (_vertices[1]))->estimate();
        Matrix6d J = JRInv(SE3::exp(_error));
        // 尝试把J近似为I?
        _jacobianOplusXi = -J * v2.inverse().Adj();
        _jacobianOplusXj = J * v2.inverse().Adj();
    }
};

int main(int argc, char **argv) {
    if (argc != 2) {
        cout << "Usage: pose_graph_g2o_SE3_lie sphere.g2o" << endl;
        return 1;
    }
    ifstream fin(argv[1]);
    if (!fin) {
        cout << "file " << argv[1] << " does not exist." << endl;
        return 1;
    }

    // 设定g2o
    /*typedef g2o::BlockSolver<g2o::BlockSolverTraits<6, 6>> BlockSolverType;
    typedef g2o::LinearSolverEigen<BlockSolverType::PoseMatrixType> LinearSolverType;
    auto solver = new g2o::OptimizationAlgorithmLevenberg(
        g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));
    */
    std::unique_ptr<g2o::BlockSolverX::LinearSolverType> linearSolver (new g2o::LinearSolverEigen<g2o::BlockSolverX::PoseMatrixType>());

    std::unique_ptr<g2o::BlockSolverX> solver_ptr (new g2o::BlockSolverX(std::move(linearSolver)));
    g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(solver_ptr));

    g2o::SparseOptimizer optimizer;     // 图模型
    optimizer.setAlgorithm(solver);   // 设置求解器
    optimizer.setVerbose(true);       // 打开调试输出

    int vertexCnt = 0, edgeCnt = 0; // 顶点和边的数量

    vector<VertexSE3LieAlgebra *> vectices;
    vector<EdgeSE3LieAlgebra *> edges;
    while (!fin.eof()) {
        string name;
        fin >> name;
        if (name == "VERTEX_SE3:QUAT") {
            // 顶点
            VertexSE3LieAlgebra *v = new VertexSE3LieAlgebra();
            int index = 0;
            fin >> index;
            v->setId(index);
            v->read(fin);
            optimizer.addVertex(v);
            vertexCnt++;
            vectices.push_back(v);
            if (index == 0)
                v->setFixed(true);
        } else if (name == "EDGE_SE3:QUAT") {
            // SE3-SE3 边
            EdgeSE3LieAlgebra *e = new EdgeSE3LieAlgebra();
            int idx1, idx2;     // 关联的两个顶点
            fin >> idx1 >> idx2;
            e->setId(edgeCnt++);
            e->setVertex(0, optimizer.vertices()[idx1]);
            e->setVertex(1, optimizer.vertices()[idx2]);
            e->read(fin);
            optimizer.addEdge(e);
            edges.push_back(e);
        }
        if (!fin.good()) break;
    }

    cout << "read total " << vertexCnt << " vertices, " << edgeCnt << " edges." << endl;

    cout << "optimizing ..." << endl;
    optimizer.initializeOptimization();
    optimizer.optimize(30);

    cout << "saving optimization results ..." << endl;

    // 因为用了自定义顶点且没有向g2o注册,这里保存自己来实现
    // 伪装成 SE3 顶点和边,让 g2o_viewer 可以认出
    ofstream fout("result_lie.g2o");
    for (VertexSE3LieAlgebra *v:vectices) {
        fout << "VERTEX_SE3:QUAT ";
        v->write(fout);
    }
    for (EdgeSE3LieAlgebra *e:edges) {
        fout << "EDGE_SE3:QUAT ";
        e->write(fout);
    }
    fout.close();
    return 0;
}

习题10

在这里插入图片描述

题1 【没推完】

如果将位姿图中的误差定义为 Δ ξ i j = ξ i ∘ ξ j − 1 \Delta \bm{\xi}_{ij}=\bm{\xi}_{i} \circ \bm{\xi}^{-1}_{j} Δξij=ξiξj1 ,推导按照此定义的左乘扰动雅克比矩阵。

本题中 位姿图的误差定义为 Δ ξ i j = ξ i ∘ ξ j − 1 = ln ⁡ ( T i T j − 1 ) ∨ \Delta \bm{\xi}_{ij}=\bm{\xi}_{i} \circ \bm{\xi}^{-1}_{j}=\ln (\bm{T}_i\bm{T}_j^{-1})^{\vee} Δξij=ξiξj1=ln(TiTj1)

  • 和 P271 的定义区别在于 是第二个 求逆。这里是相对第 j j j 个位姿的坐标系进行位姿变化讨论
  • T \bm{T} T 对应的李代数为 ξ \bm{\xi} ξ
    在这里插入图片描述

对应的李群写法为: T j i = T i T j − 1 \bm{T}_{ji}=\bm{T}_i\bm{T}_j^{-1} Tji=TiTj1

构建误差 e i j \bm{e}_{ij} eij

  • 这样构建的误差理想下是0,因为 ln( I ) = 0 \bm{I})=\bm{0} I)=0。怎么感觉应该是下面这样的🤔

e i j = ln ⁡ ( T j i − 1 T i T j − 1 ) ∨ \bm{e}_{ij}=\ln (\bm{T}_{ji}^{-1}\bm{T}_i\bm{T}_j^{-1})^{\vee} eij=ln(Tji1TiTj1)
其中

T j i = T i T j − 1 \bm{T}_{ji}=\bm{T}_i\bm{T}_j^{-1} Tji=TiTj1
T j i − 1 T j i = T j i − 1 T i T j − 1 \bm{T}_{ji}^{-1}\bm{T}_{ji}=\bm{T}_{ji}^{-1}\bm{T}_i\bm{T}_j^{-1} Tji1Tji=Tji1TiTj1
I = T j i − 1 T i T j − 1 \bm{I}=\bm{T}_{ji}^{-1}\bm{T}_i\bm{T}_j^{-1} I=Tji1TiTj1
在这里插入图片描述在这里插入图片描述

ξ i \bm{\xi}_i ξi ξ j \bm{\xi}_j ξj 各一个左扰动

e ^ i j = ln ⁡ ( T j i − 1 exp ⁡ ( Δ ξ i ∧ ) T i ( exp ⁡ ( Δ ξ j ∧ ) T j ) − 1 ) ∨ = ln ⁡ ( T j i − 1 exp ⁡ ( Δ ξ i ∧ ) T i T j − 1 ( exp ⁡ ( Δ ξ j ∧ ) − 1 ) ∨ 由式 ( 10.7 ) = ln ⁡ ( T j i − 1 T i exp ⁡ ( ( A d ( T i − 1 ) Δ ξ i ) ∧ ) exp ⁡ ( ( − A d ( T j − 1 ) Δ ξ j ) ∧ ) T j − 1 ) ∨ = l n ( T j i − 1 T i T j − 1 exp ⁡ ( ( A d ( T i − 1 ) Δ ξ i ) ∧ ) exp ⁡ ( ( − A d ( T j − 1 ) Δ ξ j ) ∧ ) ) ∨ = l n ( exp ⁡ ( e i j ) exp ⁡ ( ( A d ( T i − 1 ) Δ ξ i ) ∧ ) exp ⁡ ( ( − A d ( T j − 1 ) Δ ξ j ) ∧ ) ) ∨ \begin{align*}\bm{\hat{e}}_{ij} &=\ln (\bm{T}_{ji}^{-1}\exp(\Delta \bm{\xi}_i^{\land})\bm{T}_i(\exp(\Delta \bm{\xi}_j^{\land})\bm{T}_j)^{-1})^{\vee} \\ &= \ln (\bm{T}_{ji}^{-1}\exp(\Delta \bm{\xi}_i^{\land})\bm{T}_i\bm{T}_j^{-1}(\exp(\Delta \bm{\xi}_j^{\land})^{-1})^{\vee} \\ & 由 式 (10.7) \\ &= \ln (\bm{T}_{ji}^{-1}\bm{T}_i\exp((\mathrm{Ad}(\bm{T}_i^{-1})\Delta \bm{\xi}_i)^{\land})\exp((\mathrm{-Ad}(\bm{T}_j^{-1})\Delta \bm{\xi}_j)^{\land})\bm{T}_j^{-1})^{\vee} \\ &= \mathrm{ln}(\bm{T}_{ji}^{-1}\bm{T}_i\bm{T}_j^{-1}\exp((\mathrm{Ad}(\bm{T}_i^{-1})\Delta \bm{\xi}_i)^{\land})\exp((\mathrm{-Ad}(\bm{T}_j^{-1})\Delta \bm{\xi}_j)^{\land}))^{\vee} \\ &= \mathrm{ln}(\exp(\bm{e}_{ij})\exp((\mathrm{Ad}(\bm{T}_i^{-1})\Delta \bm{\xi}_i)^{\land})\exp((\mathrm{-Ad}(\bm{T}_j^{-1})\Delta \bm{\xi}_j)^{\land}))^{\vee} \\ \end{align*} e^ij=ln(Tji1exp(Δξi)Ti(exp(Δξj)Tj)1)=ln(Tji1exp(Δξi)TiTj1(exp(Δξj)1)由式(10.7)=ln(Tji1Tiexp((Ad(Ti1)Δξi))exp((Ad(Tj1)Δξj))Tj1)=ln(Tji1TiTj1exp((Ad(Ti1)Δξi))exp((Ad(Tj1)Δξj)))=ln(exp(eij)exp((Ad(Ti1)Δξi))exp((Ad(Tj1)Δξj)))

在这里插入图片描述
在这里插入图片描述
在这里插入图片描述

由公式:
在这里插入图片描述
对于 T i \bm{T}_i Ti
l n ( exp ⁡ ( e i j ) exp ⁡ ( ( A d ( T i − 1 ) Δ ξ i ) ∧ ) exp ⁡ ( ( − A d ( T j − 1 ) Δ ξ j ) ∧ ) ) ∨ ≈ \mathrm{ln}(\exp(\bm{e}_{ij})\exp((\mathrm{Ad}(\bm{T}_i^{-1})\Delta \bm{\xi}_i)^{\land})\exp((\mathrm{-Ad}(\bm{T}_j^{-1})\Delta \bm{\xi}_j)^{\land}))^{\vee} \approx ln(exp(eij)exp((Ad(Ti1)Δξi))exp((Ad(Tj1)Δξj)))

LaTex

$\circ$

∘ \circ

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

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

相关文章

【iOS】使用单例封装通过AFNetworking实现的网络请求

这里写目录标题 前言单例封装网络请求1. 首先创建一个继承于NSObject的单例类&#xff0c;笔者这里以Manager对单例类进行命名&#xff0c;然后声明并实现单例类的初始化方法2.实现完单例的创建方法后我们即可通过AFNetworking中的GET方法进行网络请求3.在Controller文件中创建…

音频录制和处理软件 Audio Hijack mac中文版说明

Audio Hijack mac是一款功能强大的音频录制和处理软件&#xff0c;它可以帮助用户从各种来源捕获和处理音频。 首先&#xff0c;Audio Hijack具有灵活的音频捕获功能。它支持从多个来源录制音频&#xff0c;包括麦克风、应用程序、网络流媒体、硬件设备等等。你可以选择捕获整个…

2022最新版-李宏毅机器学习深度学习课程-P26 Recurrent Neural Network

RNN 应用场景&#xff1a;填满信息 把每个单词表示成一个向量的方法&#xff1a;独热向量 还有其他方法&#xff0c;比如&#xff1a;Word hashing 单词哈希 输入&#xff1a;单词输出&#xff1a;该单词属于哪一类的概率分布 由于输入是文字序列&#xff0c;这就产生了一个问…

云表|低代码开发崛起:重新定义企业级应用开发

低代码开发这个概念在近年来越来越受到人们的关注&#xff0c;市场对于低代码的需求也日益增长。据Gartner预测&#xff0c;到2025年&#xff0c;75&#xff05;的大型企业将使用至少四种低代码/无代码开发工具&#xff0c;用于IT应用开发和公民开发计划。 那么&#xff0c;为什…

新的 Work Node 如何加入 K8s 集群 - Kubeadm ?

Author&#xff1a;rab 1、新的 work node 节点安装 kubelet、kubeadm 添加 k8s 镜像源 cat <<EOF > /etc/yum.repos.d/kubernetes.repo [kubernetes] nameKubernetes baseurlhttps://mirrors.aliyun.com/kubernetes/yum/repos/kubernetes-el7-x86_64/ enabled1 gpgch…

基于FPGA的SPI读写M25P16 Flash芯片

文章目录 一、SPI协议简介1.1 SPI引脚1.2 时钟极性和时钟相位1.3 主从模式 二、Flash&#xff08;M25P16&#xff09;2.1 Flash简介2.2 M25P16芯片分析2.3 项目所用指令时序2.3.1 WREN&#xff08;06h&#xff09;2.3.2 RDID&#xff08;9Fh&#xff09;2.3.3 READ&#xff08;…

什么是著作权?对此你了解多少?(二)

上一篇&#xff0c;已经为大家介绍了著作权的概念、著作权的分类以及著作权的内容等相关基础性认识。那么著作权如何取得呢&#xff1f; 我国采取的自动取得原则&#xff0c;当作品创作完成后&#xff0c;只要符合法律上作品的条件&#xff0c;著作权就产生了。著作权人可以申请…

百分点科技受邀参加“一带一路”国际合作高峰论坛

10月17-18日&#xff0c;第三届“一带一路”国际合作高峰论坛在北京成功举行。作为新一代信息技术出海企业代表&#xff0c;百分点科技董事长兼CEO苏萌受邀出席高峰论坛开场活动——“一带一路”企业家大会&#xff0c;与来自82个国家和地区的企业或机构、有关国际组织、经济机…

ArmSoM-W3之RK3588 MPP环境配置

1. 简介 瑞芯微提供的媒体处理软件平台&#xff08;Media Process Platform&#xff0c;简称 MPP&#xff09;是适用于瑞芯微芯片系列的 通用媒体处理软件平台。该平台对应用软件屏蔽了芯片相关的复杂底层处理&#xff0c;其目的是为了屏蔽不 同芯片的差异&#xff0c;为使用者…

el-input: 把不符合正则校验的值动态清空,只保留符合的值

<el-input v-model"form.profit" placeholder"请输入授权专利新增利润" input"handleInput" clearable />/*** 不符合正则校验,清空*/const handleInput () > {if (form.value.profit) {if (!/^\d*\.?\d*$/.test(form.value.profit))…

Error- Loaded runtime CuDNN library: 8.0.4 but source was compiled with: 8.1.0.

运行tensorflow2.5训练代码之后会出现如下报错&#xff1a; Loaded runtime CuDNN library: 8.0.4 but source was compiled with: 8.1.0. CuDNN library needs to have matching major version and equal or higher minor version. If using a binary install, upgrade your…

es6(三)——常用es6(函数、数组、对象的扩展)

ES6的系列文章目录 第一章 Python 机器学习入门之pandas的使用 文章目录 ES6的系列文章目录0、数值的扩展一、函数的扩展1、函数的默认值2、函数的reset参数 二、数组的扩展1. 将对象转成数组的Array.from()2. 将对象转成数组的Array.from()3. 实例方法 find()&#xff0c;fin…

24.项目开发之量化交易抓取数据QuantTradeData(三)

后端业务&#xff1a;分页查询股票列表基础信息 需求说明 将来股票列表基础信息会在前端页面进行展示&#xff0c;成千上万条数据是不会一次性展示在页面的&#xff0c;而是分页展示。 环境搭建 pom.xml导入依赖 <dependency><groupId>com.github.pagehelper<…

文心大模型4.0开启测试申请,百度智能云为大模型落地五大需求提供最优解

写在前面 面向企业客户启动文心大模型4.0 API调用服务测试申请&#xff0c;服务超过17000家客户&#xff0c;在各行各业的近500个场景中进行大模型应用落地探索……自今年3月面世以来&#xff0c;百度智能云千帆大模型平台作为全球首个一站式企业级大模型平台&#xff0c;为业…

PS修改背景色,线框底图

1、打开图片&#xff0c;ctrlj复制一层 2、图像-调整-反相 3、ctrll调整色阶&#xff0c;将中间的色块向右移&#xff0c;灰色线和字体的会变黑

移动端签名组件封装 借用插件 vue-esign

目录 需求实现讲解工具 - 图片旋转、base64 转换为 file 对象组件封装组件全局注册组件使用效果展示 需求 移动端需要实现手机横屏手写签名并上传签名图片功能。 实现讲解 vue-esign 插件文档地址 https://www.npmjs.com/package/vue-esign SignCanvas 组件封装原理&#xff1a…

【数据结构】830+848真题易错题汇总(自用)

【数据结构】830848易错题汇总(10-23) 文章目录 【数据结构】830848易错题汇总(10-23)选择题填空题判断题简答题&#xff1a;应用题&#xff1a;算法填空题&#xff1a;算法设计题&#xff1a;(待补) 选择题 1、顺序栈 S 的 Pop(S, e)操作弹出元素 e&#xff0c;则下列(C )是正…

虹科分享 | 选择SAS还是NVMe?虹科网络基础带您一探究竟!

存储架构师需要通过确保他们选择的存储解决方案提供支持其生态系统所需的安全性、稳定性、可扩展性和管理特性来应对当今的业务挑战。当他们考虑采用新的存储技术时&#xff0c;在采用新技术之前&#xff0c;他们应该权衡和审查一些基本的考虑因素。新的存储协议不断进入市场&a…

Postman for Mac - 轻松进行API测试的利器

在当今的数字化时代&#xff0c;应用程序编程接口(API)已成为推动软件创新和互操作性的核心动力。API测试作为确保服务质量的重要一环&#xff0c;也越来越受到开发者的重视。其中&#xff0c;Postman作为一款极其流行的API测试工具&#xff0c;其简洁易用的界面和强大的功能&a…

美妆品牌如何有效利用软文推广引流获客

近年来随着美妆品牌的转型升级和居民消费观念的转变&#xff0c;美妆行业取得了更大发展空间&#xff0c;新产品不断涌现&#xff0c;消费者拥有更多选择&#xff0c;那么在竞争激烈的市场中美妆品牌如何才能突破重围&#xff0c;找出新的价值增长点呢&#xff1f; 一、 细分消…