AirVO: An Illumination-Robust Point-Line Visual Odometry 论文笔记及源码阅读
Github开源
ABSTRACT
AirVO是一个以点、线特征为基础设计的光学性能优异且定位精度极高的双目视觉里程计系统。
为了增强系统对光照变化的适应能力,我们开发了一种基于学习的特征提取与匹配算法,并构建了一个创新性的视觉里程计架构:它整合了特征跟踪、三角测量、关键帧筛选以及图形优化等多个核心模块。
此外,在提升定位精度方面,我们主要依赖于环境中的长直线特征。
最后,在光参数稳定性的保证下,我们提出了一种改进型线追踪算法:该算法通过结合点特征求取、点分布分析以及直线特性和匹配机制实现了对动态场景中直线元素的有效跟踪。
This paper introduces our system, named AirVO—a lighting-resilient and precise stereo visual odometry platform based on point and line features. To ensure robustness against varying illumination conditions, we have integrated a learning-based feature extraction approach along with a matching technique. A novel vision pipeline has been developed for this purpose, incorporating feature tracking mechanisms such as triangulation, key-frame selection processes, and graph-based optimization procedures. Additionally, we have utilized long line features within the environment to enhance the overall accuracy of our system.
INTRODUCTION
由于低成本且高度准确的特性 ,视觉里程计在多个领域得到了广泛应用 ,特别是在增强现实与机器人技术相关的领域中 。然而现有的解决方案如MSCKF 、VINS-Mono 、OKVIS等在长时间运行时的鲁棒性仍需进一步提升 。例如 在光照条件持续变化的环境中 视觉追踪问题变得极其具有挑战性 同时其轨迹估计的质量受到了显著影响
另一方面,在机器视觉领域发挥重要作用的研究也取得了重大进展,并促进了另一个研究方向的发展。尽管基于学习的方法已逐渐出现并带来了显著的效果,在多个应用场景中展现了优势。然而这些方案通常依赖于大量计算资源导致无人机等低算力设备难以实现实时处理
在文章中
METHODOLOGY

A. System Overview
该系统采用混合语音(VO)架构,在前端部分采用学习方法,在后端部分采用传统技术。对于每一对立体图像,在前端部分我们首先使用卷积神经网络(如SuperPoint)提取特征点,并将其与特征匹配网络(如SuperGlue)进行配准。此外,在我们的系统中还利用线特征来提升准确性
如图所示的框架结构中包含: Fig.2 是一个融合了深度学习前端和传统后端优化的混合视觉里程计系统。该系统首先利用预训练的CNN模型(如SuperPoint)提取单目图像的特征点,并通过特征匹配网络(如SuperGlue)进行配准。随后,在获取关键点位置信息的过程中直接跳过了中间细节步骤,并利用线特征提取进一步提高系统定位精度。观察到在实际应用中发现许多关键点位于边缘区域的同时也位于线特征提取区域之间存在一定的关联性。基于此可以将两种不同区域中的关键点进行配准从而实现对双目图像中线条或其他不同帧图像的配准以及基于关联点结果追踪以获得更好的视觉鲁棒性效果。为了进一步提升系统的定位精度我们采用了左眼图像的不同帧进行了特追踪操作基于这些结果选取了关键帧并通过优化处理改善了关键帧之间的几何关系最终实现了对关键帧的整体调整以增强整体系统的性能表现
B. 2D Line Processing
2D Line Processing 包括线段的检测和匹配 。
Detection : 线条检测采用了AirVO技术,在这一过程中我们主要参考了传统中的LSD方法[1] 。然而该方法在处理直线分割成多部分时存在不足[2] ,为此我们进行了优化[3] 。具体而言,在满足以下条件时我们将两条线段视为同一整体:
- 线段L1和L2的角度差小于给定阈值
- 一个线段的中点到另一个线段中点的距离不大于
- 如果L1和L2在X轴和Y轴的投影不重叠,线段端点的距离小于给定值
选取更具有代表性的长线段,小于预设长度的线段会被过滤掉。
Matching
,每个线段表示为
, 其中
是
的线段的参数,
是端点。We first compute the distance between
and

through:

若
<3, 且像素

在坐标轴的投影位于线段端点的范围之内,那么像素

便属于线段

.两个图像中线段的匹配进而可以通过其中点匹配的结果来实现;在图像k中存在线段。

和图像K+1中的线段

