├── .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 |

animated animated

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 | [![IMAGE ALT TEXT](http://img.youtube.com/vi/a9jXZYc4tYw/0.jpg)](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 15 | #include 16 | 17 | namespace DBoW2 { 18 | 19 | /// Id of words 20 | typedef unsigned int WordId; 21 | 22 | /// Value of a word 23 | typedef double WordValue; 24 | 25 | /// Id of nodes in the vocabulary treee 26 | typedef unsigned int NodeId; 27 | 28 | /// L-norms for normalization 29 | enum LNorm 30 | { 31 | L1, 32 | L2 33 | }; 34 | 35 | /// Weighting type 36 | enum WeightingType 37 | { 38 | TF_IDF, 39 | TF, 40 | IDF, 41 | BINARY 42 | }; 43 | 44 | /// Scoring type 45 | enum ScoringType 46 | { 47 | L1_NORM, 48 | L2_NORM, 49 | CHI_SQUARE, 50 | KL, 51 | BHATTACHARYYA, 52 | DOT_PRODUCT 53 | }; 54 | 55 | /// Vector of words to represent images 56 | class BowVector: 57 | public std::map 58 | { 59 | public: 60 | 61 | /** 62 | * Constructor 63 | */ 64 | BowVector(void); 65 | 66 | /** 67 | * Destructor 68 | */ 69 | ~BowVector(void); 70 | 71 | /** 72 | * Adds a value to a word value existing in the vector, or creates a new 73 | * word with the given value 74 | * @param id word id to look for 75 | * @param v value to create the word with, or to add to existing word 76 | */ 77 | void addWeight(WordId id, WordValue v); 78 | 79 | /** 80 | * Adds a word with a value to the vector only if this does not exist yet 81 | * @param id word id to look for 82 | * @param v value to give to the word if this does not exist 83 | */ 84 | void addIfNotExist(WordId id, WordValue v); 85 | 86 | /** 87 | * L1-Normalizes the values in the vector 88 | * @param norm_type norm used 89 | */ 90 | void normalize(LNorm norm_type); 91 | 92 | /** 93 | * Prints the content of the bow vector 94 | * @param out stream 95 | * @param v 96 | */ 97 | friend std::ostream& operator<<(std::ostream &out, const BowVector &v); 98 | 99 | /** 100 | * Saves the bow vector as a vector in a matlab file 101 | * @param filename 102 | * @param W number of words in the vocabulary 103 | */ 104 | void saveM(const std::string &filename, size_t W) const; 105 | }; 106 | 107 | } // namespace DBoW2 108 | 109 | #endif 110 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/DBoW2.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: DBoW2.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: Generic include file for the DBoW2 classes and 6 | * the specialized vocabularies and databases 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | /*! \mainpage DBoW2 Library 12 | * 13 | * DBoW2 library for C++: 14 | * Bag-of-word image database for image retrieval. 15 | * 16 | * Written by Dorian Galvez-Lopez, 17 | * University of Zaragoza 18 | * 19 | * Check my website to obtain updates: http://doriangalvez.com 20 | * 21 | * \section requirements Requirements 22 | * This library requires the DUtils, DUtilsCV, DVision and OpenCV libraries, 23 | * as well as the boost::dynamic_bitset class. 24 | * 25 | * \section citation Citation 26 | * If you use this software in academic works, please cite: 27 |
28 |    @@ARTICLE{GalvezTRO12,
29 |     author={Galvez-Lopez, Dorian and Tardos, J. D.}, 
30 |     journal={IEEE Transactions on Robotics},
31 |     title={Bags of Binary Words for Fast Place Recognition in Image Sequences},
32 |     year={2012},
33 |     month={October},
34 |     volume={28},
35 |     number={5},
36 |     pages={1188--1197},
37 |     doi={10.1109/TRO.2012.2197158},
38 |     ISSN={1552-3098}
39 |   }
40 |  
41 | * 42 | * \section license License 43 | * This file is licensed under a Creative Commons 44 | * Attribution-NonCommercial-ShareAlike 3.0 license. 45 | * This file can be freely used and users can use, download and edit this file 46 | * provided that credit is attributed to the original author. No users are 47 | * permitted to use this file for commercial purposes unless explicit permission 48 | * is given by the original author. Derivative works must be licensed using the 49 | * same or similar license. 50 | * Check http://creativecommons.org/licenses/by-nc-sa/3.0/ to obtain further 51 | * details. 52 | * 53 | */ 54 | 55 | #ifndef __D_T_DBOW2__ 56 | #define __D_T_DBOW2__ 57 | 58 | /// Includes all the data structures to manage vocabularies and image databases 59 | namespace DBoW2 60 | { 61 | } 62 | 63 | #include "TemplatedVocabulary.h" 64 | #include "TemplatedDatabase.h" 65 | #include "BowVector.h" 66 | #include "FeatureVector.h" 67 | #include "QueryResults.h" 68 | #include "FBrief.h" 69 | #include "FORB.h" 70 | 71 | /// BRIEF Vocabulary 72 | typedef DBoW2::TemplatedVocabulary 73 | BriefVocabulary; 74 | 75 | /// BRIEF Database 76 | typedef DBoW2::TemplatedDatabase 77 | BriefDatabase; 78 | 79 | #endif 80 | 81 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/FBrief.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FBrief.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for BRIEF descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | #include "FBrief.h" 15 | 16 | using namespace std; 17 | 18 | namespace DBoW2 { 19 | 20 | // -------------------------------------------------------------------------- 21 | 22 | void FBrief::meanValue(const std::vector &descriptors, 23 | FBrief::TDescriptor &mean) 24 | { 25 | mean.reset(); 26 | 27 | if(descriptors.empty()) return; 28 | 29 | const int N2 = descriptors.size() / 2; 30 | const int L = descriptors[0]->size(); 31 | 32 | vector counters(L, 0); 33 | 34 | vector::const_iterator it; 35 | for(it = descriptors.begin(); it != descriptors.end(); ++it) 36 | { 37 | const FBrief::TDescriptor &desc = **it; 38 | for(int i = 0; i < L; ++i) 39 | { 40 | if(desc[i]) counters[i]++; 41 | } 42 | } 43 | 44 | for(int i = 0; i < L; ++i) 45 | { 46 | if(counters[i] > N2) mean.set(i); 47 | } 48 | 49 | } 50 | 51 | // -------------------------------------------------------------------------- 52 | 53 | double FBrief::distance(const FBrief::TDescriptor &a, 54 | const FBrief::TDescriptor &b) 55 | { 56 | return (double)DVision::BRIEF::distance(a, b); 57 | } 58 | 59 | // -------------------------------------------------------------------------- 60 | 61 | std::string FBrief::toString(const FBrief::TDescriptor &a) 62 | { 63 | // from boost::bitset 64 | string s; 65 | to_string(a, s); // reversed 66 | return s; 67 | } 68 | 69 | // -------------------------------------------------------------------------- 70 | 71 | void FBrief::fromString(FBrief::TDescriptor &a, const std::string &s) 72 | { 73 | // from boost::bitset 74 | stringstream ss(s); 75 | ss >> a; 76 | } 77 | 78 | // -------------------------------------------------------------------------- 79 | 80 | void FBrief::toMat32F(const std::vector &descriptors, 81 | cv::Mat &mat) 82 | { 83 | if(descriptors.empty()) 84 | { 85 | mat.release(); 86 | return; 87 | } 88 | 89 | const int N = descriptors.size(); 90 | const int L = descriptors[0].size(); 91 | 92 | mat.create(N, L, CV_32F); 93 | 94 | for(int i = 0; i < N; ++i) 95 | { 96 | const TDescriptor& desc = descriptors[i]; 97 | float *p = mat.ptr(i); 98 | for(int j = 0; j < L; ++j, ++p) 99 | { 100 | *p = (desc[j] ? 1 : 0); 101 | } 102 | } 103 | } 104 | 105 | // -------------------------------------------------------------------------- 106 | 107 | } // namespace DBoW2 108 | 109 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/FBrief.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FBrief.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for BRIEF descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_F_BRIEF__ 11 | #define __D_T_F_BRIEF__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "FClass.h" 18 | #include "../DVision/DVision.h" 19 | 20 | namespace DBoW2 { 21 | 22 | /// Functions to manipulate BRIEF descriptors 23 | class FBrief: protected FClass 24 | { 25 | public: 26 | 27 | typedef DVision::BRIEF::bitset TDescriptor; 28 | typedef const TDescriptor *pDescriptor; 29 | 30 | /** 31 | * Calculates the mean value of a set of descriptors 32 | * @param descriptors 33 | * @param mean mean descriptor 34 | */ 35 | static void meanValue(const std::vector &descriptors, 36 | TDescriptor &mean); 37 | 38 | /** 39 | * Calculates the distance between two descriptors 40 | * @param a 41 | * @param b 42 | * @return distance 43 | */ 44 | static double distance(const TDescriptor &a, const TDescriptor &b); 45 | 46 | /** 47 | * Returns a string version of the descriptor 48 | * @param a descriptor 49 | * @return string version 50 | */ 51 | static std::string toString(const TDescriptor &a); 52 | 53 | /** 54 | * Returns a descriptor from a string 55 | * @param a descriptor 56 | * @param s string version 57 | */ 58 | static void fromString(TDescriptor &a, const std::string &s); 59 | 60 | /** 61 | * Returns a mat with the descriptors in float format 62 | * @param descriptors 63 | * @param mat (out) NxL 32F matrix 64 | */ 65 | static void toMat32F(const std::vector &descriptors, 66 | cv::Mat &mat); 67 | 68 | }; 69 | 70 | } // namespace DBoW2 71 | 72 | #endif 73 | 74 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/FClass.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FClass.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: generic FClass to instantiate templated classes 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_FCLASS__ 11 | #define __D_T_FCLASS__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | namespace DBoW2 { 18 | 19 | /// Generic class to encapsulate functions to manage descriptors. 20 | /** 21 | * This class must be inherited. Derived classes can be used as the 22 | * parameter F when creating Templated structures 23 | * (TemplatedVocabulary, TemplatedDatabase, ...) 24 | */ 25 | class FClass 26 | { 27 | class TDescriptor; 28 | typedef const TDescriptor *pDescriptor; 29 | 30 | /** 31 | * Calculates the mean value of a set of descriptors 32 | * @param descriptors 33 | * @param mean mean descriptor 34 | */ 35 | virtual void meanValue(const std::vector &descriptors, 36 | TDescriptor &mean) = 0; 37 | 38 | /** 39 | * Calculates the distance between two descriptors 40 | * @param a 41 | * @param b 42 | * @return distance 43 | */ 44 | static double distance(const TDescriptor &a, const TDescriptor &b); 45 | 46 | /** 47 | * Returns a string version of the descriptor 48 | * @param a descriptor 49 | * @return string version 50 | */ 51 | static std::string toString(const TDescriptor &a); 52 | 53 | /** 54 | * Returns a descriptor from a string 55 | * @param a descriptor 56 | * @param s string version 57 | */ 58 | static void fromString(TDescriptor &a, const std::string &s); 59 | 60 | /** 61 | * Returns a mat with the descriptors in float format 62 | * @param descriptors 63 | * @param mat (out) NxL 32F matrix 64 | */ 65 | static void toMat32F(const std::vector &descriptors, 66 | cv::Mat &mat); 67 | }; 68 | 69 | } // namespace DBoW2 70 | 71 | #endif 72 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/FORB.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FORB.cpp 3 | * Date: June 2012 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for ORB descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | 16 | #include "FORB.h" 17 | 18 | using namespace std; 19 | 20 | namespace DBoW2 { 21 | 22 | // -------------------------------------------------------------------------- 23 | 24 | void FORB::meanValue(const std::vector &descriptors, 25 | FORB::TDescriptor &mean) 26 | { 27 | if(descriptors.empty()) 28 | { 29 | mean.release(); 30 | return; 31 | } 32 | else if(descriptors.size() == 1) 33 | { 34 | mean = descriptors[0]->clone(); 35 | } 36 | else 37 | { 38 | vector sum(FORB::L * 8, 0); 39 | 40 | for(size_t i = 0; i < descriptors.size(); ++i) 41 | { 42 | const cv::Mat &d = *descriptors[i]; 43 | const unsigned char *p = d.ptr(); 44 | 45 | for(int j = 0; j < d.cols; ++j, ++p) 46 | { 47 | if(*p & (1 << 7)) ++sum[ j*8 ]; 48 | if(*p & (1 << 6)) ++sum[ j*8 + 1 ]; 49 | if(*p & (1 << 5)) ++sum[ j*8 + 2 ]; 50 | if(*p & (1 << 4)) ++sum[ j*8 + 3 ]; 51 | if(*p & (1 << 3)) ++sum[ j*8 + 4 ]; 52 | if(*p & (1 << 2)) ++sum[ j*8 + 5 ]; 53 | if(*p & (1 << 1)) ++sum[ j*8 + 6 ]; 54 | if(*p & (1)) ++sum[ j*8 + 7 ]; 55 | } 56 | } 57 | 58 | mean = cv::Mat::zeros(1, FORB::L, CV_8U); 59 | unsigned char *p = mean.ptr(); 60 | 61 | const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2; 62 | for(size_t i = 0; i < sum.size(); ++i) 63 | { 64 | if(sum[i] >= N2) 65 | { 66 | // set bit 67 | *p |= 1 << (7 - (i % 8)); 68 | } 69 | 70 | if(i % 8 == 7) ++p; 71 | } 72 | } 73 | } 74 | 75 | // -------------------------------------------------------------------------- 76 | 77 | double FORB::distance(const FORB::TDescriptor &a, 78 | const FORB::TDescriptor &b) 79 | { 80 | // Bit count function got from: 81 | // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetKernighan 82 | // This implementation assumes that a.cols (CV_8U) % sizeof(uint64_t) == 0 83 | 84 | const uint64_t *pa, *pb; 85 | pa = a.ptr(); // a & b are actually CV_8U 86 | pb = b.ptr(); 87 | 88 | uint64_t v, ret = 0; 89 | for(size_t i = 0; i < a.cols / sizeof(uint64_t); ++i, ++pa, ++pb) 90 | { 91 | v = *pa ^ *pb; 92 | v = v - ((v >> 1) & (uint64_t)~(uint64_t)0/3); 93 | v = (v & (uint64_t)~(uint64_t)0/15*3) + ((v >> 2) & 94 | (uint64_t)~(uint64_t)0/15*3); 95 | v = (v + (v >> 4)) & (uint64_t)~(uint64_t)0/255*15; 96 | ret += (uint64_t)(v * ((uint64_t)~(uint64_t)0/255)) >> 97 | (sizeof(uint64_t) - 1) * CHAR_BIT; 98 | } 99 | 100 | return static_cast(ret); 101 | 102 | // // If uint64_t is not defined in your system, you can try this 103 | // // portable approach (requires DUtils from DLib) 104 | // const unsigned char *pa, *pb; 105 | // pa = a.ptr(); 106 | // pb = b.ptr(); 107 | // 108 | // int ret = 0; 109 | // for(int i = 0; i < a.cols; ++i, ++pa, ++pb) 110 | // { 111 | // ret += DUtils::LUT::ones8bits[ *pa ^ *pb ]; 112 | // } 113 | // 114 | // return ret; 115 | } 116 | 117 | // -------------------------------------------------------------------------- 118 | 119 | std::string FORB::toString(const FORB::TDescriptor &a) 120 | { 121 | stringstream ss; 122 | const unsigned char *p = a.ptr(); 123 | 124 | for(int i = 0; i < a.cols; ++i, ++p) 125 | { 126 | ss << (int)*p << " "; 127 | } 128 | 129 | return ss.str(); 130 | } 131 | 132 | // -------------------------------------------------------------------------- 133 | 134 | void FORB::fromString(FORB::TDescriptor &a, const std::string &s) 135 | { 136 | a.create(1, FORB::L, CV_8U); 137 | unsigned char *p = a.ptr(); 138 | 139 | stringstream ss(s); 140 | for(int i = 0; i < FORB::L; ++i, ++p) 141 | { 142 | int n; 143 | ss >> n; 144 | 145 | if(!ss.fail()) 146 | *p = (unsigned char)n; 147 | } 148 | 149 | } 150 | 151 | // -------------------------------------------------------------------------- 152 | 153 | void FORB::toMat32F(const std::vector &descriptors, 154 | cv::Mat &mat) 155 | { 156 | if(descriptors.empty()) 157 | { 158 | mat.release(); 159 | return; 160 | } 161 | 162 | const size_t N = descriptors.size(); 163 | 164 | mat.create(N, FORB::L*8, CV_32F); 165 | float *p = mat.ptr(); 166 | 167 | for(size_t i = 0; i < N; ++i) 168 | { 169 | const int C = descriptors[i].cols; 170 | const unsigned char *desc = descriptors[i].ptr(); 171 | 172 | for(int j = 0; j < C; ++j, p += 8) 173 | { 174 | p[0] = (desc[j] & (1 << 7) ? 1.f : 0.f); 175 | p[1] = (desc[j] & (1 << 6) ? 1.f : 0.f); 176 | p[2] = (desc[j] & (1 << 5) ? 1.f : 0.f); 177 | p[3] = (desc[j] & (1 << 4) ? 1.f : 0.f); 178 | p[4] = (desc[j] & (1 << 3) ? 1.f : 0.f); 179 | p[5] = (desc[j] & (1 << 2) ? 1.f : 0.f); 180 | p[6] = (desc[j] & (1 << 1) ? 1.f : 0.f); 181 | p[7] = (desc[j] & (1) ? 1.f : 0.f); 182 | } 183 | } 184 | } 185 | 186 | // -------------------------------------------------------------------------- 187 | 188 | void FORB::toMat32F(const cv::Mat &descriptors, cv::Mat &mat) 189 | { 190 | descriptors.convertTo(mat, CV_32F); 191 | } 192 | 193 | // -------------------------------------------------------------------------- 194 | 195 | void FORB::toMat8U(const std::vector &descriptors, 196 | cv::Mat &mat) 197 | { 198 | mat.create(descriptors.size(), FORB::L, CV_8U); 199 | 200 | unsigned char *p = mat.ptr(); 201 | 202 | for(size_t i = 0; i < descriptors.size(); ++i, p += FORB::L) 203 | { 204 | const unsigned char *d = descriptors[i].ptr(); 205 | std::copy(d, d + FORB::L, p); 206 | } 207 | 208 | } 209 | 210 | // -------------------------------------------------------------------------- 211 | 212 | } // namespace DBoW2 213 | 214 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/FORB.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FORB.h 3 | * Date: June 2012 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for ORB descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_F_ORB__ 11 | #define __D_T_F_ORB__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "FClass.h" 18 | 19 | namespace DBoW2 { 20 | 21 | /// Functions to manipulate BRIEF descriptors 22 | class FORB: protected FClass 23 | { 24 | public: 25 | 26 | /// Descriptor type 27 | typedef cv::Mat TDescriptor; // CV_8U 28 | /// Pointer to a single descriptor 29 | typedef const TDescriptor *pDescriptor; 30 | /// Descriptor length (in bytes) 31 | static const int L = 32; 32 | 33 | /** 34 | * Calculates the mean value of a set of descriptors 35 | * @param descriptors 36 | * @param mean mean descriptor 37 | */ 38 | static void meanValue(const std::vector &descriptors, 39 | TDescriptor &mean); 40 | 41 | /** 42 | * Calculates the distance between two descriptors 43 | * @param a 44 | * @param b 45 | * @return distance 46 | */ 47 | static double distance(const TDescriptor &a, const TDescriptor &b); 48 | 49 | /** 50 | * Returns a string version of the descriptor 51 | * @param a descriptor 52 | * @return string version 53 | */ 54 | static std::string toString(const TDescriptor &a); 55 | 56 | /** 57 | * Returns a descriptor from a string 58 | * @param a descriptor 59 | * @param s string version 60 | */ 61 | static void fromString(TDescriptor &a, const std::string &s); 62 | 63 | /** 64 | * Returns a mat with the descriptors in float format 65 | * @param descriptors 66 | * @param mat (out) NxL 32F matrix 67 | */ 68 | static void toMat32F(const std::vector &descriptors, 69 | cv::Mat &mat); 70 | 71 | /** 72 | * Returns a mat with the descriptors in float format 73 | * @param descriptors NxL CV_8U matrix 74 | * @param mat (out) NxL 32F matrix 75 | */ 76 | static void toMat32F(const cv::Mat &descriptors, cv::Mat &mat); 77 | 78 | /** 79 | * Returns a matrix with the descriptor in OpenCV format 80 | * @param descriptors vector of N row descriptors 81 | * @param mat (out) NxL CV_8U matrix 82 | */ 83 | static void toMat8U(const std::vector &descriptors, 84 | cv::Mat &mat); 85 | 86 | }; 87 | 88 | } // namespace DBoW2 89 | 90 | #endif 91 | 92 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/FeatureVector.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FeatureVector.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: feature vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include "FeatureVector.h" 11 | #include 12 | #include 13 | #include 14 | 15 | namespace DBoW2 { 16 | 17 | // --------------------------------------------------------------------------- 18 | 19 | FeatureVector::FeatureVector(void) 20 | { 21 | } 22 | 23 | // --------------------------------------------------------------------------- 24 | 25 | FeatureVector::~FeatureVector(void) 26 | { 27 | } 28 | 29 | // --------------------------------------------------------------------------- 30 | 31 | void FeatureVector::addFeature(NodeId id, unsigned int i_feature) 32 | { 33 | FeatureVector::iterator vit = this->lower_bound(id); 34 | 35 | if(vit != this->end() && vit->first == id) 36 | { 37 | vit->second.push_back(i_feature); 38 | } 39 | else 40 | { 41 | vit = this->insert(vit, FeatureVector::value_type(id, 42 | std::vector() )); 43 | vit->second.push_back(i_feature); 44 | } 45 | } 46 | 47 | // --------------------------------------------------------------------------- 48 | 49 | std::ostream& operator<<(std::ostream &out, 50 | const FeatureVector &v) 51 | { 52 | if(!v.empty()) 53 | { 54 | FeatureVector::const_iterator vit = v.begin(); 55 | 56 | const std::vector* f = &vit->second; 57 | 58 | out << "<" << vit->first << ": ["; 59 | if(!f->empty()) out << (*f)[0]; 60 | for(unsigned int i = 1; i < f->size(); ++i) 61 | { 62 | out << ", " << (*f)[i]; 63 | } 64 | out << "]>"; 65 | 66 | for(++vit; vit != v.end(); ++vit) 67 | { 68 | f = &vit->second; 69 | 70 | out << ", <" << vit->first << ": ["; 71 | if(!f->empty()) out << (*f)[0]; 72 | for(unsigned int i = 1; i < f->size(); ++i) 73 | { 74 | out << ", " << (*f)[i]; 75 | } 76 | out << "]>"; 77 | } 78 | } 79 | 80 | return out; 81 | } 82 | 83 | // --------------------------------------------------------------------------- 84 | 85 | } // namespace DBoW2 86 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/FeatureVector.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FeatureVector.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: feature vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_FEATURE_VECTOR__ 11 | #define __D_T_FEATURE_VECTOR__ 12 | 13 | #include "BowVector.h" 14 | #include 15 | #include 16 | #include 17 | 18 | namespace DBoW2 { 19 | 20 | /// Vector of nodes with indexes of local features 21 | class FeatureVector: 22 | public std::map > 23 | { 24 | public: 25 | 26 | /** 27 | * Constructor 28 | */ 29 | FeatureVector(void); 30 | 31 | /** 32 | * Destructor 33 | */ 34 | ~FeatureVector(void); 35 | 36 | /** 37 | * Adds a feature to an existing node, or adds a new node with an initial 38 | * feature 39 | * @param id node id to add or to modify 40 | * @param i_feature index of feature to add to the given node 41 | */ 42 | void addFeature(NodeId id, unsigned int i_feature); 43 | 44 | /** 45 | * Sends a string versions of the feature vector through the stream 46 | * @param out stream 47 | * @param v feature vector 48 | */ 49 | friend std::ostream& operator<<(std::ostream &out, const FeatureVector &v); 50 | 51 | }; 52 | 53 | } // namespace DBoW2 54 | 55 | #endif 56 | 57 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/QueryResults.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: QueryResults.cpp 3 | * Date: March, November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: structure to store results of database queries 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include "QueryResults.h" 13 | 14 | using namespace std; 15 | 16 | namespace DBoW2 17 | { 18 | 19 | // --------------------------------------------------------------------------- 20 | 21 | ostream & operator<<(ostream& os, const Result& ret ) 22 | { 23 | os << ""; 24 | return os; 25 | } 26 | 27 | // --------------------------------------------------------------------------- 28 | 29 | ostream & operator<<(ostream& os, const QueryResults& ret ) 30 | { 31 | if(ret.size() == 1) 32 | os << "1 result:" << endl; 33 | else 34 | os << ret.size() << " results:" << endl; 35 | 36 | QueryResults::const_iterator rit; 37 | for(rit = ret.begin(); rit != ret.end(); ++rit) 38 | { 39 | os << *rit; 40 | if(rit + 1 != ret.end()) os << endl; 41 | } 42 | return os; 43 | } 44 | 45 | // --------------------------------------------------------------------------- 46 | 47 | void QueryResults::saveM(const std::string &filename) const 48 | { 49 | fstream f(filename.c_str(), ios::out); 50 | 51 | QueryResults::const_iterator qit; 52 | for(qit = begin(); qit != end(); ++qit) 53 | { 54 | f << qit->Id << " " << qit->Score << endl; 55 | } 56 | 57 | f.close(); 58 | } 59 | 60 | // --------------------------------------------------------------------------- 61 | 62 | } // namespace DBoW2 63 | 64 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/QueryResults.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: QueryResults.h 3 | * Date: March, November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: structure to store results of database queries 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_QUERY_RESULTS__ 11 | #define __D_T_QUERY_RESULTS__ 12 | 13 | #include 14 | 15 | namespace DBoW2 { 16 | 17 | /// Id of entries of the database 18 | typedef unsigned int EntryId; 19 | 20 | /// Single result of a query 21 | class Result 22 | { 23 | public: 24 | 25 | /// Entry id 26 | EntryId Id; 27 | 28 | /// Score obtained 29 | double Score; 30 | 31 | /// debug 32 | int nWords; // words in common 33 | // !!! this is filled only by Bhatt score! 34 | // (and for BCMatching, BCThresholding then) 35 | 36 | double bhatScore, chiScore; 37 | /// debug 38 | 39 | // only done by ChiSq and BCThresholding 40 | double sumCommonVi; 41 | double sumCommonWi; 42 | double expectedChiScore; 43 | /// debug 44 | 45 | /** 46 | * Empty constructors 47 | */ 48 | inline Result(){} 49 | 50 | /** 51 | * Creates a result with the given data 52 | * @param _id entry id 53 | * @param _score score 54 | */ 55 | inline Result(EntryId _id, double _score): Id(_id), Score(_score){} 56 | 57 | /** 58 | * Compares the scores of two results 59 | * @return true iff this.score < r.score 60 | */ 61 | inline bool operator<(const Result &r) const 62 | { 63 | return this->Score < r.Score; 64 | } 65 | 66 | /** 67 | * Compares the scores of two results 68 | * @return true iff this.score > r.score 69 | */ 70 | inline bool operator>(const Result &r) const 71 | { 72 | return this->Score > r.Score; 73 | } 74 | 75 | /** 76 | * Compares the entry id of the result 77 | * @return true iff this.id == id 78 | */ 79 | inline bool operator==(EntryId id) const 80 | { 81 | return this->Id == id; 82 | } 83 | 84 | /** 85 | * Compares the score of this entry with a given one 86 | * @param s score to compare with 87 | * @return true iff this score < s 88 | */ 89 | inline bool operator<(double s) const 90 | { 91 | return this->Score < s; 92 | } 93 | 94 | /** 95 | * Compares the score of this entry with a given one 96 | * @param s score to compare with 97 | * @return true iff this score > s 98 | */ 99 | inline bool operator>(double s) const 100 | { 101 | return this->Score > s; 102 | } 103 | 104 | /** 105 | * Compares the score of two results 106 | * @param a 107 | * @param b 108 | * @return true iff a.Score > b.Score 109 | */ 110 | static inline bool gt(const Result &a, const Result &b) 111 | { 112 | return a.Score > b.Score; 113 | } 114 | 115 | /** 116 | * Compares the scores of two results 117 | * @return true iff a.Score > b.Score 118 | */ 119 | inline static bool ge(const Result &a, const Result &b) 120 | { 121 | return a.Score > b.Score; 122 | } 123 | 124 | /** 125 | * Returns true iff a.Score >= b.Score 126 | * @param a 127 | * @param b 128 | * @return true iff a.Score >= b.Score 129 | */ 130 | static inline bool geq(const Result &a, const Result &b) 131 | { 132 | return a.Score >= b.Score; 133 | } 134 | 135 | /** 136 | * Returns true iff a.Score >= s 137 | * @param a 138 | * @param s 139 | * @return true iff a.Score >= s 140 | */ 141 | static inline bool geqv(const Result &a, double s) 142 | { 143 | return a.Score >= s; 144 | } 145 | 146 | 147 | /** 148 | * Returns true iff a.Id < b.Id 149 | * @param a 150 | * @param b 151 | * @return true iff a.Id < b.Id 152 | */ 153 | static inline bool ltId(const Result &a, const Result &b) 154 | { 155 | return a.Id < b.Id; 156 | } 157 | 158 | /** 159 | * Prints a string version of the result 160 | * @param os ostream 161 | * @param ret Result to print 162 | */ 163 | friend std::ostream & operator<<(std::ostream& os, const Result& ret ); 164 | }; 165 | 166 | /// Multiple results from a query 167 | class QueryResults: public std::vector 168 | { 169 | public: 170 | 171 | /** 172 | * Multiplies all the scores in the vector by factor 173 | * @param factor 174 | */ 175 | inline void scaleScores(double factor); 176 | 177 | /** 178 | * Prints a string version of the results 179 | * @param os ostream 180 | * @param ret QueryResults to print 181 | */ 182 | friend std::ostream & operator<<(std::ostream& os, const QueryResults& ret ); 183 | 184 | /** 185 | * Saves a matlab file with the results 186 | * @param filename 187 | */ 188 | void saveM(const std::string &filename) const; 189 | 190 | }; 191 | 192 | // -------------------------------------------------------------------------- 193 | 194 | inline void QueryResults::scaleScores(double factor) 195 | { 196 | for(QueryResults::iterator qit = begin(); qit != end(); ++qit) 197 | qit->Score *= factor; 198 | } 199 | 200 | // -------------------------------------------------------------------------- 201 | 202 | } // namespace TemplatedBoW 203 | 204 | #endif 205 | 206 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DBoW/ScoringObject.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: ScoringObject.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions to compute bow scores 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_SCORING_OBJECT__ 11 | #define __D_T_SCORING_OBJECT__ 12 | 13 | #include "BowVector.h" 14 | 15 | namespace DBoW2 { 16 | 17 | /// Base class of scoring functions 18 | class GeneralScoring 19 | { 20 | public: 21 | /** 22 | * Computes the score between two vectors. Vectors must be sorted and 23 | * normalized if necessary 24 | * @param v (in/out) 25 | * @param w (in/out) 26 | * @return score 27 | */ 28 | virtual double score(const BowVector &v, const BowVector &w) const = 0; 29 | 30 | /** 31 | * Returns whether a vector must be normalized before scoring according 32 | * to the scoring scheme 33 | * @param norm norm to use 34 | * @return true iff must normalize 35 | */ 36 | virtual bool mustNormalize(LNorm &norm) const = 0; 37 | 38 | /// Log of epsilon 39 | static const double LOG_EPS; 40 | // If you change the type of WordValue, make sure you change also the 41 | // epsilon value (this is needed by the KL method) 42 | 43 | virtual ~GeneralScoring() {} //!< Required for virtual base classes 44 | }; 45 | 46 | /** 47 | * Macro for defining Scoring classes 48 | * @param NAME name of class 49 | * @param MUSTNORMALIZE if vectors must be normalized to compute the score 50 | * @param NORM type of norm to use when MUSTNORMALIZE 51 | */ 52 | #define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \ 53 | NAME: public GeneralScoring \ 54 | { public: \ 55 | /** \ 56 | * Computes score between two vectors \ 57 | * @param v \ 58 | * @param w \ 59 | * @return score between v and w \ 60 | */ \ 61 | virtual double score(const BowVector &v, const BowVector &w) const; \ 62 | \ 63 | /** \ 64 | * Says if a vector must be normalized according to the scoring function \ 65 | * @param norm (out) if true, norm to use 66 | * @return true iff vectors must be normalized \ 67 | */ \ 68 | virtual inline bool mustNormalize(LNorm &norm) const \ 69 | { norm = NORM; return MUSTNORMALIZE; } \ 70 | } 71 | 72 | /// L1 Scoring object 73 | class __SCORING_CLASS(L1Scoring, true, L1); 74 | 75 | /// L2 Scoring object 76 | class __SCORING_CLASS(L2Scoring, true, L2); 77 | 78 | /// Chi square Scoring object 79 | class __SCORING_CLASS(ChiSquareScoring, true, L1); 80 | 81 | /// KL divergence Scoring object 82 | class __SCORING_CLASS(KLScoring, true, L1); 83 | 84 | /// Bhattacharyya Scoring object 85 | class __SCORING_CLASS(BhattacharyyaScoring, true, L1); 86 | 87 | /// Dot product Scoring object 88 | class __SCORING_CLASS(DotProductScoring, false, L1); 89 | 90 | #undef __SCORING_CLASS 91 | 92 | } // namespace DBoW2 93 | 94 | #endif 95 | 96 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DUtils/DException.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: DException.h 3 | * Project: DUtils library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: October 6, 2009 6 | * Description: general exception of the library 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | #pragma once 12 | 13 | #ifndef __D_EXCEPTION__ 14 | #define __D_EXCEPTION__ 15 | 16 | #include 17 | #include 18 | using namespace std; 19 | 20 | namespace DUtils { 21 | 22 | /// General exception 23 | class DException : 24 | public exception 25 | { 26 | public: 27 | /** 28 | * Creates an exception with a general error message 29 | */ 30 | DException(void) throw(): m_message("DUtils exception"){} 31 | 32 | /** 33 | * Creates an exception with a custom error message 34 | * @param msg: message 35 | */ 36 | DException(const char *msg) throw(): m_message(msg){} 37 | 38 | /** 39 | * Creates an exception with a custom error message 40 | * @param msg: message 41 | */ 42 | DException(const string &msg) throw(): m_message(msg){} 43 | 44 | /** 45 | * Destructor 46 | */ 47 | virtual ~DException(void) throw(){} 48 | 49 | /** 50 | * Returns the exception message 51 | */ 52 | virtual const char* what() const throw() 53 | { 54 | return m_message.c_str(); 55 | } 56 | 57 | protected: 58 | /// Error message 59 | string m_message; 60 | }; 61 | 62 | } 63 | 64 | #endif 65 | 66 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DUtils/DUtils.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: DUtils.h 3 | * Project: DUtils library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: October 6, 2009 6 | * Description: include file for including all the library functionalities 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | /*! \mainpage DUtils Library 12 | * 13 | * DUtils library for C++: 14 | * Collection of classes with general utilities for C++ applications. 15 | * 16 | * Written by Dorian Galvez-Lopez, 17 | * University of Zaragoza 18 | * 19 | * Check my website to obtain updates: http://webdiis.unizar.es/~dorian 20 | * 21 | * \section license License 22 | * This program is free software: you can redistribute it and/or modify 23 | * it under the terms of the GNU Lesser General Public License (LGPL) as 24 | * published by the Free Software Foundation, either version 3 of the License, 25 | * or any later version. 26 | * 27 | */ 28 | 29 | 30 | #pragma once 31 | 32 | #ifndef __D_UTILS__ 33 | #define __D_UTILS__ 34 | 35 | /// Several utilities for C++ programs 36 | namespace DUtils 37 | { 38 | } 39 | 40 | // Exception 41 | #include "DException.h" 42 | 43 | #include "Timestamp.h" 44 | // Random numbers 45 | #include "Random.h" 46 | 47 | 48 | #endif 49 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DUtils/Random.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Random.cpp 3 | * Project: DUtils library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: April 2010 6 | * Description: manages pseudo-random numbers 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | #include "Random.h" 12 | #include "Timestamp.h" 13 | #include 14 | using namespace std; 15 | 16 | bool DUtils::Random::m_already_seeded = false; 17 | 18 | void DUtils::Random::SeedRand(){ 19 | Timestamp time; 20 | time.setToCurrentTime(); 21 | srand((unsigned)time.getFloatTime()); 22 | } 23 | 24 | void DUtils::Random::SeedRandOnce() 25 | { 26 | if(!m_already_seeded) 27 | { 28 | DUtils::Random::SeedRand(); 29 | m_already_seeded = true; 30 | } 31 | } 32 | 33 | void DUtils::Random::SeedRand(int seed) 34 | { 35 | srand(seed); 36 | } 37 | 38 | void DUtils::Random::SeedRandOnce(int seed) 39 | { 40 | if(!m_already_seeded) 41 | { 42 | DUtils::Random::SeedRand(seed); 43 | m_already_seeded = true; 44 | } 45 | } 46 | 47 | int DUtils::Random::RandomInt(int min, int max){ 48 | int d = max - min + 1; 49 | return int(((double)rand()/((double)RAND_MAX + 1.0)) * d) + min; 50 | } 51 | 52 | // --------------------------------------------------------------------------- 53 | // --------------------------------------------------------------------------- 54 | 55 | DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer(int min, int max) 56 | { 57 | if(min <= max) 58 | { 59 | m_min = min; 60 | m_max = max; 61 | } 62 | else 63 | { 64 | m_min = max; 65 | m_max = min; 66 | } 67 | 68 | createValues(); 69 | } 70 | 71 | // --------------------------------------------------------------------------- 72 | 73 | DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer 74 | (const DUtils::Random::UnrepeatedRandomizer& rnd) 75 | { 76 | *this = rnd; 77 | } 78 | 79 | // --------------------------------------------------------------------------- 80 | 81 | int DUtils::Random::UnrepeatedRandomizer::get() 82 | { 83 | if(empty()) createValues(); 84 | 85 | DUtils::Random::SeedRandOnce(); 86 | 87 | int k = DUtils::Random::RandomInt(0, m_values.size()-1); 88 | int ret = m_values[k]; 89 | m_values[k] = m_values.back(); 90 | m_values.pop_back(); 91 | 92 | return ret; 93 | } 94 | 95 | // --------------------------------------------------------------------------- 96 | 97 | void DUtils::Random::UnrepeatedRandomizer::createValues() 98 | { 99 | int n = m_max - m_min + 1; 100 | 101 | m_values.resize(n); 102 | for(int i = 0; i < n; ++i) m_values[i] = m_min + i; 103 | } 104 | 105 | // --------------------------------------------------------------------------- 106 | 107 | void DUtils::Random::UnrepeatedRandomizer::reset() 108 | { 109 | if((int)m_values.size() != m_max - m_min + 1) createValues(); 110 | } 111 | 112 | // --------------------------------------------------------------------------- 113 | 114 | DUtils::Random::UnrepeatedRandomizer& 115 | DUtils::Random::UnrepeatedRandomizer::operator= 116 | (const DUtils::Random::UnrepeatedRandomizer& rnd) 117 | { 118 | if(this != &rnd) 119 | { 120 | this->m_min = rnd.m_min; 121 | this->m_max = rnd.m_max; 122 | this->m_values = rnd.m_values; 123 | } 124 | return *this; 125 | } 126 | 127 | // --------------------------------------------------------------------------- 128 | 129 | 130 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DUtils/Random.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Random.h 3 | * Project: DUtils library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: April 2010, November 2011 6 | * Description: manages pseudo-random numbers 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | #pragma once 12 | #ifndef __D_RANDOM__ 13 | #define __D_RANDOM__ 14 | 15 | #include 16 | #include 17 | 18 | namespace DUtils { 19 | 20 | /// Functions to generate pseudo-random numbers 21 | class Random 22 | { 23 | public: 24 | class UnrepeatedRandomizer; 25 | 26 | public: 27 | /** 28 | * Sets the random number seed to the current time 29 | */ 30 | static void SeedRand(); 31 | 32 | /** 33 | * Sets the random number seed to the current time only the first 34 | * time this function is called 35 | */ 36 | static void SeedRandOnce(); 37 | 38 | /** 39 | * Sets the given random number seed 40 | * @param seed 41 | */ 42 | static void SeedRand(int seed); 43 | 44 | /** 45 | * Sets the given random number seed only the first time this function 46 | * is called 47 | * @param seed 48 | */ 49 | static void SeedRandOnce(int seed); 50 | 51 | /** 52 | * Returns a random number in the range [0..1] 53 | * @return random T number in [0..1] 54 | */ 55 | template 56 | static T RandomValue(){ 57 | return (T)rand()/(T)RAND_MAX; 58 | } 59 | 60 | /** 61 | * Returns a random number in the range [min..max] 62 | * @param min 63 | * @param max 64 | * @return random T number in [min..max] 65 | */ 66 | template 67 | static T RandomValue(T min, T max){ 68 | return Random::RandomValue() * (max - min) + min; 69 | } 70 | 71 | /** 72 | * Returns a random int in the range [min..max] 73 | * @param min 74 | * @param max 75 | * @return random int in [min..max] 76 | */ 77 | static int RandomInt(int min, int max); 78 | 79 | /** 80 | * Returns a random number from a gaussian distribution 81 | * @param mean 82 | * @param sigma standard deviation 83 | */ 84 | template 85 | static T RandomGaussianValue(T mean, T sigma) 86 | { 87 | // Box-Muller transformation 88 | T x1, x2, w, y1; 89 | 90 | do { 91 | x1 = (T)2. * RandomValue() - (T)1.; 92 | x2 = (T)2. * RandomValue() - (T)1.; 93 | w = x1 * x1 + x2 * x2; 94 | } while ( w >= (T)1. || w == (T)0. ); 95 | 96 | w = sqrt( ((T)-2.0 * log( w ) ) / w ); 97 | y1 = x1 * w; 98 | 99 | return( mean + y1 * sigma ); 100 | } 101 | 102 | private: 103 | 104 | /// If SeedRandOnce() or SeedRandOnce(int) have already been called 105 | static bool m_already_seeded; 106 | 107 | }; 108 | 109 | // --------------------------------------------------------------------------- 110 | 111 | /// Provides pseudo-random numbers with no repetitions 112 | class Random::UnrepeatedRandomizer 113 | { 114 | public: 115 | 116 | /** 117 | * Creates a randomizer that returns numbers in the range [min, max] 118 | * @param min 119 | * @param max 120 | */ 121 | UnrepeatedRandomizer(int min, int max); 122 | ~UnrepeatedRandomizer(){} 123 | 124 | /** 125 | * Copies a randomizer 126 | * @param rnd 127 | */ 128 | UnrepeatedRandomizer(const UnrepeatedRandomizer& rnd); 129 | 130 | /** 131 | * Copies a randomizer 132 | * @param rnd 133 | */ 134 | UnrepeatedRandomizer& operator=(const UnrepeatedRandomizer& rnd); 135 | 136 | /** 137 | * Returns a random number not given before. If all the possible values 138 | * were already given, the process starts again 139 | * @return unrepeated random number 140 | */ 141 | int get(); 142 | 143 | /** 144 | * Returns whether all the possible values between min and max were 145 | * already given. If get() is called when empty() is true, the behaviour 146 | * is the same than after creating the randomizer 147 | * @return true iff all the values were returned 148 | */ 149 | inline bool empty() const { return m_values.empty(); } 150 | 151 | /** 152 | * Returns the number of values still to be returned 153 | * @return amount of values to return 154 | */ 155 | inline unsigned int left() const { return m_values.size(); } 156 | 157 | /** 158 | * Resets the randomizer as it were just created 159 | */ 160 | void reset(); 161 | 162 | protected: 163 | 164 | /** 165 | * Creates the vector with available values 166 | */ 167 | void createValues(); 168 | 169 | protected: 170 | 171 | /// Min of range of values 172 | int m_min; 173 | /// Max of range of values 174 | int m_max; 175 | 176 | /// Available values 177 | std::vector m_values; 178 | 179 | }; 180 | 181 | } 182 | 183 | #endif 184 | 185 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DUtils/Timestamp.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Timestamp.cpp 3 | * Author: Dorian Galvez-Lopez 4 | * Date: March 2009 5 | * Description: timestamping functions 6 | * 7 | * Note: in windows, this class has a 1ms resolution 8 | * 9 | * License: see the LICENSE.txt file 10 | * 11 | */ 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | 20 | #ifdef _WIN32 21 | #ifndef WIN32 22 | #define WIN32 23 | #endif 24 | #endif 25 | 26 | #ifdef WIN32 27 | #include 28 | #define sprintf sprintf_s 29 | #else 30 | #include 31 | #endif 32 | 33 | #include "Timestamp.h" 34 | 35 | using namespace std; 36 | 37 | using namespace DUtils; 38 | 39 | Timestamp::Timestamp(Timestamp::tOptions option) 40 | { 41 | if(option & CURRENT_TIME) 42 | setToCurrentTime(); 43 | else if(option & ZERO) 44 | setTime(0.); 45 | } 46 | 47 | Timestamp::~Timestamp(void) 48 | { 49 | } 50 | 51 | bool Timestamp::empty() const 52 | { 53 | return m_secs == 0 && m_usecs == 0; 54 | } 55 | 56 | void Timestamp::setToCurrentTime(){ 57 | 58 | #ifdef WIN32 59 | struct __timeb32 timebuffer; 60 | _ftime32_s( &timebuffer ); // C4996 61 | // Note: _ftime is deprecated; consider using _ftime_s instead 62 | m_secs = timebuffer.time; 63 | m_usecs = timebuffer.millitm * 1000; 64 | #else 65 | struct timeval now; 66 | gettimeofday(&now, NULL); 67 | m_secs = now.tv_sec; 68 | m_usecs = now.tv_usec; 69 | #endif 70 | 71 | } 72 | 73 | void Timestamp::setTime(const string &stime){ 74 | string::size_type p = stime.find('.'); 75 | if(p == string::npos){ 76 | m_secs = atol(stime.c_str()); 77 | m_usecs = 0; 78 | }else{ 79 | m_secs = atol(stime.substr(0, p).c_str()); 80 | 81 | string s_usecs = stime.substr(p+1, 6); 82 | m_usecs = atol(stime.substr(p+1).c_str()); 83 | m_usecs *= (unsigned long)pow(10.0, double(6 - s_usecs.length())); 84 | } 85 | } 86 | 87 | void Timestamp::setTime(double s) 88 | { 89 | m_secs = (unsigned long)s; 90 | m_usecs = (s - (double)m_secs) * 1e6; 91 | } 92 | 93 | double Timestamp::getFloatTime() const { 94 | return double(m_secs) + double(m_usecs)/1000000.0; 95 | } 96 | 97 | string Timestamp::getStringTime() const { 98 | char buf[32]; 99 | sprintf(buf, "%.6lf", this->getFloatTime()); 100 | return string(buf); 101 | } 102 | 103 | double Timestamp::operator- (const Timestamp &t) const { 104 | return this->getFloatTime() - t.getFloatTime(); 105 | } 106 | 107 | Timestamp& Timestamp::operator+= (double s) 108 | { 109 | *this = *this + s; 110 | return *this; 111 | } 112 | 113 | Timestamp& Timestamp::operator-= (double s) 114 | { 115 | *this = *this - s; 116 | return *this; 117 | } 118 | 119 | Timestamp Timestamp::operator+ (double s) const 120 | { 121 | unsigned long secs = (long)floor(s); 122 | unsigned long usecs = (long)((s - (double)secs) * 1e6); 123 | 124 | return this->plus(secs, usecs); 125 | } 126 | 127 | Timestamp Timestamp::plus(unsigned long secs, unsigned long usecs) const 128 | { 129 | Timestamp t; 130 | 131 | const unsigned long max = 1000000ul; 132 | 133 | if(m_usecs + usecs >= max) 134 | t.setTime(m_secs + secs + 1, m_usecs + usecs - max); 135 | else 136 | t.setTime(m_secs + secs, m_usecs + usecs); 137 | 138 | return t; 139 | } 140 | 141 | Timestamp Timestamp::operator- (double s) const 142 | { 143 | unsigned long secs = (long)floor(s); 144 | unsigned long usecs = (long)((s - (double)secs) * 1e6); 145 | 146 | return this->minus(secs, usecs); 147 | } 148 | 149 | Timestamp Timestamp::minus(unsigned long secs, unsigned long usecs) const 150 | { 151 | Timestamp t; 152 | 153 | const unsigned long max = 1000000ul; 154 | 155 | if(m_usecs < usecs) 156 | t.setTime(m_secs - secs - 1, max - (usecs - m_usecs)); 157 | else 158 | t.setTime(m_secs - secs, m_usecs - usecs); 159 | 160 | return t; 161 | } 162 | 163 | bool Timestamp::operator> (const Timestamp &t) const 164 | { 165 | if(m_secs > t.m_secs) return true; 166 | else if(m_secs == t.m_secs) return m_usecs > t.m_usecs; 167 | else return false; 168 | } 169 | 170 | bool Timestamp::operator>= (const Timestamp &t) const 171 | { 172 | if(m_secs > t.m_secs) return true; 173 | else if(m_secs == t.m_secs) return m_usecs >= t.m_usecs; 174 | else return false; 175 | } 176 | 177 | bool Timestamp::operator< (const Timestamp &t) const 178 | { 179 | if(m_secs < t.m_secs) return true; 180 | else if(m_secs == t.m_secs) return m_usecs < t.m_usecs; 181 | else return false; 182 | } 183 | 184 | bool Timestamp::operator<= (const Timestamp &t) const 185 | { 186 | if(m_secs < t.m_secs) return true; 187 | else if(m_secs == t.m_secs) return m_usecs <= t.m_usecs; 188 | else return false; 189 | } 190 | 191 | bool Timestamp::operator== (const Timestamp &t) const 192 | { 193 | return(m_secs == t.m_secs && m_usecs == t.m_usecs); 194 | } 195 | 196 | 197 | string Timestamp::Format(bool machine_friendly) const 198 | { 199 | struct tm tm_time; 200 | 201 | time_t t = (time_t)getFloatTime(); 202 | 203 | #ifdef WIN32 204 | localtime_s(&tm_time, &t); 205 | #else 206 | localtime_r(&t, &tm_time); 207 | #endif 208 | 209 | char buffer[128]; 210 | 211 | if(machine_friendly) 212 | { 213 | strftime(buffer, 128, "%Y%m%d_%H%M%S", &tm_time); 214 | } 215 | else 216 | { 217 | strftime(buffer, 128, "%c", &tm_time); // Thu Aug 23 14:55:02 2001 218 | } 219 | 220 | return string(buffer); 221 | } 222 | 223 | string Timestamp::Format(double s) { 224 | int days = int(s / (24. * 3600.0)); 225 | s -= days * (24. * 3600.0); 226 | int hours = int(s / 3600.0); 227 | s -= hours * 3600; 228 | int minutes = int(s / 60.0); 229 | s -= minutes * 60; 230 | int seconds = int(s); 231 | int ms = int((s - seconds)*1e6); 232 | 233 | stringstream ss; 234 | ss.fill('0'); 235 | bool b; 236 | if((b = (days > 0))) ss << days << "d "; 237 | if((b = (b || hours > 0))) ss << setw(2) << hours << ":"; 238 | if((b = (b || minutes > 0))) ss << setw(2) << minutes << ":"; 239 | if(b) ss << setw(2); 240 | ss << seconds; 241 | if(!b) ss << "." << setw(6) << ms; 242 | 243 | return ss.str(); 244 | } 245 | 246 | 247 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DUtils/Timestamp.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Timestamp.h 3 | * Author: Dorian Galvez-Lopez 4 | * Date: March 2009 5 | * Description: timestamping functions 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_TIMESTAMP__ 11 | #define __D_TIMESTAMP__ 12 | 13 | #include 14 | using namespace std; 15 | 16 | namespace DUtils { 17 | 18 | /// Timestamp 19 | class Timestamp 20 | { 21 | public: 22 | 23 | /// Options to initiate a timestamp 24 | enum tOptions 25 | { 26 | NONE = 0, 27 | CURRENT_TIME = 0x1, 28 | ZERO = 0x2 29 | }; 30 | 31 | public: 32 | 33 | /** 34 | * Creates a timestamp 35 | * @param option option to set the initial time stamp 36 | */ 37 | Timestamp(Timestamp::tOptions option = NONE); 38 | 39 | /** 40 | * Destructor 41 | */ 42 | virtual ~Timestamp(void); 43 | 44 | /** 45 | * Says if the timestamp is "empty": seconds and usecs are both 0, as 46 | * when initiated with the ZERO flag 47 | * @return true iif secs == usecs == 0 48 | */ 49 | bool empty() const; 50 | 51 | /** 52 | * Sets this instance to the current time 53 | */ 54 | void setToCurrentTime(); 55 | 56 | /** 57 | * Sets the timestamp from seconds and microseconds 58 | * @param secs: seconds 59 | * @param usecs: microseconds 60 | */ 61 | inline void setTime(unsigned long secs, unsigned long usecs){ 62 | m_secs = secs; 63 | m_usecs = usecs; 64 | } 65 | 66 | /** 67 | * Returns the timestamp in seconds and microseconds 68 | * @param secs seconds 69 | * @param usecs microseconds 70 | */ 71 | inline void getTime(unsigned long &secs, unsigned long &usecs) const 72 | { 73 | secs = m_secs; 74 | usecs = m_usecs; 75 | } 76 | 77 | /** 78 | * Sets the timestamp from a string with the time in seconds 79 | * @param stime: string such as "1235603336.036609" 80 | */ 81 | void setTime(const string &stime); 82 | 83 | /** 84 | * Sets the timestamp from a number of seconds from the epoch 85 | * @param s seconds from the epoch 86 | */ 87 | void setTime(double s); 88 | 89 | /** 90 | * Returns this timestamp as the number of seconds in (long) float format 91 | */ 92 | double getFloatTime() const; 93 | 94 | /** 95 | * Returns this timestamp as the number of seconds in fixed length string format 96 | */ 97 | string getStringTime() const; 98 | 99 | /** 100 | * Returns the difference in seconds between this timestamp (greater) and t (smaller) 101 | * If the order is swapped, a negative number is returned 102 | * @param t: timestamp to subtract from this timestamp 103 | * @return difference in seconds 104 | */ 105 | double operator- (const Timestamp &t) const; 106 | 107 | /** 108 | * Returns a copy of this timestamp + s seconds + us microseconds 109 | * @param s seconds 110 | * @param us microseconds 111 | */ 112 | Timestamp plus(unsigned long s, unsigned long us) const; 113 | 114 | /** 115 | * Returns a copy of this timestamp - s seconds - us microseconds 116 | * @param s seconds 117 | * @param us microseconds 118 | */ 119 | Timestamp minus(unsigned long s, unsigned long us) const; 120 | 121 | /** 122 | * Adds s seconds to this timestamp and returns a reference to itself 123 | * @param s seconds 124 | * @return reference to this timestamp 125 | */ 126 | Timestamp& operator+= (double s); 127 | 128 | /** 129 | * Substracts s seconds to this timestamp and returns a reference to itself 130 | * @param s seconds 131 | * @return reference to this timestamp 132 | */ 133 | Timestamp& operator-= (double s); 134 | 135 | /** 136 | * Returns a copy of this timestamp + s seconds 137 | * @param s: seconds 138 | */ 139 | Timestamp operator+ (double s) const; 140 | 141 | /** 142 | * Returns a copy of this timestamp - s seconds 143 | * @param s: seconds 144 | */ 145 | Timestamp operator- (double s) const; 146 | 147 | /** 148 | * Returns whether this timestamp is at the future of t 149 | * @param t 150 | */ 151 | bool operator> (const Timestamp &t) const; 152 | 153 | /** 154 | * Returns whether this timestamp is at the future of (or is the same as) t 155 | * @param t 156 | */ 157 | bool operator>= (const Timestamp &t) const; 158 | 159 | /** 160 | * Returns whether this timestamp and t represent the same instant 161 | * @param t 162 | */ 163 | bool operator== (const Timestamp &t) const; 164 | 165 | /** 166 | * Returns whether this timestamp is at the past of t 167 | * @param t 168 | */ 169 | bool operator< (const Timestamp &t) const; 170 | 171 | /** 172 | * Returns whether this timestamp is at the past of (or is the same as) t 173 | * @param t 174 | */ 175 | bool operator<= (const Timestamp &t) const; 176 | 177 | /** 178 | * Returns the timestamp in a human-readable string 179 | * @param machine_friendly if true, the returned string is formatted 180 | * to yyyymmdd_hhmmss, without weekday or spaces 181 | * @note This has not been tested under Windows 182 | * @note The timestamp is truncated to seconds 183 | */ 184 | string Format(bool machine_friendly = false) const; 185 | 186 | /** 187 | * Returns a string version of the elapsed time in seconds, with the format 188 | * xd hh:mm:ss, hh:mm:ss, mm:ss or s.us 189 | * @param s: elapsed seconds (given by getFloatTime) to format 190 | */ 191 | static string Format(double s); 192 | 193 | 194 | protected: 195 | /// Seconds 196 | unsigned long m_secs; // seconds 197 | /// Microseconds 198 | unsigned long m_usecs; // microseconds 199 | }; 200 | 201 | } 202 | 203 | #endif 204 | 205 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DVision/BRIEF.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: BRIEF.cpp 3 | * Author: Dorian Galvez 4 | * Date: September 2010 5 | * Description: implementation of BRIEF (Binary Robust Independent 6 | * Elementary Features) descriptor by 7 | * Michael Calonder, Vincent Lepetitand Pascal Fua 8 | * + close binary tests (by Dorian Galvez-Lopez) 9 | * License: see the LICENSE.txt file 10 | * 11 | */ 12 | 13 | #include "BRIEF.h" 14 | #include "../DUtils/DUtils.h" 15 | #include 16 | #include 17 | 18 | using namespace std; 19 | using namespace DVision; 20 | 21 | // ---------------------------------------------------------------------------- 22 | 23 | BRIEF::BRIEF(int nbits, int patch_size, Type type): 24 | m_bit_length(nbits), m_patch_size(patch_size), m_type(type) 25 | { 26 | assert(patch_size > 1); 27 | assert(nbits > 0); 28 | generateTestPoints(); 29 | } 30 | 31 | // ---------------------------------------------------------------------------- 32 | 33 | BRIEF::~BRIEF() 34 | { 35 | } 36 | 37 | // --------------------------------------------------------------------------- 38 | 39 | void BRIEF::compute(const cv::Mat &image, 40 | const std::vector &points, 41 | vector &descriptors, 42 | bool treat_image) const 43 | { 44 | const float sigma = 2.f; 45 | const cv::Size ksize(9, 9); 46 | 47 | cv::Mat im; 48 | if(treat_image) 49 | { 50 | cv::Mat aux; 51 | if(image.depth() == 3) 52 | { 53 | cv::cvtColor(image, aux, CV_RGB2GRAY); 54 | } 55 | else 56 | { 57 | aux = image; 58 | } 59 | 60 | cv::GaussianBlur(aux, im, ksize, sigma, sigma); 61 | 62 | } 63 | else 64 | { 65 | im = image; 66 | } 67 | 68 | assert(im.type() == CV_8UC1); 69 | assert(im.isContinuous()); 70 | 71 | // use im now 72 | const int W = im.cols; 73 | const int H = im.rows; 74 | 75 | descriptors.resize(points.size()); 76 | std::vector::iterator dit; 77 | 78 | std::vector::const_iterator kit; 79 | 80 | int x1, y1, x2, y2; 81 | 82 | dit = descriptors.begin(); 83 | for(kit = points.begin(); kit != points.end(); ++kit, ++dit) 84 | { 85 | dit->resize(m_bit_length); 86 | dit->reset(); 87 | 88 | for(unsigned int i = 0; i < m_x1.size(); ++i) 89 | { 90 | x1 = (int)(kit->pt.x + m_x1[i]); 91 | y1 = (int)(kit->pt.y + m_y1[i]); 92 | x2 = (int)(kit->pt.x + m_x2[i]); 93 | y2 = (int)(kit->pt.y + m_y2[i]); 94 | 95 | if(x1 >= 0 && x1 < W && y1 >= 0 && y1 < H 96 | && x2 >= 0 && x2 < W && y2 >= 0 && y2 < H) 97 | { 98 | if( im.ptr(y1)[x1] < im.ptr(y2)[x2] ) 99 | { 100 | dit->set(i); 101 | } 102 | } // if (x,y)_1 and (x,y)_2 are in the image 103 | 104 | } // for each (x,y) 105 | } // for each keypoint 106 | } 107 | 108 | // --------------------------------------------------------------------------- 109 | 110 | void BRIEF::generateTestPoints() 111 | { 112 | m_x1.resize(m_bit_length); 113 | m_y1.resize(m_bit_length); 114 | m_x2.resize(m_bit_length); 115 | m_y2.resize(m_bit_length); 116 | 117 | const float g_mean = 0.f; 118 | const float g_sigma = 0.2f * (float)m_patch_size; 119 | const float c_sigma = 0.08f * (float)m_patch_size; 120 | 121 | float sigma2; 122 | if(m_type == RANDOM) 123 | sigma2 = g_sigma; 124 | else 125 | sigma2 = c_sigma; 126 | 127 | const int max_v = m_patch_size / 2; 128 | 129 | DUtils::Random::SeedRandOnce(); 130 | 131 | for(int i = 0; i < m_bit_length; ++i) 132 | { 133 | int x1, y1, x2, y2; 134 | 135 | do 136 | { 137 | x1 = DUtils::Random::RandomGaussianValue(g_mean, g_sigma); 138 | } while( x1 > max_v || x1 < -max_v); 139 | 140 | do 141 | { 142 | y1 = DUtils::Random::RandomGaussianValue(g_mean, g_sigma); 143 | } while( y1 > max_v || y1 < -max_v); 144 | 145 | float meanx, meany; 146 | if(m_type == RANDOM) 147 | meanx = meany = g_mean; 148 | else 149 | { 150 | meanx = x1; 151 | meany = y1; 152 | } 153 | 154 | do 155 | { 156 | x2 = DUtils::Random::RandomGaussianValue(meanx, sigma2); 157 | } while( x2 > max_v || x2 < -max_v); 158 | 159 | do 160 | { 161 | y2 = DUtils::Random::RandomGaussianValue(meany, sigma2); 162 | } while( y2 > max_v || y2 < -max_v); 163 | 164 | m_x1[i] = x1; 165 | m_y1[i] = y1; 166 | m_x2[i] = x2; 167 | m_y2[i] = y2; 168 | } 169 | 170 | } 171 | 172 | // ---------------------------------------------------------------------------- 173 | 174 | 175 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DVision/BRIEF.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: BRIEF.h 3 | * Author: Dorian Galvez-Lopez 4 | * Date: March 2011 5 | * Description: implementation of BRIEF (Binary Robust Independent 6 | * Elementary Features) descriptor by 7 | * Michael Calonder, Vincent Lepetit and Pascal Fua 8 | * + close binary tests (by Dorian Galvez-Lopez) 9 | * 10 | * If you use this code with the RANDOM_CLOSE descriptor version, please cite: 11 | @INPROCEEDINGS{GalvezIROS11, 12 | author={Galvez-Lopez, Dorian and Tardos, Juan D.}, 13 | booktitle={Intelligent Robots and Systems (IROS), 2011 IEEE/RSJ International Conference on}, 14 | title={Real-time loop detection with bags of binary words}, 15 | year={2011}, 16 | month={sept.}, 17 | volume={}, 18 | number={}, 19 | pages={51 -58}, 20 | keywords={}, 21 | doi={10.1109/IROS.2011.6094885}, 22 | ISSN={2153-0858} 23 | } 24 | * 25 | * License: see the LICENSE.txt file 26 | * 27 | */ 28 | 29 | #ifndef __D_BRIEF__ 30 | #define __D_BRIEF__ 31 | 32 | #include 33 | #include 34 | #include 35 | #include 36 | 37 | namespace DVision { 38 | 39 | /// BRIEF descriptor 40 | class BRIEF 41 | { 42 | public: 43 | 44 | /// Bitset type 45 | typedef boost::dynamic_bitset<> bitset; 46 | 47 | /// Type of pairs 48 | enum Type 49 | { 50 | RANDOM, // random pairs (Calonder's original version) 51 | RANDOM_CLOSE, // random but close pairs (used in GalvezIROS11) 52 | }; 53 | 54 | public: 55 | 56 | /** 57 | * Creates the BRIEF a priori data for descriptors of nbits length 58 | * @param nbits descriptor length in bits 59 | * @param patch_size 60 | * @param type type of pairs to generate 61 | */ 62 | BRIEF(int nbits = 256, int patch_size = 48, Type type = RANDOM_CLOSE); 63 | virtual ~BRIEF(); 64 | 65 | /** 66 | * Returns the descriptor length in bits 67 | * @return descriptor length in bits 68 | */ 69 | inline int getDescriptorLengthInBits() const 70 | { 71 | return m_bit_length; 72 | } 73 | 74 | /** 75 | * Returns the type of classifier 76 | */ 77 | inline Type getType() const 78 | { 79 | return m_type; 80 | } 81 | 82 | /** 83 | * Returns the size of the patch 84 | */ 85 | inline int getPatchSize() const 86 | { 87 | return m_patch_size; 88 | } 89 | 90 | /** 91 | * Returns the BRIEF descriptors of the given keypoints in the given image 92 | * @param image 93 | * @param points 94 | * @param descriptors 95 | * @param treat_image (default: true) if true, the image is converted to 96 | * grayscale if needed and smoothed. If not, it is assumed the image has 97 | * been treated by the user 98 | * @note this function is similar to BRIEF::compute 99 | */ 100 | inline void operator() (const cv::Mat &image, 101 | const std::vector &points, 102 | std::vector &descriptors, 103 | bool treat_image = true) const 104 | { 105 | compute(image, points, descriptors, treat_image); 106 | } 107 | 108 | /** 109 | * Returns the BRIEF descriptors of the given keypoints in the given image 110 | * @param image 111 | * @param points 112 | * @param descriptors 113 | * @param treat_image (default: true) if true, the image is converted to 114 | * grayscale if needed and smoothed. If not, it is assumed the image has 115 | * been treated by the user 116 | * @note this function is similar to BRIEF::operator() 117 | */ 118 | void compute(const cv::Mat &image, 119 | const std::vector &points, 120 | std::vector &descriptors, 121 | bool treat_image = true) const; 122 | 123 | /** 124 | * Exports the test pattern 125 | * @param x1 x1 coordinates of pairs 126 | * @param y1 y1 coordinates of pairs 127 | * @param x2 x2 coordinates of pairs 128 | * @param y2 y2 coordinates of pairs 129 | */ 130 | inline void exportPairs(std::vector &x1, std::vector &y1, 131 | std::vector &x2, std::vector &y2) const 132 | { 133 | x1 = m_x1; 134 | y1 = m_y1; 135 | x2 = m_x2; 136 | y2 = m_y2; 137 | } 138 | 139 | /** 140 | * Sets the test pattern 141 | * @param x1 x1 coordinates of pairs 142 | * @param y1 y1 coordinates of pairs 143 | * @param x2 x2 coordinates of pairs 144 | * @param y2 y2 coordinates of pairs 145 | */ 146 | inline void importPairs(const std::vector &x1, 147 | const std::vector &y1, const std::vector &x2, 148 | const std::vector &y2) 149 | { 150 | m_x1 = x1; 151 | m_y1 = y1; 152 | m_x2 = x2; 153 | m_y2 = y2; 154 | m_bit_length = x1.size(); 155 | } 156 | 157 | /** 158 | * Returns the Hamming distance between two descriptors 159 | * @param a first descriptor vector 160 | * @param b second descriptor vector 161 | * @return hamming distance 162 | */ 163 | inline static int distance(const bitset &a, const bitset &b) 164 | { 165 | return (a^b).count(); 166 | } 167 | 168 | protected: 169 | 170 | /** 171 | * Generates random points in the patch coordinates, according to 172 | * m_patch_size and m_bit_length 173 | */ 174 | void generateTestPoints(); 175 | 176 | protected: 177 | 178 | /// Descriptor length in bits 179 | int m_bit_length; 180 | 181 | /// Patch size 182 | int m_patch_size; 183 | 184 | /// Type of pairs 185 | Type m_type; 186 | 187 | /// Coordinates of test points relative to the center of the patch 188 | std::vector m_x1, m_x2; 189 | std::vector m_y1, m_y2; 190 | 191 | }; 192 | 193 | } // namespace DVision 194 | 195 | #endif 196 | 197 | 198 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/DVision/DVision.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: DVision.h 3 | * Project: DVision library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: October 4, 2010 6 | * Description: several functions for computer vision 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | /*! \mainpage DVision Library 12 | * 13 | * DVision library for C++ and OpenCV: 14 | * Collection of classes with computer vision functionality 15 | * 16 | * Written by Dorian Galvez-Lopez, 17 | * University of Zaragoza 18 | * 19 | * Check my website to obtain updates: http://webdiis.unizar.es/~dorian 20 | * 21 | * \section requirements Requirements 22 | * This library requires the DUtils and DUtilsCV libraries and the OpenCV library. 23 | * 24 | * \section license License 25 | * This program is free software: you can redistribute it and/or modify 26 | * it under the terms of the GNU Lesser General Public License (LGPL) as 27 | * published by the Free Software Foundation, either version 3 of the License, 28 | * or any later version. 29 | * 30 | */ 31 | 32 | #ifndef __D_VISION__ 33 | #define __D_VISION__ 34 | 35 | 36 | /// Computer vision functions 37 | namespace DVision 38 | { 39 | } 40 | 41 | #include "BRIEF.h" 42 | 43 | #endif 44 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/VocabularyBinary.cpp: -------------------------------------------------------------------------------- 1 | #include "VocabularyBinary.hpp" 2 | #include 3 | using namespace std; 4 | 5 | VINSLoop::Vocabulary::Vocabulary() 6 | : nNodes(0), nodes(nullptr), nWords(0), words(nullptr) { 7 | } 8 | 9 | VINSLoop::Vocabulary::~Vocabulary() { 10 | if (nodes != nullptr) { 11 | delete [] nodes; 12 | nodes = nullptr; 13 | } 14 | 15 | if (words != nullptr) { 16 | delete [] words; 17 | words = nullptr; 18 | } 19 | } 20 | 21 | void VINSLoop::Vocabulary::serialize(ofstream& stream) { 22 | stream.write((const char *)this, staticDataSize()); 23 | stream.write((const char *)nodes, sizeof(Node) * nNodes); 24 | stream.write((const char *)words, sizeof(Word) * nWords); 25 | } 26 | 27 | void VINSLoop::Vocabulary::deserialize(ifstream& stream) { 28 | stream.read((char *)this, staticDataSize()); 29 | 30 | nodes = new Node[nNodes]; 31 | stream.read((char *)nodes, sizeof(Node) * nNodes); 32 | 33 | words = new Word[nWords]; 34 | stream.read((char *)words, sizeof(Word) * nWords); 35 | } 36 | -------------------------------------------------------------------------------- /loop_fusion/ThirdParty/VocabularyBinary.hpp: -------------------------------------------------------------------------------- 1 | #ifndef VocabularyBinary_hpp 2 | #define VocabularyBinary_hpp 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | namespace VINSLoop { 9 | 10 | struct Node { 11 | int32_t nodeId; 12 | int32_t parentId; 13 | double weight; 14 | uint64_t descriptor[4]; 15 | }; 16 | 17 | struct Word { 18 | int32_t nodeId; 19 | int32_t wordId; 20 | }; 21 | 22 | struct Vocabulary { 23 | int32_t k; 24 | int32_t L; 25 | int32_t scoringType; 26 | int32_t weightingType; 27 | 28 | int32_t nNodes; 29 | int32_t nWords; 30 | 31 | Node* nodes; 32 | Word* words; 33 | 34 | Vocabulary(); 35 | ~Vocabulary(); 36 | 37 | void serialize(std::ofstream& stream); 38 | void deserialize(std::ifstream& stream); 39 | 40 | inline static size_t staticDataSize() { 41 | return sizeof(Vocabulary) - sizeof(Node*) - sizeof(Word*); 42 | } 43 | }; 44 | 45 | } 46 | 47 | #endif /* VocabularyBinary_hpp */ 48 | -------------------------------------------------------------------------------- /loop_fusion/factor/ceresBA.hpp: -------------------------------------------------------------------------------- 1 | #include "ceres/ceres.h" 2 | #include "ceres/rotation.h" 3 | 4 | 5 | 6 | 7 | struct ReprojectionError { 8 | ReprojectionError(Eigen::Vector3d _pts3d, 9 | Eigen::Vector2d _pts2d, 10 | Eigen::Vector3d _trgP,Eigen::Quaterniond _trgQ, 11 | Eigen::Vector3d _srcrelP,Eigen::Quaterniond _srcrelQ, 12 | Eigen::Vector3d _i2cP,Eigen::Quaterniond _i2cQ) 13 | : pts3d(_pts3d), pts2d(_pts2d), 14 | trgP(_trgP),srcrelP(_srcrelP),i2cP(_i2cP), 15 | trgQ(_trgQ),srcrelQ(_srcrelQ),i2cQ(_i2cQ) 16 | { 17 | sqrt_info = 460 / 1.5 * Eigen::Matrix2d::Identity(); 18 | } 19 | 20 | template 21 | bool operator()(const T* const p_ts, 22 | const T* const q_ts, 23 | const T* const sel_ptr, 24 | T* residuals) const { 25 | 26 | Eigen::Map > T_ts(p_ts); 27 | Eigen::Map > Q_ts(q_ts); 28 | 29 | //pts3d = pts_camera_i 30 | Eigen::Vector3d pts_imu_trg = i2cQ * pts3d + i2cP; 31 | Eigen::Vector3d pts_imu_world = trgQ * pts_imu_trg + trgP; 32 | Eigen::Matrix pts_src_ref = 33 | Q_ts.template cast().conjugate() * (pts_imu_world.template cast()-T_ts); 34 | Eigen::Matrix pts_imu_src = 35 | srcrelQ.template cast().conjugate() * (pts_src_ref-srcrelP.template cast()); 36 | Eigen::Matrix pts_cam_src = 37 | i2cQ.template cast().conjugate() * (pts_imu_src-i2cP.template cast()); 38 | 39 | Eigen::Matrix ptCamProj; 40 | ptCamProj<< pts_cam_src(0) / pts_cam_src(2) - (T)pts2d(0), 41 | pts_cam_src(1) / pts_cam_src(2) - (T)pts2d(1); 42 | 43 | 44 | Eigen::Map> residual(residuals); 45 | residual = sel_ptr[0] * ptCamProj; 46 | return true; 47 | } 48 | 49 | // Factory to hide the construction of the CostFunction object from 50 | // the client code. 51 | static ceres::CostFunction* Create(Eigen::Vector3d _pts3d, 52 | Eigen::Vector2d _pts2d, 53 | Eigen::Vector3d _trgP,Eigen::Quaterniond _trgQ, 54 | Eigen::Vector3d _srcrelP,Eigen::Quaterniond _srcrelQ, 55 | Eigen::Vector3d _i2cP,Eigen::Quaterniond _i2cQ) { 56 | return new ceres::AutoDiffCostFunction( 57 | new ReprojectionError(_pts3d, _pts2d, _trgP,_trgQ, _srcrelP, 58 | _srcrelQ, _i2cP, _i2cQ)); 59 | } 60 | 61 | Eigen::Vector3d pts3d; 62 | Eigen::Vector2d pts2d; 63 | Eigen::Vector3d trgP,srcrelP,i2cP; 64 | Eigen::Quaterniond trgQ, srcrelQ,i2cQ; 65 | Eigen::Matrix2d sqrt_info; 66 | }; 67 | 68 | class ResistFactor : public ceres::SizedCostFunction<1, 1> 69 | { 70 | public: 71 | ResistFactor() = delete; 72 | ResistFactor(double _gamma):gamma(_gamma) 73 | { 74 | } 75 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const 76 | { 77 | double sel = parameters[0][0]; 78 | Eigen::Map> residual(residuals); 79 | residual(0,0) = gamma * (1-sel); 80 | 81 | if (jacobians) 82 | { 83 | if (jacobians[0]) 84 | { 85 | Eigen::Map> jacobian_sel(jacobians[0]); 86 | jacobian_sel(0,0)=-gamma; 87 | } 88 | } 89 | 90 | return true; 91 | } 92 | 93 | double gamma; 94 | 95 | }; 96 | -------------------------------------------------------------------------------- /loop_fusion/keyframe.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include "camodocal/camera_models/CameraFactory.h" 19 | #include "camodocal/camera_models/CataCamera.h" 20 | #include "camodocal/camera_models/PinholeCamera.h" 21 | #include "utility/tic_toc.h" 22 | #include "utility/utility.h" 23 | #include "parameters.h" 24 | #include "ThirdParty/DBoW/DBoW2.h" 25 | #include "ThirdParty/DVision/DVision.h" 26 | 27 | 28 | 29 | using namespace Eigen; 30 | using namespace std; 31 | using namespace DVision; 32 | 33 | 34 | class BriefExtractor 35 | { 36 | public: 37 | virtual void operator()(const cv::Mat &im, vector &keys, vector &descriptors) const; 38 | BriefExtractor(const std::string &pattern_file); 39 | 40 | DVision::BRIEF m_brief; 41 | }; 42 | 43 | class KeyFrame 44 | { 45 | public: 46 | KeyFrame(double _time_stamp, int _index, Vector3d &_vio_T_w_i, Matrix3d &_vio_R_w_i, cv::Mat &_image, 47 | vector &_point_3d,vector &_point_2d_uv, vector &_point_2d_normal, 48 | vector &_point_id,vector &_point_weight, int _sequence); 49 | void getIndexById(const vector absId,vector & index); 50 | void computeCurrentBRIEFPoint(); 51 | void removeFeature(const vector featureId); 52 | void getVioPose(Eigen::Vector3d &_T_w_i, Eigen::Matrix3d &_R_w_i); 53 | void getPose(Eigen::Vector3d &_T_w_i, Eigen::Matrix3d &_R_w_i); 54 | void updatePose(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i); 55 | void updateVioPose(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i); 56 | void updateLoop(Eigen::Matrix &_loop_info); 57 | 58 | Eigen::Vector3d getLoopRelativeT(); 59 | double getLoopRelativeYaw(); 60 | Eigen::Quaterniond getLoopRelativeQ(); 61 | void searchByBRIEFDes(std::vector &matched_2d_old, 62 | std::vector &matched_2d_old_norm, 63 | std::vector &matched_old_id, 64 | std::vector &status, 65 | const std::vector &descriptors_old, 66 | const std::vector &keypoints_old, 67 | const std::vector &keypoints_old_norm); 68 | bool findConnection(KeyFrame* old_kf,Vector3d& rel_t,Quaterniond& rel_q, double& rel_yaw, 69 | vector& curId, vector& tarId); 70 | int HammingDis(const BRIEF::bitset &a, const BRIEF::bitset &b); 71 | bool searchInAera(const BRIEF::bitset window_descriptor, 72 | const std::vector &descriptors_old, 73 | const std::vector &keypoints_old, 74 | const std::vector &keypoints_old_norm, 75 | int & best_id, 76 | cv::Point2f &best_match, 77 | cv::Point2f &best_match_norm); 78 | void PnPRANSAC(const vector &matched_2d_old_norm, 79 | const std::vector &matched_3d, 80 | std::vector &status, 81 | Eigen::Vector3d &PnP_T_old, Eigen::Matrix3d &PnP_R_old); 82 | 83 | 84 | double time_stamp; 85 | int index; 86 | int local_index; 87 | Eigen::Vector3d vio_T_w_i; 88 | Eigen::Matrix3d vio_R_w_i; 89 | Eigen::Vector3d T_w_i; 90 | Eigen::Matrix3d R_w_i; 91 | Eigen::Vector3d origin_vio_T; 92 | Eigen::Matrix3d origin_vio_R; 93 | cv::Mat image; 94 | cv::Mat thumbnail; 95 | vector point_3d_ref; 96 | vector point_3d; 97 | vector point_2d_uv; 98 | vector point_2d_norm; 99 | vector point_id; 100 | vector point_weight; 101 | vector dynamic_id; 102 | 103 | vector keypoints; 104 | vector keypoints_norm; 105 | vector brief_descriptors; 106 | bool has_fast_point; 107 | int sequence; 108 | 109 | bool has_loop; 110 | int loop_index; 111 | Eigen::Matrix loop_info; 112 | }; 113 | 114 | -------------------------------------------------------------------------------- /loop_fusion/parameters.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include "camodocal/camera_models/CameraFactory.h" 15 | #include "camodocal/camera_models/CataCamera.h" 16 | #include "camodocal/camera_models/PinholeCamera.h" 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | 24 | #define TYPE_UNKNOWN -1 25 | #define TYPE_STATIC 0 26 | #define TYPE_DYNAMIC 1 27 | 28 | #define MIN_KEYFRAME 8 29 | 30 | extern camodocal::CameraPtr m_camera; 31 | extern Eigen::Vector3d tic; 32 | extern Eigen::Matrix3d qic; 33 | extern ros::Publisher pub_match_img; 34 | extern int VISUALIZATION_SHIFT_X; 35 | extern int VISUALIZATION_SHIFT_Y; 36 | extern std::string BRIEF_PATTERN_FILE; 37 | extern std::string POSE_GRAPH_SAVE_PATH; 38 | extern int ROW; 39 | extern int COL; 40 | extern std::string VINS_RESULT_PATH; 41 | extern int DEBUG_IMAGE; 42 | 43 | extern float MIN_SCORE; 44 | extern float MIN_OVERLAP; 45 | extern float MAX_KEYFRAME; 46 | extern float MIN_LOOP_NUM; 47 | 48 | extern float MAX_HYPODIFF_DIST; 49 | extern float MAX_HYPODIFF_YAW; 50 | extern float HYPOPRIOR_GAMMA; 51 | extern float HYPOPRIOR_ALT_CONV; 52 | 53 | 54 | -------------------------------------------------------------------------------- /loop_fusion/utility/CameraPoseVisualization.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include "../parameters.h" 20 | 21 | class CameraPoseVisualization { 22 | public: 23 | std::string m_marker_ns; 24 | 25 | CameraPoseVisualization(float r, float g, float b, float a); 26 | 27 | void setImageBoundaryColor(float r, float g, float b, float a=1.0); 28 | void setOpticalCenterConnectorColor(float r, float g, float b, float a=1.0); 29 | void setScale(double s); 30 | void setLineWidth(double width); 31 | 32 | void add_pose(const Eigen::Vector3d& p, const Eigen::Quaterniond& q); 33 | void reset(); 34 | 35 | void publish_by(ros::Publisher& pub, const std_msgs::Header& header); 36 | void add_edge(const Eigen::Vector3d& p0, const Eigen::Vector3d& p1); 37 | void add_loopedge(const Eigen::Vector3d& p0, const Eigen::Vector3d& p1, const double weight); 38 | //void add_image(const Eigen::Vector3d& T, const Eigen::Matrix3d& R, const cv::Mat &src); 39 | void publish_image_by( ros::Publisher &pub, const std_msgs::Header &header); 40 | private: 41 | std::vector m_markers; 42 | std_msgs::ColorRGBA m_image_boundary_color; 43 | std_msgs::ColorRGBA m_optical_center_connector_color; 44 | double m_scale; 45 | double m_line_width; 46 | visualization_msgs::Marker image; 47 | int LOOP_EDGE_NUM; 48 | int tmp_loop_edge_num; 49 | 50 | static const Eigen::Vector3d imlt; 51 | static const Eigen::Vector3d imlb; 52 | static const Eigen::Vector3d imrt; 53 | static const Eigen::Vector3d imrb; 54 | static const Eigen::Vector3d oc ; 55 | static const Eigen::Vector3d lt0 ; 56 | static const Eigen::Vector3d lt1 ; 57 | static const Eigen::Vector3d lt2 ; 58 | }; 59 | -------------------------------------------------------------------------------- /loop_fusion/utility/tic_toc.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | 16 | class TicToc 17 | { 18 | public: 19 | TicToc() 20 | { 21 | tic(); 22 | } 23 | 24 | void tic() 25 | { 26 | start = std::chrono::system_clock::now(); 27 | } 28 | 29 | double toc() 30 | { 31 | end = std::chrono::system_clock::now(); 32 | std::chrono::duration elapsed_seconds = end - start; 33 | return elapsed_seconds.count() * 1000; 34 | } 35 | 36 | private: 37 | std::chrono::time_point start, end; 38 | }; 39 | -------------------------------------------------------------------------------- /loop_fusion/utility/utility.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #include "utility.h" 11 | 12 | Eigen::Matrix3d Utility::g2R(const Eigen::Vector3d &g) 13 | { 14 | Eigen::Matrix3d R0; 15 | Eigen::Vector3d ng1 = g.normalized(); 16 | Eigen::Vector3d ng2{0, 0, 1.0}; 17 | R0 = Eigen::Quaterniond::FromTwoVectors(ng1, ng2).toRotationMatrix(); 18 | double yaw = Utility::R2ypr(R0).x(); 19 | R0 = Utility::ypr2R(Eigen::Vector3d{-yaw, 0, 0}) * R0; 20 | // R0 = Utility::ypr2R(Eigen::Vector3d{-90, 0, 0}) * R0; 21 | return R0; 22 | } 23 | 24 | -------------------------------------------------------------------------------- /loop_fusion/utility/utility.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | class Utility 19 | { 20 | public: 21 | template 22 | static Eigen::Quaternion deltaQ(const Eigen::MatrixBase &theta) 23 | { 24 | typedef typename Derived::Scalar Scalar_t; 25 | 26 | Eigen::Quaternion dq; 27 | Eigen::Matrix half_theta = theta; 28 | half_theta /= static_cast(2.0); 29 | dq.w() = static_cast(1.0); 30 | dq.x() = half_theta.x(); 31 | dq.y() = half_theta.y(); 32 | dq.z() = half_theta.z(); 33 | return dq; 34 | } 35 | 36 | template 37 | static Eigen::Matrix skewSymmetric(const Eigen::MatrixBase &q) 38 | { 39 | Eigen::Matrix ans; 40 | ans << typename Derived::Scalar(0), -q(2), q(1), 41 | q(2), typename Derived::Scalar(0), -q(0), 42 | -q(1), q(0), typename Derived::Scalar(0); 43 | return ans; 44 | } 45 | 46 | template 47 | static Eigen::Quaternion positify(const Eigen::QuaternionBase &q) 48 | { 49 | //printf("a: %f %f %f %f", q.w(), q.x(), q.y(), q.z()); 50 | //Eigen::Quaternion p(-q.w(), -q.x(), -q.y(), -q.z()); 51 | //printf("b: %f %f %f %f", p.w(), p.x(), p.y(), p.z()); 52 | //return q.template w() >= (typename Derived::Scalar)(0.0) ? q : Eigen::Quaternion(-q.w(), -q.x(), -q.y(), -q.z()); 53 | return q; 54 | } 55 | 56 | template 57 | static Eigen::Matrix Qleft(const Eigen::QuaternionBase &q) 58 | { 59 | Eigen::Quaternion qq = positify(q); 60 | Eigen::Matrix ans; 61 | ans(0, 0) = qq.w(), ans.template block<1, 3>(0, 1) = -qq.vec().transpose(); 62 | ans.template block<3, 1>(1, 0) = qq.vec(), ans.template block<3, 3>(1, 1) = qq.w() * Eigen::Matrix::Identity() + skewSymmetric(qq.vec()); 63 | return ans; 64 | } 65 | 66 | template 67 | static Eigen::Matrix Qright(const Eigen::QuaternionBase &p) 68 | { 69 | Eigen::Quaternion pp = positify(p); 70 | Eigen::Matrix ans; 71 | ans(0, 0) = pp.w(), ans.template block<1, 3>(0, 1) = -pp.vec().transpose(); 72 | ans.template block<3, 1>(1, 0) = pp.vec(), ans.template block<3, 3>(1, 1) = pp.w() * Eigen::Matrix::Identity() - skewSymmetric(pp.vec()); 73 | return ans; 74 | } 75 | 76 | static Eigen::Vector3d R2ypr(const Eigen::Matrix3d &R) 77 | { 78 | Eigen::Vector3d n = R.col(0); 79 | Eigen::Vector3d o = R.col(1); 80 | Eigen::Vector3d a = R.col(2); 81 | 82 | Eigen::Vector3d ypr(3); 83 | double y = atan2(n(1), n(0)); 84 | double p = atan2(-n(2), n(0) * cos(y) + n(1) * sin(y)); 85 | double r = atan2(a(0) * sin(y) - a(1) * cos(y), -o(0) * sin(y) + o(1) * cos(y)); 86 | ypr(0) = y; 87 | ypr(1) = p; 88 | ypr(2) = r; 89 | 90 | return ypr / M_PI * 180.0; 91 | } 92 | 93 | template 94 | static Eigen::Matrix ypr2R(const Eigen::MatrixBase &ypr) 95 | { 96 | typedef typename Derived::Scalar Scalar_t; 97 | 98 | Scalar_t y = ypr(0) / 180.0 * M_PI; 99 | Scalar_t p = ypr(1) / 180.0 * M_PI; 100 | Scalar_t r = ypr(2) / 180.0 * M_PI; 101 | 102 | Eigen::Matrix Rz; 103 | Rz << cos(y), -sin(y), 0, 104 | sin(y), cos(y), 0, 105 | 0, 0, 1; 106 | 107 | Eigen::Matrix Ry; 108 | Ry << cos(p), 0., sin(p), 109 | 0., 1., 0., 110 | -sin(p), 0., cos(p); 111 | 112 | Eigen::Matrix Rx; 113 | Rx << 1., 0., 0., 114 | 0., cos(r), -sin(r), 115 | 0., sin(r), cos(r); 116 | 117 | return Rz * Ry * Rx; 118 | } 119 | 120 | static Eigen::Matrix3d g2R(const Eigen::Vector3d &g); 121 | 122 | template 123 | struct uint_ 124 | { 125 | }; 126 | 127 | template 128 | void unroller(const Lambda &f, const IterT &iter, uint_) 129 | { 130 | unroller(f, iter, uint_()); 131 | f(iter + N); 132 | } 133 | 134 | template 135 | void unroller(const Lambda &f, const IterT &iter, uint_<0>) 136 | { 137 | f(iter); 138 | } 139 | 140 | template 141 | static T normalizeAngle(const T& angle_degrees) { 142 | T two_pi(2.0 * 180); 143 | if (angle_degrees > 0) 144 | return angle_degrees - 145 | two_pi * std::floor((angle_degrees + T(180)) / two_pi); 146 | else 147 | return angle_degrees + 148 | two_pi * std::floor((-angle_degrees + T(180)) / two_pi); 149 | }; 150 | }; 151 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | dynaVINS 4 | 0.0.0 5 | The vins package 6 | 7 | 8 | 9 | 10 | qintong 11 | 12 | 13 | 14 | 15 | 16 | GPLv3 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 | catkin 43 | roscpp 44 | image_transport 45 | camera_models 46 | 47 | roscpp 48 | image_transport 49 | camera_models 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | -------------------------------------------------------------------------------- /readme_resource/city_main.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/url-kaist/dynaVINS/0b4f492aeeb1a3752507a9b9a50124e10bfcf091/readme_resource/city_main.gif -------------------------------------------------------------------------------- /readme_resource/parking_main.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/url-kaist/dynaVINS/0b4f492aeeb1a3752507a9b9a50124e10bfcf091/readme_resource/parking_main.gif -------------------------------------------------------------------------------- /support_files/contents.txt: -------------------------------------------------------------------------------- 1 | Due to the file size, you can download the contents of the support_files folder in VINS-Fusion repository. 2 | (https://github.com/HKUST-Aerial-Robotics/VINS-Fusion/tree/master/support_files) 3 | Download brief_k10L6.bin and brief_pattern.yml files into support_files folder. 4 | -------------------------------------------------------------------------------- /vins_estimator/estimator/estimator.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | 23 | #include "parameters.h" 24 | #include "feature_manager.h" 25 | #include "../utility/utility.h" 26 | #include "../utility/tic_toc.h" 27 | #include "../initial/solve_5pts.h" 28 | #include "../initial/initial_sfm.h" 29 | #include "../initial/initial_alignment.h" 30 | #include "../initial/initial_ex_rotation.h" 31 | #include "../factor/imu_factor.h" 32 | #include "../factor/pose_local_parameterization.h" 33 | #include "../factor/marginalization_factor.h" 34 | #include "../factor/projectionTwoFrameOneCamFactor.h" 35 | #include "../factor/projectionTwoFrameTwoCamFactor.h" 36 | #include "../factor/projectionOneFrameTwoCamFactor.h" 37 | #include "../factor/prior_factor.h" 38 | #include "../featureTracker/feature_tracker.h" 39 | 40 | 41 | class Estimator 42 | { 43 | public: 44 | Estimator(); 45 | ~Estimator(); 46 | void setParameter(); 47 | 48 | // interface 49 | void initFirstPose(Eigen::Vector3d p, Eigen::Matrix3d r); 50 | void inputIMU(double t, const Vector3d &linearAcceleration, const Vector3d &angularVelocity); 51 | void inputFeature(double t, const map>>> &featureFrame); 52 | void inputImage(double t, const cv::Mat &_img, const cv::Mat &_img1 = cv::Mat()); 53 | void processIMU(double t, double dt, const Vector3d &linear_acceleration, const Vector3d &angular_velocity); 54 | void processImage(const map>>> &image, const double header); 55 | void processMeasurements(); 56 | void changeSensorType(int use_imu, int use_stereo); 57 | 58 | // internal 59 | void clearState(); 60 | bool initialStructure(); 61 | bool visualInitialAlign(); 62 | bool relativePose(Matrix3d &relative_R, Vector3d &relative_T, int &l); 63 | void slideWindow(); 64 | void slideWindowNew(); 65 | void slideWindowOld(); 66 | void optimization(); 67 | void optimizeVIO(bool flagOptimizeWeight,double & costDiff); 68 | void vector2double(); 69 | void double2vector(); 70 | bool failureDetection(); 71 | bool getIMUInterval(double t0, double t1, vector> &accVector, 72 | vector> &gyrVector); 73 | void getPoseInWorldFrame(Eigen::Matrix4d &T); 74 | void getPoseInWorldFrame(int index, Eigen::Matrix4d &T); 75 | void predictPtsInNextFrame(); 76 | double reprojectionError(Matrix3d &Ri, Vector3d &Pi, Matrix3d &rici, Vector3d &tici, 77 | Matrix3d &Rj, Vector3d &Pj, Matrix3d &ricj, Vector3d &ticj, 78 | double depth, Vector3d &uvi, Vector3d &uvj); 79 | void updateLatestStates(); 80 | void fastPredictIMU(double t, Eigen::Vector3d linear_acceleration, Eigen::Vector3d angular_velocity); 81 | bool IMUAvailable(double t); 82 | void initFirstIMUPose(vector> &accVector); 83 | 84 | enum SolverFlag 85 | { 86 | INITIAL, 87 | NON_LINEAR 88 | }; 89 | 90 | enum MarginalizationFlag 91 | { 92 | MARGIN_OLD = 0, 93 | MARGIN_SECOND_NEW = 1 94 | }; 95 | 96 | std::mutex mProcess; 97 | std::mutex mBuf; 98 | std::mutex mPropagate; 99 | queue> accBuf; 100 | queue> gyrBuf; 101 | queue> imageBuf_0; 102 | queue> imageBuf_1; 103 | queue > > > > > featureBuf; 104 | double prevTime, curTime; 105 | bool openExEstimation; 106 | 107 | std::thread trackThread; 108 | std::thread processThread; 109 | 110 | FeatureTracker featureTracker; 111 | 112 | SolverFlag solver_flag; 113 | MarginalizationFlag marginalization_flag; 114 | Vector3d g; 115 | 116 | Matrix3d ric[2]; 117 | Vector3d tic[2]; 118 | 119 | Vector3d Ps[(WINDOW_SIZE + 1)]; 120 | Vector3d Vs[(WINDOW_SIZE + 1)]; 121 | Matrix3d Rs[(WINDOW_SIZE + 1)]; 122 | Vector3d Bas[(WINDOW_SIZE + 1)]; 123 | Vector3d Bgs[(WINDOW_SIZE + 1)]; 124 | double td; 125 | 126 | Matrix3d back_R0, last_R, last_R0; 127 | Vector3d back_P0, last_P, last_P0; 128 | double Headers[(WINDOW_SIZE + 1)]; 129 | 130 | IntegrationBase *pre_integrations[(WINDOW_SIZE + 1)]; 131 | Vector3d acc_0, gyr_0; 132 | 133 | vector dt_buf[(WINDOW_SIZE + 1)]; 134 | vector linear_acceleration_buf[(WINDOW_SIZE + 1)]; 135 | vector angular_velocity_buf[(WINDOW_SIZE + 1)]; 136 | 137 | int frame_count; 138 | int sum_of_outlier, sum_of_back, sum_of_front, sum_of_invalid; 139 | int inputImageCnt; 140 | 141 | FeatureManager f_manager; 142 | MotionEstimator m_estimator; 143 | InitialEXRotation initial_ex_rotation; 144 | 145 | bool first_imu; 146 | bool is_valid, is_key; 147 | bool failure_occur; 148 | 149 | vector point_cloud; 150 | vector margin_cloud; 151 | vector key_poses; 152 | double initial_timestamp; 153 | 154 | 155 | double para_Pose[WINDOW_SIZE + 1][SIZE_POSE]; 156 | double para_SpeedBias[WINDOW_SIZE + 1][SIZE_SPEEDBIAS]; 157 | double para_Feature[NUM_OF_F][SIZE_FEATURE]; 158 | double para_FeatureWeight[NUM_OF_F][SIZE_FEATURE]; 159 | int para_FeatureWeightNum[NUM_OF_F][SIZE_FEATURE]; 160 | double para_Ex_Pose[2][SIZE_POSE]; 161 | double para_Retrive_Pose[SIZE_POSE]; 162 | double para_Td[1][1]; 163 | double para_Tr[1][1]; 164 | 165 | int loop_window_index; 166 | 167 | MarginalizationInfo *last_marginalization_info; 168 | vector last_marginalization_parameter_blocks; 169 | 170 | map all_image_frame; 171 | // map> all_image_cv; 172 | IntegrationBase *tmp_pre_integration; 173 | 174 | Eigen::Vector3d initP; 175 | Eigen::Matrix3d initR; 176 | 177 | double latest_time; 178 | Eigen::Vector3d latest_P, latest_V, latest_Ba, latest_Bg, latest_acc_0, latest_gyr_0; 179 | Eigen::Quaterniond latest_Q; 180 | 181 | bool initFirstPoseFlag; 182 | bool initThreadFlag; 183 | }; 184 | -------------------------------------------------------------------------------- /vins_estimator/estimator/feature_manager.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #ifndef FEATURE_MANAGER_H 11 | #define FEATURE_MANAGER_H 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | using namespace std; 18 | 19 | #include 20 | using namespace Eigen; 21 | 22 | #include 23 | #include 24 | 25 | #include "parameters.h" 26 | #include "../utility/tic_toc.h" 27 | 28 | class FeaturePerFrame 29 | { 30 | public: 31 | FeaturePerFrame(const Eigen::Matrix &_point, double td) 32 | { 33 | point.x() = _point(0); 34 | point.y() = _point(1); 35 | point.z() = _point(2); 36 | uv.x() = _point(3); 37 | uv.y() = _point(4); 38 | velocity.x() = _point(5); 39 | velocity.y() = _point(6); 40 | cur_td = td; 41 | is_stereo = false; 42 | } 43 | void rightObservation(const Eigen::Matrix &_point) 44 | { 45 | pointRight.x() = _point(0); 46 | pointRight.y() = _point(1); 47 | pointRight.z() = _point(2); 48 | uvRight.x() = _point(3); 49 | uvRight.y() = _point(4); 50 | velocityRight.x() = _point(5); 51 | velocityRight.y() = _point(6); 52 | is_stereo = true; 53 | } 54 | double cur_td; 55 | Vector3d point, pointRight; 56 | Vector2d uv, uvRight; 57 | Vector2d velocity, velocityRight; 58 | bool is_stereo; 59 | }; 60 | 61 | class FeaturePerId 62 | { 63 | public: 64 | const int feature_id; 65 | int start_frame; 66 | vector feature_per_frame; 67 | int used_num; 68 | double estimated_depth; 69 | int solve_flag; // 0 haven't solve yet; 1 solve succ; 2 solve fail; 70 | int weightNum; 71 | double weight; 72 | 73 | FeaturePerId(int _feature_id, int _start_frame) 74 | : feature_id(_feature_id), start_frame(_start_frame), 75 | used_num(0), estimated_depth(-1.0), solve_flag(0) 76 | { 77 | weight = 1.0; 78 | weightNum = 1; 79 | } 80 | 81 | int endFrame(); 82 | }; 83 | 84 | class FeatureManager 85 | { 86 | public: 87 | FeatureManager(Matrix3d _Rs[]); 88 | 89 | void setRic(Matrix3d _ric[]); 90 | void clearState(); 91 | int getFeatureCount(); 92 | bool addFeatureCheckParallax(int frame_count, const map>>> &image, double td); 93 | vector> getCorresponding(int frame_count_l, int frame_count_r); 94 | //void updateDepth(const VectorXd &x); 95 | void setDepth(const VectorXd &x); 96 | void setWeight(const VectorXd &x); 97 | void removeFailures(); 98 | void clearDepth(); 99 | VectorXd getDepthVector(); 100 | VectorXd getWeightVector(); 101 | void triangulate(int frameCnt, Vector3d Ps[], Matrix3d Rs[], Vector3d tic[], Matrix3d ric[]); 102 | void triangulatePoint(Eigen::Matrix &Pose0, Eigen::Matrix &Pose1, 103 | Eigen::Vector2d &point0, Eigen::Vector2d &point1, Eigen::Vector3d &point_3d); 104 | void initFramePoseByPnP(int frameCnt, Vector3d Ps[], Matrix3d Rs[], Vector3d tic[], Matrix3d ric[]); 105 | bool solvePoseByPnP(Eigen::Matrix3d &R_initial, Eigen::Vector3d &P_initial, 106 | vector &pts2D, vector &pts3D); 107 | void removeBackShiftDepth(Eigen::Matrix3d marg_R, Eigen::Vector3d marg_P, Eigen::Matrix3d new_R, Eigen::Vector3d new_P); 108 | void removeBack(); 109 | void removeFront(int frame_count); 110 | void removeOutlier(set &outlierIndex); 111 | list feature; 112 | int last_track_num; 113 | double last_average_parallax; 114 | int new_feature_num; 115 | int long_track_num; 116 | 117 | private: 118 | double compensatedParallax2(const FeaturePerId &it_per_id, int frame_count); 119 | const Matrix3d *Rs; 120 | Matrix3d ric[2]; 121 | }; 122 | 123 | #endif 124 | -------------------------------------------------------------------------------- /vins_estimator/estimator/parameters.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #include "parameters.h" 11 | 12 | 13 | bool DYN_ON = true; 14 | double DYN_ALT_CONV = 0.9; 15 | double DYN_FEAT_MARGIN_THRESH = 0.1; 16 | bool DYN_PRIOR_ON = true; 17 | double FEATURE_RESIST_GAMMA; 18 | double FEATURE_PRIOR_GAMMA; 19 | 20 | int SHOW_IMAGE_WEIGHT; 21 | double MAX_DEPTH; 22 | 23 | int TEST_MONO; 24 | double INIT_DEPTH; 25 | double MIN_PARALLAX; 26 | double ACC_N, ACC_W; 27 | double GYR_N, GYR_W; 28 | 29 | std::vector RIC; 30 | std::vector TIC; 31 | 32 | Eigen::Vector3d G{0.0, 0.0, 9.8}; 33 | 34 | double BIAS_ACC_THRESHOLD; 35 | double BIAS_GYR_THRESHOLD; 36 | double SOLVER_TIME; 37 | int NUM_ITERATIONS; 38 | int ESTIMATE_EXTRINSIC; 39 | int ESTIMATE_TD; 40 | int ROLLING_SHUTTER; 41 | std::string EX_CALIB_RESULT_PATH; 42 | std::string VINS_RESULT_PATH; 43 | std::string OUTPUT_FOLDER; 44 | std::string IMU_TOPIC; 45 | int ROW, COL; 46 | double TD; 47 | int NUM_OF_CAM; 48 | int STEREO; 49 | int USE_IMU; 50 | int MULTIPLE_THREAD; 51 | map pts_gt; 52 | std::string IMAGE0_TOPIC, IMAGE1_TOPIC; 53 | std::string FISHEYE_MASK; 54 | std::vector CAM_NAMES; 55 | int MAX_CNT; 56 | int MIN_DIST; 57 | double F_THRESHOLD; 58 | int SHOW_TRACK; 59 | int FLOW_BACK; 60 | 61 | 62 | template 63 | T readParam(ros::NodeHandle &n, std::string name) 64 | { 65 | T ans; 66 | if (n.getParam(name, ans)) 67 | { 68 | ROS_INFO_STREAM("Loaded " << name << ": " << ans); 69 | } 70 | else 71 | { 72 | ROS_ERROR_STREAM("Failed to load " << name); 73 | n.shutdown(); 74 | } 75 | return ans; 76 | } 77 | 78 | void readParameters(std::string config_file) 79 | { 80 | FILE *fh = fopen(config_file.c_str(),"r"); 81 | if(fh == NULL){ 82 | ROS_WARN("config_file dosen't exist; wrong config_file path"); 83 | ROS_BREAK(); 84 | return; 85 | } 86 | fclose(fh); 87 | 88 | cv::FileStorage fsSettings(config_file, cv::FileStorage::READ); 89 | if(!fsSettings.isOpened()) 90 | { 91 | std::cerr << "ERROR: Wrong path to settings" << std::endl; 92 | } 93 | 94 | fsSettings["image0_topic"] >> IMAGE0_TOPIC; 95 | fsSettings["image1_topic"] >> IMAGE1_TOPIC; 96 | TEST_MONO = fsSettings["test_mono"]; 97 | MAX_CNT = fsSettings["max_cnt"]; 98 | MIN_DIST = fsSettings["min_dist"]; 99 | F_THRESHOLD = fsSettings["F_ ̄threshold"]; 100 | SHOW_TRACK = fsSettings["show_track"]; 101 | FLOW_BACK = fsSettings["flow_back"]; 102 | SHOW_IMAGE_WEIGHT = fsSettings["show_image_feat_weight"]; 103 | MAX_DEPTH = fsSettings["max_depth"]; 104 | MULTIPLE_THREAD = fsSettings["multiple_thread"]; 105 | 106 | USE_IMU = fsSettings["imu"]; 107 | printf("USE_IMU: %d←\n", USE_IMU); 108 | if(USE_IMU) 109 | { 110 | fsSettings["imu_topic"] >> IMU_TOPIC; 111 | printf("IMU_TOPIC: %s\n", IMU_TOPIC.c_str()); 112 | ACC_N = fsSettings["acc_n"]; 113 | ACC_W = fsSettings["acc_w"]; 114 | GYR_N = fsSettings["gyr_n"]; 115 | GYR_W = fsSettings["gyr_w"]; 116 | G.z() = fsSettings["g_norm"]; 117 | } 118 | DYN_ON = true; 119 | string dyna_on = fsSettings["dyna_on"]; 120 | if(dyna_on=="False" || dyna_on=="false" || dyna_on=="FALSE") DYN_ON =false; 121 | 122 | DYN_ALT_CONV = fsSettings["alternating_converge"]; 123 | DYN_FEAT_MARGIN_THRESH = fsSettings["margin_feature_thresh"]; 124 | DYN_PRIOR_ON = true; 125 | string prior_on = fsSettings["momentum_on"]; 126 | if(prior_on=="False" || prior_on=="false" || prior_on=="FALSE") DYN_PRIOR_ON =false; 127 | 128 | FEATURE_RESIST_GAMMA = fsSettings["regularization_lambda"]; 129 | FEATURE_PRIOR_GAMMA = fsSettings["momentum_lambda"]; 130 | SOLVER_TIME = fsSettings["max_solver_time"]; 131 | NUM_ITERATIONS = fsSettings["max_num_iterations"]; 132 | MIN_PARALLAX = fsSettings["keyframe_parallax"]; 133 | MIN_PARALLAX = MIN_PARALLAX / FOCAL_LENGTH; 134 | 135 | fsSettings["output_path"] >> OUTPUT_FOLDER; 136 | VINS_RESULT_PATH = OUTPUT_FOLDER + "/vio.csv"; 137 | std::cout << "result path " << VINS_RESULT_PATH << std::endl; 138 | std::ofstream fout(VINS_RESULT_PATH, std::ios::out); 139 | fout.close(); 140 | 141 | ESTIMATE_EXTRINSIC = fsSettings["estimate_extrinsic"]; 142 | if (ESTIMATE_EXTRINSIC == 2) 143 | { 144 | ROS_WARN("have no prior about extrinsic param, calibrate extrinsic param"); 145 | RIC.push_back(Eigen::Matrix3d::Identity()); 146 | TIC.push_back(Eigen::Vector3d::Zero()); 147 | EX_CALIB_RESULT_PATH = OUTPUT_FOLDER + "/extrinsic_parameter.csv"; 148 | } 149 | else 150 | { 151 | if ( ESTIMATE_EXTRINSIC == 1) 152 | { 153 | ROS_WARN(" Optimize extrinsic param around initial guess!"); 154 | EX_CALIB_RESULT_PATH = OUTPUT_FOLDER + "/extrinsic_parameter.csv"; 155 | } 156 | if (ESTIMATE_EXTRINSIC == 0) 157 | ROS_WARN(" fix extrinsic param "); 158 | 159 | cv::Mat cv_T; 160 | fsSettings["body_T_cam0"] >> cv_T; 161 | Eigen::Matrix4d T; 162 | cv::cv2eigen(cv_T, T); 163 | RIC.push_back(T.block<3, 3>(0, 0)); 164 | TIC.push_back(T.block<3, 1>(0, 3)); 165 | } 166 | 167 | NUM_OF_CAM = fsSettings["num_of_cam"]; 168 | printf("camera number %d\n", NUM_OF_CAM); 169 | 170 | if(NUM_OF_CAM != 1 && NUM_OF_CAM != 2) 171 | { 172 | printf("num_of_cam should be 1 or 2\n"); 173 | assert(0); 174 | } 175 | 176 | 177 | int pn = config_file.find_last_of('/'); 178 | std::string configPath = config_file.substr(0, pn); 179 | 180 | std::string cam0Calib; 181 | fsSettings["cam0_calib"] >> cam0Calib; 182 | std::string cam0Path = configPath + "/" + cam0Calib; 183 | CAM_NAMES.push_back(cam0Path); 184 | 185 | if(NUM_OF_CAM == 2) 186 | { 187 | STEREO = 1; 188 | std::string cam1Calib; 189 | fsSettings["cam1_calib"] >> cam1Calib; 190 | std::string cam1Path = configPath + "/" + cam1Calib; 191 | //printf("%s cam1 path\n", cam1Path.c_str() ); 192 | CAM_NAMES.push_back(cam1Path); 193 | 194 | cv::Mat cv_T; 195 | fsSettings["body_T_cam1"] >> cv_T; 196 | Eigen::Matrix4d T; 197 | cv::cv2eigen(cv_T, T); 198 | RIC.push_back(T.block<3, 3>(0, 0)); 199 | TIC.push_back(T.block<3, 1>(0, 3)); 200 | } 201 | 202 | INIT_DEPTH = 5.0; 203 | BIAS_ACC_THRESHOLD = 0.1; 204 | BIAS_GYR_THRESHOLD = 0.1; 205 | 206 | TD = fsSettings["td"]; 207 | ESTIMATE_TD = fsSettings["estimate_td"]; 208 | if (ESTIMATE_TD) 209 | ROS_INFO_STREAM("Unsynchronized sensors, online estimate time offset, initial td: " << TD); 210 | else 211 | ROS_INFO_STREAM("Synchronized sensors, fix time offset: " << TD); 212 | 213 | ROW = fsSettings["image_height"]; 214 | COL = fsSettings["image_width"]; 215 | ROS_INFO("ROW: %d COL: %d ", ROW, COL); 216 | 217 | if(!USE_IMU) 218 | { 219 | ESTIMATE_EXTRINSIC = 0; 220 | ESTIMATE_TD = 0; 221 | printf("no imu, fix extrinsic param; no time offset calibration\n"); 222 | } 223 | 224 | fsSettings.release(); 225 | } 226 | -------------------------------------------------------------------------------- /vins_estimator/estimator/parameters.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include "../utility/utility.h" 16 | #include 17 | #include 18 | #include 19 | #include 20 | 21 | using namespace std; 22 | 23 | //FOR DYNAVINS 24 | extern bool DYN_ON; 25 | extern double DYN_ALT_CONV; 26 | extern double DYN_FEAT_MARGIN_THRESH; 27 | extern bool DYN_PRIOR_ON; 28 | extern double FEATURE_RESIST_GAMMA; 29 | extern double FEATURE_PRIOR_GAMMA; 30 | 31 | //---------------// 32 | 33 | 34 | const double FOCAL_LENGTH = 460.0; 35 | const int WINDOW_SIZE = 10; 36 | const int NUM_OF_F = 1000; 37 | 38 | extern int TEST_MONO; 39 | 40 | extern double MAX_DEPTH; 41 | 42 | extern int SHOW_IMAGE_WEIGHT; 43 | //#define UNIT_SPHERE_ERROR 44 | 45 | extern double INIT_DEPTH; 46 | extern double MIN_PARALLAX; 47 | extern int ESTIMATE_EXTRINSIC; 48 | 49 | 50 | extern double ACC_N, ACC_W; 51 | extern double GYR_N, GYR_W; 52 | 53 | extern std::vector RIC; 54 | extern std::vector TIC; 55 | extern Eigen::Vector3d G; 56 | 57 | extern double BIAS_ACC_THRESHOLD; 58 | extern double BIAS_GYR_THRESHOLD; 59 | extern double SOLVER_TIME; 60 | extern int NUM_ITERATIONS; 61 | extern std::string EX_CALIB_RESULT_PATH; 62 | extern std::string VINS_RESULT_PATH; 63 | extern std::string OUTPUT_FOLDER; 64 | extern std::string IMU_TOPIC; 65 | extern double TD; 66 | extern int ESTIMATE_TD; 67 | extern int ROLLING_SHUTTER; 68 | extern int ROW, COL; 69 | extern int NUM_OF_CAM; 70 | extern int STEREO; 71 | extern int USE_IMU; 72 | extern int MULTIPLE_THREAD; 73 | // pts_gt for debug purpose; 74 | extern map pts_gt; 75 | 76 | extern std::string IMAGE0_TOPIC, IMAGE1_TOPIC; 77 | extern std::string FISHEYE_MASK; 78 | extern std::vector CAM_NAMES; 79 | extern int MAX_CNT; 80 | extern int MIN_DIST; 81 | extern double F_THRESHOLD; 82 | extern int SHOW_TRACK; 83 | extern int FLOW_BACK; 84 | 85 | void readParameters(std::string config_file); 86 | 87 | enum SIZE_PARAMETERIZATION 88 | { 89 | SIZE_POSE = 7, 90 | SIZE_SPEEDBIAS = 9, 91 | SIZE_FEATURE = 1 92 | }; 93 | 94 | enum StateOrder 95 | { 96 | O_P = 0, 97 | O_R = 3, 98 | O_V = 6, 99 | O_BA = 9, 100 | O_BG = 12 101 | }; 102 | 103 | enum NoiseOrder 104 | { 105 | O_AN = 0, 106 | O_GN = 3, 107 | O_AW = 6, 108 | O_GW = 9 109 | }; 110 | -------------------------------------------------------------------------------- /vins_estimator/factor/initial_bias_factor.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | #include 16 | #include 17 | #include "../utility/utility.h" 18 | #include "../utility/tic_toc.h" 19 | #include "../estimator/parameters.h" 20 | 21 | class InitialBiasFactor : public ceres::SizedCostFunction<6, 9> 22 | { 23 | public: 24 | InitialBiasFactor(const Eigen::Vector3d &_Ba, const Eigen::Vector3d &_Bg) 25 | { 26 | init_Ba = _Ba; 27 | init_Bg = _Bg; 28 | sqrt_info = 1.0 / (0.001) * Eigen::Matrix::Identity(); 29 | } 30 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const 31 | { 32 | Eigen::Vector3d Ba(parameters[0][3], parameters[0][4], parameters[0][5]); 33 | Eigen::Vector3d Bg(parameters[0][6], parameters[0][7], parameters[0][8]); 34 | 35 | Eigen::Map> residual(residuals); 36 | residual.block<3, 1>(0, 0) = Ba - init_Ba; 37 | residual.block<3, 1>(3, 0) = Bg - init_Bg; 38 | residual = sqrt_info * residual; 39 | 40 | if (jacobians) 41 | { 42 | if (jacobians[0]) 43 | { 44 | Eigen::Map> jacobian_bias(jacobians[0]); 45 | jacobian_bias.setZero(); 46 | jacobian_bias.block<3, 3>(0, 3) = Eigen::Matrix3d::Identity(); 47 | jacobian_bias.block<3, 3>(3, 6) = Eigen::Matrix3d::Identity(); 48 | jacobian_bias = sqrt_info * jacobian_bias; 49 | } 50 | } 51 | return true; 52 | } 53 | 54 | Eigen::Vector3d init_Ba, init_Bg; 55 | Eigen::Matrix sqrt_info; 56 | }; 57 | -------------------------------------------------------------------------------- /vins_estimator/factor/initial_pose_factor.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | #include 16 | #include 17 | #include "../utility/utility.h" 18 | #include "../utility/tic_toc.h" 19 | #include "../estimator/parameters.h" 20 | 21 | class InitialPoseFactor : public ceres::SizedCostFunction<6, 7> 22 | { 23 | public: 24 | InitialPoseFactor(const Eigen::Vector3d &_P, const Eigen::Quaterniond &_Q) 25 | { 26 | init_P = _P; 27 | init_Q = _Q; 28 | sqrt_info = 1000 * Eigen::Matrix::Identity(); 29 | } 30 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const 31 | { 32 | Eigen::Vector3d P(parameters[0][0], parameters[0][1], parameters[0][2]); 33 | Eigen::Quaterniond Q(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]); 34 | 35 | Eigen::Map> residual(residuals); 36 | residual.block<3, 1>(0, 0) = P - init_P; 37 | residual.block<3, 1>(3, 0) = 2 * (init_Q.inverse() * Q).vec(); 38 | residual = sqrt_info * residual; 39 | 40 | if (jacobians) 41 | { 42 | if (jacobians[0]) 43 | { 44 | Eigen::Map> jacobian_pose(jacobians[0]); 45 | jacobian_pose.setZero(); 46 | jacobian_pose.block<3, 3>(0, 0) = Eigen::Matrix3d::Identity(); 47 | jacobian_pose.block<3, 3>(3, 3) = Utility::Qleft(init_Q.inverse() * Q).bottomRightCorner<3, 3>(); 48 | jacobian_pose = sqrt_info * jacobian_pose; 49 | } 50 | 51 | } 52 | return true; 53 | 54 | } 55 | 56 | void check(double **parameters) 57 | { 58 | double *res = new double[6]; 59 | double **jaco = new double *[1]; 60 | jaco[0] = new double[6 * 7]; 61 | Evaluate(parameters, res, jaco); 62 | puts("check begins"); 63 | 64 | puts("my"); 65 | 66 | std::cout << Eigen::Map>(res).transpose() << std::endl 67 | << std::endl; 68 | std::cout << Eigen::Map>(jaco[0]) << std::endl 69 | << std::endl; 70 | 71 | Eigen::Vector3d P(parameters[0][0], parameters[0][1], parameters[0][2]); 72 | Eigen::Quaterniond Q(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]); 73 | 74 | Eigen::Matrix residual; 75 | residual.block<3, 1>(0, 0) = P - init_P; 76 | residual.block<3, 1>(3, 0) = 2 * (init_Q.inverse()* Q).vec(); 77 | residual = sqrt_info * residual; 78 | 79 | puts("num"); 80 | std::cout << residual.transpose() << std::endl; 81 | 82 | const double eps = 1e-6; 83 | Eigen::Matrix num_jacobian; 84 | for (int k = 0; k < 6; k++) 85 | { 86 | Eigen::Vector3d P(parameters[0][0], parameters[0][1], parameters[0][2]); 87 | Eigen::Quaterniond Q(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]); 88 | 89 | int a = k / 3, b = k % 3; 90 | Eigen::Vector3d delta = Eigen::Vector3d(b == 0, b == 1, b == 2) * eps; 91 | 92 | if (a == 0) 93 | P += delta; 94 | else if (a == 1) 95 | Q = Q * Utility::deltaQ(delta); 96 | 97 | 98 | Eigen::Matrix tmp_residual; 99 | tmp_residual.block<3, 1>(0, 0) = P - init_P; 100 | tmp_residual.block<3, 1>(3, 0) = 2 * (init_Q.inverse()* Q).vec(); 101 | tmp_residual = sqrt_info * tmp_residual; 102 | 103 | num_jacobian.col(k) = (tmp_residual - residual) / eps; 104 | } 105 | std::cout << num_jacobian << std::endl; 106 | 107 | } 108 | 109 | Eigen::Vector3d init_P; 110 | Eigen::Quaterniond init_Q; 111 | Eigen::Matrix sqrt_info; 112 | }; 113 | -------------------------------------------------------------------------------- /vins_estimator/factor/marginalization_factor.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | #include "../utility/utility.h" 20 | #include "../utility/tic_toc.h" 21 | 22 | const int NUM_THREADS = 4; 23 | 24 | struct ResidualBlockInfo 25 | { 26 | ResidualBlockInfo(ceres::CostFunction *_cost_function, ceres::LossFunction *_loss_function, std::vector _parameter_blocks, std::vector _drop_set) 27 | : cost_function(_cost_function), loss_function(_loss_function), parameter_blocks(_parameter_blocks), drop_set(_drop_set) {} 28 | 29 | void Evaluate(); 30 | 31 | ceres::CostFunction *cost_function; 32 | ceres::LossFunction *loss_function; 33 | std::vector parameter_blocks; 34 | std::vector drop_set; 35 | 36 | double **raw_jacobians; 37 | std::vector> jacobians; 38 | Eigen::VectorXd residuals; 39 | 40 | int localSize(int size) 41 | { 42 | return size == 7 ? 6 : size; 43 | } 44 | }; 45 | 46 | struct ThreadsStruct 47 | { 48 | std::vector sub_factors; 49 | Eigen::MatrixXd A; 50 | Eigen::VectorXd b; 51 | std::unordered_map parameter_block_size; //global size 52 | std::unordered_map parameter_block_idx; //local size 53 | }; 54 | 55 | class MarginalizationInfo 56 | { 57 | public: 58 | MarginalizationInfo(){valid = true;}; 59 | ~MarginalizationInfo(); 60 | int localSize(int size) const; 61 | int globalSize(int size) const; 62 | void addResidualBlockInfo(ResidualBlockInfo *residual_block_info); 63 | void preMarginalize(); 64 | void marginalize(); 65 | std::vector getParameterBlocks(std::unordered_map &addr_shift); 66 | 67 | std::vector factors; 68 | int m, n; 69 | std::unordered_map parameter_block_size; //global size 70 | int sum_block_size; 71 | std::unordered_map parameter_block_idx; //local size 72 | std::unordered_map parameter_block_data; 73 | 74 | std::vector keep_block_size; //global size 75 | std::vector keep_block_idx; //local size 76 | std::vector keep_block_data; 77 | 78 | Eigen::MatrixXd linearized_jacobians; 79 | Eigen::VectorXd linearized_residuals; 80 | const double eps = 1e-8; 81 | bool valid; 82 | 83 | }; 84 | 85 | class MarginalizationFactor : public ceres::CostFunction 86 | { 87 | public: 88 | MarginalizationFactor(MarginalizationInfo* _marginalization_info); 89 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const; 90 | 91 | MarginalizationInfo* marginalization_info; 92 | }; 93 | -------------------------------------------------------------------------------- /vins_estimator/factor/pose_local_parameterization.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #include "pose_local_parameterization.h" 11 | 12 | bool PoseLocalParameterization::Plus(const double *x, const double *delta, double *x_plus_delta) const 13 | { 14 | Eigen::Map _p(x); 15 | Eigen::Map _q(x + 3); 16 | 17 | Eigen::Map dp(delta); 18 | 19 | Eigen::Quaterniond dq = Utility::deltaQ(Eigen::Map(delta + 3)); 20 | 21 | Eigen::Map p(x_plus_delta); 22 | Eigen::Map q(x_plus_delta + 3); 23 | 24 | p = _p + dp; 25 | q = (_q * dq).normalized(); 26 | 27 | return true; 28 | } 29 | bool PoseLocalParameterization::ComputeJacobian(const double *x, double *jacobian) const 30 | { 31 | Eigen::Map> j(jacobian); 32 | j.topRows<6>().setIdentity(); 33 | j.bottomRows<1>().setZero(); 34 | 35 | return true; 36 | } 37 | -------------------------------------------------------------------------------- /vins_estimator/factor/pose_local_parameterization.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include "../utility/utility.h" 15 | 16 | class PoseLocalParameterization : public ceres::LocalParameterization 17 | { 18 | virtual bool Plus(const double *x, const double *delta, double *x_plus_delta) const; 19 | virtual bool ComputeJacobian(const double *x, double *jacobian) const; 20 | virtual int GlobalSize() const { return 7; }; 21 | virtual int LocalSize() const { return 6; }; 22 | }; 23 | -------------------------------------------------------------------------------- /vins_estimator/factor/prior_factor.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | #include 12 | #include 13 | #include 14 | 15 | #include "../utility/utility.h" 16 | #include "../estimator/parameters.h" 17 | 18 | #include 19 | 20 | class ResistFactor : public ceres::SizedCostFunction<1, 1> 21 | { 22 | public: 23 | ResistFactor() = delete; 24 | ResistFactor(double _gamma):gamma(_gamma) 25 | { 26 | } 27 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const 28 | { 29 | double sel = parameters[0][0]; 30 | Eigen::Map> residual(residuals); 31 | residual(0,0) = gamma * (1-sel); 32 | 33 | if (jacobians) 34 | { 35 | if (jacobians[0]) 36 | { 37 | Eigen::Map> jacobian_sel(jacobians[0]); 38 | jacobian_sel(0,0)=-gamma; 39 | } 40 | } 41 | 42 | return true; 43 | } 44 | 45 | double gamma; 46 | 47 | }; 48 | 49 | 50 | class PriorFactor : public ceres::SizedCostFunction<1, 1> 51 | { 52 | public: 53 | PriorFactor() = delete; 54 | PriorFactor(double _gamma,double _prior):gamma(_gamma),prior(_prior) 55 | { 56 | } 57 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const 58 | { 59 | double sel = parameters[0][0]; 60 | Eigen::Map> residual(residuals); 61 | residual(0,0) = fabs(gamma * (prior-sel)); 62 | 63 | if (jacobians) 64 | { 65 | if (jacobians[0]) 66 | { 67 | Eigen::Map> jacobian_sel(jacobians[0]); 68 | if(prior 15 | #include 16 | #include 17 | #include "../utility/utility.h" 18 | #include "../utility/tic_toc.h" 19 | #include "../estimator/parameters.h" 20 | 21 | class ProjectionOneFrameTwoCamFactor : public ceres::SizedCostFunction<2, 7, 7, 1, 1> 22 | { 23 | public: 24 | ProjectionOneFrameTwoCamFactor(const Eigen::Vector3d &_pts_i, const Eigen::Vector3d &_pts_j, 25 | const Eigen::Vector2d &_velocity_i, const Eigen::Vector2d &_velocity_j, 26 | const double _td_i, const double _td_j); 27 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const; 28 | void check(double **parameters); 29 | 30 | Eigen::Vector3d pts_i, pts_j; 31 | Eigen::Vector3d velocity_i, velocity_j; 32 | double td_i, td_j; 33 | Eigen::Matrix tangent_base; 34 | static Eigen::Matrix2d sqrt_info; 35 | static double sum_t; 36 | }; 37 | -------------------------------------------------------------------------------- /vins_estimator/factor/projectionTwoFrameOneCamFactor.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | #include 16 | #include 17 | #include "../utility/utility.h" 18 | #include "../utility/tic_toc.h" 19 | #include "../estimator/parameters.h" 20 | 21 | class ProjectionTwoFrameOneCamFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 1, 1, 1> 22 | { 23 | public: 24 | ProjectionTwoFrameOneCamFactor(const Eigen::Vector3d &_pts_i, const Eigen::Vector3d &_pts_j, 25 | const Eigen::Vector2d &_velocity_i, const Eigen::Vector2d &_velocity_j, 26 | const double _td_i, const double _td_j); 27 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const; 28 | void check(double **parameters); 29 | 30 | Eigen::Vector3d pts_i, pts_j; 31 | Eigen::Vector3d velocity_i, velocity_j; 32 | double td_i, td_j; 33 | Eigen::Matrix tangent_base; 34 | static Eigen::Matrix2d sqrt_info; 35 | static double sum_t; 36 | }; 37 | -------------------------------------------------------------------------------- /vins_estimator/factor/projectionTwoFrameTwoCamFactor.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | #include 16 | #include 17 | #include "../utility/utility.h" 18 | #include "../utility/tic_toc.h" 19 | #include "../estimator/parameters.h" 20 | 21 | class ProjectionTwoFrameTwoCamFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 7, 1, 1, 1> 22 | { 23 | public: 24 | ProjectionTwoFrameTwoCamFactor(const Eigen::Vector3d &_pts_i, const Eigen::Vector3d &_pts_j, 25 | const Eigen::Vector2d &_velocity_i, const Eigen::Vector2d &_velocity_j, 26 | const double _td_i, const double _td_j); 27 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const; 28 | void check(double **parameters); 29 | 30 | Eigen::Vector3d pts_i, pts_j; 31 | Eigen::Vector3d velocity_i, velocity_j; 32 | double td_i, td_j; 33 | Eigen::Matrix tangent_base; 34 | static Eigen::Matrix2d sqrt_info; 35 | static double sum_t; 36 | }; 37 | -------------------------------------------------------------------------------- /vins_estimator/factor/projection_factor.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include "../utility/utility.h" 16 | #include "../utility/tic_toc.h" 17 | #include "../estimator/parameters.h" 18 | 19 | class ProjectionFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 1> 20 | { 21 | public: 22 | ProjectionFactor(const Eigen::Vector3d &_pts_i, const Eigen::Vector3d &_pts_j); 23 | virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const; 24 | void check(double **parameters); 25 | 26 | Eigen::Vector3d pts_i, pts_j; 27 | Eigen::Matrix tangent_base; 28 | static Eigen::Matrix2d sqrt_info; 29 | static double sum_t; 30 | }; 31 | -------------------------------------------------------------------------------- /vins_estimator/featureTracker/feature_tracker.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | 23 | #include "camodocal/camera_models/CameraFactory.h" 24 | #include "camodocal/camera_models/CataCamera.h" 25 | #include "camodocal/camera_models/PinholeCamera.h" 26 | #include "../estimator/parameters.h" 27 | #include "../utility/tic_toc.h" 28 | 29 | using namespace std; 30 | using namespace camodocal; 31 | using namespace Eigen; 32 | 33 | bool inBorder(const cv::Point2f &pt); 34 | void reduceVector(vector &v, vector status); 35 | void reduceVector(vector &v, vector status); 36 | 37 | class FeatureTracker 38 | { 39 | public: 40 | FeatureTracker(); 41 | map>>> trackImage(double _cur_time, const cv::Mat &_img, const cv::Mat &_img1 = cv::Mat()); 42 | void setMask(); 43 | void readIntrinsicParameter(const vector &calib_file); 44 | void showUndistortion(const string &name); 45 | void rejectWithF(); 46 | void undistortedPoints(); 47 | vector undistortedPts(vector &pts, camodocal::CameraPtr cam); 48 | vector ptsVelocity(vector &ids, vector &pts, 49 | map &cur_id_pts, map &prev_id_pts); 50 | void showTwoImage(const cv::Mat &img1, const cv::Mat &img2, 51 | vector pts1, vector pts2); 52 | void drawTrack(const cv::Mat &imLeft, const cv::Mat &imRight, 53 | vector &curLeftIds, 54 | vector &curLeftPts, 55 | vector &curRightPts, 56 | map &prevLeftPtsMap); 57 | void drawTrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, 58 | vector &curLeftIds, 59 | vector &curRightIds, 60 | vector &curLeftPts, 61 | vector &curRightPts, 62 | map &prevLeftPtsMap); 63 | void setPrediction(map &predictPts); 64 | double distance(cv::Point2f &pt1, cv::Point2f &pt2); 65 | void removeOutliers(set &removePtsIds); 66 | cv::Mat getTrackImage(); 67 | bool inBorder(const cv::Point2f &pt); 68 | 69 | int row, col; 70 | cv::Mat imTrack; 71 | cv::Mat mask; 72 | cv::Mat fisheye_mask; 73 | cv::Mat prev_img, cur_img; 74 | vector n_pts; 75 | vector predict_pts; 76 | vector predict_pts_debug; 77 | vector prev_pts, cur_pts, cur_right_pts; 78 | vector prev_un_pts, cur_un_pts, cur_un_right_pts; 79 | vector pts_velocity, right_pts_velocity; 80 | vector ids, ids_right; 81 | vector track_cnt; 82 | map cur_un_pts_map, prev_un_pts_map; 83 | map cur_un_right_pts_map, prev_un_right_pts_map; 84 | map prevLeftPtsMap; 85 | vector m_camera; 86 | double cur_time; 87 | double prev_time; 88 | bool stereo_cam; 89 | int n_id; 90 | bool hasPrediction; 91 | }; 92 | -------------------------------------------------------------------------------- /vins_estimator/initial/initial_alignment.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | #include 14 | #include 15 | #include "../factor/imu_factor.h" 16 | #include "../utility/utility.h" 17 | #include 18 | #include 19 | #include "../estimator/feature_manager.h" 20 | 21 | using namespace Eigen; 22 | using namespace std; 23 | 24 | class ImageFrame 25 | { 26 | public: 27 | ImageFrame(){}; 28 | ImageFrame(const map>>>& _points, double _t):t{_t},is_key_frame{false} 29 | { 30 | points = _points; 31 | }; 32 | map> > > points; 33 | double t; 34 | Matrix3d R; 35 | Vector3d T; 36 | IntegrationBase *pre_integration; 37 | bool is_key_frame; 38 | }; 39 | void solveGyroscopeBias(map &all_image_frame, Vector3d* Bgs); 40 | void solveGyroscopeBiasOnly(map &all_image_frame,Matrix3d* Rs, Vector3d* Bgs); 41 | 42 | bool VisualIMUAlignment(map &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x); 43 | -------------------------------------------------------------------------------- /vins_estimator/initial/initial_ex_rotation.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #include "initial_ex_rotation.h" 13 | 14 | InitialEXRotation::InitialEXRotation(){ 15 | frame_count = 0; 16 | Rc.push_back(Matrix3d::Identity()); 17 | Rc_g.push_back(Matrix3d::Identity()); 18 | Rimu.push_back(Matrix3d::Identity()); 19 | ric = Matrix3d::Identity(); 20 | } 21 | 22 | bool InitialEXRotation::CalibrationExRotation(vector> corres, Quaterniond delta_q_imu, Matrix3d &calib_ric_result) 23 | { 24 | frame_count++; 25 | Rc.push_back(solveRelativeR(corres)); 26 | Rimu.push_back(delta_q_imu.toRotationMatrix()); 27 | Rc_g.push_back(ric.inverse() * delta_q_imu * ric); 28 | 29 | Eigen::MatrixXd A(frame_count * 4, 4); 30 | A.setZero(); 31 | int sum_ok = 0; 32 | for (int i = 1; i <= frame_count; i++) 33 | { 34 | Quaterniond r1(Rc[i]); 35 | Quaterniond r2(Rc_g[i]); 36 | 37 | double angular_distance = 180 / M_PI * r1.angularDistance(r2); 38 | ROS_DEBUG( 39 | "%d %f", i, angular_distance); 40 | 41 | double huber = angular_distance > 5.0 ? 5.0 / angular_distance : 1.0; 42 | ++sum_ok; 43 | Matrix4d L, R; 44 | 45 | double w = Quaterniond(Rc[i]).w(); 46 | Vector3d q = Quaterniond(Rc[i]).vec(); 47 | L.block<3, 3>(0, 0) = w * Matrix3d::Identity() + Utility::skewSymmetric(q); 48 | L.block<3, 1>(0, 3) = q; 49 | L.block<1, 3>(3, 0) = -q.transpose(); 50 | L(3, 3) = w; 51 | 52 | Quaterniond R_ij(Rimu[i]); 53 | w = R_ij.w(); 54 | q = R_ij.vec(); 55 | R.block<3, 3>(0, 0) = w * Matrix3d::Identity() - Utility::skewSymmetric(q); 56 | R.block<3, 1>(0, 3) = q; 57 | R.block<1, 3>(3, 0) = -q.transpose(); 58 | R(3, 3) = w; 59 | 60 | A.block<4, 4>((i - 1) * 4, 0) = huber * (L - R); 61 | } 62 | 63 | JacobiSVD svd(A, ComputeFullU | ComputeFullV); 64 | Matrix x = svd.matrixV().col(3); 65 | Quaterniond estimated_R(x); 66 | ric = estimated_R.toRotationMatrix().inverse(); 67 | //cout << svd.singularValues().transpose() << endl; 68 | //cout << ric << endl; 69 | Vector3d ric_cov; 70 | ric_cov = svd.singularValues().tail<3>(); 71 | if (frame_count >= WINDOW_SIZE && ric_cov(1) > 0.25) 72 | { 73 | calib_ric_result = ric; 74 | return true; 75 | } 76 | else 77 | return false; 78 | } 79 | 80 | Matrix3d InitialEXRotation::solveRelativeR(const vector> &corres) 81 | { 82 | if (corres.size() >= 9) 83 | { 84 | vector ll, rr; 85 | for (int i = 0; i < int(corres.size()); i++) 86 | { 87 | ll.push_back(cv::Point2f(corres[i].first(0), corres[i].first(1))); 88 | rr.push_back(cv::Point2f(corres[i].second(0), corres[i].second(1))); 89 | } 90 | cv::Mat E = cv::findFundamentalMat(ll, rr); 91 | cv::Mat_ R1, R2, t1, t2; 92 | decomposeE(E, R1, R2, t1, t2); 93 | 94 | if (determinant(R1) + 1.0 < 1e-09) 95 | { 96 | E = -E; 97 | decomposeE(E, R1, R2, t1, t2); 98 | } 99 | double ratio1 = max(testTriangulation(ll, rr, R1, t1), testTriangulation(ll, rr, R1, t2)); 100 | double ratio2 = max(testTriangulation(ll, rr, R2, t1), testTriangulation(ll, rr, R2, t2)); 101 | cv::Mat_ ans_R_cv = ratio1 > ratio2 ? R1 : R2; 102 | 103 | Matrix3d ans_R_eigen; 104 | for (int i = 0; i < 3; i++) 105 | for (int j = 0; j < 3; j++) 106 | ans_R_eigen(j, i) = ans_R_cv(i, j); 107 | return ans_R_eigen; 108 | } 109 | return Matrix3d::Identity(); 110 | } 111 | 112 | double InitialEXRotation::testTriangulation(const vector &l, 113 | const vector &r, 114 | cv::Mat_ R, cv::Mat_ t) 115 | { 116 | cv::Mat pointcloud; 117 | cv::Matx34f P = cv::Matx34f(1, 0, 0, 0, 118 | 0, 1, 0, 0, 119 | 0, 0, 1, 0); 120 | cv::Matx34f P1 = cv::Matx34f(R(0, 0), R(0, 1), R(0, 2), t(0), 121 | R(1, 0), R(1, 1), R(1, 2), t(1), 122 | R(2, 0), R(2, 1), R(2, 2), t(2)); 123 | cv::triangulatePoints(P, P1, l, r, pointcloud); 124 | int front_count = 0; 125 | for (int i = 0; i < pointcloud.cols; i++) 126 | { 127 | double normal_factor = pointcloud.col(i).at(3); 128 | 129 | cv::Mat_ p_3d_l = cv::Mat(P) * (pointcloud.col(i) / normal_factor); 130 | cv::Mat_ p_3d_r = cv::Mat(P1) * (pointcloud.col(i) / normal_factor); 131 | if (p_3d_l(2) > 0 && p_3d_r(2) > 0) 132 | front_count++; 133 | } 134 | ROS_DEBUG("MotionEstimator: %f", 1.0 * front_count / pointcloud.cols); 135 | return 1.0 * front_count / pointcloud.cols; 136 | } 137 | 138 | void InitialEXRotation::decomposeE(cv::Mat E, 139 | cv::Mat_ &R1, cv::Mat_ &R2, 140 | cv::Mat_ &t1, cv::Mat_ &t2) 141 | { 142 | cv::SVD svd(E, cv::SVD::MODIFY_A); 143 | cv::Matx33d W(0, -1, 0, 144 | 1, 0, 0, 145 | 0, 0, 1); 146 | cv::Matx33d Wt(0, 1, 0, 147 | -1, 0, 0, 148 | 0, 0, 1); 149 | R1 = svd.u * cv::Mat(W) * svd.vt; 150 | R2 = svd.u * cv::Mat(Wt) * svd.vt; 151 | t1 = svd.u.col(2); 152 | t2 = -svd.u.col(2); 153 | } 154 | -------------------------------------------------------------------------------- /vins_estimator/initial/initial_ex_rotation.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | #include "../estimator/parameters.h" 16 | using namespace std; 17 | 18 | #include 19 | 20 | #include 21 | using namespace Eigen; 22 | #include 23 | 24 | /* This class help you to calibrate extrinsic rotation between imu and camera when your totally don't konw the extrinsic parameter */ 25 | class InitialEXRotation 26 | { 27 | public: 28 | InitialEXRotation(); 29 | bool CalibrationExRotation(vector> corres, Quaterniond delta_q_imu, Matrix3d &calib_ric_result); 30 | private: 31 | Matrix3d solveRelativeR(const vector> &corres); 32 | 33 | double testTriangulation(const vector &l, 34 | const vector &r, 35 | cv::Mat_ R, cv::Mat_ t); 36 | void decomposeE(cv::Mat E, 37 | cv::Mat_ &R1, cv::Mat_ &R2, 38 | cv::Mat_ &t1, cv::Mat_ &t2); 39 | int frame_count; 40 | 41 | vector< Matrix3d > Rc; 42 | vector< Matrix3d > Rimu; 43 | vector< Matrix3d > Rc_g; 44 | Matrix3d ric; 45 | }; 46 | 47 | 48 | -------------------------------------------------------------------------------- /vins_estimator/initial/initial_sfm.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | using namespace Eigen; 23 | using namespace std; 24 | 25 | 26 | 27 | struct SFMFeature 28 | { 29 | bool state; 30 | int id; 31 | vector> observation; 32 | double position[3]; 33 | double depth; 34 | }; 35 | 36 | struct ReprojectionError3D 37 | { 38 | ReprojectionError3D(double observed_u, double observed_v) 39 | :observed_u(observed_u), observed_v(observed_v) 40 | {} 41 | 42 | template 43 | bool operator()(const T* const camera_R, const T* const camera_T, const T* point, T* residuals) const 44 | { 45 | T p[3]; 46 | ceres::QuaternionRotatePoint(camera_R, point, p); 47 | p[0] += camera_T[0]; p[1] += camera_T[1]; p[2] += camera_T[2]; 48 | T xp = p[0] / p[2]; 49 | T yp = p[1] / p[2]; 50 | residuals[0] = xp - T(observed_u); 51 | residuals[1] = yp - T(observed_v); 52 | return true; 53 | } 54 | 55 | static ceres::CostFunction* Create(const double observed_x, 56 | const double observed_y) 57 | { 58 | return (new ceres::AutoDiffCostFunction< 59 | ReprojectionError3D, 2, 4, 3, 3>( 60 | new ReprojectionError3D(observed_x,observed_y))); 61 | } 62 | 63 | double observed_u; 64 | double observed_v; 65 | }; 66 | 67 | class GlobalSFM 68 | { 69 | public: 70 | GlobalSFM(); 71 | bool construct(int frame_num, Quaterniond* q, Vector3d* T, int l, 72 | const Matrix3d relative_R, const Vector3d relative_T, 73 | vector &sfm_f, map &sfm_tracked_points); 74 | 75 | private: 76 | bool solveFrameByPnP(Matrix3d &R_initial, Vector3d &P_initial, int i, vector &sfm_f); 77 | 78 | void triangulatePoint(Eigen::Matrix &Pose0, Eigen::Matrix &Pose1, 79 | Vector2d &point0, Vector2d &point1, Vector3d &point_3d); 80 | void triangulateTwoFrames(int frame0, Eigen::Matrix &Pose0, 81 | int frame1, Eigen::Matrix &Pose1, 82 | vector &sfm_f); 83 | 84 | int feature_num; 85 | }; -------------------------------------------------------------------------------- /vins_estimator/initial/solve_5pts.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #pragma once 13 | 14 | #include 15 | using namespace std; 16 | 17 | #include 18 | //#include 19 | #include 20 | using namespace Eigen; 21 | 22 | #include 23 | 24 | class MotionEstimator 25 | { 26 | public: 27 | 28 | bool solveRelativeRT(const vector> &corres, Matrix3d &R, Vector3d &T); 29 | 30 | private: 31 | double testTriangulation(const vector &l, 32 | const vector &r, 33 | cv::Mat_ R, cv::Mat_ t); 34 | void decomposeE(cv::Mat E, 35 | cv::Mat_ &R1, cv::Mat_ &R2, 36 | cv::Mat_ &t1, cv::Mat_ &t2); 37 | }; 38 | 39 | 40 | -------------------------------------------------------------------------------- /vins_estimator/rosNodeTest.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | * 9 | * Author: Qin Tong (qintonguav@gmail.com) 10 | *******************************************************/ 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include "estimator/estimator.h" 21 | #include "estimator/parameters.h" 22 | #include "utility/visualization.h" 23 | 24 | Estimator estimator; 25 | 26 | queue imu_buf; 27 | queue feature_buf; 28 | queue img0_buf; 29 | queue img1_buf; 30 | std::mutex m_buf; 31 | 32 | 33 | void img0_callback(const sensor_msgs::ImageConstPtr &img_msg) 34 | { 35 | m_buf.lock(); 36 | img0_buf.push(img_msg); 37 | m_buf.unlock(); 38 | } 39 | 40 | void img1_callback(const sensor_msgs::ImageConstPtr &img_msg) 41 | { 42 | m_buf.lock(); 43 | img1_buf.push(img_msg); 44 | m_buf.unlock(); 45 | } 46 | 47 | 48 | cv::Mat getImageFromMsg(const sensor_msgs::ImageConstPtr &img_msg) 49 | { 50 | cv_bridge::CvImageConstPtr ptr; 51 | if (img_msg->encoding == "8UC1") 52 | { 53 | sensor_msgs::Image img; 54 | img.header = img_msg->header; 55 | img.height = img_msg->height; 56 | img.width = img_msg->width; 57 | img.is_bigendian = img_msg->is_bigendian; 58 | img.step = img_msg->step; 59 | img.data = img_msg->data; 60 | img.encoding = "mono8"; 61 | ptr = cv_bridge::toCvCopy(img, sensor_msgs::image_encodings::MONO8); 62 | } 63 | else 64 | ptr = cv_bridge::toCvCopy(img_msg, sensor_msgs::image_encodings::MONO8); 65 | 66 | cv::Mat img = ptr->image.clone(); 67 | return img; 68 | } 69 | 70 | // extract images with same timestamp from two topics 71 | void sync_process() 72 | { 73 | while(1) 74 | { 75 | if(STEREO) 76 | { 77 | cv::Mat image0, image1; 78 | std_msgs::Header header; 79 | double time = 0; 80 | m_buf.lock(); 81 | if (!img0_buf.empty() && !img1_buf.empty()) 82 | { 83 | double time0 = img0_buf.front()->header.stamp.toSec(); 84 | double time1 = img1_buf.front()->header.stamp.toSec(); 85 | // 0.003s sync tolerance 86 | if(time0 < time1 - 0.003) 87 | { 88 | img0_buf.pop(); 89 | printf("throw img0\n"); 90 | } 91 | else if(time0 > time1 + 0.003) 92 | { 93 | img1_buf.pop(); 94 | printf("throw img1\n"); 95 | } 96 | else 97 | { 98 | time = img0_buf.front()->header.stamp.toSec(); 99 | header = img0_buf.front()->header; 100 | image0 = getImageFromMsg(img0_buf.front()); 101 | img0_buf.pop(); 102 | image1 = getImageFromMsg(img1_buf.front()); 103 | img1_buf.pop(); 104 | //printf("find img0 and img1\n"); 105 | } 106 | } 107 | m_buf.unlock(); 108 | if(!image0.empty()) 109 | estimator.inputImage(time, image0, image1); 110 | } 111 | else 112 | { 113 | cv::Mat image; 114 | std_msgs::Header header; 115 | double time = 0; 116 | m_buf.lock(); 117 | if(!img0_buf.empty()) 118 | { 119 | time = img0_buf.front()->header.stamp.toSec(); 120 | header = img0_buf.front()->header; 121 | image = getImageFromMsg(img0_buf.front()); 122 | img0_buf.pop(); 123 | } 124 | m_buf.unlock(); 125 | if(!image.empty()) 126 | estimator.inputImage(time, image); 127 | } 128 | 129 | std::chrono::milliseconds dura(2); 130 | std::this_thread::sleep_for(dura); 131 | } 132 | } 133 | 134 | 135 | void imu_callback(const sensor_msgs::ImuConstPtr &imu_msg) 136 | { 137 | double t = imu_msg->header.stamp.toSec(); 138 | double dx = imu_msg->linear_acceleration.x; 139 | double dy = imu_msg->linear_acceleration.y; 140 | double dz = imu_msg->linear_acceleration.z; 141 | double rx = imu_msg->angular_velocity.x; 142 | double ry = imu_msg->angular_velocity.y; 143 | double rz = imu_msg->angular_velocity.z; 144 | Vector3d acc(dx, dy, dz); 145 | Vector3d gyr(rx, ry, rz); 146 | estimator.inputIMU(t, acc, gyr); 147 | return; 148 | } 149 | 150 | void restart_callback(const std_msgs::BoolConstPtr &restart_msg) 151 | { 152 | if (restart_msg->data == true) 153 | { 154 | ROS_WARN("restart the estimator!"); 155 | estimator.clearState(); 156 | estimator.setParameter(); 157 | } 158 | return; 159 | } 160 | 161 | void imu_switch_callback(const std_msgs::BoolConstPtr &switch_msg) 162 | { 163 | if (switch_msg->data == true) 164 | { 165 | //ROS_WARN("use IMU!"); 166 | estimator.changeSensorType(1, STEREO); 167 | } 168 | else 169 | { 170 | //ROS_WARN("disable IMU!"); 171 | estimator.changeSensorType(0, STEREO); 172 | } 173 | return; 174 | } 175 | 176 | void cam_switch_callback(const std_msgs::BoolConstPtr &switch_msg) 177 | { 178 | if (switch_msg->data == true) 179 | { 180 | //ROS_WARN("use stereo!"); 181 | estimator.changeSensorType(USE_IMU, 1); 182 | } 183 | else 184 | { 185 | //ROS_WARN("use mono camera (left)!"); 186 | estimator.changeSensorType(USE_IMU, 0); 187 | } 188 | return; 189 | } 190 | 191 | int main(int argc, char **argv) 192 | { 193 | ros::init(argc, argv, "vins_estimator"); 194 | ros::NodeHandle n("~"); 195 | ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info); 196 | 197 | if(argc != 2) 198 | { 199 | printf("please intput: rosrun vins vins_node [config file] \n" 200 | "for example: rosrun vins vins_node " 201 | "~/catkin_ws/src/VINS-Fusion/config/euroc/euroc_stereo_imu_config.yaml \n"); 202 | return 1; 203 | } 204 | 205 | string config_file = argv[1]; 206 | printf("config_file: %s\n", argv[1]); 207 | 208 | readParameters(config_file); 209 | estimator.setParameter(); 210 | 211 | #ifdef EIGEN_DONT_PARALLELIZE 212 | ROS_DEBUG("EIGEN_DONT_PARALLELIZE"); 213 | #endif 214 | 215 | ROS_WARN("waiting for image and imu..."); 216 | 217 | registerPub(n); 218 | 219 | ros::Subscriber sub_imu; 220 | if(USE_IMU) 221 | { 222 | sub_imu = n.subscribe(IMU_TOPIC, 2000, imu_callback, ros::TransportHints().tcpNoDelay()); 223 | } 224 | ros::Subscriber sub_img0 = n.subscribe(IMAGE0_TOPIC, 100, img0_callback); 225 | ros::Subscriber sub_img1; 226 | if(STEREO) 227 | { 228 | sub_img1 = n.subscribe(IMAGE1_TOPIC, 100, img1_callback); 229 | } 230 | ros::Subscriber sub_restart = n.subscribe("/vins_restart", 100, restart_callback); 231 | ros::Subscriber sub_imu_switch = n.subscribe("/vins_imu_switch", 100, imu_switch_callback); 232 | ros::Subscriber sub_cam_switch = n.subscribe("/vins_cam_switch", 100, cam_switch_callback); 233 | 234 | std::thread sync_thread{sync_process}; 235 | ros::spin(); 236 | 237 | return 0; 238 | } 239 | -------------------------------------------------------------------------------- /vins_estimator/utility/CameraPoseVisualization.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #include "CameraPoseVisualization.h" 11 | 12 | const Eigen::Vector3d CameraPoseVisualization::imlt = Eigen::Vector3d(-1.0, -0.5, 1.0); 13 | const Eigen::Vector3d CameraPoseVisualization::imrt = Eigen::Vector3d( 1.0, -0.5, 1.0); 14 | const Eigen::Vector3d CameraPoseVisualization::imlb = Eigen::Vector3d(-1.0, 0.5, 1.0); 15 | const Eigen::Vector3d CameraPoseVisualization::imrb = Eigen::Vector3d( 1.0, 0.5, 1.0); 16 | const Eigen::Vector3d CameraPoseVisualization::lt0 = Eigen::Vector3d(-0.7, -0.5, 1.0); 17 | const Eigen::Vector3d CameraPoseVisualization::lt1 = Eigen::Vector3d(-0.7, -0.2, 1.0); 18 | const Eigen::Vector3d CameraPoseVisualization::lt2 = Eigen::Vector3d(-1.0, -0.2, 1.0); 19 | const Eigen::Vector3d CameraPoseVisualization::oc = Eigen::Vector3d(0.0, 0.0, 0.0); 20 | 21 | void Eigen2Point(const Eigen::Vector3d& v, geometry_msgs::Point& p) { 22 | p.x = v.x(); 23 | p.y = v.y(); 24 | p.z = v.z(); 25 | } 26 | 27 | CameraPoseVisualization::CameraPoseVisualization(float r, float g, float b, float a) 28 | : m_marker_ns("CameraPoseVisualization"), m_scale(0.2), m_line_width(0.01) { 29 | m_image_boundary_color.r = r; 30 | m_image_boundary_color.g = g; 31 | m_image_boundary_color.b = b; 32 | m_image_boundary_color.a = a; 33 | m_optical_center_connector_color.r = r; 34 | m_optical_center_connector_color.g = g; 35 | m_optical_center_connector_color.b = b; 36 | m_optical_center_connector_color.a = a; 37 | } 38 | 39 | void CameraPoseVisualization::setImageBoundaryColor(float r, float g, float b, float a) { 40 | m_image_boundary_color.r = r; 41 | m_image_boundary_color.g = g; 42 | m_image_boundary_color.b = b; 43 | m_image_boundary_color.a = a; 44 | } 45 | 46 | void CameraPoseVisualization::setOpticalCenterConnectorColor(float r, float g, float b, float a) { 47 | m_optical_center_connector_color.r = r; 48 | m_optical_center_connector_color.g = g; 49 | m_optical_center_connector_color.b = b; 50 | m_optical_center_connector_color.a = a; 51 | } 52 | 53 | void CameraPoseVisualization::setScale(double s) { 54 | m_scale = s; 55 | } 56 | void CameraPoseVisualization::setLineWidth(double width) { 57 | m_line_width = width; 58 | } 59 | void CameraPoseVisualization::add_edge(const Eigen::Vector3d& p0, const Eigen::Vector3d& p1){ 60 | visualization_msgs::Marker marker; 61 | 62 | marker.ns = m_marker_ns; 63 | marker.id = m_markers.size() + 1; 64 | marker.type = visualization_msgs::Marker::LINE_LIST; 65 | marker.action = visualization_msgs::Marker::ADD; 66 | marker.scale.x = 0.005; 67 | 68 | marker.color.g = 1.0f; 69 | marker.color.a = 1.0; 70 | 71 | geometry_msgs::Point point0, point1; 72 | 73 | Eigen2Point(p0, point0); 74 | Eigen2Point(p1, point1); 75 | 76 | marker.points.push_back(point0); 77 | marker.points.push_back(point1); 78 | 79 | m_markers.push_back(marker); 80 | } 81 | 82 | void CameraPoseVisualization::add_loopedge(const Eigen::Vector3d& p0, const Eigen::Vector3d& p1){ 83 | visualization_msgs::Marker marker; 84 | 85 | marker.ns = m_marker_ns; 86 | marker.id = m_markers.size() + 1; 87 | marker.type = visualization_msgs::Marker::LINE_LIST; 88 | marker.action = visualization_msgs::Marker::ADD; 89 | marker.scale.x = 0.04; 90 | //marker.scale.x = 0.3; 91 | 92 | marker.color.r = 1.0f; 93 | marker.color.b = 1.0f; 94 | marker.color.a = 1.0; 95 | 96 | geometry_msgs::Point point0, point1; 97 | 98 | Eigen2Point(p0, point0); 99 | Eigen2Point(p1, point1); 100 | 101 | marker.points.push_back(point0); 102 | marker.points.push_back(point1); 103 | 104 | m_markers.push_back(marker); 105 | } 106 | 107 | 108 | void CameraPoseVisualization::add_pose(const Eigen::Vector3d& p, const Eigen::Quaterniond& q) { 109 | visualization_msgs::Marker marker; 110 | 111 | marker.ns = m_marker_ns; 112 | marker.id = m_markers.size() + 1; 113 | marker.type = visualization_msgs::Marker::LINE_STRIP; 114 | marker.action = visualization_msgs::Marker::ADD; 115 | marker.scale.x = m_line_width; 116 | 117 | marker.pose.position.x = 0.0; 118 | marker.pose.position.y = 0.0; 119 | marker.pose.position.z = 0.0; 120 | marker.pose.orientation.w = 1.0; 121 | marker.pose.orientation.x = 0.0; 122 | marker.pose.orientation.y = 0.0; 123 | marker.pose.orientation.z = 0.0; 124 | 125 | 126 | geometry_msgs::Point pt_lt, pt_lb, pt_rt, pt_rb, pt_oc, pt_lt0, pt_lt1, pt_lt2; 127 | 128 | Eigen2Point(q * (m_scale *imlt) + p, pt_lt); 129 | Eigen2Point(q * (m_scale *imlb) + p, pt_lb); 130 | Eigen2Point(q * (m_scale *imrt) + p, pt_rt); 131 | Eigen2Point(q * (m_scale *imrb) + p, pt_rb); 132 | Eigen2Point(q * (m_scale *lt0 ) + p, pt_lt0); 133 | Eigen2Point(q * (m_scale *lt1 ) + p, pt_lt1); 134 | Eigen2Point(q * (m_scale *lt2 ) + p, pt_lt2); 135 | Eigen2Point(q * (m_scale *oc ) + p, pt_oc); 136 | 137 | // image boundaries 138 | marker.points.push_back(pt_lt); 139 | marker.points.push_back(pt_lb); 140 | marker.colors.push_back(m_image_boundary_color); 141 | marker.colors.push_back(m_image_boundary_color); 142 | 143 | marker.points.push_back(pt_lb); 144 | marker.points.push_back(pt_rb); 145 | marker.colors.push_back(m_image_boundary_color); 146 | marker.colors.push_back(m_image_boundary_color); 147 | 148 | marker.points.push_back(pt_rb); 149 | marker.points.push_back(pt_rt); 150 | marker.colors.push_back(m_image_boundary_color); 151 | marker.colors.push_back(m_image_boundary_color); 152 | 153 | marker.points.push_back(pt_rt); 154 | marker.points.push_back(pt_lt); 155 | marker.colors.push_back(m_image_boundary_color); 156 | marker.colors.push_back(m_image_boundary_color); 157 | 158 | // top-left indicator 159 | marker.points.push_back(pt_lt0); 160 | marker.points.push_back(pt_lt1); 161 | marker.colors.push_back(m_image_boundary_color); 162 | marker.colors.push_back(m_image_boundary_color); 163 | 164 | marker.points.push_back(pt_lt1); 165 | marker.points.push_back(pt_lt2); 166 | marker.colors.push_back(m_image_boundary_color); 167 | marker.colors.push_back(m_image_boundary_color); 168 | 169 | // optical center connector 170 | marker.points.push_back(pt_lt); 171 | marker.points.push_back(pt_oc); 172 | marker.colors.push_back(m_optical_center_connector_color); 173 | marker.colors.push_back(m_optical_center_connector_color); 174 | 175 | 176 | marker.points.push_back(pt_lb); 177 | marker.points.push_back(pt_oc); 178 | marker.colors.push_back(m_optical_center_connector_color); 179 | marker.colors.push_back(m_optical_center_connector_color); 180 | 181 | marker.points.push_back(pt_rt); 182 | marker.points.push_back(pt_oc); 183 | marker.colors.push_back(m_optical_center_connector_color); 184 | marker.colors.push_back(m_optical_center_connector_color); 185 | 186 | marker.points.push_back(pt_rb); 187 | marker.points.push_back(pt_oc); 188 | marker.colors.push_back(m_optical_center_connector_color); 189 | marker.colors.push_back(m_optical_center_connector_color); 190 | 191 | m_markers.push_back(marker); 192 | } 193 | 194 | void CameraPoseVisualization::reset() { 195 | m_markers.clear(); 196 | } 197 | 198 | void CameraPoseVisualization::publish_by( ros::Publisher &pub, const std_msgs::Header &header ) { 199 | visualization_msgs::MarkerArray markerArray_msg; 200 | 201 | for(auto& marker : m_markers) { 202 | marker.header = header; 203 | markerArray_msg.markers.push_back(marker); 204 | } 205 | 206 | pub.publish(markerArray_msg); 207 | } -------------------------------------------------------------------------------- /vins_estimator/utility/CameraPoseVisualization.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | class CameraPoseVisualization { 20 | public: 21 | std::string m_marker_ns; 22 | 23 | CameraPoseVisualization(float r, float g, float b, float a); 24 | 25 | void setImageBoundaryColor(float r, float g, float b, float a=1.0); 26 | void setOpticalCenterConnectorColor(float r, float g, float b, float a=1.0); 27 | void setScale(double s); 28 | void setLineWidth(double width); 29 | 30 | void add_pose(const Eigen::Vector3d& p, const Eigen::Quaterniond& q); 31 | void reset(); 32 | 33 | void publish_by(ros::Publisher& pub, const std_msgs::Header& header); 34 | void add_edge(const Eigen::Vector3d& p0, const Eigen::Vector3d& p1); 35 | void add_loopedge(const Eigen::Vector3d& p0, const Eigen::Vector3d& p1); 36 | private: 37 | std::vector m_markers; 38 | std_msgs::ColorRGBA m_image_boundary_color; 39 | std_msgs::ColorRGBA m_optical_center_connector_color; 40 | double m_scale; 41 | double m_line_width; 42 | 43 | static const Eigen::Vector3d imlt; 44 | static const Eigen::Vector3d imlb; 45 | static const Eigen::Vector3d imrt; 46 | static const Eigen::Vector3d imrb; 47 | static const Eigen::Vector3d oc ; 48 | static const Eigen::Vector3d lt0 ; 49 | static const Eigen::Vector3d lt1 ; 50 | static const Eigen::Vector3d lt2 ; 51 | }; 52 | -------------------------------------------------------------------------------- /vins_estimator/utility/tic_toc.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | 16 | class TicToc 17 | { 18 | public: 19 | TicToc() 20 | { 21 | tic(); 22 | } 23 | 24 | void tic() 25 | { 26 | start = std::chrono::system_clock::now(); 27 | } 28 | 29 | double toc() 30 | { 31 | end = std::chrono::system_clock::now(); 32 | std::chrono::duration elapsed_seconds = end - start; 33 | return elapsed_seconds.count() * 1000; 34 | } 35 | 36 | private: 37 | std::chrono::time_point start, end; 38 | }; 39 | -------------------------------------------------------------------------------- /vins_estimator/utility/utility.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #include "utility.h" 11 | 12 | Eigen::Matrix3d Utility::g2R(const Eigen::Vector3d &g) 13 | { 14 | Eigen::Matrix3d R0; 15 | Eigen::Vector3d ng1 = g.normalized(); 16 | Eigen::Vector3d ng2{0, 0, 1.0}; 17 | R0 = Eigen::Quaterniond::FromTwoVectors(ng1, ng2).toRotationMatrix(); 18 | double yaw = Utility::R2ypr(R0).x(); 19 | R0 = Utility::ypr2R(Eigen::Vector3d{-yaw, 0, 0}) * R0; 20 | // R0 = Utility::ypr2R(Eigen::Vector3d{-90, 0, 0}) * R0; 21 | return R0; 22 | } 23 | -------------------------------------------------------------------------------- /vins_estimator/utility/utility.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | 17 | class Utility 18 | { 19 | public: 20 | template 21 | static Eigen::Quaternion deltaQ(const Eigen::MatrixBase &theta) 22 | { 23 | typedef typename Derived::Scalar Scalar_t; 24 | 25 | Eigen::Quaternion dq; 26 | Eigen::Matrix half_theta = theta; 27 | half_theta /= static_cast(2.0); 28 | dq.w() = static_cast(1.0); 29 | dq.x() = half_theta.x(); 30 | dq.y() = half_theta.y(); 31 | dq.z() = half_theta.z(); 32 | return dq; 33 | } 34 | 35 | template 36 | static Eigen::Matrix skewSymmetric(const Eigen::MatrixBase &q) 37 | { 38 | Eigen::Matrix ans; 39 | ans << typename Derived::Scalar(0), -q(2), q(1), 40 | q(2), typename Derived::Scalar(0), -q(0), 41 | -q(1), q(0), typename Derived::Scalar(0); 42 | return ans; 43 | } 44 | 45 | template 46 | static Eigen::Quaternion positify(const Eigen::QuaternionBase &q) 47 | { 48 | //printf("a: %f %f %f %f", q.w(), q.x(), q.y(), q.z()); 49 | //Eigen::Quaternion p(-q.w(), -q.x(), -q.y(), -q.z()); 50 | //printf("b: %f %f %f %f", p.w(), p.x(), p.y(), p.z()); 51 | //return q.template w() >= (typename Derived::Scalar)(0.0) ? q : Eigen::Quaternion(-q.w(), -q.x(), -q.y(), -q.z()); 52 | return q; 53 | } 54 | 55 | template 56 | static Eigen::Matrix Qleft(const Eigen::QuaternionBase &q) 57 | { 58 | Eigen::Quaternion qq = positify(q); 59 | Eigen::Matrix ans; 60 | ans(0, 0) = qq.w(), ans.template block<1, 3>(0, 1) = -qq.vec().transpose(); 61 | ans.template block<3, 1>(1, 0) = qq.vec(), ans.template block<3, 3>(1, 1) = qq.w() * Eigen::Matrix::Identity() + skewSymmetric(qq.vec()); 62 | return ans; 63 | } 64 | 65 | template 66 | static Eigen::Matrix Qright(const Eigen::QuaternionBase &p) 67 | { 68 | Eigen::Quaternion pp = positify(p); 69 | Eigen::Matrix ans; 70 | ans(0, 0) = pp.w(), ans.template block<1, 3>(0, 1) = -pp.vec().transpose(); 71 | ans.template block<3, 1>(1, 0) = pp.vec(), ans.template block<3, 3>(1, 1) = pp.w() * Eigen::Matrix::Identity() - skewSymmetric(pp.vec()); 72 | return ans; 73 | } 74 | 75 | static Eigen::Vector3d R2ypr(const Eigen::Matrix3d &R) 76 | { 77 | Eigen::Vector3d n = R.col(0); 78 | Eigen::Vector3d o = R.col(1); 79 | Eigen::Vector3d a = R.col(2); 80 | 81 | Eigen::Vector3d ypr(3); 82 | double y = atan2(n(1), n(0)); 83 | double p = atan2(-n(2), n(0) * cos(y) + n(1) * sin(y)); 84 | double r = atan2(a(0) * sin(y) - a(1) * cos(y), -o(0) * sin(y) + o(1) * cos(y)); 85 | ypr(0) = y; 86 | ypr(1) = p; 87 | ypr(2) = r; 88 | 89 | return ypr / M_PI * 180.0; 90 | } 91 | 92 | template 93 | static Eigen::Matrix ypr2R(const Eigen::MatrixBase &ypr) 94 | { 95 | typedef typename Derived::Scalar Scalar_t; 96 | 97 | Scalar_t y = ypr(0) / 180.0 * M_PI; 98 | Scalar_t p = ypr(1) / 180.0 * M_PI; 99 | Scalar_t r = ypr(2) / 180.0 * M_PI; 100 | 101 | Eigen::Matrix Rz; 102 | Rz << cos(y), -sin(y), 0, 103 | sin(y), cos(y), 0, 104 | 0, 0, 1; 105 | 106 | Eigen::Matrix Ry; 107 | Ry << cos(p), 0., sin(p), 108 | 0., 1., 0., 109 | -sin(p), 0., cos(p); 110 | 111 | Eigen::Matrix Rx; 112 | Rx << 1., 0., 0., 113 | 0., cos(r), -sin(r), 114 | 0., sin(r), cos(r); 115 | 116 | return Rz * Ry * Rx; 117 | } 118 | 119 | static Eigen::Matrix3d g2R(const Eigen::Vector3d &g); 120 | 121 | template 122 | struct uint_ 123 | { 124 | }; 125 | 126 | template 127 | void unroller(const Lambda &f, const IterT &iter, uint_) 128 | { 129 | unroller(f, iter, uint_()); 130 | f(iter + N); 131 | } 132 | 133 | template 134 | void unroller(const Lambda &f, const IterT &iter, uint_<0>) 135 | { 136 | f(iter); 137 | } 138 | 139 | template 140 | static T normalizeAngle(const T& angle_degrees) { 141 | T two_pi(2.0 * 180); 142 | if (angle_degrees > 0) 143 | return angle_degrees - 144 | two_pi * std::floor((angle_degrees + T(180)) / two_pi); 145 | else 146 | return angle_degrees + 147 | two_pi * std::floor((-angle_degrees + T(180)) / two_pi); 148 | }; 149 | }; 150 | -------------------------------------------------------------------------------- /vins_estimator/utility/visualization.h: -------------------------------------------------------------------------------- 1 | /******************************************************* 2 | * Copyright (C) 2019, Aerial Robotics Group, Hong Kong University of Science and Technology 3 | * 4 | * This file is part of VINS. 5 | * 6 | * Licensed under the GNU General Public License v3.0; 7 | * you may not use this file except in compliance with the License. 8 | *******************************************************/ 9 | 10 | #pragma once 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | #include 25 | #include 26 | #include 27 | #include "CameraPoseVisualization.h" 28 | #include 29 | #include "../estimator/estimator.h" 30 | #include "../estimator/parameters.h" 31 | #include 32 | 33 | #include 34 | #include 35 | #include 36 | 37 | extern ros::Publisher pub_odometry; 38 | extern ros::Publisher pub_path, pub_pose; 39 | extern ros::Publisher pub_cloud, pub_map; 40 | extern ros::Publisher pub_key_poses; 41 | extern ros::Publisher pub_ref_pose, pub_cur_pose; 42 | extern ros::Publisher pub_key_frame_feat; 43 | extern ros::Publisher pub_key; 44 | extern nav_msgs::Path path; 45 | extern ros::Publisher pub_pose_graph; 46 | extern int IMAGE_ROW, IMAGE_COL; 47 | 48 | void registerPub(ros::NodeHandle &n); 49 | 50 | void pubLatestOdometry(const Eigen::Vector3d &P, const Eigen::Quaterniond &Q, const Eigen::Vector3d &V, double t); 51 | 52 | void pubTrackImage(const cv::Mat &imgTrack, const double t); 53 | 54 | void printStatistics(const Estimator &estimator, double t); 55 | 56 | void pubOdometry(const Estimator &estimator, const std_msgs::Header &header); 57 | 58 | void pubInitialGuess(const Estimator &estimator, const std_msgs::Header &header); 59 | 60 | void pubKeyPoses(const Estimator &estimator, const std_msgs::Header &header); 61 | 62 | void pubCameraPose(const Estimator &estimator, const std_msgs::Header &header); 63 | 64 | void pubPointCloud(const Estimator &estimator, const std_msgs::Header &header); 65 | 66 | void pubTF(const Estimator &estimator, const std_msgs::Header &header); 67 | 68 | void pubKeyframe(Estimator &estimator); 69 | 70 | void pubRelocalization(const Estimator &estimator); 71 | 72 | void pubCar(const Estimator & estimator, const std_msgs::Header &header); 73 | --------------------------------------------------------------------------------