VINS-Mono代码详解 ——— (1)启动文件euroc.launch + 参数配置文件euroc_config.yaml

一、启动文件euroc.launch

启动文件euroc.launch:为了一次运行多个node

1. 文件位置

在这里插入图片描述

2. 文件内容

在这里插入图片描述

2.1 launch文件语法

在这里插入图片描述

  • pkg=package名字(在package.xml定义)
    在这里插入图片描述
    在这里插入图片描述

  • type=可执行文件名字(在CMakeLists.txt定义)
    在这里插入图片描述

在这里插入图片描述

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

2.2 设置局部变量"config_path",表示euroc_config.yaml的具体地址;

<arg name="config_path" default = "$(find feature_tracker)/../config/euroc/euroc_config.yaml" />
	  <arg name="vins_path" default = "$(find feature_tracker)/../config/../" />

设置局部变量"vins_path",在parameters.cpp中使用鱼眼相机mask中用到:

std::string VINS_FOLDER_PATH = readParam<std::string>(n, "vins_folder");
if (FISHEYE == 1)
        FISHEYE_MASK = VINS_FOLDER_PATH + "config/fisheye_mask.jpg";

2.3 启动"feature_tracker"节点,在该节点中需要读取参数文件,地址为config_file,即config_path;

<node name="feature_tracker" pkg="feature_tracker" type="feature_tracker" output="log">
    <param name="config_file" type="string" value="$(arg config_path)" />
    <param name="vins_folder" type="string" value="$(arg vins_path)" />
</node>

2.4 启动"vins_estimator"节点,内容同上;

<node name="vins_estimator" pkg="vins_estimator" type="vins_estimator" output="screen">
   <param name="config_file" type="string" value="$(arg config_path)" />
   <param name="vins_folder" type="string" value="$(arg vins_path)" />
</node>

2.5 启动"pose_graph"节点,除了参数配置文件的地址外还设置了4个参数:

<node name="pose_graph" pkg="pose_graph" type="pose_graph" output="screen">
    <param name="config_file" type="string" value="$(arg config_path)" />
    <param name="visualization_shift_x" type="int" value="0" />
    <param name="visualization_shift_y" type="int" value="0" />
    <param name="skip_cnt" type="int" value="0" />
    <param name="skip_dis" type="double" value="0" />
</node>

visualization_shift_xvisualization_shift_y表示在进行位姿图优化后,对得到的位姿在x坐标和y坐标的偏移量(一般都设为0);

geometry_msgs::PoseStamped pose_stamped;
pose_stamped.header.stamp = ros::Time(cur_kf->time_stamp);
pose_stamped.header.frame_id = "world";
pose_stamped.pose.position.x = P.x() + VISUALIZATION_SHIFT_X;
pose_stamped.pose.position.y = P.y() + VISUALIZATION_SHIFT_Y;
pose_stamped.pose.position.z = P.z();

skip_cntpose_graph_node的process()中,表示每隔skip_cnt个图像帧才进行一次处理;
skip_dis也在pose_graph_nodeprocess()中,目的是将距上一帧的时间间隔超过SKIP_DIS的图像创建为位姿图中的关键帧。

二、参数配置文件euroc_config.yaml

1. 文件位置

在这里插入图片描述

2. 文件内容

在这里插入图片描述

%YAML:1.0

#common parameters
imu_topic: "/imu0"                          
image_topic: "/cam0/image_raw"
output_path: "/home/shaozu/output/"

#camera calibration 
model_type: PINHOLE
camera_name: camera
image_width: 752
image_height: 480
distortion_parameters:
   k1: -2.917e-01
   k2: 8.228e-02
   p1: 5.333e-05
   p2: -1.578e-04
projection_parameters:
   fx: 4.616e+02
   fy: 4.603e+02
   cx: 3.630e+02
   cy: 2.481e+02

# Extrinsic parameter between IMU and Camera.
#IMU与摄像机之间的外部参数。
estimate_extrinsic: 0   # 0  Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
                        # 1  Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
                        # 2  Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.                        
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam

                        # 0 有一个精确的外部参数。 我们会信任下面的imu和r_cam,imu和t_cam,不要改变它。
                        # 1 对外部参数有初步的猜测。 我们将围绕您的初步猜测进行优化。
                        # 2 对外界参数一无所知。 你不需要给R,T。 我们会试着校准的。 开始时做一些旋转动作。
# 如果你选择01,你应该写下下面的矩阵。
# 从相机架旋转到imu架、imu^r_cam
extrinsicRotation: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [0.0148655429818, -0.999880929698, 0.00414029679422,
           0.999557249008, 0.0149672133247, 0.025715529948, 
           -0.0257744366974, 0.00375618835797, 0.999660727178]
#Translation from camera frame to imu frame, imu^T_cam
#从相机到imu的转换,imu^T_cam
extrinsicTranslation: !!opencv-matrix
   rows: 3
   cols: 1
   dt: d
   data: [-0.0216401454975,-0.064676986768, 0.00981073058949]

#feature traker paprameters
#特征跟踪参数
max_cnt: 150            # max feature number in feature tracking
					    # 进行特征光流跟踪时保持的最大特征点数量
min_dist: 30            # min distance between two features 
                        # 两个相邻特征之间像素的最小间隔
freq: 10                # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image 
                        # (赫兹) 发布跟踪结果。 至少10Hz,以获得良好的估计。 如果设置为0,频率将与原始图像相同
F_threshold: 1.0        # ransac threshold (pixel)
                        # ransac阈值 (像素)
show_track: 1           # publish tracking image as topic
                        # 发布跟踪图像作为主题
equalize: 1             # if image is too dark or light, trun on equalize to find enough features
                        # 如果图像太暗或太亮,按直方图均衡化查找足够的特征
fisheye: 0              # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
                        # 如果用鱼眼,就转动它。 将加载一个圆形掩码以消除边缘噪声点
                        # 鱼眼相机一般需要圆形的mask,以去除外部噪声点。mask图在config文件夹中。

#optimization parameters
#优化参数
max_solver_time: 0.04  # max solver itration time (ms), to guarantee real time
                       # ceres优化器的最大迭代时间,以保证实时性。
max_num_iterations: 8   # max solver itrations, to guarantee real time
                        # ceres优化器的最大迭代次数,以保证实时性。
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
                        # 关键帧选择阈值 (像素)
#imu parameters       The more accurate parameters you provide, the better performance
#imu参数              您提供的参数越准确,性能越好
acc_n: 0.08          # accelerometer measurement noise standard deviation. #0.2   0.04
                     # 加速度传感器测量噪声标准差
gyr_n: 0.004         # gyroscope measurement noise standard deviation.     #0.05  0.004
                     # 陀螺仪测量噪声标准差
acc_w: 0.00004         # accelerometer bias random work noise standard deviation.  #0.02
                       # 加速度计偏置随机噪声标准差
gyr_w: 2.0e-6       # gyroscope bias random work noise standard deviation.     #4.0e-5
                    # 随机噪声标准偏差
g_norm: 9.81007     # gravity magnitude
                    # 重力大小

#loop closure parameters
#闭环参数
loop_closure: 1                    # start loop closure
                                   # 使用闭环
load_previous_pose_graph: 0        # load and reuse previous pose graph; load from 'pose_graph_save_path'
                                   # 加载并重用前一个pose图;pose_graph_save_pathe的负载
fast_relocalization: 0             # useful in real-time and large project
                                   # 可用于实时大型项目
pose_graph_save_path: "/home/shaozu/output/pose_graph/" # save and load path
                                                        # 储存及载入路径

#unsynchronization parameters
#在线时差校准
estimate_td: 0                      # online estimate time offset between camera and imu
                                    # 摄像机与imu之间的在线估计时间偏移
td: 0.0                             # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
                                    # 时间偏移的初始值。 单位:s。readed图像时钟+td=real image时钟 (IMU时钟)

#rolling shutter parameters
# 支持卷帘相机
rolling_shutter: 0                  # 0: global shutter camera, 1: rolling shutter camera
                                    # 0表示全局曝光相机;设置为1表示卷帘曝光相机
rolling_shutter_tr: 0               # unit: s. rolling shutter read out time per frame (from data sheet). 
                                    # 单位:s  卷动快门读出时间 (来自数据表)
#visualization parameters
# 可视化参数
save_image: 1                   # save image in pose graph for visualization prupose; you can close this 
function by setting 0 
                                # 将图像保存在体位图中,实现可视化保存;您可以通过设置0关闭此函数
visualize_imu_forward: 0        # output imu forward propogation to achieve low latency and high frequence results
                                # 输出imu前馈实现低延迟、高频率的效果
visualize_camera_size: 0.4      # size of camera marker in RVIZ
                                # 摄像机标记在RVIZ中的尺寸

三、参考文献

CSDN博主「Manii」的文章

  • 4
    点赞
  • 18
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值