VINS_FUSION入门系列---GPS与VIO融合

2023-05-16

参考的博客:https://blog.csdn.net/subiluo/article/details/105429471
http://www.luyixian.cn/news_show_313718.aspx
在这里插入图片描述

state: 状态量,位姿,速度,bias等
Local Factor: 局部观测约束,VIO相对位姿变换, 计算的是相邻两帧之间位姿的残差

1.代码的输入输出

输入输出的定义都在globalOptNode.cpp这个文件里面

    ros::Subscriber sub_GPS = n.subscribe("/gps", 100, GPS_callback);
    ros::Subscriber sub_vio = n.subscribe("/vins_estimator/odometry", 100, vio_callback);
    pub_global_path = n.advertise<nav_msgs::Path>("global_path", 100);
    pub_global_odometry = n.advertise<nav_msgs::Odometry>("global_odometry", 100);
    pub_car = n.advertise<visualization_msgs::MarkerArray>("car_model", 1000);

vio的输入函数

void vio_callback(const nav_msgs::Odometry::ConstPtr &pose_msg)
{
    //printf("vio_callback! \n");
    double t = pose_msg->header.stamp.toSec();
    last_vio_t = t;
    //获取VIO输出的位置(三维向量),姿态(四元数)
    Eigen::Vector3d vio_t(pose_msg->pose.pose.position.x, pose_msg->pose.pose.position.y, pose_msg->pose.pose.position.z);
    Eigen::Quaterniond vio_q;
    vio_q.w() = pose_msg->pose.pose.orientation.w;
    vio_q.x() = pose_msg->pose.pose.orientation.x;
    vio_q.y() = pose_msg->pose.pose.orientation.y;
    vio_q.z() = pose_msg->pose.pose.orientation.z;
    //位姿传入global Estimator中
    globalEstimator.inputOdom(t, vio_t, vio_q);


    m_buf.lock();
    //寻找与VIO时间戳相对应的GPS信息
    while(!gpsQueue.empty())
    {
        //获得最老的GPS数据和其时间
        sensor_msgs::NavSatFixConstPtr GPS_msg = gpsQueue.front();
        double gps_t = GPS_msg->header.stamp.toSec();
        printf("vio t: %f, gps t: %f \n", t, gps_t);
        // 10ms sync tolerance
        if(gps_t >= t - 0.01 && gps_t <= t + 0.01)
        {
            //printf("receive GPS with timestamp %f\n", GPS_msg->header.stamp.toSec());
            //GPS的经纬度,海拔高度
            double latitude = GPS_msg->latitude;
            double longitude = GPS_msg->longitude;
            double altitude = GPS_msg->altitude;
            //int numSats = GPS_msg->status.service;
            //GPS数据的方差
            double pos_accuracy = GPS_msg->position_covariance[0];
            if(pos_accuracy <= 0)
                pos_accuracy = 1;
            //printf("receive covariance %lf \n", pos_accuracy);
            //if(GPS_msg->status.status > 8)
            //向globalEstimator中输入GPS数据
            globalEstimator.inputGPS(t, latitude, longitude, altitude, pos_accuracy);
            gpsQueue.pop();
            //此处break,意味只存储了一个GPS数据后就break了。后来想明白了GPS不同于imu,是绝对位
            break;
        }
        else if(gps_t < t - 0.01)
            gpsQueue.pop();
        else if(gps_t > t + 0.01)
            break;
    }
    m_buf.unlock();

    Eigen::Vector3d global_t;
    Eigen:: Quaterniond global_q;
    globalEstimator.getGlobalOdom(global_t, global_q);

    nav_msgs::Odometry odometry;
    odometry.header = pose_msg->header;
    odometry.header.frame_id = "world";
    odometry.child_frame_id = "world";
    odometry.pose.pose.position.x = global_t.x();
    odometry.pose.pose.position.y = global_t.y();
    odometry.pose.pose.position.z = global_t.z();
    odometry.pose.pose.orientation.x = global_q.x();
    odometry.pose.pose.orientation.y = global_q.y();
    odometry.pose.pose.orientation.z = global_q.z();
    odometry.pose.pose.orientation.w = global_q.w();
    pub_global_odometry.publish(odometry);
    pub_global_path.publish(*global_path);
    publish_car_model(t, global_t, global_q);


    // write result to file
    std::ofstream foutC("/home/tony-ws1/output/vio_global.csv", ios::app);
    foutC.setf(ios::fixed, ios::floatfield);
    foutC.precision(0);
    foutC << pose_msg->header.stamp.toSec() * 1e9 << ",";
    foutC.precision(5);
    foutC << global_t.x() << ","
            << global_t.y() << ","
            << global_t.z() << ","
            << global_q.w() << ","
            << global_q.x() << ","
            << global_q.y() << ","
            << global_q.z() << endl;
    foutC.close();
}

