Ceres用法及Ceres-Sophus在位姿图优化问题的应用

2023-05-16

(一)Ceres-Solver的一般用法

简述:

Ceres Solver is an open source C++ library for modeling and solving large, complicated optimization problems.

使用 Ceres Solver 求解非线性优化问题,主要包括以下几部分:

  • 构建代价函数(cost function)或残差(residual)
  • 构建优化问题(ceres::Problem):通过 AddResidualBlock 添加代价函数(cost function)、损失函数(loss function核函数) 和 待优化状态量
  • 配置求解器(ceres::Solver::Options)
  • 运行求解器(ceres::Solve(options, &problem, &summary))

注意:与g2o优化中直接在边上添加information(信息矩阵)不同,Ceres无法直接实现此功能。由于Ceres只接受最小二乘优化就,即min(r^{^{T}}r);若要对残差加权,使用马氏距离即min (r^{^{T}}\Sigma r),则要对信息矩阵(协方差矩阵)\Sigma做Cholesky分解:LL^{^{T}}=\Sigma,则r^{^{T}}\Sigma r=r^{^{T}}(LL^{^{T}})r=(L^{^{T}}r)^{T}(L^{T}r),令r'=L^{T}r,最终得到纯种的最小二乘优化:min(r'^{^{T}}r')

Ceres优化步骤:

Step1:构建Cost Function

(1)AutoDiffCostFunction(自动求导)

  • 构造 代价函数结构体或代价函数类(例如:struct CostFunctor),在其结构体内对模板括号() 重载用来定义残差;
  • 在重载的 () 函数形参中,最后一个为残差,前面几个为待优化状态量,注意:形参类型必须是模板类型。
struct CostFunctor {
    template<typename T>
    bool operator()(const T *const x, T *residual) const {
        residual[0] = 10.0 - x[0]; // r(x) = 10 - x
        return true;
    }
};
  • 利用ceres::CostFunction *cost_function=new ceres::AutoDiffCostFunction<functype,dimension1,dimension2>(new costFunc),获得Cost Function

模板参数分别是:代价结构体仿函数类型名,残差维度,第一个优化变量维度,第二个....;函数参数(new costFunc)是代价结构体(或类)对象,即此对象重载的 () 函数的函数指针

(2)NumericDiffCostFunction(数值求导)

  • 数值求导法 也是构造 代价函数结构体,也需要重载括号()来定义残差,但在重载括号() 时没有用模板; 
struct CostFunctorNum {
    bool operator()(const double *const x, double *residual) const {
        residual[0] = 10.0 - x[0]; // r(x) = 10 - x
        return true;
    }
};
  • 并且在实例化代价函数时也稍微有点区别,多了一个模板参数 ceres::CENTRAL
ceres::CostFunction *cost_function;
cost_function =new ceres::NumericDiffCostFunction<CostFunctorNum, ceres::CENTRAL, 1, 1>(new CostFunctorNum);

(3)自定义CostFunction

  • 构建一个 继承自 ceres::SizedCostFunction<1,1> 的类,同样,对于模板参数的数字,第一个为残差的维度,后面几个为待优化状态量的维度 ;
  • 重载虚函数virtual bool Evaluate(double const* const* parameters, double *residuals, double **jacobians) const,根据 待优化变量,实现 残差和雅克比矩阵的计算(雅克比矩阵计算需要提供公式);