,我们会计算一个分数来表示他们是同一条线段的确信度。

是位于线段

和线段

上的特征点数之间的一个数,

和

分别是位于线段

上的特征点数目。相应的,若
且

,(此处,

和

是两个预设的阈值)。我们将认为

和

是同一条线。
The point matching mechanism exhibits robustness to illumination variations, ensuring that feature associations remain unaffected by changes in lighting conditions.
C. 3D Line Processing
在三维空间中存在更高的自由度,在几何建模中通常采用参数化的方法来描述曲线。首先阐述其在各个阶段的表现形式,在具体实施时可以通过三角剖分的方法实现二维到三维直线的转换。例如通过三角剖分的方法实现二维到三维直线的转换,在具体实施时可以通过三角剖分的方法实现二维到三维直线的转换。例如通过三角剖分的方法实现二维到三维直线的转换,在具体实施时可以通过三角剖分的方法实现二维到三维直线的转换。
- Representation: 使用普鲁克坐标系表示3D空间的直线

方向向量 v 描述了直线的方向;法向量 n 定义了由线段及光心决定平面的垂直方向;普鲁克坐标在三角化、变换以及图像映射方面被广泛应用于三维直线处理;由于其参数冗余性(即六个参数中仅有四个独立自由度),这种坐标系统显得有些多余;在图形优化阶段引入额外的自由度可能会增加计算成本,并可能导致数值不稳定;因此我们采用正则表示来减少这些冗余。

The connection between Plücker parameters and the orthonormal formulation mirrors that of SO(3) Lie group and its corresponding Lie algebra so(3). The orthonormal formulation can be derived using the Plücker parameters via a specific formula, which establishes a direct relationship between these mathematical constructs in the context of geometric algebra.

2.Triangulation : Triangulation is defined as the process of establishing a three-dimensional line based on multiple two-dimensional line measurements.
系统中使用了两种3D直线的三角化方法,分别如下:
- 三维直线可由两个平面计算得出。为了实现这一目标,在两张图像上分别选择两条线段l₁和l₂(均为同一三维直线的两次观测结果)。通过反向投影法将这两条线段分别映射至两个平面π₁和π₂上。
- 然后该三维直线可被视为这两个平面π₁与π₂的交线。
- 如果上述方法失效(即在使用点来计算三维直线的情形下),则需转而采用其他策略。
- 在第III-B节中我们已经将点特征与线特征进行了关联(即Section III-B中我们已经将点特征与线特征进行了关联)。
- 因此,在初始化一条三维直线时我们需要选取两条三角化的点X₁和X₂(其中X₁=(x₁,y₁,z₁)、X₂=(x₂,y₂,z₂)),这两条点位于同一条直线上并且在图像平面上的距离最短。
- 这样一来这条直线的Plücker坐标便可通过上述方法求得。

Because in the point triangulating stage, the selected 3D points have already been triangulated, this method does not incur significant computational overhead. It is highly efficient and reliable.
3.Reprojection:采用Puck坐标系完成对三维直线的变换及重投射过程。第一步是将三维直线从全局坐标系转换至相机坐标系。

D. Key-Frame Selection
仅根据当前帧与关键帧之间的匹配关系进行处理,并基于此判断是否为关键帧。如果满足以下条件,则该帧被视为关键帧。
Recognizing that the learning-based data association method can effectively manage two frames separated by a large distance, we observe that this approach differs from conventional methods. Thus, unlike typical frame-by-frame tracking strategies employed in other Vision Odometry (VO) or Simultaneous Localization and Mapping (SLAM) systems, our method exclusively associates the current frame with key-frames. Key-frames are chosen for each frame based on any of these criteria:

E. Graph Optimization
我们选取N个关键帧并搭建一个类似于ORB-SLAM[17]的共同可见度图。其中地图点、三维线和关键帧作为顶点构成框架,在此框架下建立连接关系即为约束边。该图包含四种类型的约束关系:单目线检测、双目线匹配、单目点检测以及双目点匹配等。
,那么重新投影的误差定义为:


2)双目线约束。 如果第k帧的左摄像机和右摄像机都能观察到三维线
, 那么,重新投影的误差定义为

3)单目点约束。 如果3D点
只能左相机的第k帧观察到,那么重新投射的误差为:

4)双目点约束 。如果一个三维点
被第k帧的左摄像机和右摄像机观察到,那么重新投影的误差定义为:

5)成本函数。假设观察结果服从于高斯分布,最终的成本函数可以定义为:

( inverse covariance matrices:逆协方差矩阵)
EXPERIMENTS
我们经过严格优化未做任何参数微调的SuperPoint和SuperGlue分别提取并匹配关键点,在两个典型数据集:OIVIO dataset(编号51)与UMA视觉惯性数据集(编号6)上进行实验。同时与PL-SLAM [26]、VINS-Fusion [3]、StructVIO [34]、UV-SLAM [30]以及Stereo ORB-SLAM2[19]等算法进行定位精度对比实验。
In this section, experimental results will be presented to validate the performance of our method. The approach leverages pre-trained SuperPoint and SuperGlue for feature detection and matching without further fine-tuning. The experiments were conducted on two datasets: OIVIO dataset (51) and UMA visual-inertial dataset (6). The proposed method's localization accuracy is compared with PL-SLAM (26), VINS-Fusion (3), StructVIO (34), UV-SLAM (30), and Stereo ORB-SLAM2 (19).
Since our proposed approach is based on a Visual Odometry (VO) framework, we omitted the loop closure mechanism taken from standard baselines. It is important to note that our method cannot be directly compared to DX-SLAM [15] or GCNv2-SLAM [22], as these approaches rely solely on RGB-D data for their computations.


A. Results on OIVIO Benchmark
OIVIO数据集收集了隧道和矿井中的视觉-惯性数据 。在每个序列中,场景被一个大约1300、4500或9000的机载灯照亮 。我们选择了由徕卡TCRP获得的所有9个具有地面实况的序列。徕卡TCRP1203 R300获得。性能平移误差的表现见表一。两个最准确的结果分别以高亮和下划线表示。AirVO在6个序列上取得了最好的性能,在其他3个序列上取得了第二好的性能,在其他3个序列上取得了第二好的性能,胜过其他最先进的算法。我们注意到我们注意到,VINS-Fusion、StructVIO和UV-SLAM在许多序列上失去了追踪的机会。序列,这可能是由于他们的特征跟踪方法。即KLT稀疏光流,ZNCC,LBD描述符,不是光照度的影响。为了显示所提出的线条处理方法的有效性线条处理方法的有效性,我们将线条特征从AirVO去除,并将其命名为AirVO w/o line。可以看出,加入线条特征后,平均平移误差下降了13.2%。这证明了使用线条可以提高我们系统的准确性。
我们对比了图5中的我们的方法与OIVIO MN_050_GV_02序列选定的基线。通过这一对比可以看出,在这种特定条件下,在机载照明下机器人穿越了一个矿井,在纵轴上表示成功运行的比例,在横轴上则根据对准误差阈值划分比例区间。该对比表明在该序列表现最为精确的是AirVO系统
B. Results on UMA-VI Benchmark
UMA-VI数据集是一种融合视觉与惯性感知的数据集合;它是在光照条件复杂多变的情况下通过手持式定制设备采集生成的。
C. Runtime Analysis
本节详细讨论了拟议系统的运行时间和性能表现。
评估是在一台配备AMD Ryzen Threadripper PRO 3975WX 处理器和NVIDIA Geforce RTX 3090 GPU 的笔记本电脑上完成的。
输入图像的分辨率设定为752×480像素。
在我们的系统中,每幅图像的特征点检测与跟踪所需的时间仅为15毫秒(ms),相较于原始Python代码而言(需40ms),时间成本降低了62.5%。
表中列出了各模块的具体运行时间数据。
值得注意的是:
其中,
- 特征检测模块负责识别双目相机中的点和线;
- 追踪模块则处理双目匹配以及帧间特征追踪任务;
- 可以看出,
整个系统能够稳定达到20帧每秒(FPS)的工作频率,
充分满足实时性需求。