再看一下inputOdom函数,这个函数把vio的结果存储在localPoseMap中,然后使用外参 WGPS_T_WVIO把VIO的结果转换到GPS坐标系下存储在globalPoseMap中。注意,此时我们考虑刚开始gps没对齐时,此时外参WGPS_T_WVIO是单位矩阵,所以globalPoseMap里的位姿和VIO的结果一样。globalPoseMap是存储融合优化后的位姿的,这也符合逻辑:在没有gps数据时,融合结果完全和VIO一样。我的理解就是这个值也是放在GPS里面进行优化状态量的初始值,然后进行迭代优化的.
在这里插入图片描述

void GlobalOptimization::inputOdom(double t, Eigen::Vector3d OdomP, Eigen::Quaterniond OdomQ)
{
	mPoseMap.lock();
    // 把vio直接输出的位姿存入 localPoseMap 中
    vector<double> localPose{OdomP.x(), OdomP.y(), OdomP.z(), 
    					     OdomQ.w(), OdomQ.x(), OdomQ.y(), OdomQ.z()};
    localPoseMap[t] = localPose;

    // 把VIO转换到GPS坐标系下,准确的说是转换到以第一帧GPS为原点的坐标系下
    // 转换之后的位姿插入到globalPoseMap 中
    Eigen::Quaterniond globalQ;
    globalQ = WGPS_T_WVIO.block<3, 3>(0, 0) * OdomQ;
    Eigen::Vector3d globalP = WGPS_T_WVIO.block<3, 3>(0, 0) * OdomP + WGPS_T_WVIO.block<3, 1>(0, 3);
    vector<double> globalPose{globalP.x(), globalP.y(), globalP.z(),
                              globalQ.w(), globalQ.x(), globalQ.y(), globalQ.z()};
    globalPoseMap[t] = globalPose;
    lastP = globalP;
    lastQ = globalQ;
    //把vio转换坐标系后的结果赋值给global_path,给最新传入的一个初始值。
    geometry_msgs::PoseStamped pose_stamped;
    pose_stamped.header.stamp = ros::Time(t);
    pose_stamped.header.frame_id = "world";
    pose_stamped.pose.position.x = lastP.x();
    pose_stamped.pose.position.y = lastP.y();
    pose_stamped.pose.position.z = lastP.z();
    pose_stamped.pose.orientation.x = lastQ.x();
    pose_stamped.pose.orientation.y = lastQ.y();
    pose_stamped.pose.orientation.z = lastQ.z();
    pose_stamped.pose.orientation.w = lastQ.w();
    global_path.header = pose_stamped.header;
    global_path.poses.push_back(pose_stamped);

    mPoseMap.unlock();
}

对gps信号转换坐标系
这里是输入的VO数据的10ms内的GPS数据进行坐标系转换,GPS2XYZ函数将GPS的经纬度坐标转换为ENU坐标,并且第一帧的GPS数据作为原点[0,0,0]转换之后的gps数据和协方差一起存入到GPSPositionMap中

void GlobalOptimization::inputGPS(double t, double latitude, double longitude, double altitude, double posAccuracy)
{
	double xyz[3];
    // 因为经纬度表示的是地球上的坐标,而地球是一个球形,
    // 需要首先把经纬度转化到平面坐标系上
    // 值得一提的是,GPS2XYZ()并非把经纬度转化到世界坐标系下(以0经度,0纬度为原点),
    // 而是以第一帧GPS数据为坐标原点,这一点需要额外注意
	GPS2XYZ(latitude, longitude, altitude, xyz);
    // 存入经纬度计算出的平面坐标,存入GPSPositionMap中
	vector<double> tmp{xyz[0], xyz[1], xyz[2], posAccuracy};
    //printf("new gps: t: %f x: %f y: %f z:%f \n", t, tmp[0], tmp[1], tmp[2]);
	GPSPositionMap[t] = tmp;
    newGPS = true;

}

接着就是进行优化了,先讲VIO的优化,加载优化的相关参数.

map<double, vector<double>>::iterator iter;
            iter = globalPoseMap.begin();
            for (int i = 0; i < length; i++, iter++)
            {
                t_array[i][0] = iter->second[0];
                t_array[i][1] = iter->second[1];
                t_array[i][2] = iter->second[2];
                q_array[i][0] = iter->second[3];
                q_array[i][1] = iter->second[4];
                q_array[i][2] = iter->second[5];
                q_array[i][3] = iter->second[6];
                problem.AddParameterBlock(q_array[i], 4, local_parameterization);
                problem.AddParameterBlock(t_array[i], 3);
            }

将观测值两帧VIO的差传入到优化框架中

                //vio factor
                iterVIONext = iterVIO;
                iterVIONext++;
                // 添加VIO残差,观测量是两帧VIO数据之差,是相对的。而下面的GPS是绝对的
                if(iterVIONext != localPoseMap.end())
                {
                    Eigen::Matrix4d wTi = Eigen::Matrix4d::Identity();
                    Eigen::Matrix4d wTj = Eigen::Matrix4d::Identity();
                    wTi.block<3, 3>(0, 0) = Eigen::Quaterniond(iterVIO->second[3], iterVIO->second[4], 
                                                               iterVIO->second[5], iterVIO->second[6]).toRotationMatrix();
                    wTi.block<3, 1>(0, 3) = Eigen::Vector3d(iterVIO->second[0], iterVIO->second[1], iterVIO->second[2]);
                    wTj.block<3, 3>(0, 0) = Eigen::Quaterniond(iterVIONext->second[3], iterVIONext->second[4], 
                                                               iterVIONext->second[5], iterVIONext->second[6]).toRotationMatrix();
                    wTj.block<3, 1>(0, 3) = Eigen::Vector3d(iterVIONext->second[0], iterVIONext->second[1], iterVIONext->second[2]);
                    Eigen::Matrix4d iTj = wTi.inverse() * wTj;
                    Eigen::Quaterniond iQj;
                    iQj = iTj.block<3, 3>(0, 0);
                    Eigen::Vector3d iPj = iTj.block<3, 1>(0, 3);

                    ceres::CostFunction* vio_function = RelativeRTError::Create(iPj.x(), iPj.y(), iPj.z(),
                                                                                iQj.w(), iQj.x(), iQj.y(), iQj.z(),
                                                                                0.1, 0.01);
                    problem.AddResidualBlock(vio_function, NULL, q_array[i], t_array[i], q_array[i+1], t_array[i+1]);

,而VIO的数据和状态量的残差定义为:(j时刻的状态量-i时刻的状态量)得到的增量-vio增量。其意味着融合后的位置必须和GPS位置尽可能重合,而两帧间的增量要和VIO尽可能相等。这对理解坐标转换至关重要,这样的处理意味着vio的数据并不对融合后的绝对位置做约束,只要求融合后的位置增量和vio的增量误差尽可能小。所以融合后的位置会在GPS坐标系下。

	bool operator()(const T* const w_q_i, const T* ti, const T* w_q_j, const T* tj, T* residuals) const
	{
		T t_w_ij[3];//世界坐标系下ij帧的位置增量
		t_w_ij[0] = tj[0] - ti[0];
		t_w_ij[1] = tj[1] - ti[1];
		t_w_ij[2] = tj[2] - ti[2];

		T i_q_w[4];//i帧的四元数逆
		QuaternionInverse(w_q_i, i_q_w);

		T t_i_ij[3];//i帧坐标系下,ij帧的位置增量
		ceres::QuaternionRotatePoint(i_q_w, t_w_ij, t_i_ij);

		residuals[0] = (t_i_ij[0] - T(t_x)) / T(t_var);
		residuals[1] = (t_i_ij[1] - T(t_y)) / T(t_var);
		residuals[2] = (t_i_ij[2] - T(t_z)) / T(t_var);

		T relative_q[4];//传入观测的四元数增量
		relative_q[0] = T(q_w);
		relative_q[1] = T(q_x);
		relative_q[2] = T(q_y);
		relative_q[3] = T(q_z);

		T q_i_j[4];//状态量计算的四元数增量
		ceres::QuaternionProduct(i_q_w, w_q_j, q_i_j);

		T relative_q_inv[4];
		QuaternionInverse(relative_q, relative_q_inv);

		T error_q[4];//状态量计算的增量乘上测量量的逆,定义了残差
		ceres::QuaternionProduct(relative_q_inv, q_i_j, error_q); 

		residuals[3] = T(2) * error_q[1] / T(q_var);
		residuals[4] = T(2) * error_q[2] / T(q_var);
		residuals[5] = T(2) * error_q[3] / T(q_var);

		return true;
	}

对GPS因子的优化.
加载GPS观测值

//gps factor
                // GPS残差,这个观测量直接就是GPS的测量数据,
                // 残差计算的是GPS和优化变量的差,这个是绝对的差。
                double t = iterVIO->first;
                iterGPS = GPSPositionMap.find(t);
                if (iterGPS != GPSPositionMap.end())
                {
                    ceres::CostFunction* gps_function = TError::Create(iterGPS->second[0], iterGPS->second[1], 
                                                                       iterGPS->second[2], iterGPS->second[3]);
                    //printf("inverse weight %f \n", iterGPS->second[3]);
                    problem.AddResidualBlock(gps_function, loss_function, t_array[i]);

这个里的状态量就是前面从VIO坐标系转到GPS坐标系作为初值进行优化.

TError(double t_x, double t_y, double t_z, double var)
				  :t_x(t_x), t_y(t_y), t_z(t_z), var(var){}
	//首先是GPS的数据和状态量定义的残差:状态量位置-gps算出来的位置
	template <typename T>
	bool operator()(const T* tj, T* residuals) const
	{
		residuals[0] = (tj[0] - T(t_x)) / T(var);
		residuals[1] = (tj[1] - T(t_y)) / T(var);
		residuals[2] = (tj[2] - T(t_z)) / T(var);

		return true;
	}

在优化求解完成以后,会遍历globalPoseMap,对其更新。即globalPoseMap里面存储着优化后的位姿。同时,之后会用在VIO坐标系下的位置(localPoseMap里)和优化后在GPS坐标系下的位置(globalPose)对外参WGPS_T_WVIO进行更新。还是考虑第一次同步的gps数据传入,优化完成后。外参WGPS_T_WVIO之前是单位矩阵,而第一次更新,会算出真正和实际相符的外参。

iter = globalPoseMap.begin();
            for (int i = 0; i < length; i++, iter++)
            {
            	vector<double> globalPose{t_array[i][0], t_array[i][1], t_array[i][2],
            							  q_array[i][0], q_array[i][1], q_array[i][2], q_array[i][3]};
            	iter->second = globalPose;
            	if(i == length - 1)
            	{
            	    Eigen::Matrix4d WVIO_T_body = Eigen::Matrix4d::Identity(); 
            	    Eigen::Matrix4d WGPS_T_body = Eigen::Matrix4d::Identity();
            	    double t = iter->first;
            	    WVIO_T_body.block<3, 3>(0, 0) = Eigen::Quaterniond(localPoseMap[t][3], localPoseMap[t][4], 
            	                                                       localPoseMap[t][5], localPoseMap[t][6]).toRotationMatrix();
            	    WVIO_T_body.block<3, 1>(0, 3) = Eigen::Vector3d(localPoseMap[t][0], localPoseMap[t][1], localPoseMap[t][2]);
            	    WGPS_T_body.block<3, 3>(0, 0) = Eigen::Quaterniond(globalPose[3], globalPose[4], 
            	                                                        globalPose[5], globalPose[6]).toRotationMatrix();
            	    WGPS_T_body.block<3, 1>(0, 3) = Eigen::Vector3d(globalPose[0], globalPose[1], globalPose[2]);
            	    WGPS_T_WVIO = WGPS_T_body * WVIO_T_body.inverse();
            	}
            }
            updateGlobalPath();
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

VINS_FUSION入门系列---GPS与VIO融合 的相关文章

  • k-近邻实现手写数字识别

    1 k 近邻工作原理 简单地说 xff0c K近邻算法采用测量不同特征值之间的距离方法进行分类 该算法具有一下特点 优点 xff1a 精度高 对异常值不敏感 无数据输入假定 缺点 xff1a 计算复杂度高 空间复杂度高 K近邻算法的工作原理
  • 吴恩达教你读论文:持续而缓慢的学习,才是正道

    转载这篇文章 xff0c 主要是有两句话特别认同 xff1a 持续而缓慢的学习 xff0c 而不是临时抱佛脚 xff0c 才能带来长久的成长 吴恩达 智慧不是学校教育的产物 xff0c 而是终身学习的产物 阿尔伯特 爱因斯坦 以下为原文 x
  • The Lighting Handbook, Tenth Edition 读书札记

    这本照明书可以说是经典了 xff0c 对照明从微观到宏观 xff0c 从理性到感性 xff0c 从物理到艺术洋洋洒洒做了比较充分和严谨的说明 xff0c 书中引用的论文也是浩浩荡荡 xff0c 可以说是一本集结了众多头脑 xff0c 闪烁着
  • 国家电网公司标准化建设成果应用目录(2015)参考书目

    国家电网标准化图集有很多 xff0c 但有时找的时候又很难记住书名 xff0c 因此把2015年之前的书籍目录摘录出来以便查找 目前是最先的版本了 xff0c 另外有一些06年的废止的分册不再列出了 2016年又增加了一本 国家电网公司输变
  • pyecharts——WordCloud词云图

    转自 xff1a pyecharts学习笔记 WordCloud词云图 码农家园 基本 词云图 注意数据格式 xff0c word1 count1 word2 count2 xff0c 可使用 counter 做词频统计 xff0c 生成这
  • 一个中文词云项目的使用总结

    一个中文词云项目的使用总结 用一个pa wordcloud项目来生成词云图的时候碰到了好几个问题 xff0c 一个pillow库安装问题 xff0c 卸载重新安装了最新版本 xff0c 就是numpy版本不匹配问题 xff0c 安装了对应p
  • 圆周率怎么计算来的?教你利用欧拉恒等式,生成圆周率万能公式!

    原文链接 xff1a http www twoeggz com news 4791962 html 在古代 xff0c 缺少数学技巧的情况下 xff0c 圆周率的计算是相当困难的 xff0c 我们国家伟大的数学家 xff0c 天文学家祖冲之
  • 影片avi转rmvb教程

    昨天被迫压制 MS IGLOO 正好学习了下影片avi转rmvb的技术 找来找去发现篇文章似乎不错 现在根据自己的操作过程 xff0c 加点操作心得再内 xff0c 保留一篇备用 xff01 首先还是要有专门压制的的软件 xff0c 之前我
  • 手机摄像头的等效焦距

    笔者随意拿出一张最近评测文章中的样张 xff0c EXIF信息就位于照片的下方 我们看到 xff0c 光圈 ISO感光度 曝光时间 曝光补偿这样的参数都比较好理解 xff0c 唯独这个焦距确实让不少人生疑 焦距 4mm 光圈 f 2 4 I
  • 关于3D打印文件格式:STL、OBJ、AMF、3MF的详解

    很多人对3D打印的数据格式颇有微词 xff0c 辛辛苦苦用三维软件设计好的作品 xff0c 一转换成3D打印格式 xff0c 基本就从白天鹅变成丑小鸭了 xff0c 既没有颜色 xff0c 数据也不完整 xff0c 形状重叠表面破损那是常有
  • 在线绘制函数图像和在线图标绘制网址

    经过寻找 xff0c 找到了几个在线绘制函数图像的网址 xff0c 可以不用matlab和geogebra软件绘制了 数学函数图像 xff1a 第一个 xff1a Desmos 首推 第二个 xff1a fooplot 可以绘制分段函数比如
  • geogebra中函数的定义域的输入

    ggb中函数的输入有如下几种方式 xff1a 一 如果if做法 1 区间函数 xff1a 做出函数在某区间上的图象 xff1a f x 61 if x gt 61 0 amp amp x lt 61 2 x 2 43 2x 1 2 分段函数
  • 升级Ubuntu内核

    自己下载deb或使用某些其他工具 xff0c 无脑dpkg deb会导致Depends libc6 gt 61 2 33 but 2 31 ubuntu9 2 is to be installed的错误 xff08 猜测该错误产生的原因是没
  • 在ROS的noetic版本中通过rosrun运行python文件

    xff08 1 xff09 不要将python文件放入scr目录中 xff0c 否则后续编译工作空间会报如图所示的错误 首先要在功能包文件夹 xff08 catkin ws src learnning topic xff09 中创建一个sc
  • linux音量调节

    转自 xff1a https www jianshu com p fc8c8cad67d6 一 alsa设置默认声卡 alsa设置默认声卡 理解和使用Alsa的配置文件 alsa的配置文件是alsa conf位于 usr share als
  • FutureTask实际应用案例

    GetResultTask java package com cwp data service service task import com cwp data intelligence common exception RRExcepti
  • 异常检测算法综述

    一 异常检测 随着人工智能的火热 xff0c 运维人员也开始考虑将算法引入运维领域 xff0c 对传统DevOps的核心功能进行优化改进 异常检测是运维不可或缺的重要要功能模块之一 xff0c 可以提升企业运维能力和效率 xff0c 释放运
  • 每日一书丨嵌入式C语言自我修养:从芯片、编译器到操作系统

    最近 xff0c 阅读了王工 xff08 王利涛 xff09 赠送的一本由他编著的书籍 嵌入式C语言自我修养 xff0c 感觉写的挺不错 今天分享一下这本书籍 嵌入式C语言自我修养 xff1a 从芯片 编译器到操作系统 从芯片 编译器到操作
  • JSP提交仍然停留在当前页面

    在C S结构中 xff0c 用户提交内容以后 xff0c 系统任停留在当前页面上 xff0c 直到服务返回处理成功或者失败的提示 而用户录入的信息 xff0c 除非程序清除 xff0c 否则不会自动消失 xff0c 方便用户修改 为了解决这
  • FreeRTOS Queue

    变量定义 span class token keyword typedef span span class token keyword void span span class token operator span QueueHandle

随机推荐

  • 专门讲解无人机航拍图像处理的书【包括图像拼接!!!】

    最近正式开始做课设啦 xff0c 博主在网上搜集到有专门的书讲解无人机航拍图像的处理 xff0c 包括图像拼接 xff01 xff01 xff01 更非常激动的是博主在图书馆把两本书都找到了 xff0c 俺滴学校i了i了 两本书如下所示 x
  • 1.2 向量与线性代数

    向量与线性代数 图形学基础向量向量点乘向量叉乘矩阵 图形学基础 基础数学 xff1a 线性代数 统计学 微积分基础物理 xff1a 其他课程 xff1a 信号处理 数学分析一点点 xff1a 美学课程 向量 方向长度单位向量向量加法 向量点
  • 2.1 变换

    矩阵变换 二维变换齐次坐标齐次坐标下的二维变换矩阵逆变换 xff08 逆矩阵 xff09 复合变换三维空间仿射变换 modeling and viewing 模型变换和视角变换 二维变换 尺度变换 Scale 镜像变换 切变变换 旋转变换
  • 2.2 变换(模型、视图、投影)

    变换 xff08 模型 视图 投影 xff09 三维变换观测变换 xff08 Viewing transformation xff09 视图 xff08 View xff09 定义相机如何将相机移动到约定俗成位置 投影 xff08 Proj
  • 四轴飞行器入门——基础知识

    引言 从2016年起 xff0c 细细数来入门无人机已经有两年时间 两年期间 xff0c 自己边学边摸索 xff0c 组装过机架四轴无人机 xff0c 也修改过开源飞控的代码 xff0c 但是因为种种原因 xff0c 始终没有写过相关博客记
  • Linux系统下搭建PX4/Pixhawk原生固件编译环境

    简介 PX4固件是Pixhawk飞行控制器的官方固件 xff0c Pixhawk官网也给出了Linux windows下搭建开发环境的方法 由于种种原因 xff0c 搭建开发环境时总会遇到各种各样的bug xff0c 致使PX4固件编译失败
  • main(int argc, char *argv[])

    这是UNIX和Linux中的标准主函数 argc 用来统计运行时发送给main函数的命令行参数的个数 argv 其中每个元素都是上述参数 以字符串形式存储 的首地址 argv 0 指向程序运行的全路径名 argv 1 指向程序名后的第一个参
  • 为PX4添加串口通讯模块(模块结构)

    主要讲模块的结构 不贴代码 从最外层开始 执行read uart main start dev ttyS1 read uart main int argc char argv 入口函数 判断任务进程read uart task是否存在 根据
  • C++抽象基类与虚基类(C++ primer)

    c 43 43 primer plus P508 xff0c 抽象基类 c 43 43 primer plus P556 xff0c 虚基类 抽象基类 xff08 abstract base class xff0c ABC xff09 抽象
  • MFC学习笔记(二)处理命令行选项

    目标 让应用程序处理这里所见的命令行标志 gt XXX exe c d 策略 一个MFC应用程序可以用CCommandLineInfo类的成员函数ParseParam 处理一些标准标 志 要添加我们自己的标志 xff0c 而仍然能够支持另外
  • C++ expection异常类、捕获所有异常(C++ primer,P639)

    expection类 头文件 lt expection gt stdexcept类 C 43 43 primer plus xff0c P632 包含以下异常 xff1a domain errorinvalid argumentlength
  • 5.1 运输层协议

    运输层协议 运输层的复用与常见端口常用端口 UDP协议特点UDP帧格式 TCP协议特点socket套接字可靠传输工作原理TCP帧首部重要字段 TCP可靠传输以字节为单位的滑动窗口选择超时重传时间选择确认SACK xff08 未经常使用P22
  • Linux上VScode + cmake + gcc开发环境搭建

    VScode 43 cmake 43 gcc 下载 安装vscode安装插件cmake文件结构vscode修改json文件编译 调试的过程 下载 安装 span class token comment cmake gcc 安装都很简单 sp
  • 软件测试面试04:实战项目介绍

    4 1 简单介绍下最近做过的项目 根据自己的项目整理完成 xff0c 要点 xff1a 1 xff09 项目背景 业务 需求 核心业务的流程 2 xff09 项目架构 xff0c B S还是C 5 xff0c 数据库用的什么 中间件用的什么
  • 一张图搞定SDF的概念

    本文仅代表个人理解 xff0c 谬误之处请指正 SDF Signed Distance Field 译为有向距离场 xff0c 有向 距离 场 这三个词非常精确的描述了 sdf 究竟是个什么东西 GPU Gems 3 中是这么描述 sdf
  • Ubuntu Windows双系统切换最简方法!!!

    安装完Ubuntu windows双系统后的第一个问题 xff1a 该怎么在两个系统间快速自由切换呢 xff1f 本文给出两种无需命令行的实用易上手方式 一 什么 xff0c 你要快快快快速切换 xff1f 这里直接给出答案 xff0c F
  • C++primer(第五版)习题答案

    前两章习题较简单 xff0c 这里就不作整理了 xff0c 直接从第三章开始 持续更新 xff1a Chapter 3 Strings Vectors and Arrays Exercise 3 1 part 1 include lt io
  • PX4源码地址和wiki

    源码 https github com 987419640 Firmware wiki https dev px4 io v1 9 0 zh concept architecture html
  • 视觉十四讲:第七讲_2D-2D:对极几何估计姿态

    1 对极几何 从2张图片中 得到若干个配对好的2d特征点 就可以运用对极几何来恢复出两帧之间的运动 设P的空间坐标为 P 61 X Y Z T 两个像素点 p 1 p 2 的像素坐标为 s 1 p 1 61 KP s 2 p 2 61 K
  • VINS_FUSION入门系列---GPS与VIO融合

    参考的博客 https blog csdn net subiluo article details 105429471 http www luyixian cn news show 313718 aspx state 状态量 位姿 速度 b