class PoseGraphCFunc : public ceres::SizedCostFunction<6,6,6>
{
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    PoseGraphCFunc(const Sophus::SE3 measure,const Matrix6d covariance):_measure(measure),_covariance(covariance){}
    ~PoseGraphCFunc(){}
    virtual bool Evaluate(double const* const* parameters,
                          double *residuals,
                          double **jacobians)const
    {
        Sophus::SE3 pose_i=Sophus::SE3::exp(Vector6d(parameters[0]));//Eigen::MtatrixXd可以通过double指针来构造
        Sophus::SE3 pose_j=Sophus::SE3::exp(Vector6d(parameters[1]));
        Eigen::Map<Vector6d> residual(residuals);//Eigen::Map<typename MatrixX>(ptr)函数的作用是通过传入指针将c++数据映射为Eigen上的Matrix数据,有点与&相似
        residual=(_measure.inverse()*pose_i.inverse()*pose_j).log();
        Matrix6d sqrt_info=Eigen::LLT<Matrix6d>(_covariance).matrixLLT().transpose();
        if(jacobians)
        {
            if(jacobians[0])
            {
                Eigen::Map<Eigen::Matrix<double,6,6,Eigen::RowMajor>> jacobian_i(jacobians[0]);
                Matrix6d Jr=JRInv(Sophus::SE3::exp(residual));
                jacobian_i=(sqrt_info)*(-Jr)*pose_j.inverse().Adj();
            }
            if(jacobians[1])
            {
                Eigen::Map<Eigen::Matrix<double,6,6, Eigen::RowMajor>> jacobian_j(jacobians[1]);
                Matrix6d J = JRInv(Sophus::SE3::exp(residual));
                jacobian_j = sqrt_info * J * pose_j.inverse().Adj();
            }
        }
        residual=sqrt_info*residual;
        return true;

    }
private:
    const Sophus::SE3 _measure;
    const Matrix6d _covariance;

};

  • 如果待优化变量处于流形上则需自定义 一个继承于LocalParameterization的类,重载其中的Plus()函数实现迭代递增,重载computeJacobian()定义流形到切平面的雅克比矩阵

class Parameterization:public ceres::LocalParameterization
{
public:
    Parameterization(){}
    virtual ~Parameterization(){}
    virtual bool Plus(const double* x,
                      const double * delta,
                      double *x_plus_delta)const
    {
        Vector6d lie(x);
        Vector6d lie_delta(delta);
        Sophus::SE3 T=Sophus::SE3::exp(lie);
        Sophus::SE3 T_delta=Sophus::SE3::exp(lie_delta);

        Eigen::Map<Vector6d> x_plus(x_plus_delta);
        x_plus=(T_delta*T).log();
        return true;

    }
    //流形到其切平面的雅克比矩阵
    virtual bool ComputeJacobian(const double *x,
                                 double * jacobian) const
    {
        ceres::MatrixRef(jacobian,6,6)=ceres::Matrix::Identity(6,6);//ceres::MatrixRef()函数也类似于Eigen::Map,通过模板参数传入C++指针将c++数据映射为Ceres::Matrix
        return true;
    }
    //定义流形和切平面维度:在本问题中是李代数到李代数故都为6
    virtual int GlobalSize()const{return 6;}
    virtual int LocalSize()const {return 6;}
};

Step2:AddResidualBlock

  • 声明 ceres::Problem problem;
  • 通过 AddResidualBlock 将 代价函数(cost function)、损失函数(loss function) 和 待优化状态量 添加到 problem
ceres::LossFunction *loss = new ceres::HuberLoss(1.0);
ceres::CostFunction *costfunc = new PoseGraphCFunc(measurement, covariance);//定义costfunction
problem.AddResidualBlock(costfunc, loss, param[vertex_i].se3, param[vertex_j].se3);//为整体代价函数加入快,ceres的优点就是直接在param[vertex_i].se3上优化
problem.SetParameterization(param[vertex_i].se3, local_param);//为待优化的两个位姿变量定义迭代递增方式
problem.SetParameterization(param[vertex_j].se3, local_param);

Step3:配置优化参数并优化Config&solve

  • 定义ceres::Solver::Options options;对options成员进行赋值以配置优化参数;
  • 定义ceres::Solver::Summary summary;用来存储优化输出;
  • 求解:ceres::Solve(options, &problem, &summary);
ceres::Solver::Options options;//配置优化设置
options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
options.trust_region_strategy_type=ceres::LEVENBERG_MARQUARDT;
options.max_linear_solver_iterations = 50;
options.minimizer_progress_to_stdout = true;
ceres::Solver::Summary summary;//summary用来存储优化过程
ceres::Solve(options, &problem, &summary);//开始优化

(二)Ceres-Sophus在位姿优图化的应用

残差及雅克比矩阵推导:

(1)基于李代数的公式推导

  • 残差(运动方程):

  • 雅克比矩阵(左扰动模型):

(2)基于四元数或其他空间转换表达形式的公式推导(暂省后补)

代码实现:


#include <iostream>
#include <eigen3/Eigen/Core>
#include <fstream>
#include <assert.h>
#include <sophus/so3.h>
#include <sophus/se3.h>
#include <ceres/ceres.h>

using namespace std;
using namespace Eigen;
//using namespace ceres;

typedef Matrix<double, 6, 6> Matrix6d;
typedef Matrix<double, 6, 1> Vector6d;