Conclusions
Within this study, we introduced an illumination-resistant visual odometry system grounded in learning-driven keypoint detection and matching techniques.To enhance precision, line features are incorporated into our framework. Through extensive testing, we demonstrated that the proposed method exhibited superior performance under varying illumination conditions while maintaining real-time operation capabilities. We made our source code available as part of this work, inviting further exploration of its applications within robotics domains. For future research directions, we propose extending AirVO to a SLAM system by integrating loop closing, re-localization mechanisms, and map-reuse strategies with enhanced robustness under diverse lighting scenarios. Our ultimate goal is to establish a reliable illumination-insensitive visual mapping system for enduring localization tasks across various environments
本研究提出了一种基于学习的点特征提取与匹配算法,在动态光照环境下展现出良好的性能。该方法现已开源,并计划在未来增加回环检测、重定位以及地图复用等功能以增强AireVO的能力。
AirVO源码阅读分析:
main.cpp
主要包括三个核心环节:从配置中读取参数设置、读取并加载输入数据序列以及对每一张单幅图像进行特征提取。在这一过程中会涉及判断当前图像是否为关键帧,并通过分析关键帧特征信息计算相机的姿态与位置;最终将提取到的结果保存至轨迹文件中。
int main(int argc, char **argv) {
ros::init(argc, argv, "air_vo");
//获取参数配置
std::string config_path, model_dir;
...
ros::param::get("~traj_path", traj_path);
Dataset dataset(configs.dataroot);//获取数据集
MapBuilder map_builder(configs); //初始配置
size_t dataset_length = dataset.GetDatasetLength();
for(size_t i = 0; i < dataset_length && ros::ok(); ++i){
std::cout << "i ===== " << i << std::endl;
auto before_infer = std::chrono::steady_clock::now();
cv::Mat left_image, right_image;
double timestamp;
//获取第i帧,左右图像
if(!dataset.GetData(i, left_image, right_image, timestamp)) continue;
map_builder.AddInput(i, left_image, right_image, timestamp);
auto after_infer = std::chrono::steady_clock::now();
auto cost_time = std::chrono::duration_cast<std::chrono::milliseconds>(after_infer - before_infer).count();
std::cout << "One Frame Processinh Time: " << cost_time << " ms." << std::endl;
}
map_builder.SaveTrajectory(traj_path);
ros::shutdown();
return 0;
}
map_builder(configs) 部分代码如下:
创建新对象的过程
MapBuilder::MapBuilder(Configs& configs): _init(false), _track_id(0), _line_track_id(0),
_to_update_local_map(false), _configs(configs){
_camera = std::shared_ptr<Camera>(new Camera(configs.camera_config_path));
_superpoint = std::shared_ptr<SuperPoint>(new SuperPoint(configs.superpoint_config));
if (!_superpoint->build()){
std::cout << "Error in SuperPoint building" << std::endl;
exit(0);
}
_point_matching = std::shared_ptr<PointMatching>(new PointMatching(configs.superglue_config));
_line_detector = std::shared_ptr<LineDetector>(new LineDetector(configs.line_detector_config));
_ros_publisher = std::shared_ptr<RosPublisher>(new RosPublisher(configs.ros_publisher_config));
_map = std::shared_ptr<Map>(new Map(_configs.backend_optimization_config, _camera, _ros_publisher));
}
map_builder.AddInput(i, left_image, right_image, timestamp):
- 图像畸形校正
- 特征点提取:从supoint推导出inference
- 线检测器:LineExtactor
- 双目特征点匹配(如使用superGlue)
- 初始化并构建关键帧的操作步骤包括初始化主框架(init frame)
- 根据关键帧进行追踪
void MapBuilder::AddInput(int frame_id, cv::Mat& image_left, cv::Mat& image_right, double timestamp){
// undistort image
cv::Mat image_left_rect, image_right_rect;
_camera->UndistortImage(image_left, image_right, image_left_rect, image_right_rect);
// extract features
Eigen::Matrix<double, 259, Eigen::Dynamic> features_left, features_right;
std::vector<Eigen::Vector4d> lines_left, lines_right;Matrix
if(!_superpoint->infer(image_left_rect, features_left)){
std::cout << "Failed when extracting features of left image !" << std::endl;
return;
}
if(!_superpoint->infer(image_right_rect, features_right)){
std::cout << "Failed when extracting features of right image !" << std::endl;
return;
}
_line_detector->LineExtractor(image_left_rect, lines_left);
_line_detector->LineExtractor(image_right_rect, lines_right);
// stereo_match
std::vector<cv::DMatch> stereo_matches;
StereoMatch(features_left, features_right, stereo_matches);
// construct frame
FramePtr frame = std::shared_ptr<Frame>(new Frame(frame_id, false, _camera, timestamp));
frame->AddFeatures(features_left, features_right, lines_left, lines_right, stereo_matches);
std::cout << "Detected feature point number = " << features_left.cols() << std::endl;
// init
if(!_init){
if(stereo_matches.size() < 100) return;
_init = Init(frame);
_last_frame_track_well = _init;
if(_init){
_last_frame = frame;
_last_image = image_left_rect;
_last_keyimage = image_left_rect;
}
PublishFrame(frame, image_left_rect);
return;
}
// first track with last keyframe
std::vector<cv::DMatch> matches;
int num_match = TrackFrame(_last_keyframe, frame, matches);
if(num_match < _configs.keyframe_config.min_num_match){
_last_frame_track_well = false;
if(_num_since_last_keyframe > 1 && _last_frame_track_well){
// if failed, track with last frame
InsertKeyframe(_last_frame);
_last_keyimage = _last_image;
matches.clear();
num_match = TrackFrame(_last_frame, frame, matches);
if(num_match < _configs.keyframe_config.min_num_match) return;
}else{
return;
}
}
frame->SetPreviousFrame(_last_keyframe);
// int track_local_map_num = TrackLocalMap(frame, num_match);
// UpdateReferenceFrame(frame);
// num_match = (track_local_map_num > 0) ? track_local_map_num : num_match;
// for debug
// SaveTrackingResult(_last_keyimage, image_left, _last_keyframe, frame, matches, _configs.saving_dir);
PublishFrame(frame, image_left_rect);
_last_frame_track_well = true;
if(AddKeyframe(_last_keyframe, frame, num_match)){
InsertKeyframe(frame);
_last_keyimage = image_left_rect;
}
_last_frame = frame;
_last_image = image_left_rect;
return;
}
map_builder.SaveTrajectory:
void MapBuilder::SaveTrajectory(std::string file_path){
_map->SaveKeyframeTrajectory(file_path);
}
SaveKeyframeTrajectory(file_path):
void Map::SaveKeyframeTrajectory(std::string file_path){
std::cout << "Save file to " << file_path << std::endl;
std::ofstream f;
f.open(file_path.c_str());
f << std::fixed;
std::cout << "_keyframe_ids.size = " << _keyframe_ids.size() << std::endl;
for(auto& frame_id : _keyframe_ids){
FramePtr kf = _keyframes[frame_id];
Eigen::Matrix4d& pose = kf->GetPose();
Eigen::Vector3d t = pose.block<3, 1>(0, 3);
Eigen::Quaterniond q(pose.block<3, 3>(0, 0));
f << std::setprecision(9) << kf->GetTimestamp() << " "
<< std::setprecision(9) << t(0) << " " << t(1) << " " << t(2) << " "
<< q.x() << " " << q.y() << " " << q.z() << " " << q.w() << std::endl;
}
f.close();
}
在其中进行MapBuilder::Init(Frame)代码块的初始化过程以及Frame::AddFeatures特征的添加操作都是一个非常关键的重要环节。
bool MapBuilder::Init(FramePtr frame){
int feature_num = frame->FeatureNum();
if(feature_num < 150) return false;
// Eigen::Matrix4d init_pose = Eigen::Matrix4d::Identity();
Eigen::Matrix4d init_pose;
init_pose << 1, 0, 0, 0, 0, 0, 1, 0, 0, -1, 0, 1, 0, 0, 0, 1;
frame->SetPose(init_pose);
frame->SetPoseFixed(true);
Eigen::Matrix3d Rwc = init_pose.block<3, 3>(0, 0);
Eigen::Vector3d twc = init_pose.block<3, 1>(0, 3);
// construct mappoints
std::vector<int> track_ids(feature_num, -1);
int stereo_point_num = 0;
int frame_id = frame->GetFrameId();
Eigen::Vector3d tmp_position;
std::vector<MappointPtr> new_mappoints;
for(size_t i = 0; i < feature_num; i++){
if(frame->BackProjectPoint(i, tmp_position)){
tmp_position = Rwc * tmp_position + twc;
stereo_point_num++;
track_ids[i] = _track_id++;
Eigen::Matrix<double, 256, 1> descriptor;
if(!frame->GetDescriptor(i, descriptor)) continue;
MappointPtr mappoint = std::shared_ptr<Mappoint>(new Mappoint(track_ids[i], tmp_position, descriptor));
mappoint->AddObverser(frame_id, i);
frame->InsertMappoint(i, mappoint);
new_mappoints.push_back(mappoint);
}
}
if(stereo_point_num < 100) return false;
frame->SetTrackIds(track_ids);
// construct maplines
size_t line_num = frame->LineNum();
std::vector<MaplinePtr> new_maplines;
for(size_t i = 0; i < line_num; i++){
frame->SetLineTrackId(i, _line_track_id);
MaplinePtr mapline = std::shared_ptr<Mapline>(new Mapline(_line_track_id));
Vector6d endpoints;
if(frame->TrianguateStereoLine(i, endpoints)){
mapline->SetEndpoints(endpoints);
mapline->SetObverserEndpointStatus(frame_id, 1);
}else{
mapline->SetObverserEndpointStatus(frame_id, 0);
}
mapline->AddObverser(frame_id, i);
frame->InsertMapline(i, mapline);
new_maplines.push_back(mapline);
_line_track_id++;
}
// add frame and mappoints to map
InsertKeyframe(frame);
for(MappointPtr mappoint : new_mappoints){
_map->InsertMappoint(mappoint);
}
for(MaplinePtr mapline : new_maplines){
_map->InsertMapline(mapline);
}
_ref_keyframe = frame;
_last_frame = frame;
return true;
}
该函数用于从两个视角提取并匹配特征点对(特征矩阵)。具体而言,在左视图中提取了\mathbf{features}_{\text{left}}(大小为259×动态大小)以及右视图中的\mathbf{features}_{\text{right}}(同样大小),同时匹配到了对应的直线对(矢量cv.DMatch)\mathbf{stereo}_{\text{matches}}以及左右直线配对(矢量cv.Vector4d)\mathbf{lines}_{\text{left}}}和\mathbf{lines}_{\text{right}}}。
void Frame::AddFeatures(Eigen::Matrix<double, 259, Eigen::Dynamic>& features_left,
Eigen::Matrix<double, 259, Eigen::Dynamic>& features_right, std::vector<Eigen::Vector4d>& lines_left,
std::vector<Eigen::Vector4d>& lines_right, std::vector<cv::DMatch>& stereo_matches){
_features = features_left;
// fill in keypoints and assign features to grids
size_t features_left_size = _features.cols();
for(size_t i = 0; i < features_left_size; ++i){
double score = _features(0, i);
double x = _features(1, i);
double y = _features(2, i);
_keypoints.emplace_back(x, y, 8, -1, score);
int grid_x, grid_y;
bool found = FindGrid(x, y, grid_x, grid_y);
assert(found);
_feature_grid[grid_x][grid_y].push_back(i);
}
// Trianguate stereo points
_u_right = std::vector<double>(features_left_size, -1);
_depth = std::vector<double>(features_left_size, -1);
for(cv::DMatch& match : stereo_matches){
int idx_left = match.queryIdx;
int idx_right = match.trainIdx;
assert(idx_left < _u_right.size());
_u_right[idx_left] = features_right(1, idx_right);
_depth[idx_left] = _camera->BF() / (features_left(1, idx_left) - features_right(1, idx_right));
}
// initialize track_ids and mappoints
std::vector<int> track_ids(features_left_size, -1);
SetTrackIds(track_ids);
std::vector<MappointPtr> mappoints(features_left_size, nullptr);
_mappoints = mappoints;
// assign points to lines
_lines = lines_left;
std::vector<std::map<int, double>> points_on_line_left, points_on_line_right;
std::vector<int> line_matches;
AssignPointsToLines(lines_left, features_left, points_on_line_left);
_points_on_lines = points_on_line_left;
AssignPointsToLines(lines_right, features_right, points_on_line_right);
// match stereo lines
size_t line_num = _lines.size();
_lines_right.resize(line_num);
_lines_right_valid.resize(line_num);
MatchLines(points_on_line_left, points_on_line_right, stereo_matches, features_left.cols(), features_right.cols(), line_matches);
for(size_t i = 0; i < line_num; i++){
if(line_matches[i] > 0){
_lines_right[i] = lines_right[line_matches[i]];
_lines_right_valid[i] = true;
}else{
_lines_right_valid[i] = false;
}
}
// initialize line track ids and maplines
std::vector<int> line_track_ids(line_num, -1);
_line_track_ids = line_track_ids;
std::vector<MaplinePtr> maplines(line_num, nullptr);
_maplines = maplines;
// for debug
line_left_to_right_match = line_matches;
relation_left = points_on_line_left;
relation_right = points_on_line_right;
}
源码思维导图:



