├── .gitignore
├── CMakeLists.txt
├── LICENSE
├── README.md
├── cmake
└── FindEigen.cmake
├── config
├── realsense_d455
│ ├── left.yaml
│ ├── realsense_stereo_imu_config_mono.yaml
│ ├── realsense_stereo_imu_config_stereo.yaml
│ ├── right.yaml
│ └── rs_camera.launch
├── vins_rviz_config.rviz
└── viode
│ ├── calibration_mono.yaml
│ ├── calibration_stereo.yaml
│ ├── cam0_pinhole.yaml
│ └── cam1_pinhole.yaml
├── launch
├── d455
│ ├── d455_mono.launch
│ └── d455_stereo.launch
├── vins_rviz.launch
└── viode
│ ├── viode_mono.launch
│ └── viode_stereo.launch
├── loop_fusion
├── ThirdParty
│ ├── DBoW
│ │ ├── BowVector.cpp
│ │ ├── BowVector.h
│ │ ├── DBoW2.h
│ │ ├── FBrief.cpp
│ │ ├── FBrief.h
│ │ ├── FClass.h
│ │ ├── FORB.cpp
│ │ ├── FORB.h
│ │ ├── FeatureVector.cpp
│ │ ├── FeatureVector.h
│ │ ├── QueryResults.cpp
│ │ ├── QueryResults.h
│ │ ├── ScoringObject.cpp
│ │ ├── ScoringObject.h
│ │ ├── TemplatedDatabase.h
│ │ └── TemplatedVocabulary.h
│ ├── DUtils
│ │ ├── DException.h
│ │ ├── DUtils.h
│ │ ├── Random.cpp
│ │ ├── Random.h
│ │ ├── Timestamp.cpp
│ │ └── Timestamp.h
│ ├── DVision
│ │ ├── BRIEF.cpp
│ │ ├── BRIEF.h
│ │ └── DVision.h
│ ├── VocabularyBinary.cpp
│ └── VocabularyBinary.hpp
├── factor
│ └── ceresBA.hpp
├── keyframe.cpp
├── keyframe.h
├── parameters.h
├── pose_graph.cpp
├── pose_graph.h
├── pose_graph_node.cpp
└── utility
│ ├── CameraPoseVisualization.cpp
│ ├── CameraPoseVisualization.h
│ ├── tic_toc.h
│ ├── utility.cpp
│ └── utility.h
├── package.xml
├── readme_resource
├── city_main.gif
└── parking_main.gif
├── support_files
└── contents.txt
└── vins_estimator
├── estimator
├── estimator.cpp
├── estimator.h
├── feature_manager.cpp
├── feature_manager.h
├── parameters.cpp
└── parameters.h
├── factor
├── imu_factor.h
├── initial_bias_factor.h
├── initial_pose_factor.h
├── integration_base.h
├── marginalization_factor.cpp
├── marginalization_factor.h
├── pose_local_parameterization.cpp
├── pose_local_parameterization.h
├── prior_factor.h
├── projectionOneFrameTwoCamFactor.cpp
├── projectionOneFrameTwoCamFactor.h
├── projectionTwoFrameOneCamFactor.cpp
├── projectionTwoFrameOneCamFactor.h
├── projectionTwoFrameTwoCamFactor.cpp
├── projectionTwoFrameTwoCamFactor.h
├── projection_factor.cpp
└── projection_factor.h
├── featureTracker
├── feature_tracker.cpp
└── feature_tracker.h
├── initial
├── initial_aligment.cpp
├── initial_alignment.h
├── initial_ex_rotation.cpp
├── initial_ex_rotation.h
├── initial_sfm.cpp
├── initial_sfm.h
├── solve_5pts.cpp
└── solve_5pts.h
├── rosNodeTest.cpp
└── utility
├── CameraPoseVisualization.cpp
├── CameraPoseVisualization.h
├── tic_toc.h
├── utility.cpp
├── utility.h
├── visualization.cpp
└── visualization.h
/.gitignore:
--------------------------------------------------------------------------------
1 | cmake-build-release*
2 | cmake-build-debug*
3 | vscode/*
4 | .idea/*
5 | .idea/
6 | vscode/
7 |
8 | .codes/*
9 | .code/*
10 | .cmake/*
11 |
12 | # IMPORTANT! These filed should be ignored
13 | support_files/brief_k10L6.bin
14 | support_files/brief_pattern.yml
15 |
16 | build/*
17 |
18 | *bin
19 | *pcd
20 |
21 | # Created by https://www.gitignore.io/api/c++,code,cmake,eclipse
22 | # Edit at https://www.gitignore.io/?templates=c++,code,cmake,eclipse
23 |
24 | ### C++ ###
25 | # Prerequisites
26 | *.d
27 |
28 | # Compiled Object files
29 | *.slo
30 | *.lo
31 | *.o
32 | *.obj
33 |
34 | # Precompiled Headers
35 | *.gch
36 | *.pch
37 |
38 | # Compiled Dynamic libraries
39 | *.so
40 | *.dylib
41 | *.dll
42 |
43 | # Fortran module files
44 | *.mod
45 | *.smod
46 |
47 | # Compiled Static libraries
48 | *.lai
49 | *.la
50 | *.a
51 | *.lib
52 |
53 | # Executables
54 | *.exe
55 | *.out
56 | *.app
57 |
58 | ### CMake ###
59 | CMakeLists.txt.user
60 | CMakeCache.txt
61 | CMakeFiles
62 | CMakeScripts
63 | Testing
64 | Makefile
65 | cmake_install.cmake
66 | install_manifest.txt
67 | compile_commands.json
68 | CTestTestfile.cmake
69 | _deps
70 |
71 | ### CMake Patch ###
72 | # External projects
73 | *-prefix/
74 |
75 | ### Code ###
76 | .vscode/*
77 | !.vscode/settings.json
78 | !.vscode/tasks.json
79 | !.vscode/launch.json
80 | !.vscode/extensions.json
81 |
82 | ### Eclipse ###
83 | .metadata
84 | bin/
85 | tmp/
86 | *.tmp
87 | *.bak
88 | *.swp
89 | *~.nib
90 | local.properties
91 | .settings/
92 | .loadpath
93 | .recommenders
94 |
95 | # External tool builders
96 | .externalToolBuilders/
97 |
98 |
99 | # PyDev specific (Python IDE for Eclipse)
100 | *.pydevproject
101 |
102 | # CDT-specific (C/C++ Development Tooling)
103 | .cproject
104 |
105 | # CDT- autotools
106 | .autotools
107 |
108 | # Java annotation processor (APT)
109 | .factorypath
110 |
111 | # PDT-specific (PHP Development Tools)
112 | .buildpath
113 |
114 | # sbteclipse plugin
115 | .target
116 |
117 | # Tern plugin
118 | .tern-project
119 |
120 | # TeXlipse plugin
121 | .texlipse
122 |
123 | # STS (Spring Tool Suite)
124 | .springBeans
125 |
126 | # Code Recommenders
127 | .recommenders/
128 |
129 | # Annotation Processing
130 | .apt_generated/
131 |
132 | # Scala IDE specific (Scala & Java development for Eclipse)
133 | .cache-main
134 | .scala_dependencies
135 | .worksheet
136 |
137 | ### Eclipse Patch ###
138 | # Eclipse Core
139 | .project
140 |
141 | # JDT-specific (Eclipse Java Development Tools)
142 | .classpath
143 |
144 | # Annotation Processing
145 | .apt_generated
146 |
147 | .sts4-cache/
148 |
149 | # End of https://www.gitignore.io/api/c++,code,cmake,eclipse
150 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(dynaVINS)
3 |
4 | set(CMAKE_BUILD_TYPE "Release")
5 | set(CMAKE_CXX_FLAGS "-std=c++11")
6 | #-DEIGEN_USE_MKL_ALL")
7 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g")
8 |
9 | find_package(catkin REQUIRED COMPONENTS
10 | roscpp
11 | std_msgs
12 | geometry_msgs
13 | nav_msgs
14 | tf
15 | cv_bridge
16 | camera_models
17 | image_transport
18 | pcl_conversions
19 | pcl_ros
20 | roslib)
21 |
22 | find_package(OpenCV REQUIRED)
23 |
24 | # message(WARNING "OpenCV_VERSION: ${OpenCV_VERSION}")
25 |
26 | find_package(PCL REQUIRED)
27 | find_package(Ceres REQUIRED)
28 |
29 | include_directories(${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS})
30 |
31 | set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake)
32 | find_package(Eigen3)
33 | include_directories(
34 | ${catkin_INCLUDE_DIRS}
35 | ${EIGEN3_INCLUDE_DIR}
36 | ${PCL_INCLUDE_DIRS}
37 | )
38 |
39 | catkin_package()
40 |
41 | add_executable(vins_node
42 | vins_estimator/rosNodeTest.cpp
43 | vins_estimator/estimator/parameters.cpp
44 | vins_estimator/estimator/estimator.cpp
45 | vins_estimator/estimator/feature_manager.cpp
46 | vins_estimator/factor/pose_local_parameterization.cpp
47 | vins_estimator/factor/projectionTwoFrameOneCamFactor.cpp
48 | vins_estimator/factor/projectionTwoFrameTwoCamFactor.cpp
49 | vins_estimator/factor/projectionOneFrameTwoCamFactor.cpp
50 | vins_estimator/factor/marginalization_factor.cpp
51 | vins_estimator/utility/utility.cpp
52 | vins_estimator/utility/visualization.cpp
53 | vins_estimator/utility/CameraPoseVisualization.cpp
54 | vins_estimator/initial/solve_5pts.cpp
55 | vins_estimator/initial/initial_aligment.cpp
56 | vins_estimator/initial/initial_sfm.cpp
57 | vins_estimator/initial/initial_ex_rotation.cpp
58 | vins_estimator/featureTracker/feature_tracker.cpp)
59 | target_link_libraries(vins_node ${catkin_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES})
60 |
61 |
62 | add_executable(loop_fusion_node
63 | loop_fusion/pose_graph_node.cpp
64 | loop_fusion/pose_graph.cpp
65 | loop_fusion/keyframe.cpp
66 | loop_fusion/utility/CameraPoseVisualization.cpp
67 | loop_fusion/ThirdParty/DBoW/BowVector.cpp
68 | loop_fusion/ThirdParty/DBoW/FBrief.cpp
69 | loop_fusion/ThirdParty/DBoW/FORB.cpp
70 | loop_fusion/ThirdParty/DBoW/FeatureVector.cpp
71 | loop_fusion/ThirdParty/DBoW/QueryResults.cpp
72 | loop_fusion/ThirdParty/DBoW/ScoringObject.cpp
73 | loop_fusion/ThirdParty/DUtils/Random.cpp
74 | loop_fusion/ThirdParty/DUtils/Timestamp.cpp
75 | loop_fusion/ThirdParty/DVision/BRIEF.cpp
76 | loop_fusion/ThirdParty/VocabularyBinary.cpp
77 | loop_fusion/factor/ceresBA.hpp
78 | )
79 |
80 | target_link_libraries(loop_fusion_node ${catkin_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES})
81 |
82 |
83 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # DynaVINS: A Visual-Inertial SLAM for Dynamic Environments
2 |
3 | ## :bookmark_tabs: About DynaVINS (IEEE RA-L'22)
4 |
5 | * A robust **visual-inertial state estimator algorithm** for dynamic environments.
6 | * The robust bundle adjustment is used for dynamic objects such as cars :car:, humans :runner:, buses :bus:, etc.
7 |
8 |

9 |
10 | * Please refer our [paper][arXivlink] for detailed explanantions and experimental results\!
11 | * The BA module validated on [VIODE dataset][VIODElink] dataset\.
12 | * The loop closure module validated on [Our dataset][ourdatalink]\.
13 | * Algorithm is based on [VINS\-Fusion][vinsfusionlink]\.
14 | * Youtube video for the detailed explanation and the demo video.
15 |
16 | [](http://www.youtube.com/watch?v=a9jXZYc4tYw "DynaVINS")
17 |
18 | [arXivlink]: https://arxiv.org/abs/2208.11500
19 | [VIODElink]: https://github.com/kminoda/VIODE
20 | [ourdatalink]: http://gofile.me/4355j/tsjdofd6S
21 | [vinsfusionlink]: https://github.com/HKUST-Aerial-Robotics/VINS-Fusion
22 |
23 | ## :heavy_plus_sign: Additional package : VINS-Fusion-SC (SwitchableConstraints)
24 |
25 | * In our paper\, [VINS\-Fusion][vinsfusionlink] combined with [Switchable Constraints][switchpaperlink] \([git][switchgitlink]\)was compared with DynaVINS\.
26 | * VINS-Fusion-SC, an algorithm that integrates Switchable Constraints into the loop closure module of VINS-Fusion, is also useful, so we released the algorithm.
27 | * You can visit [here][vfsclink] to use VINS\-Fusion\-SC\.
28 | * When using VINS-Fusion-SC for your paper, don't forget to cite our paper!:wink:
29 |
30 | [switchpaperlink]: https://ieeexplore.ieee.org/document/6385590
31 | [switchgitlink]: https://github.com/sswan940505/switchable\_constraints
32 | [vfsclink]:https://github.com/url-kaist/VinsFusionSC
33 |
34 | ---
35 |
36 | ## Test Env.
37 |
38 | This code is tested on
39 |
40 | * Linux 18.04 LTS
41 | * ROS Melodic
42 | * Ceres Solver 1.14.0
43 | * OpenCV 3.4.1
44 |
45 | ## :package: Prerequisites
46 |
47 | The dependency of DynaVINS is equal to that of VINS-Fusion.
48 |
49 | ### 1. **Ubuntu** and **ROS**
50 | Ubuntu 64-bit 16.04 or 18.04.
51 | ROS Kinetic or Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation)
52 |
53 |
54 | ### 2. **Ceres Solver**
55 | Follow [Ceres Installation](http://ceres-solver.org/installation.html).
56 |
57 | ### 3. **Support file from VINS-Fusion**
58 |
59 | Due to the limiting file size of Github, we need **one** package and **two** files from the [VINS-Fusion repository](https://github.com/HKUST-Aerial-Robotics/VINS-Fusion/tree/master/support_files).
60 |
61 | 1. Set the `camera_models` package in your workspace, which is included in VINS-Fusion.
62 | 2. Copy `support_files/brief_k10L6.bin` in VINS-Fusion into our `support_files` folder
63 | 3. Copy `support_files/brief_pattern.yml` in VINS-Fusion into our `support_files` folder
64 |
65 | ## :building_construction: How to build
66 |
67 | > Please follow the below commands to build DynaVINS (on ROS).
68 |
69 | ``` bash
70 | $ cd ~/catkin_ws/src
71 | $ git clone https://github.com/url-kaist/dynaVINS
72 | $ cd ../
73 | $ catkin_make
74 | (or if you use catkin tools) catkin build
75 | $ source ~/catkin_ws/devel/setup.bash
76 | ```
77 |
78 | ## :runner: To run the demo codes
79 |
80 | ### VIODE dataset (Only BA) examples
81 |
82 | For convenience, we also provide `3_high.bag` file in the `parking_lot` scene. You can download the file by the following command:
83 |
84 | ```bash
85 | $ wget https://urserver.kaist.ac.kr/publicdata/dynaVINS/VIODE_dataset/parking_lot/3_high.bag
86 | ```
87 | * If direct download not works, download the dataset from : [Link](https://urserver.kaist.ac.kr:8148/sharing/rNg30Nh0Q)
88 | * Other sequence of VIODE dataset can be found in original repository : https://github.com/kminoda/VIODE
89 |
90 | Note that the larger the number of bag files in the VIODE dataset is, the more dynamic objects exist.
91 |
92 | #### 1. **VIODE sequence with monocular camera + IMU**
93 |
94 | ``` bash
95 | $ roslaunch dynaVINS viode_mono.launch
96 | $ rosbag play 3_high.bag (or 0_none.bag, 1_low.bag, ...)
97 | ```
98 |
99 | #### 2. **VIODE sequence with stereo camera + IMU**
100 |
101 | ``` bash
102 | $ roslaunch dynaVINS viode_stereo.launch
103 | $ rosbag play 3_high.bag (or 0_none.bag, 1_low.bag, ...)
104 | ```
105 |
106 |
107 | ### Our dataset (with Loop Closure module) examples
108 | > You can use your own intel realsense d455! (calibration is required)
109 |
110 | You can easily download our bag file by the following command:
111 |
112 | ```bash
113 | $ wget https://urserver.kaist.ac.kr/publicdata/dynaVINS/d455_urban_robotics/e_shape.bag
114 | $ wget https://urserver.kaist.ac.kr/publicdata/dynaVINS/d455_urban_robotics/loop_static.bag
115 | $ wget https://urserver.kaist.ac.kr/publicdata/dynaVINS/d455_urban_robotics/loop_tempstatic.bag
116 | ```
117 | * If direct download not works, download the dataset from : [Link](https://urserver.kaist.ac.kr:8148/sharing/Me4t2JZxg)
118 |
119 | ``` bash
120 | $ roslaunch dynaVINS d455_mono.launch
121 | $ rosbag play e_shape.bag (or loop_tempstatic.bag, ...)
122 | ```
123 |
124 | ``` bash
125 | $ roslaunch dynaVINS d455_stereo.launch
126 | $ rosbag play e_shape.bag (or loop_tempstatic.bag, ...)
127 | ```
128 |
129 | ---
130 |
131 | ## :gear: Parameters
132 |
133 | > Parameters of DynaVINS. You can find the results of each parameter on the [wiki page (param)][wikilink1]
134 |
135 | > Time comparison according to various parameters can be found on the [wiki page (time)][wikilink2].
136 |
137 | + `regularization_lambda`
138 |
139 | The Lambda value of regularization term in paper. (Section III-C)
140 |
141 | + `momentum_on`
142 |
143 | Using the momentum factor or not (true/false)
144 |
145 | + `momentum_lambda`
146 |
147 | The Lambda value of momentum term in paper. (Section III-D)
148 |
149 | + `alternating_converge`
150 |
151 | The threshold for checking the convergence of the alternating optimization.\
152 | 90% is usually enough. If you want faster speed, please try to reduce it.\
153 | Time comparison can be found on the wiki page.
154 |
155 | + `margin_feature_thresh`
156 |
157 | Features which have less weight than this value are not used in marginalization.\
158 | This may affect accuracy, but is effective at reducing time costs.\
159 | You can try uncomment line 848 of "vins_estimator/estimator/estimator.cpp" to enable these features also in optimization.
160 |
161 | ```c++
162 | //ADDITIONAL FEATURE : NO USE IN OPT.
163 | //if(it_per_id.weight
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
--------------------------------------------------------------------------------
/config/viode/calibration_mono.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #common parameters
4 | #support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
5 | imu: 1
6 | num_of_cam:1
7 |
8 | imu_topic: "/imu0"
9 | image0_topic: "/cam0/image_raw"
10 | image1_topic: "/cam1/image_raw"
11 | output_path: "/home/seungwon/.ros/dynaVINS"
12 |
13 | cam0_calib: "cam0_pinhole.yaml"
14 | cam1_calib: "cam1_pinhole.yaml"
15 | image_width: 752
16 | image_height: 480
17 |
18 |
19 | # Extrinsic parameter between IMU and Camera.
20 | estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
21 | # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
22 |
23 | body_T_cam0: !!opencv-matrix
24 | rows: 4
25 | cols: 4
26 | dt: d
27 | data: [0.0, 0.0, 1.0, 0.0,
28 | 1.0, 0.0, 0.0, 0.0,
29 | 0.0, 1.0, 0.0, 0.0,
30 | 0.0, 0.0, 0.0, 1.0]
31 |
32 | body_T_cam1: !!opencv-matrix
33 | rows: 4
34 | cols: 4
35 | dt: d
36 | data: [0.0, 0.0, 1.0, 0.0,
37 | 1.0, 0.0, 0.0, 0.05,
38 | 0.0, 1.0, 0.0, 0.0,
39 | 0.0, 0.0, 0.0, 1.0]
40 |
41 | #Multiple thread support
42 | multiple_thread: 1
43 |
44 |
45 | #feature traker paprameters
46 | max_cnt: 150 # max feature number in feature tracking
47 | min_dist: 15 # min distance between two features
48 | 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
49 | F_threshold: 2.0 # ransac threshold (pixel)
50 | max_depth: 10.0 # max estimated depth (m)
51 | show_track: 1
52 | show_image_feat_weight: 1
53 | # publish tracking image as topic
54 | flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy
55 |
56 | #dynaVINS parameters
57 | dyna_on: true # do not change it to false
58 | regularization_lambda: 2.0
59 | momentum_on: true
60 | momentum_lambda: 0.2
61 | alternating_converge: 0.9
62 | margin_feature_thresh: 0.1
63 |
64 |
65 | #optimization parameters
66 | max_solver_time: 0.3 # max solver itration time (ms), to guarantee real time
67 | max_num_iterations: 10 # max solver itrations, to guarantee real time
68 | keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
69 |
70 | #imu parameters The more accurate parameters you provide, the better performance
71 | acc_n: 0.2 # accelerometer measurement noise standard deviation.
72 | gyr_n: 0.05 # gyroscope measurement noise standard deviation.
73 | acc_w: 0.02 # accelerometer bias random work noise standard deviation.
74 | gyr_w: 4.0e-5 # gyroscope bias random work noise standard deviation.
75 | g_norm: 9.81007 # gravity magnitude
76 |
77 | #unsynchronization parameters
78 | estimate_td: 0 # online estimate time offset between camera and imu
79 | td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
80 |
--------------------------------------------------------------------------------
/config/viode/calibration_stereo.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #common parameters
4 | #support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
5 | imu: 1
6 | num_of_cam:2
7 |
8 | imu_topic: "/imu0"
9 | image0_topic: "/cam0/image_raw"
10 | image1_topic: "/cam1/image_raw"
11 | output_path: "/home/seungwon/.ros/dynaVINS"
12 |
13 | cam0_calib: "cam0_pinhole.yaml"
14 | cam1_calib: "cam1_pinhole.yaml"
15 | image_width: 752
16 | image_height: 480
17 |
18 |
19 | # Extrinsic parameter between IMU and Camera.
20 | estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
21 | # 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
22 |
23 | body_T_cam0: !!opencv-matrix
24 | rows: 4
25 | cols: 4
26 | dt: d
27 | data: [0.0, 0.0, 1.0, 0.0,
28 | 1.0, 0.0, 0.0, 0.0,
29 | 0.0, 1.0, 0.0, 0.0,
30 | 0.0, 0.0, 0.0, 1.0]
31 |
32 | body_T_cam1: !!opencv-matrix
33 | rows: 4
34 | cols: 4
35 | dt: d
36 | data: [0.0, 0.0, 1.0, 0.0,
37 | 1.0, 0.0, 0.0, 0.05,
38 | 0.0, 1.0, 0.0, 0.0,
39 | 0.0, 0.0, 0.0, 1.0]
40 |
41 | #Multiple thread support
42 | multiple_thread: 1
43 |
44 | #feature traker paprameters
45 | max_cnt: 150 # max feature number in feature tracking
46 | min_dist: 15 # min distance between two features
47 | 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
48 | F_threshold: 2.0 # ransac threshold (pixel)
49 | max_depth: 10.0 # max estimated depth (m)
50 | show_track: 1
51 | show_image_feat_weight: 1
52 | # publish tracking image as topic
53 | flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy
54 |
55 | #dynaVINS parameters
56 | dyna_on: true # do not change it to false
57 | regularization_lambda: 2.0
58 | momentum_on: true
59 | momentum_lambda: 0.2
60 | alternating_converge: 0.9
61 | margin_feature_thresh: 0.1
62 |
63 |
64 | #optimization parameters
65 | max_solver_time: 0.3 # max solver itration time (ms), to guarantee real time
66 | max_num_iterations: 10 # max solver itrations, to guarantee real time
67 | keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
68 |
69 | #imu parameters The more accurate parameters you provide, the better performance
70 | acc_n: 0.2 # accelerometer measurement noise standard deviation.
71 | gyr_n: 0.05 # gyroscope measurement noise standard deviation.
72 | acc_w: 0.02 # accelerometer bias random work noise standard deviation.
73 | gyr_w: 4.0e-5 # gyroscope bias random work noise standard deviation.
74 | g_norm: 9.81007 # gravity magnitude
75 |
76 | #unsynchronization parameters
77 | estimate_td: 0 # online estimate time offset between camera and imu
78 | td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
79 |
80 |
81 |
--------------------------------------------------------------------------------
/config/viode/cam0_pinhole.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 | ---
3 | model_type: PINHOLE
4 | camera_name: camera
5 | image_width: 752
6 | image_height: 480
7 | distortion_parameters:
8 | k1: 0.0
9 | k2: 0.0
10 | p1: 0.0
11 | p2: 0.0
12 | projection_parameters:
13 | fx: 376.0
14 | fy: 376.0
15 | cx: 376.0
16 | cy: 240.0
--------------------------------------------------------------------------------
/config/viode/cam1_pinhole.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 | ---
3 | model_type: PINHOLE
4 | camera_name: camera
5 | image_width: 752
6 | image_height: 480
7 | distortion_parameters:
8 | k1: 0.0
9 | k2: 0.0
10 | p1: 0.0
11 | p2: 0.0
12 | projection_parameters:
13 | fx: 376.0
14 | fy: 376.0
15 | cx: 376.0
16 | cy: 240.0
--------------------------------------------------------------------------------
/launch/d455/d455_mono.launch:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
6 |
8 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/launch/d455/d455_stereo.launch:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
6 |
8 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/launch/vins_rviz.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/launch/viode/viode_mono.launch:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/launch/viode/viode_stereo.launch:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/loop_fusion/ThirdParty/DBoW/BowVector.cpp:
--------------------------------------------------------------------------------
1 | /**
2 | * File: BowVector.cpp
3 | * Date: March 2011
4 | * Author: Dorian Galvez-Lopez
5 | * Description: bag of words vector
6 | * License: see the LICENSE.txt file
7 | *
8 | */
9 |
10 | #include
11 | #include
12 | #include
13 | #include
14 | #include
15 |
16 | #include "BowVector.h"
17 |
18 | namespace DBoW2 {
19 |
20 | // --------------------------------------------------------------------------
21 |
22 | BowVector::BowVector(void)
23 | {
24 | }
25 |
26 | // --------------------------------------------------------------------------
27 |
28 | BowVector::~BowVector(void)
29 | {
30 | }
31 |
32 | // --------------------------------------------------------------------------
33 |
34 | void BowVector::addWeight(WordId id, WordValue v)
35 | {
36 | BowVector::iterator vit = this->lower_bound(id);
37 |
38 | if(vit != this->end() && !(this->key_comp()(id, vit->first)))
39 | {
40 | vit->second += v;
41 | }
42 | else
43 | {
44 | this->insert(vit, BowVector::value_type(id, v));
45 | }
46 | }
47 |
48 | // --------------------------------------------------------------------------
49 |
50 | void BowVector::addIfNotExist(WordId id, WordValue v)
51 | {
52 | BowVector::iterator vit = this->lower_bound(id);
53 |
54 | if(vit == this->end() || (this->key_comp()(id, vit->first)))
55 | {
56 | this->insert(vit, BowVector::value_type(id, v));
57 | }
58 | }
59 |
60 | // --------------------------------------------------------------------------
61 |
62 | void BowVector::normalize(LNorm norm_type)
63 | {
64 | double norm = 0.0;
65 | BowVector::iterator it;
66 |
67 | if(norm_type == DBoW2::L1)
68 | {
69 | for(it = begin(); it != end(); ++it)
70 | norm += fabs(it->second);
71 | }
72 | else
73 | {
74 | for(it = begin(); it != end(); ++it)
75 | norm += it->second * it->second;
76 | norm = sqrt(norm);
77 | }
78 |
79 | if(norm > 0.0)
80 | {
81 | for(it = begin(); it != end(); ++it)
82 | it->second /= norm;
83 | }
84 | }
85 |
86 | // --------------------------------------------------------------------------
87 |
88 | std::ostream& operator<< (std::ostream &out, const BowVector &v)
89 | {
90 | BowVector::const_iterator vit;
91 | std::vector::const_iterator iit;
92 | unsigned int i = 0;
93 | const unsigned int N = v.size();
94 | for(vit = v.begin(); vit != v.end(); ++vit, ++i)
95 | {
96 | out << "<" << vit->first << ", " << vit->second << ">";
97 |
98 | if(i < N-1) out << ", ";
99 | }
100 | return out;
101 | }
102 |
103 | // --------------------------------------------------------------------------
104 |
105 | void BowVector::saveM(const std::string &filename, size_t W) const
106 | {
107 | std::fstream f(filename.c_str(), std::ios::out);
108 |
109 | WordId last = 0;
110 | BowVector::const_iterator bit;
111 | for(bit = this->begin(); bit != this->end(); ++bit)
112 | {
113 | for(; last < bit->first; ++last)
114 | {
115 | f << "0 ";
116 | }
117 | f << bit->second << " ";
118 |
119 | last = bit->first + 1;
120 | }
121 | for(; last < (WordId)W; ++last)
122 | f << "0 ";
123 |
124 | f.close();
125 | }
126 |
127 | // --------------------------------------------------------------------------
128 |
129 | } // namespace DBoW2
130 |
131 |
--------------------------------------------------------------------------------
/loop_fusion/ThirdParty/DBoW/BowVector.h:
--------------------------------------------------------------------------------
1 | /**
2 | * File: BowVector.h
3 | * Date: March 2011
4 | * Author: Dorian Galvez-Lopez
5 | * Description: bag of words vector
6 | * License: see the LICENSE.txt file
7 | *
8 | */
9 |
10 | #ifndef __D_T_BOW_VECTOR__
11 | #define __D_T_BOW_VECTOR__
12 |
13 | #include
14 | #include