typedef struct {
    int id = 0;
    double param[7] = {0};
    double se3[6] = {0};//(t,r)
} param_type;



Matrix6d JRInv(const Sophus::SE3 &e){
    Matrix6d J;
    J.block(0,0,3,3) = Sophus::SO3::hat(e.so3().log());
    J.block(0,3,3,3) = Sophus::SO3::hat(e.translation());
    J.block(3,0,3,3) = Matrix3d::Zero(3,3);
    J.block(3,3,3,3) = Sophus::SO3::hat(e.so3().log());
    J = 0.5 * J + Matrix6d::Identity();
    return J;
//    return Matrix6d::Identity();
}

class Parameterization:public ceres::LocalParameterization
{
public:
    Parameterization(){}
    virtual ~Parameterization(){}
    virtual bool Plus(const double* x,
                      const double * delta,
                      double *x_plus_delta)const
    {
        Vector6d lie(x);
        Vector6d lie_delta(delta);
        Sophus::SE3 T=Sophus::SE3::exp(lie);
        Sophus::SE3 T_delta=Sophus::SE3::exp(lie_delta);

        Eigen::Map<Vector6d> x_plus(x_plus_delta);
        x_plus=(T_delta*T).log();
        return true;

    }
    //流形到其切平面的雅克比矩阵
    virtual bool ComputeJacobian(const double *x,
                                 double * jacobian) const
    {
        ceres::MatrixRef(jacobian,6,6)=ceres::Matrix::Identity(6,6);//ceres::MatrixRef()函数也类似于Eigen::Map,通过模板参数传入C++指针将c++数据映射为Ceres::Matrix
        return true;
    }
    //定义流形和切平面维度:在本问题中是李代数到李代数故都为6
    virtual int GlobalSize()const{return 6;}
    virtual int LocalSize()const {return 6;}
};

class PoseGraphCFunc : public ceres::SizedCostFunction<6,6,6>
{
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
    PoseGraphCFunc(const Sophus::SE3 measure,const Matrix6d covariance):_measure(measure),_covariance(covariance){}
    ~PoseGraphCFunc(){}
    virtual bool Evaluate(double const* const* parameters,
                          double *residuals,
                          double **jacobians)const
    {
        Sophus::SE3 pose_i=Sophus::SE3::exp(Vector6d(parameters[0]));//Eigen::MtatrixXd可以通过double指针来构造
        Sophus::SE3 pose_j=Sophus::SE3::exp(Vector6d(parameters[1]));
        Eigen::Map<Vector6d> residual(residuals);//Eigen::Map<typename MatrixX>(ptr)函数的作用是通过传入指针将c++数据映射为Eigen上的Matrix数据,有点与&相似
        residual=(_measure.inverse()*pose_i.inverse()*pose_j).log();
        Matrix6d sqrt_info=Eigen::LLT<Matrix6d>(_covariance).matrixLLT().transpose();
        if(jacobians)
        {
            if(jacobians[0])
            {
                Eigen::Map<Eigen::Matrix<double,6,6,Eigen::RowMajor>> jacobian_i(jacobians[0]);
                Matrix6d Jr=JRInv(Sophus::SE3::exp(residual));
                jacobian_i=(sqrt_info)*(-Jr)*pose_j.inverse().Adj();
            }
            if(jacobians[1])
            {
                Eigen::Map<Eigen::Matrix<double,6,6, Eigen::RowMajor>> jacobian_j(jacobians[1]);
                Matrix6d J = JRInv(Sophus::SE3::exp(residual));
                jacobian_j = sqrt_info * J * pose_j.inverse().Adj();
            }
        }
        residual=sqrt_info*residual;
        return true;

    }
private:
    const Sophus::SE3 _measure;
    const Matrix6d _covariance;

};



void Convert2se3(param_type &_p){
    Quaterniond q(_p.param[6], _p.param[3], _p.param[4], _p.param[5]);
    Vector3d t(_p.param[0], _p.param[1], _p.param[2]);
    Vector6d se = Sophus::SE3(q.normalized(),t).log();
//    auto tmp = Sophus::SE3(q,t).log();
//    auto tmp1 = Sophus::SE3::exp(tmp);
    for(int i = 0; i < 6; i++){
        _p.se3[i] = se(i, 0);
    }
}


