紧耦合后端非线性优化-局部优化(Marginalization)

简介: 紧耦合后端非线性优化-局部优化(Marginalization)

0.前言


局部优化作为VSLAM当中常用的策略,其作用相当于激光SLAM中的局部地图的ICP or NDT优化(scan2localmap)。


如下图所示,在VIO当中,随着时间的推移,路标特征点(landmark)和相机的位姿pose越来越多,BA的计算量随着变量的增加而增加,即使BA的H矩阵是稀疏的,也吃不消。因此,我们要限制优化变量的多少,不能只一味的增加待优化的变量到BA里,而应该去掉一些变量。


那么如何丢变量就成了一个很重要的问题!在vins mono和vins fusion中都存在void Estimator::optimization()函数用来用滑窗执行Ceres优化,边缘化,更新滑窗内图像帧的状态(位姿、速度、偏置、外参、逆深度、相机与IMU时差),但是这个之前在VINS-FUSION 前端后端代码全详解忽略了这一重要的部分。所以在写完回环后发现,关注了全局优化的同时,局部优化却没有关注。


为此写着一篇文章来分析vins中的局部优化部分


87342acd691d4dcc8197cd9a9baad212.png


1. VIO中的状态向量与代价函数


aeb5cfc301c44e18a367923f485e6cc8.png


视觉惯性BA:这三项依次为边缘化的先验信息、IMU的测量残差、视觉的重投影误差

BA优化模型分为三部分:


1、视觉误差函数部分(滑动窗口中特征点在相机下视觉重投影残差)


2、IMU残差部分(滑动窗口中相邻帧间的IMU产生)


3、Marg边缘化残差部分(滑动窗口中去掉位姿和特征点约束)代码中使用Google开源的Ceres solver解决。


2. 视觉约束


这部分要拟合的目标可以通过重投影误差约束,求解的是对同一个路标点的观测值和估计值之间的误差,注意是在归一化平面上表示。


e00b923d1e174f748aa3368e172151ba.png


当某路标点在第i帧观测到并进行初始化操作得到路标点逆深度,当其在第j帧也被观测到时,估计其在第j帧中的坐标为:


f5be14e837864eaba350db7849ef064d.png


此时的视觉残差为:(左侧为根据i帧反推估计的位置,右侧为观测值)


3423b419c41249009aaa74566cb5e3fd.png


逆深度作为参数原因:


1)观测到的特征点深度可能非常大,难以进行优化;

2)可以减少实际优化的参数变量;

3)逆深度更加服从高斯分布。这里特征点的逆深度在第i帧初始化操作中得到。


我们可以看到在vins fusion中