int main(int argc, char **argv) {

    google::InitGoogleLogging(argv[0]);

    string fin_path = "./sphere.g2o";

    ceres::Problem problem;
    vector<param_type> param;

    ifstream fin;
    fin.open(fin_path);
   assert(fin.is_open());
    ceres::LocalParameterization *local_param = new Parameterization();
    while(!fin.eof()){
        string name;
        fin >> name;
        if(name == "VERTEX_SE3:QUAT"){
            param_type p;
            fin >> p.id;
            for(int i = 0; i < 7; i++) fin >> p.param[i];
            Convert2se3(p);
            param.push_back(p);

//            problem.AddParameterBlock(param.back().se3, 6, local_param);
        }
        else if(name == "EDGE_SE3:QUAT"){
            int vertex_i, vertex_j;
            fin >> vertex_i >> vertex_j;
            //输入观测值
            double m[7];//temporary measurement result
            for(int i = 0; i < 7; i++) fin >> m[i];
            Sophus::SE3 measurement(Quaternion<double>(m[6], m[3], m[4], m[5]).normalized(),
                                    Vector3d(m[0], m[1], m[2]));
            //输入信息矩阵
            Matrix6d covariance;
            for(int i = 0; i < 6 && fin.good(); i++){
                for(int j = i; j < 6 && fin.good(); j++){
                    fin >> covariance(i,j);
                    if(j != i) covariance(j,i) = covariance(i,j);
                }
            }
            ceres::LossFunction *loss = new ceres::HuberLoss(1.0);
            ceres::CostFunction *costfunc = new PoseGraphCFunc(measurement, covariance);//定义costfunction
            problem.AddResidualBlock(costfunc, loss, param[vertex_i].se3, param[vertex_j].se3);//为整体代价函数加入快,ceres的优点就是直接在param[vertex_i].se3上优化
            problem.SetParameterization(param[vertex_i].se3, local_param);//为待优化的两个位姿变量定义迭代递增方式
            problem.SetParameterization(param[vertex_j].se3, local_param);
        }
    }
    fin.close();

    cout << param.size() << endl;
    ceres::Solver::Options options;//配置优化设置
    options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
    options.trust_region_strategy_type=ceres::LEVENBERG_MARQUARDT;
    options.max_linear_solver_iterations = 50;
    options.minimizer_progress_to_stdout = true;

    ceres::Solver::Summary summary;//summary用来存储优化过程
    ceres::Solve(options, &problem, &summary);//开始优化

    cout << summary.FullReport() << endl;
    std::ofstream txt("./result_ceres.g2o");
    for( int i=0; i < param.size(); i++ )
    {
        Eigen::Map<const Eigen::Matrix<double,6,1>> poseAVec6d( param[i].se3 );
        Sophus::SE3 poseSE3 = Sophus::SE3::exp(poseAVec6d);
        Quaternion<double> q = poseSE3.so3().unit_quaternion();//将SE3中的SO3转换为四元数

        txt << "VERTEX_SE3:QUAT" << ' ';
        txt << i << ' ';
        txt << poseSE3.translation().transpose() << ' ';
        txt << q.x() <<' '<< q.y()<< ' ' << q.z() <<' '<< q.w()<<' ' << endl;
    }
    fin.open(fin_path);
    while(!fin.eof()){
        string s;
        getline(fin, s);
        if(s[0] != 'E') continue;
        else txt << s << endl;
    }
    fin.close();
    txt.close();
    return 0;
}

待解决问题:ceres里如何设置固定节点,类似于g2o中的setfixed()。

参考1:https://blog.csdn.net/u011178262/article/details/88774577

参考2:https://blog.csdn.net/weixin_42099090/article/details/106907271

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

Ceres用法及Ceres-Sophus在位姿图优化问题的应用 的相关文章

  • Windows Docker Desktop开放API端口2375用于远程调用

    Windows Docker Desktop开放API端口2375用于远程调用 问题解决开启IP Helper服务开启Docker配置开放2375端口 端口映射找到需要暴露的IP执行端口映射命令 Windows防火墙关闭防火墙添加防火墙规则
  • Linksys WRT路由器刷入OpenWrt与原厂固件双固件及切换

    Linksys路由器OpenWrt与原厂固件双固件刷入及切换 双固件机制使用原厂固件刷其他固件使用原厂固件切换启动分区使用OpenWrt刷入Sysupgrade使用OpenWrt刷入Img使用OpenWrt切换分区通用的硬切换分区 xff0
  • 如何在 Ubuntu 20.04 上安装 Apache

    简介 xff1a Apache 是世界上最流行的网站服务器之一 它是开源并且跨平台的 HTTP 服务器 xff0c 它托管了互联网上大量的网站 Apache 提供了很多强大的功能 xff0c 并且可以扩展其他的模块 本文主要为大家介绍如何在
  • 浅谈C++中的多线程(一)

    本篇文章围绕以下几个问题展开 xff1a 何为进程 xff1f 何为线程 xff1f 两者有何区别 xff1f 何为并发 xff1f C 43 43 中如何解决并发问题 xff1f C 43 43 中多线程的语言实现 xff1f 同步互斥原
  • 如何用ASCII码表白

    前提摘要 刚好学到了字符流输入输出那块东西 xff0c 从文本文档里敲入老师课件里的东西 xff0c 控制台 输出了对应的数字编码 xff0c 就萌生了 xff1a 嗯 可以用来表白的小想法 xff0c 就是把一对酷酷的扔 过去 xff0c
  • 走进前端 VScode插件安装 Gitee提交

    一 xff0c 认识前端 什么是前端 前端即网站前台部分 xff0c 运行在PC端 xff0c 移动端等浏览器上展现给用户浏览的网页 前端技术一般分为前端设计和前端开发 xff0c 前端设计理解为网站网页的视觉设计 xff0c 前端开发则是
  • freeRTOS与ucos II区别

    freeRTOS比uCOS II优胜的地方 1 内核ROM和耗费RAM都比uCOS 小 xff0c 特别是RAM 这在单片机里面是稀缺资源 xff0c UCOS至少要5K以上 xff0c 而freeOS用2 3K也可以跑的很好 xff1b
  • 嵌入式软件架构设计

    如何设计一个好的软件架构 xff0c 如何提高软件的扩展性 xff0c 移植性 xff0c 复用性和可读性 xff1f 很多做嵌入式开发的朋友经常会遇到这种情况 xff1a 一个项目软件设计完成了 xff0c 客户提出了一些新的功能需求 这
  • 深入理解C语言小括号用法

    学了这么多年C语言 xff0c 你真的会用小括号吗 xff1f 我们今天来总结一下小括号 xff08 xff09 有哪些用法 xff0c 用法如下表 xff1a 示例 1 聚组 聚组是用来改变运算优先级 xff0c 实例如下 xff1a 例
  • 嵌入式实时操作系统1——初识嵌入式实时操作系统

    嵌入式实时操作系统是什么 嵌入式实时操作系统是一个特殊的程序 xff0c 是一个支持多任务的运行环境 嵌入式实时操作系统最大的特点就是 实时性 xff0c 如果有一个任务需要执行 xff0c 实时操作系统会立即执行该任务 xff0c 不会有
  • 嵌入式实时操作系统3——任务切换

    任务切换原理 假设有一程序 xff0c 程序内有一个无限循环 xff0c 在循环内部有5个表达式 xff0c 代码如下 xff1a 程序在循环中 xff0c 会依次执行表达式1 表达式2 表达式3 表达式4 表达式5 表达式1无限循环 假设
  • 嵌入式软件设计必看书籍

    提高C语言编程能力 以上4本书籍可以提高C语言编程能力 xff0c 深入理解C语言指针用法 xff0c 深入理解C语言标准 提高软件架构设计能力 以上2本书籍掌握以下知识 xff1a 1 软件设计原则 2 软件设计模式 3 软件设计构架 4
  • 如何使用 Docker 进行编译和开发

    简介 xff1a 本文主要为大家讲解不同环境下如何使用docker进行日常开发和编译 镜像下载 域名解析 时间同步请点击 阿里巴巴开源镜像站 一 Linux环境开发 适用于Linux环境开发者 xff0c 有专门代码服务器或虚拟机 1 安装
  • 嵌入式实时操作系统9——中断系统

    1 中断是什么 中断是计算机中一个非常重要的概念 xff0c 现代计算机中毫无例外地都要采用中断技术 早期的计算机没有中断系统 xff0c 人们往往需要等上一个任务运行结束才能运行下一个任务 xff0c 这极大的限制了计算机的执行效率 早期
  • 从零开始构建嵌入式实时操作系统1——任务切换

    1 前言 随着计算机技术和微电子技术的迅速发展 xff0c 嵌入式系统应用领域越来越广泛 xff0c 尤其是其具备低功耗技术的特点得到人们的重视 随着工信部提出NB IoT基站建设具体目标 三大运营商加速建设 xff0c 即将迎来万物互联的
  • 从零开始构建嵌入式实时操作系统2——重构

    1 前言 本人是一个普通的中年程序员 xff0c 并不是圈内的大牛 xff0c 写嵌入式操作系统这一系列的文章并不是要显示自己的技术 xff0c 而是出于对嵌入式的热爱 非常幸运 xff0c 本人毕业后的十几年一直从事嵌入式行业 xff0c
  • 从零开始构建嵌入式实时操作系统3——任务状态切换

    1 前言 一个行者问老道长 xff1a 您得道前 xff0c 做什么 xff1f 老道长 xff1a 砍柴担水做饭 行者问 xff1a 那得道后呢 xff1f 老道长 xff1a 砍柴担水做饭 行者又问 xff1a 那何谓得道 xff1f
  • 从零开始构建嵌入式实时操作系统4——深入讲解任务切换

    1 前言 操作系统可以为我们执行丰富的应用程序 xff0c 可以同时满足我们的各种使用需要 操作系统之所以能同时完成我们各种需求 xff0c 是因为操作系统能并发执行多个用户的应用程序 事实上除了多核处理器系统中是真正的多任务并行之外 xf
  • Linux启动流程之ROM-CODE

    1 从哪里开始 xff1f 下图是AM335X核心板和功能框图 xff1a AM335X核心板的存储信息如下 xff1a AM335X核心板运行linux系统 xff0c 在这里提出一个问题 xff1a 上电后指令从哪里开始执行 xff1f
  • 全志V3S开发板星光闪烁(linux LED驱动)

    1 前言 本文描述了基于全志V3S开发板的LED驱动程序和测试应用程序的设计流程 通过本次实验我们可以控制V3S电路板上的LED xff0c 模拟星空的星星 xff0c 一闪一闪亮晶晶 xff01 2 设计流程概述 本次实验的设计步骤如下

随机推荐

  • 人脑能否重启?

    1 重启是什么 人脑能否重启 这个问题还不简单 xff0c 人睡眠后清醒就是重启 事实真的是如此简单吗 xff1f 我们先不急着给出结论 xff0c 前面提到 人睡眠后清醒就是重启 xff0c 这句话中有两概念 xff1a 1 睡眠和觉醒
  • 嵌入式技术之IAP,自从有了它老板再也不担心我的代码了!(中)

    上篇文章我们一起学习了IAP的工作原理和IAP包含的3个重要功能 xff1a 数据交互 数据存储和程序跳转 这3个重要功能称为 IAP的三板斧 xff0c 接下来我们看这三板斧具体完成哪些细节工作 xff0c 如何实现这三板斧 1 数据交互
  • 超导量子计算机

    1 超导量子计算机发展状况 2018年3月5日美国物理学会年会上 xff0c 谷歌展示了其正在测试的72量子位超导量子芯片Bristlecone 谷歌物理学家朱利安 凯利表示 xff0c 研讨团队希望初次运用更大的量子芯片来展现霸权 xff
  • Ubuntu 快速更换阿里源

    简介 xff1a 本文主要给大家讲解如何为Ubuntu更换阿里源 xff0c 通过以下四个步骤即可快速实现换源 镜像下载 域名解析 时间同步请点击 阿里巴巴开源镜像站 一 查看ubuntu的Codename lsb release a gr
  • 建造《流浪地球2》中要毁灭人类的超级量子计算机MOSS的核心量子技术是什么?

    1 流浪地球2 中的量子计算机 2023年中国最火的电影非 流浪地球2 莫属 xff0c 在 流浪地球2 中有一个人工智能机器人MOSS xff0c 它的前身是 550W 超级量子计算机 xff0c MOSS 是它给自己起的名字 xff08
  • 离子阱量子计算机

    1 新闻 2020年6月 xff0c 科技制造企业霍尼韦尔 xff08 Honeywell xff09 发布第一台离子阱量子计算机H0 xff0c 它拥有64量子体积 xff0c 它是IBM和谷歌同时期量子计算机的两倍 公司表示之所以能取得
  • ROS Melodic安装、配置和使用turtlebot2(集成众多源代码直接下载)

    已经有前辈将ubuntu14 04下的turtlebot教程翻译了过来 xff0c 可以先行查看 xff0c 对turtlebot的知识建立总体的认识 xff1a https www ncnynl com archives 201609 7
  • FreeRTOS学习 第一讲 操作系统的移植

    FreeRTOS学习 第一讲 操作系统的移植 基本介绍 xff1a 系统分类 1 xff09 前后台系统 while 1 循环 适用情况 xff08 简单和小的需求 处理需求相对来说较少 xff09 2 xff09 实时操作系统 实时操作系
  • Python调用playsound时报错:指定的设备未打开,或不被 MCI 所识别

    报错信息 xff1a Error 263 for command close audio mp3 指定的设备未打开 或不被 MCI 所识别 原因 xff1a windows不支持utf 16编码 xff0c 需修改playsound源码 p
  • 【无人机学习】Mission Planner(pc端)和QGroundControl(android端)

    无人机学习 Mission Planner xff08 pc端 xff09 和QGroundControl xff08 android端 xff09 系列文章目录 提示 xff1a 这里是收集了无人机的相关文章 无人机学习 无人机基础知识
  • 【无人机学习之QGroundControl】android端App初解4-遥控器通道

    无人机学习之QGroundControl android端App初解4 遥控器通道 系列文章目录 提示 xff1a 这里是收集了无人机的相关文章 无人机学习 无人机基础知识 无人机学习 Mission Planner xff08 pc端 x
  • 百度2014校园招聘 软件研发工程师 笔试题

    一 简答题 xff08 本题共30 xff09 1 动态链接库和静态链接库分别有什么优缺点 xff1f xff08 10 xff09 2 轮询任务调度与抢占式任务调度的区别 xff1f xff08 10 xff09 3 请列出数据库中常用的
  • Kubernetes 日志查询分析实践

    简介 xff1a 本文将介绍如何基于日志服务实现对 Kubernetes xff08 以下简称 K8s xff09 日志的采集以及查询分析 xff0c 此外 xff0c 还附带了对 Ingress Audit 方案的简要介绍 为了方便大家通
  • C++算法题

    目录 一 排序算法 1 冒泡排序 2 快速排序 3 归并排序 4 堆排序 5 插入排序 6 topK 二 二分查找 1 一维数组二分查找 2 二维数组二分查找 3 寻找旋转排序数组中的最小值 三 有序数组的平方 xff08 双指针法 xff
  • QT通过UDP分包传输大图像(测试可传6M)

    参考博客 UDP传数据每帧数据最大传64k xff0c 而图片文件一般远大于64K xff0c 此时就需要将图像数据分包传输 xff0c 接收端也分包接收 xff0c 直到整个图片数据都收到 xff0c 再进行其他处理 发送端 发送数据 v
  • github代码如何定位到历史版本(历史commit点)

    关于使用git在本地进行版本管理见linux下的版本管理 工作项目中git流程实操见git简明实操模板 想我们在写代码时候 xff0c 数次修改并提交commit xff0c 如果在这个过程中我们后悔了 xff0c 想回到当初的某一个com
  • Intel RealSense学习之图像及图像深度数据获取

    本文将介绍如何获取到彩色图像的深度信息 大家都知道我们可以从realsense 摄像头中获取到RGB数据 xff0c 红外数据 xff0c 以及图像的深度数据 至于图像的深度数据我的理解是realsense摄像投抓到的图像的相关距离信息 x
  • ROS机器人编程实践——读书笔记1

    目的 xff1a 写一个最小基于ROS的机器人控制软件 一 写一个运动命令流 xff0c 每秒10次 xff0c 每三秒启动一次 在移动时 xff0c 发送前进命令 xff0c 速度0 5米每秒 xff0c 停止时发送速度0米每秒 命名为
  • SLAM后端:因子图优化

    xff08 一 xff09 贝叶斯网络 贝叶斯网络是种概率图 xff0c 由随机变量节点和表达随机变量条件独立性的边组成 xff0c 形成一个有向无环图 在 SLAM 中 由于我们有运动方程和观测方程 它们恰好表示了状态变量之间的条件概率
  • Ceres用法及Ceres-Sophus在位姿图优化问题的应用

    xff08 一 xff09 Ceres Solver的一般用法 简述 xff1a Ceres Solver is an open source C 43 43 library for modeling and solving large c