//左相机在i时刻和j时刻分别观测到路标点
    ProjectionTwoFrameOneCamFactor *f_td = new ProjectionTwoFrameOneCamFactor(pts_i, pts_j, it_per_id.feature_per_frame[0].velocity, it_per_frame.velocity,
                                                     it_per_id.feature_per_frame[0].cur_td, it_per_frame.cur_td);
    problem.AddResidualBlock(f_td, loss_function, para_Pose[imu_i], para_Pose[imu_j], para_Ex_Pose[0], para_Feature[feature_index], para_Td[0]);
}
if(STEREO && it_per_frame.is_stereo)
{                
    Vector3d pts_j_right = it_per_frame.pointRight;
    if(imu_i != imu_j)
    {   //左相机在i时刻、右相机在j时刻分别观测到路标点
        ProjectionTwoFrameTwoCamFactor *f = new ProjectionTwoFrameTwoCamFactor(pts_i, pts_j_right, it_per_id.feature_per_frame[0].velocity, it_per_frame.velocityRight,
                                                     it_per_id.feature_per_frame[0].cur_td, it_per_frame.cur_td);
        problem.AddResidualBlock(f, loss_function, para_Pose[imu_i], para_Pose[imu_j], para_Ex_Pose[0], para_Ex_Pose[1], para_Feature[feature_index], para_Td[0]);
    }
    else
    {   //左相机和右相机在i时刻分别观测到路标点
        ProjectionOneFrameTwoCamFactor *f = new ProjectionOneFrameTwoCamFactor(pts_i, pts_j_right, it_per_id.feature_per_frame[0].velocity, it_per_frame.velocityRight,
                                                     it_per_id.feature_per_frame[0].cur_td, it_per_frame.cur_td);
        problem.AddResidualBlock(f, loss_function, para_Ex_Pose[0], para_Ex_Pose[1], para_Feature[feature_index], para_Td[0]);
    }

 

目前我们将以ProjectionTwoFrameOneCamFactor为例子介绍特征点逆深度求解


/**
 * 迭代优化每一步调用,计算变量x在当前状态下的残差,以及残差对变量的Jacobian,用于计算delta_x,更新变量x
 * 优化重投影误差
 * 1、优化变量:前一帧位姿,当前帧位姿,相机与IMU外参,特征点逆深度,相机与IMU时差。对匹配点构建重投影误差
 * 2、计算残差对优化变量的Jacobian
 * @param parameters    优化变量的值
 * @param residuals     output 残差
 * @param jacobians     output 残差对优化变量的Jacobian
*/
bool ProjectionTwoFrameOneCamFactor::Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
{
    // 优化变量:前一帧位姿7,当前位姿7,相机与IMU外参7,特征点逆深度1,相机与IMU时差1
    TicToc tic_toc;
    Eigen::Vector3d Pi(parameters[0][0], parameters[0][1], parameters[0][2]);
    Eigen::Quaterniond Qi(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]);
    Eigen::Vector3d Pj(parameters[1][0], parameters[1][1], parameters[1][2]);
    Eigen::Quaterniond Qj(parameters[1][6], parameters[1][3], parameters[1][4], parameters[1][5]);
    Eigen::Vector3d tic(parameters[2][0], parameters[2][1], parameters[2][2]);
    Eigen::Quaterniond qic(parameters[2][6], parameters[2][3], parameters[2][4], parameters[2][5]);
    double inv_dep_i = parameters[3][0];
    double td = parameters[4][0];
    Eigen::Vector3d pts_i_td, pts_j_td;
    // 匹配点ij, 归一化相机点时差校正,对应到采集时刻的位置,因为IMU数据是对应图像采集时刻的
    pts_i_td = pts_i - (td - td_i) * velocity_i;
    pts_j_td = pts_j - (td - td_j) * velocity_j;
    // 转到相机系
    Eigen::Vector3d pts_camera_i = pts_i_td / inv_dep_i;
    // 转到IMU系
    Eigen::Vector3d pts_imu_i = qic * pts_camera_i + tic;
    // 转到世界系
    Eigen::Vector3d pts_w = Qi * pts_imu_i + Pi;
    // 转到j的IMU系
    Eigen::Vector3d pts_imu_j = Qj.inverse() * (pts_w - Pj);
    // 转到j的相机系
    Eigen::Vector3d pts_camera_j = qic.inverse() * (pts_imu_j - tic);
    Eigen::Map<Eigen::Vector2d> residual(residuals);
#ifdef UNIT_SPHERE_ERROR 
    residual =  tangent_base * (pts_camera_j.normalized() - pts_j_td.normalized());
#else
    // 计算归一化相机平面上的两点误差
    double dep_j = pts_camera_j.z();
    residual = (pts_camera_j / dep_j).head<2>() - pts_j_td.head<2>();
#endif
    residual = sqrt_info * residual;
    if (jacobians)
    {
        Eigen::Matrix3d Ri = Qi.toRotationMatrix();
        Eigen::Matrix3d Rj = Qj.toRotationMatrix();
        Eigen::Matrix3d ric = qic.toRotationMatrix();
        Eigen::Matrix<double, 2, 3> reduce(2, 3);
#ifdef UNIT_SPHERE_ERROR
        double norm = pts_camera_j.norm();
        Eigen::Matrix3d norm_jaco;
        double x1, x2, x3;
        x1 = pts_camera_j(0);
        x2 = pts_camera_j(1);
        x3 = pts_camera_j(2);
        norm_jaco << 1.0 / norm - x1 * x1 / pow(norm, 3), - x1 * x2 / pow(norm, 3),            - x1 * x3 / pow(norm, 3),
                     - x1 * x2 / pow(norm, 3),            1.0 / norm - x2 * x2 / pow(norm, 3), - x2 * x3 / pow(norm, 3),
                     - x1 * x3 / pow(norm, 3),            - x2 * x3 / pow(norm, 3),            1.0 / norm - x3 * x3 / pow(norm, 3);
        reduce = tangent_base * norm_jaco;
#else
        reduce << 1. / dep_j, 0, -pts_camera_j(0) / (dep_j * dep_j),
            0, 1. / dep_j, -pts_camera_j(1) / (dep_j * dep_j);
#endif
        reduce = sqrt_info * reduce;
        // 下面是计算残差对优化变量的Jacobian
        if (jacobians[0])
        {
            Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_pose_i(jacobians[0]);
            Eigen::Matrix<double, 3, 6> jaco_i;
            jaco_i.leftCols<3>() = ric.transpose() * Rj.transpose();
            jaco_i.rightCols<3>() = ric.transpose() * Rj.transpose() * Ri * -Utility::skewSymmetric(pts_imu_i);
            jacobian_pose_i.leftCols<6>() = reduce * jaco_i;
            jacobian_pose_i.rightCols<1>().setZero();
        }
        if (jacobians[1])
        {
            Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_pose_j(jacobians[1]);
            Eigen::Matrix<double, 3, 6> jaco_j;
            jaco_j.leftCols<3>() = ric.transpose() * -Rj.transpose();
            jaco_j.rightCols<3>() = ric.transpose() * Utility::skewSymmetric(pts_imu_j);
            jacobian_pose_j.leftCols<6>() = reduce * jaco_j;
            jacobian_pose_j.rightCols<1>().setZero();
        }
        if (jacobians[2])
        {
            Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_ex_pose(jacobians[2]);
            Eigen::Matrix<double, 3, 6> jaco_ex;
            jaco_ex.leftCols<3>() = ric.transpose() * (Rj.transpose() * Ri - Eigen::Matrix3d::Identity());
            Eigen::Matrix3d tmp_r = ric.transpose() * Rj.transpose() * Ri * ric;
            jaco_ex.rightCols<3>() = -tmp_r * Utility::skewSymmetric(pts_camera_i) + Utility::skewSymmetric(tmp_r * pts_camera_i) +
                                     Utility::skewSymmetric(ric.transpose() * (Rj.transpose() * (Ri * tic + Pi - Pj) - tic));
            jacobian_ex_pose.leftCols<6>() = reduce * jaco_ex;
            jacobian_ex_pose.rightCols<1>().setZero();
        }
        if (jacobians[3])
        {
            Eigen::Map<Eigen::Vector2d> jacobian_feature(jacobians[3]);
            jacobian_feature = reduce * ric.transpose() * Rj.transpose() * Ri * ric * pts_i_td * -1.0 / (inv_dep_i * inv_dep_i);
        }
        if (jacobians[4])
        {
            Eigen::Map<Eigen::Vector2d> jacobian_td(jacobians[4]);
            jacobian_td = reduce * ric.transpose() * Rj.transpose() * Ri * ric * velocity_i / inv_dep_i * -1.0  +
                          sqrt_info * velocity_j.head(2);
        }
    }
    sum_t += tic_toc.toc();
    return true;
}


…详情请参照古月居

相关文章
|
10天前
|
机器学习/深度学习 前端开发 算法
婚恋交友系统平台 相亲交友平台系统 婚恋交友系统APP 婚恋系统源码 婚恋交友平台开发流程 婚恋交友系统架构设计 婚恋交友系统前端/后端开发 婚恋交友系统匹配推荐算法优化
婚恋交友系统平台通过线上互动帮助单身男女找到合适伴侣,提供用户注册、个人资料填写、匹配推荐、实时聊天、社区互动等功能。开发流程包括需求分析、技术选型、系统架构设计、功能实现、测试优化和上线运维。匹配推荐算法优化是核心,通过用户行为数据分析和机器学习提高匹配准确性。
38 3
|
22天前
|
机器学习/深度学习 人工智能 算法
【AI系统】AI 编译器后端优化
AI编译器采用多层架构,首先通过前端优化将不同框架的模型转化为统一的Graph IR并进行计算图级别的优化,如图算融合、内存优化等。接着,通过后端优化,将优化后的计算图转换为TensorIR,针对单个算子进行具体实现优化,包括循环优化、算子融合等,以适应不同的硬件架构,最终生成高效执行的机器代码。后端优化是提升算子性能的关键步骤,涉及复杂的优化策略和技术。
44 3
|
1月前
|
弹性计算 运维 开发者
后端架构优化:微服务与容器化的协同进化
在现代软件开发中,后端架构的优化是提高系统性能和可维护性的关键。本文探讨了微服务架构与容器化技术如何相辅相成,共同推动后端系统的高效运行。通过分析两者的优势和挑战,我们提出了一系列最佳实践策略,旨在帮助开发者构建更加灵活、可扩展的后端服务。
|
1月前
|
Kubernetes API Docker
构建高效后端服务:微服务架构的深度实践与优化####
本文深入探讨了微服务架构在现代后端开发中的应用,通过剖析其核心概念、设计原则及实施策略,结合具体案例分析,展示了如何有效提升系统的可扩展性、可靠性和维护性。文章还详细阐述了微服务拆分的方法论、服务间通信的最佳实践、以及容器化与编排工具(如Docker和Kubernetes)的应用技巧,为读者提供了一份全面的微服务架构落地指南。 ####
|
5月前
|
存储 缓存 负载均衡
高效后端开发中的架构设计与优化策略
在当今快速发展的技术环境中,高效的后端开发不仅仅依赖于编程技能,更需要精心设计的架构和优化策略。本文探讨了如何通过合理的架构设计和优化策略,提升后端系统的性能和可维护性,以应对复杂的业务需求和大规模的用户访问。【7月更文挑战第5天】
79 1
|
5月前
|
存储 NoSQL 数据处理
高效数据处理与后端优化:现代技术实践与挑战
在当今数字化快速发展的环境下,高效的数据处理成为了后端开发的核心挑战之一。本文探讨了现代后端技术中的数据处理方法与优化策略,深入分析了面临的挑战及其解决方案,旨在为开发者提供实用的指导与技术思路。【7月更文挑战第4天】
79 1
|
1月前
|
存储 SQL 数据库
深入浅出后端开发之数据库优化实战
【10月更文挑战第35天】在软件开发的世界里,数据库性能直接关系到应用的响应速度和用户体验。本文将带你了解如何通过合理的索引设计、查询优化以及恰当的数据存储策略来提升数据库性能。我们将一起探索这些技巧背后的原理,并通过实际案例感受优化带来的显著效果。
50 4
|
2月前
|
监控 API 开发者
后端开发中的微服务架构实践与优化
【10月更文挑战第17天】 本文深入探讨了微服务架构在后端开发中的应用及其优化策略。通过分析微服务的核心理念、设计原则及实际案例,揭示了如何构建高效、可扩展的微服务系统。文章强调了微服务架构对于提升系统灵活性、降低耦合度的重要性,并提供了实用的优化建议,帮助开发者更好地应对复杂业务场景下的挑战。
30 7
|
5月前
|
缓存 开发框架 监控
优化后端服务响应时间的关键策略与实践
在当今数字化时代,优化后端服务响应时间至关重要。本文探讨了几种关键策略和实践方法,帮助开发团队提高系统性能和用户体验。通过合理的资源分配、技术选型和代码优化,可以有效缩短响应时间,提升系统的整体效率和稳定性。【7月更文挑战第5天】
157 0
|
3月前
|
JavaScript 前端开发 数据库
优化后端性能:如何使用异步编程提升系统响应速度
异步编程已成为现代后端系统性能优化的重要策略。通过避免阻塞操作,异步编程可以显著提高系统的响应速度和并发处理能力。本文章深入探讨了异步编程的基本概念,比较了常见的异步编程模型,并通过实际案例演示如何在Node.js和Python中实现异步操作,以提升系统性能。

热门文章

最新文章