├── .gitignore ├── DM-VIO ├── camchain_kaistvio.yaml ├── camera_kaistvio.txt ├── dm_vio.rviz ├── setting_kaistvio.yaml └── visualizer.py ├── EnVIO ├── camchain-imucam-kaistviodataset.yaml ├── nesl_envio_kaistviodataset.launch └── nesl_euroc.rviz ├── LICENSE ├── NVIDIA_Isaac_Elbrus └── elbrus.launch.py ├── ORB-SLAM2 ├── flightgoggles │ ├── flight-stereo.launch │ ├── flight_new.launch │ └── flightstereo.yaml └── inteld435i │ ├── d435i-stereo.launch │ ├── emitter_disabled_60fps.json │ ├── inteld435i.yaml │ └── rs_camera.launch ├── OpenGLHeader.patch ├── OpenVINS └── kaist.launch ├── README.md ├── ROVIO ├── d435i │ ├── CMakeLists.txt │ ├── d435i_rovio.info │ ├── d435i_rovio_node.launch │ ├── emitter_disabled_60fps.json │ ├── hector_trajectory_server.cpp │ ├── rovio_cam1.yaml │ ├── rovio_cam2.yaml │ ├── rovio_rviz_config.rviz │ └── rs_camera.launch ├── flightgoggles-rovio │ ├── CMakeLists.txt │ ├── cam-flight.yaml │ ├── flight.info │ ├── flight640480.info │ ├── flight640480.launch │ ├── rovio_cam1.yaml │ ├── rovio_cam1640480.yaml │ ├── rovioflight.launch │ ├── rviz.rviz │ └── scripts │ │ ├── rgb2gray.py │ │ └── simple_angle_control.py └── pointgrey_myahrs │ ├── camera.launch │ ├── pt_rovio_node.launch │ ├── rovio_ptcam.yaml │ └── rovio_ptmy.info ├── VINS-Fusion ├── left.yaml ├── right.yaml └── vins_kaistvio.yaml ├── camera_models ├── CMakeLists.txt ├── camera_calib_example │ ├── calibrationdata │ │ ├── left-0000.png │ │ ├── left-0001.png │ │ ├── left-0002.png │ │ ├── left-0003.png │ │ ├── left-0004.png │ │ ├── left-0005.png │ │ ├── left-0006.png │ │ ├── left-0007.png │ │ ├── left-0008.png │ │ ├── left-0009.png │ │ ├── left-0010.png │ │ ├── left-0011.png │ │ ├── left-0012.png │ │ ├── left-0013.png │ │ ├── left-0014.png │ │ ├── left-0015.png │ │ ├── left-0016.png │ │ ├── left-0017.png │ │ ├── left-0018.png │ │ ├── left-0019.png │ │ ├── left-0020.png │ │ ├── left-0021.png │ │ ├── left-0022.png │ │ ├── left-0023.png │ │ ├── left-0024.png │ │ ├── left-0025.png │ │ ├── left-0026.png │ │ ├── left-0027.png │ │ ├── left-0028.png │ │ ├── left-0029.png │ │ ├── left-0030.png │ │ ├── left-0031.png │ │ ├── left-0032.png │ │ ├── left-0033.png │ │ ├── left-0034.png │ │ ├── left-0035.png │ │ ├── left-0036.png │ │ ├── left-0037.png │ │ ├── left-0038.png │ │ ├── left-0039.png │ │ ├── left-0040.png │ │ ├── left-0041.png │ │ ├── left-0042.png │ │ ├── left-0043.png │ │ ├── left-0044.png │ │ ├── left-0045.png │ │ ├── left-0046.png │ │ ├── left-0047.png │ │ ├── left-0048.png │ │ ├── left-0049.png │ │ ├── left-0050.png │ │ ├── left-0051.png │ │ ├── left-0052.png │ │ ├── left-0053.png │ │ ├── left-0054.png │ │ ├── left-0055.png │ │ ├── left-0056.png │ │ ├── left-0057.png │ │ ├── left-0058.png │ │ ├── left-0059.png │ │ ├── left-0060.png │ │ ├── left-0061.png │ │ ├── left-0062.png │ │ ├── left-0063.png │ │ ├── left-0064.png │ │ ├── left-0065.png │ │ ├── left-0066.png │ │ ├── left-0067.png │ │ ├── left-0068.png │ │ ├── left-0069.png │ │ ├── left-0070.png │ │ ├── left-0071.png │ │ ├── left-0072.png │ │ ├── left-0073.png │ │ ├── left-0074.png │ │ ├── left-0075.png │ │ ├── left-0076.png │ │ ├── left-0077.png │ │ ├── left-0078.png │ │ ├── left-0079.png │ │ ├── left-0080.png │ │ ├── left-0081.png │ │ ├── left-0082.png │ │ ├── left-0083.png │ │ └── left-0084.png │ └── readme.txt ├── cmake │ └── FindEigen.cmake ├── include │ └── camodocal │ │ ├── calib │ │ └── CameraCalibration.h │ │ ├── camera_models │ │ ├── Camera.h │ │ ├── CameraFactory.h │ │ ├── CataCamera.h │ │ ├── CostFunctionFactory.h │ │ ├── EquidistantCamera.h │ │ ├── PinholeCamera.h │ │ ├── PinholeFullCamera.h │ │ └── ScaramuzzaCamera.h │ │ ├── chessboard │ │ ├── Chessboard.h │ │ ├── ChessboardCorner.h │ │ ├── ChessboardQuad.h │ │ └── Spline.h │ │ ├── gpl │ │ ├── EigenQuaternionParameterization.h │ │ ├── EigenUtils.h │ │ └── gpl.h │ │ └── sparse_graph │ │ └── Transform.h ├── package.xml ├── readme.md └── src │ ├── calib │ └── CameraCalibration.cc │ ├── camera_models │ ├── Camera.cc │ ├── CameraFactory.cc │ ├── CataCamera.cc │ ├── CostFunctionFactory.cc │ ├── EquidistantCamera.cc │ ├── PinholeCamera.cc │ ├── PinholeFullCamera.cc │ └── ScaramuzzaCamera.cc │ ├── chessboard │ └── Chessboard.cc │ ├── gpl │ ├── EigenQuaternionParameterization.cc │ └── gpl.cc │ ├── intrinsic_calib.cc │ └── sparse_graph │ └── Transform.cc ├── extrinsic.png ├── imu.yaml ├── pitching.png ├── s-msckf_flightgoggles ├── camchain-imucam-flightgoggles.yaml ├── flightgoggles.launch ├── image_processor_flightgoggles.launch └── msckf_vio.cpp ├── vins-fusion-px4 ├── README.md ├── loop_fusion │ ├── CMakeLists.txt │ ├── cmake │ │ └── FindEigen.cmake │ ├── package.xml │ └── src │ │ ├── ThirdParty │ │ ├── DBoW │ │ │ ├── BowVector.cpp │ │ │ ├── BowVector.h │ │ │ ├── DBoW2.h │ │ │ ├── FBrief.cpp │ │ │ ├── FBrief.h │ │ │ ├── FClass.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 │ │ ├── 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 ├── mask_img.jpg ├── masking.m ├── support_files │ ├── brief_k10L6.bin │ └── brief_pattern.yml ├── vins.yaml └── vins_estimator │ ├── CMakeLists.txt │ ├── cmake │ └── FindEigen.cmake │ ├── launch │ └── vins_rviz.launch │ ├── package.xml │ └── src │ ├── KITTIGPSTest.cpp │ ├── KITTIOdomTest.cpp │ ├── 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 │ ├── 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 └── vins_estimator ├── CMakeLists.txt ├── cmake └── FindEigen.cmake ├── launch └── vins_rviz.launch ├── package.xml └── src ├── 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 ├── 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 | DM-VIO/babiasdso.txt 2 | DM-VIO/bagravdir.txt 3 | DM-VIO/bavel.txt 4 | DM-VIO/coarsebiasdso.txt 5 | DM-VIO/logs/ 6 | DM-VIO/mats/ 7 | DM-VIO/result.txt 8 | DM-VIO/scalesdso.txt 9 | DM-VIO/timings.txt 10 | DM-VIO/usedSettingsdso.txt 11 | -------------------------------------------------------------------------------- /DM-VIO/camchain_kaistvio.yaml: -------------------------------------------------------------------------------- 1 | cam0: 2 | T_cam_imu: 3 | - [-0.04030123999740945, -0.9989998755524683, 0.01936643232049068, 0.02103955032447366] 4 | - [0.026311325355146964, -0.020436499663524704, -0.9994448777394171, -0.038224929976612206] 5 | - [0.9988410905708309, -0.0397693113802049, 0.027108627033059024, -0.1363488241088845] 6 | - [0.0, 0.0, 0.0, 1.0] 7 | # - [-0.040301239997409, 0.026311325355147, 0.998841090570831, 0.138044476707325] 8 | # - [-0.998999875552468, -0.020436499663525, -0.039769311380205, 0.014814825544913] 9 | # - [0.019366432320491, -0.999444877739417, 0.027108627033059, -0.034914942075322] 10 | # - [0.0, 0.0, 0.0, 1.0] 11 | -------------------------------------------------------------------------------- /DM-VIO/camera_kaistvio.txt: -------------------------------------------------------------------------------- 1 | RadTan 380.9229090195708 380.29264802262736 324.68121181846755 224.6741321466431 0.006896928127777268 -0.009144207062654397 0.000254113977103925 0.0021434982252719545 2 | 640 480 3 | none 4 | 640 480 5 | -------------------------------------------------------------------------------- /DM-VIO/setting_kaistvio.yaml: -------------------------------------------------------------------------------- 1 | accelerometer_noise_density: 0.224 2 | gyroscope_noise_density: 0.01280 3 | accelerometer_random_walk: 0.0430 4 | gyroscope_random_walk: 0.00110 5 | integration_sigma: 0.316227 6 | maxSkipFramesVisualOnlyMode: 1 # This many frames can be skipped at a time while in visual-only mode. 7 | maxSkipFramesVisualInertial: 2 # This many frames can be skipped at a time while in visual-inertial mode. 8 | skipFramesVisualOnlyDelay: 30 # After visual initializer finished, wait this amount of frames before switching to the visualOnly threshold. This is useful because during the first frames the system might be less stable than later. 9 | minQueueSizeForSkipping: 2 # Don't skip frames if the image queue is smaller than this. 10 | maxTimeBetweenInitFrames: 1.0 # Reset the visual initializer if this time has passed between the first and last frame. 11 | init_pgba_skipFirstKFs: 1 12 | init_requestFullResetNormalizedErrorThreshold: 0.1 # If the error after the CoarseIMUInit is larger than this we assume the visual system failed and reset the full system. 13 | # With the following settings, VIO is initialized a bit earlier (default values in comment behind it). 14 | # To adjust these settings you can read the CoarseIMUInit scale and variance printed out by the system and see with which variance it typically outputs a reasonable scale. 15 | init_coarseScaleUncertaintyThresh: 5 # 1.0 16 | init_pgba_scaleUncertaintyThresh: 5 # 1.0 17 | init_pgba_reinitScaleUncertaintyThresh: 1 # 0.5 18 | # If you are sure that no clouds will cover a large part of the image you can include points with any depth by enabling the following line. 19 | # setting_minIdepth: 0.0 20 | 21 | 22 | ### Visualization 23 | normalizeCamSize: 0.3 # Sets the size of the displayed camera (normalized with the scale obtained from IMU data). 24 | KFCam: 1 25 | CurrCam: 1 26 | Trajectory: 0 27 | FullTrajectory: 1 28 | -------------------------------------------------------------------------------- /DM-VIO/visualizer.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | # -*- coding: utf-8 -*- 3 | """ 4 | Created on Tue May 19 00:28:30 2020 5 | 6 | @author: mason 7 | """ 8 | 9 | ''' import libraries ''' 10 | import rospy 11 | from nav_msgs.msg import Path 12 | from geometry_msgs.msg import PoseStamped 13 | from sensor_msgs.msg import Image, Imu 14 | 15 | import sys 16 | import signal 17 | 18 | def signal_handler(signal, frame): # ctrl + c -> exit program 19 | print('You pressed Ctrl+C!') 20 | sys.exit(0) 21 | signal.signal(signal.SIGINT, signal_handler) 22 | 23 | 24 | ''' class ''' 25 | 26 | class visualizer(): 27 | def __init__(self): 28 | rospy.init_node('path_pubb', anonymous=True) 29 | self.imu_pub = rospy.Publisher("/imu0", Imu, queue_size=1) 30 | self.img_pub = rospy.Publisher("/cam0/image_raw", Image, queue_size=1) 31 | self.imu_sub = rospy.Subscriber("/mavros/imu/data", Imu, self.imu_cb) 32 | self.img_sub = rospy.Subscriber("/camera/infra1/image_rect_raw", Image, self.img_cb) 33 | 34 | self.gt_sub = rospy.Subscriber("/pose_transformed", PoseStamped, self.gt_cb) 35 | self.gt_path_pub = rospy.Publisher("/gt_path", Path, queue_size=1) 36 | self.dmvio_sub = rospy.Subscriber("/dmvio/metric_pose", PoseStamped, self.pose_cb) 37 | self.dmvio_path_pub = rospy.Publisher("/dmvio_path", Path, queue_size=1) 38 | 39 | self.rate = rospy.Rate(1) 40 | 41 | self.gt_path = Path() 42 | self.gt_path.header.frame_id = "world" 43 | self.gt_counter=0 44 | self.dmvio_path = Path() 45 | self.dmvio_path.header.frame_id = "world" 46 | self.dmvio_counter=0 47 | 48 | def imu_cb(self, msg): 49 | self.imu_pub.publish(msg) 50 | def img_cb(self, msg): 51 | self.img_pub.publish(msg) 52 | 53 | def gt_cb(self, msg): 54 | self.gt_counter = self.gt_counter+1 55 | if self.gt_counter % 10 == 0: 56 | self.gt_path.poses.append(msg) 57 | self.gt_path_pub.publish(self.gt_path) 58 | 59 | def pose_cb(self, msg): 60 | self.dmvio_counter = self.dmvio_counter+1 61 | if self.dmvio_counter % 2 == 0: 62 | self.dmvio_path.poses.append(msg) 63 | self.dmvio_path_pub.publish(self.dmvio_path) 64 | 65 | ''' main ''' 66 | vis_ = visualizer() 67 | 68 | if __name__ == '__main__': 69 | while 1: 70 | try: 71 | vis_.rate.sleep() 72 | except (rospy.ROSInterruptException, SystemExit, KeyboardInterrupt) : 73 | sys.exit(0) 74 | # except: 75 | # print("exception") 76 | # pass 77 | -------------------------------------------------------------------------------- /EnVIO/camchain-imucam-kaistviodataset.yaml: -------------------------------------------------------------------------------- 1 | # kaistvio dataset yaml file 2 | 3 | cam0: 4 | T_cam_imu: 5 | [-0.04030123999740945, -0.9989998755524683, 0.01936643232049068, 0.02103955032447366, 6 | 0.026311325355146964, -0.020436499663524704, -0.9994448777394171, -0.038224929976612206, 7 | 0.9988410905708309, -0.0397693113802049, 0.027108627033059024, -0.1363488241088845, 8 | 0.0, 0.0, 0.0, 1.0] 9 | cam_overlaps: [1] 10 | camera_model: pinhole 11 | distortion_coeffs: [0.006896928127777268, -0.009144207062654397, 0.000254113977103925, 0.0021434982252719545] 12 | distortion_model: radtan 13 | intrinsics: [380.9229090195708, 380.29264802262736, 324.68121181846755, 224.6741321466431] 14 | resolution: [640, 480] 15 | rostopic: /camera/infra1/image_rect_raw 16 | timeshift_cam_imu: -0.029958533056650416 17 | cam1: 18 | T_cam_imu: 19 | [-0.03905752472566068, -0.9990498568899562, 0.019336318430946575, -0.02909273113160158, 20 | 0.025035478432625047, -0.020323396666370924, -0.9994799569614147, -0.03811090793611019, 21 | 0.99892328763622, -0.03855311914877835, 0.02580547271309183, -0.13656684822705098, 22 | 0.0, 0.0, 0.0, 1.0] 23 | T_cn_cnm1: 24 | [0.9999992248836708, 6.384241340452582e-05, 0.0012434452955667624, -0.049960282472300055, 25 | -6.225102643531651e-05, 0.9999991790958949, -0.0012798173093508036, -5.920119010064575e-05, 26 | -0.001243525981443161, 0.0012797389115975439, 0.9999984079544582, -0.00014316003395349448, 27 | 0.0, 0.0, 0.0, 1.0] 28 | cam_overlaps: [0] 29 | camera_model: pinhole 30 | distortion_coeffs: [0.007044055287844759, -0.010251485722185347, 0.0006674304399871926, 0.001678899816379666] 31 | distortion_model: radtan 32 | intrinsics: [380.95187095303424, 380.3065956074995, 324.0678433553536, 225.9586983198407] 33 | resolution: [640, 480] 34 | rostopic: /camera/infra2/image_rect_raw 35 | timeshift_cam_imu: -0.030340187355085417 36 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2022, EungChang-Mason-Lee 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /NVIDIA_Isaac_Elbrus/elbrus.launch.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2021, NVIDIA CORPORATION. All rights reserved. 2 | # 3 | # NVIDIA CORPORATION and its licensors retain all intellectual property 4 | # and proprietary rights in and to this software, related documentation 5 | # and any modifications thereto. Any use, reproduction, disclosure or 6 | # distribution of this software and related documentation without an express 7 | # license agreement from NVIDIA CORPORATION is strictly prohibited. 8 | 9 | import launch 10 | 11 | from launch_ros.actions import ComposableNodeContainer, Node 12 | from launch_ros.descriptions import ComposableNode 13 | 14 | 15 | def generate_launch_description(): 16 | ld = launch.LaunchDescription() 17 | 18 | visual_slam_node = ComposableNode( 19 | name='visual_slam_node', 20 | package='isaac_ros_visual_slam', 21 | plugin='isaac_ros::visual_slam::VisualSlamNode', 22 | parameters=[{ 23 | 'enable_rectified_pose': True, 24 | 'denoise_input_images': False, 25 | 'rectified_images': True, 26 | 'enable_debug_mode': False, 27 | 'debug_dump_path': '/tmp/elbrus', 28 | 'enable_slam_visualization': True, 29 | 'enable_landmarks_view': True, 30 | 'enable_observations_view': True, 31 | 'map_frame': 'map', 32 | 'odom_frame': 'odom', 33 | 'base_frame': 'camera_link', 34 | 'input_left_camera_frame': 'camera_infra1_frame', 35 | 'input_right_camera_frame': 'camera_infra2_frame', 36 | 'path_max_size': 8192 37 | }], 38 | remappings=[('stereo_camera/left/image', '/camera/infra1/image_rect_raw'), 39 | ('stereo_camera/left/camera_info', '/camera/infra1/camera_info'), 40 | ('stereo_camera/right/image', '/camera/infra2/image_rect_raw'), 41 | ('stereo_camera/right/camera_info', '/camera/infra2/camera_info')] 42 | ) 43 | 44 | visual_slam_launch_container = ComposableNodeContainer( 45 | name='visual_slam_launch_container', 46 | namespace='', 47 | package='rclcpp_components', 48 | executable='component_container', 49 | #prefix=['xterm -e gdb -ex run --args'], 50 | composable_node_descriptions=[ 51 | visual_slam_node 52 | ], 53 | output='screen' 54 | ) 55 | 56 | 57 | node1 = Node(package = "tf2_ros", 58 | executable = "static_transform_publisher", 59 | arguments = ["0", "0", "0", "0", "0", "0", "camera_link", "camera_infra1_frame"]) 60 | node2 = Node(package = "tf2_ros", 61 | executable = "static_transform_publisher", 62 | arguments = ["0", "-0.050198", "0", "0", "0", "0", "camera_link", "camera_infra2_frame"]) 63 | 64 | ld.add_action(visual_slam_launch_container) 65 | ld.add_action(node1) 66 | ld.add_action(node2) 67 | 68 | return ld 69 | -------------------------------------------------------------------------------- /ORB-SLAM2/flightgoggles/flight-stereo.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /ORB-SLAM2/flightgoggles/flight_new.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 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 | -------------------------------------------------------------------------------- /ORB-SLAM2/flightgoggles/flightstereo.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | 3 | # Camera calibration and distortion parameters (OpenCV) 4 | 5 | Camera.fx: 385.5999 6 | Camera.fy: 385.5999 7 | Camera.cx: 360.0 8 | Camera.cy: 270.0 9 | 10 | Camera.k1: 0.0 11 | Camera.k2: 0.0 12 | Camera.p1: 0.0 13 | Camera.p2: 0.0 14 | Camera.k3: 0.0 15 | 16 | Camera.width: 720 17 | Camera.height: 540 18 | 19 | # Camera frames per second 20 | Camera.fps: 60.0 21 | 22 | # stereo baseline (distance between cameras in m?) times fx 23 | Camera.bf: 123.3919 # 40 24 | 25 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) 26 | Camera.RGB: 0 27 | 28 | # Close/Far threshold. Baseline times. 29 | ThDepth: 40 # what is this? 30 | 31 | # seen elsewhere... what is this? 32 | #DepthMapFactor: 1000.0 33 | 34 | #-------------------------------------------------------------------------------------------- 35 | # ORB Parameters 36 | #-------------------------------------------------------------------------------------------- 37 | 38 | # ORB Extractor: Number of features per image 39 | ORBextractor.nFeatures: 1200 40 | 41 | # ORB Extractor: Scale factor between levels in the scale pyramid 42 | ORBextractor.scaleFactor: 1.2 43 | 44 | # ORB Extractor: Number of levels in the scale pyramid 45 | ORBextractor.nLevels: 8 46 | 47 | # ORB Extractor: Fast threshold 48 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. 49 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST 50 | # You can lower these values if your images have low contrast 51 | ORBextractor.iniThFAST: 20 52 | ORBextractor.minThFAST: 7 53 | -------------------------------------------------------------------------------- /ORB-SLAM2/inteld435i/d435i-stereo.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /ORB-SLAM2/inteld435i/inteld435i.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | 3 | # Camera calibration and distortion parameters (OpenCV) 4 | 5 | Camera.fx: 391.3 6 | Camera.fy: 390.67 7 | Camera.cx: 328.86 8 | Camera.cy: 244.25 9 | 10 | Camera.k1: 0.01 11 | Camera.k2: -0.0001 12 | Camera.p1: 0.0023 13 | Camera.p2: 0.0028 14 | Camera.k3: 0.0 15 | 16 | Camera.width: 640 17 | Camera.height: 480 18 | 19 | # Camera frames per second 20 | Camera.fps: 60.0 21 | 22 | # stereo baseline (distance between cameras in m?) times fx 23 | Camera.bf: 19.565 # 40 24 | 25 | # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) 26 | Camera.RGB: 0 27 | 28 | # Close/Far threshold. Baseline times. 29 | ThDepth: 40 # what is this? 30 | 31 | # seen elsewhere... what is this? 32 | #DepthMapFactor: 1000.0 33 | 34 | #-------------------------------------------------------------------------------------------- 35 | # ORB Parameters 36 | #-------------------------------------------------------------------------------------------- 37 | 38 | # ORB Extractor: Number of features per image 39 | ORBextractor.nFeatures: 1200 40 | 41 | # ORB Extractor: Scale factor between levels in the scale pyramid 42 | ORBextractor.scaleFactor: 1.2 43 | 44 | # ORB Extractor: Number of levels in the scale pyramid 45 | ORBextractor.nLevels: 8 46 | 47 | # ORB Extractor: Fast threshold 48 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. 49 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST 50 | # You can lower these values if your images have low contrast 51 | ORBextractor.iniThFAST: 20 52 | ORBextractor.minThFAST: 7 53 | -------------------------------------------------------------------------------- /OpenGLHeader.patch: -------------------------------------------------------------------------------- 1 | diff --git a/cuda_gl_interop.h b/cuda_gl_interop.h 2 | index 0f4aa17..e8c538c 100644 3 | --- a/cuda_gl_interop.h 4 | +++ b/cuda_gl_interop.h 5 | @@ -59,13 +59,13 @@ 6 | 7 | #else /* __APPLE__ */ 8 | 9 | -#if defined(__arm__) || defined(__aarch64__) 10 | -#ifndef GL_VERSION 11 | -#error Please include the appropriate gl headers before including cuda_gl_interop.h 12 | -#endif 13 | -#else 14 | +//#if defined(__arm__) || defined(__aarch64__) 15 | +//#ifndef GL_VERSION 16 | +//#error Please include the appropriate gl headers before including cuda_gl_interop.h 17 | +//#endif 18 | +//#else 19 | #include 20 | -#endif 21 | +//#endif 22 | 23 | #endif /* __APPLE__ */ 24 | -------------------------------------------------------------------------------- /ROVIO/d435i/d435i_rovio_node.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /ROVIO/d435i/rovio_cam1.yaml: -------------------------------------------------------------------------------- 1 | image_width: 640 2 | image_height: 480 3 | camera_name: cam1 4 | camera_matrix: 5 | rows: 3 6 | cols: 3 7 | data: [391.351108945, 0.0, 329.166066519, 0.0, 390.748509835, 244.176384407, 0.0, 0.0, 1.0] 8 | distortion_model: plumb_bob 9 | distortion_coefficients: 10 | rows: 1 11 | cols: 5 12 | data: [0.00983000225152, 0.00051267917248, 0.00234779532547, 0.00313474198775, 0.0] 13 | 14 | -------------------------------------------------------------------------------- /ROVIO/d435i/rovio_cam2.yaml: -------------------------------------------------------------------------------- 1 | image_width: 640 2 | image_height: 480 3 | camera_name: cam2 4 | camera_matrix: 5 | rows: 3 6 | cols: 3 7 | data: [391.264660077, 0.0, 328.524505429, 0.0, 390.587456319, 244.345194454, 0.0, 0.0, 1.0] 8 | distortion_model: plumb_bob 9 | distortion_coefficients: 10 | rows: 1 11 | cols: 5 12 | data: [0.0103635965474, -0.000818868598708, 0.00238270254234, 0.00260454741479, 0.0] 13 | 14 | -------------------------------------------------------------------------------- /ROVIO/flightgoggles-rovio/cam-flight.yaml: -------------------------------------------------------------------------------- 1 | cam0: 2 | T_cam_imu: 3 | - [0.0, 0.0, 1.0, 0.0] 4 | - [-1.0, 0.0, 0.0, 0.0] 5 | - [0.0, -1.0, 0.0, 0.0] 6 | - [0.0, 0.0, 0.0, 1.0] 7 | cam_overlaps: [0] 8 | camera_model: pinhole 9 | distortion_coeffs: [0.0, 0.0, 0.0, 10 | 0.0] 11 | distortion_model: radtan 12 | intrinsics: [385.5999755859375, 385.5999755859375, 360.0, 270.0] 13 | resolution: [720, 540] 14 | rostopic: /image_mono 15 | timeshift_cam_imu: -0.0 16 | -------------------------------------------------------------------------------- /ROVIO/flightgoggles-rovio/flight640480.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /ROVIO/flightgoggles-rovio/rovio_cam1.yaml: -------------------------------------------------------------------------------- 1 | image_width: 720 2 | image_height: 540 3 | camera_name: cam1 4 | camera_matrix: 5 | rows: 3 6 | cols: 3 7 | data: [385.5999755859375, 0.0, 360.0, 0.0, 385.5999755859375, 270.0, 0.0, 0.0, 1.0] 8 | distortion_model: plumb_bob 9 | distortion_coefficients: 10 | rows: 1 11 | cols: 5 12 | data: [0.0, 0.0, 0.0, 0.0, 0.0] 13 | 14 | -------------------------------------------------------------------------------- /ROVIO/flightgoggles-rovio/rovio_cam1640480.yaml: -------------------------------------------------------------------------------- 1 | image_width: 640 2 | image_height: 480 3 | camera_name: cam1 4 | camera_matrix: 5 | rows: 3 6 | cols: 3 7 | data: [342.7555236816406, 0.0, 320.0, 0.0, 342.7555236816406, 240.0, 0.0, 0.0, 1.0] 8 | distortion_model: plumb_bob 9 | distortion_coefficients: 10 | rows: 1 11 | cols: 5 12 | data: [0.0, 0.0, 0.0, 0.0, 0.0] 13 | -------------------------------------------------------------------------------- /ROVIO/flightgoggles-rovio/rovioflight.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /ROVIO/flightgoggles-rovio/scripts/rgb2gray.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | # -*- coding: utf-8 -*- 3 | 4 | import time 5 | import rospy 6 | import cv2 7 | import sys 8 | import signal 9 | 10 | from sensor_msgs.msg import Image 11 | from sensor_msgs.msg import CompressedImage 12 | from sensor_msgs.msg import Imu 13 | from cv_bridge import CvBridge, CvBridgeError 14 | 15 | 16 | def signal_handler(signal, frame): # ctrl + c -> exit program 17 | print('You pressed Ctrl+C!') 18 | sys.exit(0) 19 | signal.signal(signal.SIGINT, signal_handler) 20 | 21 | 22 | class robot(): 23 | def __init__(self): 24 | rospy.init_node('robot_controller', anonymous=True) 25 | #self.img_subscriber = rospy.Subscriber('/raspicam_node/image/compressed',CompressedImage,self.callback_compressed_img) 26 | self.img_publisher = rospy.Publisher('/image_mono',Image,queue_size=1) 27 | self.img_subscriber = rospy.Subscriber('/uav/camera/left/image_rect_color',Image,self.callback) 28 | self.imu_subscriber = rospy.Subscriber('/uav/sensors/imu', Imu, self.imu_callback) 29 | self.imu_publisher = rospy.Publisher('/imu_data', Imu, queue_size=1) 30 | self.bridge = CvBridge() 31 | 32 | # def callback_compressed_img(self,data): 33 | # np_arr = np.fromstring(data.data, np.uint8) 34 | # self.image_np = cv2.imdecode(np_arr, cv2.IMREAD_COLOR) # OpenCV >= 3.0: 35 | 36 | def callback(self,data): 37 | try : 38 | # self.time = time.time() 39 | cvimage=self.bridge.imgmsg_to_cv2(data,"bgr8") 40 | 41 | cv_image=cv2.cvtColor(cvimage,cv2.COLOR_BGR2GRAY) 42 | 43 | img=self.bridge.cv2_to_imgmsg(cv_image, "mono8") 44 | 45 | img.header.stamp = rospy.Time.now() 46 | self.img_publisher.publish(img) 47 | # print(time.time()-self.time) 48 | except CvBridgeError as e: 49 | pass 50 | 51 | def imu_callback(self,data): 52 | data.header.stamp = rospy.Time.now() 53 | self.imu_publisher.publish(data) 54 | 55 | if __name__=='__main__': 56 | gray=robot() 57 | time.sleep(1) 58 | while 1: 59 | pass 60 | -------------------------------------------------------------------------------- /ROVIO/pointgrey_myahrs/camera.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 19 | 20 | 21 | 22 | 24 | 25 | 26 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /ROVIO/pointgrey_myahrs/pt_rovio_node.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /ROVIO/pointgrey_myahrs/rovio_ptcam.yaml: -------------------------------------------------------------------------------- 1 | image_width: 1288 2 | image_height: 964 3 | camera_name: cama 4 | camera_matrix: 5 | rows: 3 6 | cols: 3 7 | data: [1470.04952381, 0.0, 673.513447492, 0.0, 1467.95252459, 483.078434589, 0.0, 0.0, 1.0] 8 | distortion_model: plumb_bob 9 | distortion_coefficients: 10 | rows: 1 11 | cols: 5 12 | data: [-0.1027464124, 0.210335325835, -0.00164239121263, 0.00183980066445, 0.0] 13 | 14 | -------------------------------------------------------------------------------- /VINS-Fusion/left.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | --- 3 | model_type: PINHOLE 4 | camera_name: camera 5 | image_width: 640 6 | image_height: 480 7 | distortion_parameters: 8 | k1: 0.006896928127777268 9 | k2: -0.009144207062654397 10 | p1: 0.000254113977103925 11 | p2: 0.0021434982252719545 12 | projection_parameters: 13 | fx: 380.9229090195708 14 | fy: 380.29264802262736 15 | cx: 324.68121181846755 16 | cy: 224.6741321466431 17 | -------------------------------------------------------------------------------- /VINS-Fusion/right.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | --- 3 | model_type: PINHOLE 4 | camera_name: camera 5 | image_width: 640 6 | image_height: 480 7 | distortion_parameters: 8 | k1: 0.007044055287844759 9 | k2: -0.010251485722185347 10 | p1: 0.0006674304399871926 11 | p2: 0.001678899816379666 12 | projection_parameters: 13 | fx: 380.95187095303424 14 | fy: 380.3065956074995 15 | cx: 324.0678433553536 16 | cy: 225.9586983198407 17 | -------------------------------------------------------------------------------- /VINS-Fusion/vins_kaistvio.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: "/mavros/imu/data" 9 | image0_topic: "/camera/infra1/image_rect_raw" 10 | image1_topic: "/camera/infra2/image_rect_raw" 11 | output_path: "/home/dji/output/" 12 | 13 | cam0_calib: "left.yaml" 14 | cam1_calib: "right.yaml" 15 | image_width: 640 16 | image_height: 480 17 | 18 | 19 | # Extrinsic parameter between IMU and Camera. 20 | estimate_extrinsic: 1 # 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.040301239997409, 0.026311325355147, 0.998841090570831, 0.138044476707325, -0.998999875552468, -0.020436499663525, -0.039769311380205, 0.014814825544913, 0.019366432320491, -0.999444877739417, 0.027108627033059, -0.034914942075322, 0., 0., 0., 1. ] 28 | 29 | body_T_cam1: !!opencv-matrix 30 | rows: 4 31 | cols: 4 32 | dt: d 33 | data: [ -0.039057524725661, 0.025035478432625, 0.998923287636220, 0.136237639761255, -0.999049856889956, -0.020323396666371, -0.038553119148778, -0.035104709944336, 0.019336318430947, -0.999479956961414, 0.025805472713092, -0.034004370235121, 0., 0., 0., 1. ] 34 | 35 | #Multiple thread support 36 | multiple_thread: 1 37 | 38 | #feature traker paprameters 39 | max_cnt: 150 # max feature number in feature tracking 40 | min_dist: 30 # min distance between two features 41 | freq: 0 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image 42 | F_threshold: 1.0 # ransac threshold (pixel) 43 | show_track: 1 # publish tracking image as topic 44 | flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy 45 | 46 | #optimization parameters 47 | max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time 48 | max_num_iterations: 8 # max solver itrations, to guarantee real time 49 | keyframe_parallax: 10.0 # keyframe selection threshold (pixel) 50 | 51 | #imu parameters The more accurate parameters you provide, the better performance 52 | acc_n: 0.1 # accelerometer measurement noise standard deviation. #0.2 0.04 53 | gyr_n: 0.01 # gyroscope measurement noise standard deviation. #0.05 0.004 54 | acc_w: 0.001 # accelerometer bias random work noise standard deviation. #0.002 55 | gyr_w: 0.0001 # gyroscope bias random work noise standard deviation. #4.0e-5 56 | g_norm: 9.805 # gravity magnitude 57 | 58 | #unsynchronization parameters 59 | estimate_td: 1 # online estimate time offset between camera and imu 60 | td: 0.00 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock) 61 | -------------------------------------------------------------------------------- /camera_models/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(camera_models) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | set(CMAKE_CXX_FLAGS "-std=c++11") 6 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -fPIC") 7 | 8 | find_package(catkin REQUIRED COMPONENTS 9 | roscpp 10 | std_msgs 11 | ) 12 | 13 | find_package(Boost REQUIRED COMPONENTS filesystem program_options system) 14 | include_directories(${Boost_INCLUDE_DIRS}) 15 | 16 | find_package(OpenCV REQUIRED) 17 | 18 | # set(EIGEN_INCLUDE_DIR "/usr/local/include/eigen3") 19 | find_package(Ceres REQUIRED) 20 | include_directories(${CERES_INCLUDE_DIRS}) 21 | 22 | 23 | catkin_package( 24 | INCLUDE_DIRS include 25 | LIBRARIES camera_models 26 | CATKIN_DEPENDS roscpp std_msgs 27 | # DEPENDS system_lib 28 | ) 29 | 30 | include_directories( 31 | ${catkin_INCLUDE_DIRS} 32 | ) 33 | 34 | include_directories("include") 35 | 36 | add_executable(Calibrations 37 | src/intrinsic_calib.cc 38 | src/chessboard/Chessboard.cc 39 | src/calib/CameraCalibration.cc 40 | src/camera_models/Camera.cc 41 | src/camera_models/CameraFactory.cc 42 | src/camera_models/CostFunctionFactory.cc 43 | src/camera_models/PinholeCamera.cc 44 | src/camera_models/PinholeFullCamera.cc 45 | src/camera_models/CataCamera.cc 46 | src/camera_models/EquidistantCamera.cc 47 | src/camera_models/ScaramuzzaCamera.cc 48 | src/sparse_graph/Transform.cc 49 | src/gpl/gpl.cc 50 | src/gpl/EigenQuaternionParameterization.cc) 51 | 52 | add_library(camera_models 53 | src/chessboard/Chessboard.cc 54 | src/calib/CameraCalibration.cc 55 | src/camera_models/Camera.cc 56 | src/camera_models/CameraFactory.cc 57 | src/camera_models/CostFunctionFactory.cc 58 | src/camera_models/PinholeCamera.cc 59 | src/camera_models/PinholeFullCamera.cc 60 | src/camera_models/CataCamera.cc 61 | src/camera_models/EquidistantCamera.cc 62 | src/camera_models/ScaramuzzaCamera.cc 63 | src/sparse_graph/Transform.cc 64 | src/gpl/gpl.cc 65 | src/gpl/EigenQuaternionParameterization.cc) 66 | 67 | target_link_libraries(Calibrations ${Boost_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) 68 | target_link_libraries(camera_models ${Boost_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) 69 | -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0000.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0000.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0001.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0001.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0002.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0002.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0003.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0003.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0004.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0004.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0005.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0005.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0006.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0006.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0007.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0007.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0008.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0008.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0009.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0009.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0010.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0010.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0011.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0011.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0012.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0012.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0013.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0013.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0014.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0014.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0015.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0015.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0016.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0016.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0017.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0017.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0018.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0018.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0019.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0019.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0020.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0020.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0021.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0021.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0022.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0022.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0023.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0023.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0024.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0024.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0025.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0025.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0026.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0026.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0027.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0027.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0028.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0028.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0029.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0029.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0030.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0030.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0031.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0031.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0032.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0032.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0033.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0033.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0034.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0034.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0035.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0035.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0036.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0036.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0037.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0037.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0038.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0038.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0039.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0039.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0040.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0040.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0041.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0041.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0042.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0042.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0043.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0043.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0044.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0044.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0045.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0045.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0046.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0046.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0047.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0047.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0048.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0048.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0049.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0049.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0050.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0050.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0051.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0051.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0052.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0052.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0053.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0053.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0054.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0054.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0055.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0055.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0056.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0056.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0057.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0057.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0058.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0058.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0059.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0059.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0060.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0060.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0061.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0061.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0062.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0062.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0063.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0063.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0064.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0064.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0065.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0065.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0066.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0066.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0067.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0067.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0068.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0068.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0069.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0069.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0070.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0070.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0071.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0071.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0072.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0072.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0073.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0073.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0074.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0074.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0075.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0075.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0076.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0076.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0077.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0077.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0078.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0078.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0079.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0079.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0080.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0080.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0081.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0081.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0082.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0082.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0083.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0083.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/calibrationdata/left-0084.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/camera_models/camera_calib_example/calibrationdata/left-0084.png -------------------------------------------------------------------------------- /camera_models/camera_calib_example/readme.txt: -------------------------------------------------------------------------------- 1 | # help for checking input parameters. 2 | rosrun camera_models Calibrations --help 3 | 4 | # example pinhole model. 5 | rosrun camera_models Calibrations -w 12 -h 8 -s 80 -i calibrationdata --camera-model pinhole 6 | 7 | # example mei model. 8 | rosrun camera_models Calibrations -w 12 -h 8 -s 80 -i calibrationdata --camera-model mei 9 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/calib/CameraCalibration.h: -------------------------------------------------------------------------------- 1 | #ifndef CAMERACALIBRATION_H 2 | #define CAMERACALIBRATION_H 3 | 4 | #include 5 | 6 | #include "camodocal/camera_models/Camera.h" 7 | 8 | namespace camodocal 9 | { 10 | 11 | class CameraCalibration 12 | { 13 | public: 14 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 15 | CameraCalibration(); 16 | 17 | CameraCalibration(Camera::ModelType modelType, 18 | const std::string& cameraName, 19 | const cv::Size& imageSize, 20 | const cv::Size& boardSize, 21 | float squareSize); 22 | 23 | void clear(void); 24 | 25 | void addChessboardData(const std::vector& corners); 26 | 27 | bool calibrate(void); 28 | 29 | int sampleCount(void) const; 30 | std::vector >& imagePoints(void); 31 | const std::vector >& imagePoints(void) const; 32 | std::vector >& scenePoints(void); 33 | const std::vector >& scenePoints(void) const; 34 | CameraPtr& camera(void); 35 | const CameraConstPtr camera(void) const; 36 | 37 | Eigen::Matrix2d& measurementCovariance(void); 38 | const Eigen::Matrix2d& measurementCovariance(void) const; 39 | 40 | cv::Mat& cameraPoses(void); 41 | const cv::Mat& cameraPoses(void) const; 42 | 43 | void drawResults(std::vector& images) const; 44 | 45 | void writeParams(const std::string& filename) const; 46 | 47 | bool writeChessboardData(const std::string& filename) const; 48 | bool readChessboardData(const std::string& filename); 49 | 50 | void setVerbose(bool verbose); 51 | 52 | private: 53 | bool calibrateHelper(CameraPtr& camera, 54 | std::vector& rvecs, std::vector& tvecs) const; 55 | 56 | void optimize(CameraPtr& camera, 57 | std::vector& rvecs, std::vector& tvecs) const; 58 | 59 | template 60 | void readData(std::ifstream& ifs, T& data) const; 61 | 62 | template 63 | void writeData(std::ofstream& ofs, T data) const; 64 | 65 | cv::Size m_boardSize; 66 | float m_squareSize; 67 | 68 | CameraPtr m_camera; 69 | cv::Mat m_cameraPoses; 70 | 71 | std::vector > m_imagePoints; 72 | std::vector > m_scenePoints; 73 | 74 | Eigen::Matrix2d m_measurementCovariance; 75 | 76 | bool m_verbose; 77 | }; 78 | 79 | } 80 | 81 | #endif 82 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/camera_models/CameraFactory.h: -------------------------------------------------------------------------------- 1 | #ifndef CAMERAFACTORY_H 2 | #define CAMERAFACTORY_H 3 | 4 | #include 5 | #include 6 | 7 | #include "camodocal/camera_models/Camera.h" 8 | 9 | namespace camodocal 10 | { 11 | 12 | class CameraFactory 13 | { 14 | public: 15 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 16 | CameraFactory(); 17 | 18 | static boost::shared_ptr instance(void); 19 | 20 | CameraPtr generateCamera(Camera::ModelType modelType, 21 | const std::string& cameraName, 22 | cv::Size imageSize) const; 23 | 24 | CameraPtr generateCameraFromYamlFile(const std::string& filename); 25 | 26 | private: 27 | static boost::shared_ptr m_instance; 28 | }; 29 | 30 | } 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/chessboard/Chessboard.h: -------------------------------------------------------------------------------- 1 | #ifndef CHESSBOARD_H 2 | #define CHESSBOARD_H 3 | 4 | #include 5 | #include 6 | 7 | namespace camodocal 8 | { 9 | 10 | // forward declarations 11 | class ChessboardCorner; 12 | typedef boost::shared_ptr ChessboardCornerPtr; 13 | class ChessboardQuad; 14 | typedef boost::shared_ptr ChessboardQuadPtr; 15 | 16 | class Chessboard 17 | { 18 | public: 19 | Chessboard(cv::Size boardSize, cv::Mat& image); 20 | 21 | void findCorners(bool useOpenCV = false); 22 | const std::vector& getCorners(void) const; 23 | bool cornersFound(void) const; 24 | 25 | const cv::Mat& getImage(void) const; 26 | const cv::Mat& getSketch(void) const; 27 | 28 | private: 29 | bool findChessboardCorners(const cv::Mat& image, 30 | const cv::Size& patternSize, 31 | std::vector& corners, 32 | int flags, bool useOpenCV); 33 | 34 | bool findChessboardCornersImproved(const cv::Mat& image, 35 | const cv::Size& patternSize, 36 | std::vector& corners, 37 | int flags); 38 | 39 | void cleanFoundConnectedQuads(std::vector& quadGroup, cv::Size patternSize); 40 | 41 | void findConnectedQuads(std::vector& quads, 42 | std::vector& group, 43 | int group_idx, int dilation); 44 | 45 | // int checkQuadGroup(std::vector& quadGroup, 46 | // std::vector& outCorners, 47 | // cv::Size patternSize); 48 | 49 | void labelQuadGroup(std::vector& quad_group, 50 | cv::Size patternSize, bool firstRun); 51 | 52 | void findQuadNeighbors(std::vector& quads, int dilation); 53 | 54 | int augmentBestRun(std::vector& candidateQuads, int candidateDilation, 55 | std::vector& existingQuads, int existingDilation); 56 | 57 | void generateQuads(std::vector& quads, 58 | cv::Mat& image, int flags, 59 | int dilation, bool firstRun); 60 | 61 | bool checkQuadGroup(std::vector& quads, 62 | std::vector& corners, 63 | cv::Size patternSize); 64 | 65 | void getQuadrangleHypotheses(const std::vector< std::vector >& contours, 66 | std::vector< std::pair >& quads, 67 | int classId) const; 68 | 69 | bool checkChessboard(const cv::Mat& image, cv::Size patternSize) const; 70 | 71 | bool checkBoardMonotony(std::vector& corners, 72 | cv::Size patternSize); 73 | 74 | bool matchCorners(ChessboardQuadPtr& quad1, int corner1, 75 | ChessboardQuadPtr& quad2, int corner2) const; 76 | 77 | cv::Mat mImage; 78 | cv::Mat mSketch; 79 | std::vector mCorners; 80 | cv::Size mBoardSize; 81 | bool mCornersFound; 82 | }; 83 | 84 | } 85 | 86 | #endif 87 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/chessboard/ChessboardCorner.h: -------------------------------------------------------------------------------- 1 | #ifndef CHESSBOARDCORNER_H 2 | #define CHESSBOARDCORNER_H 3 | 4 | #include 5 | #include 6 | 7 | namespace camodocal 8 | { 9 | 10 | class ChessboardCorner; 11 | typedef boost::shared_ptr ChessboardCornerPtr; 12 | 13 | class ChessboardCorner 14 | { 15 | public: 16 | ChessboardCorner() : row(0), column(0), needsNeighbor(true), count(0) {} 17 | 18 | float meanDist(int &n) const 19 | { 20 | float sum = 0; 21 | n = 0; 22 | for (int i = 0; i < 4; ++i) 23 | { 24 | if (neighbors[i].get()) 25 | { 26 | float dx = neighbors[i]->pt.x - pt.x; 27 | float dy = neighbors[i]->pt.y - pt.y; 28 | sum += sqrt(dx*dx + dy*dy); 29 | n++; 30 | } 31 | } 32 | return sum / std::max(n, 1); 33 | } 34 | 35 | cv::Point2f pt; // X and y coordinates 36 | int row; // Row and column of the corner 37 | int column; // in the found pattern 38 | bool needsNeighbor; // Does the corner require a neighbor? 39 | int count; // number of corner neighbors 40 | ChessboardCornerPtr neighbors[4]; // pointer to all corner neighbors 41 | }; 42 | 43 | } 44 | 45 | #endif 46 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/chessboard/ChessboardQuad.h: -------------------------------------------------------------------------------- 1 | #ifndef CHESSBOARDQUAD_H 2 | #define CHESSBOARDQUAD_H 3 | 4 | #include 5 | 6 | #include "camodocal/chessboard/ChessboardCorner.h" 7 | 8 | namespace camodocal 9 | { 10 | 11 | class ChessboardQuad; 12 | typedef boost::shared_ptr ChessboardQuadPtr; 13 | 14 | class ChessboardQuad 15 | { 16 | public: 17 | ChessboardQuad() : count(0), group_idx(-1), edge_len(FLT_MAX), labeled(false) {} 18 | 19 | int count; // Number of quad neighbors 20 | int group_idx; // Quad group ID 21 | float edge_len; // Smallest side length^2 22 | ChessboardCornerPtr corners[4]; // Coordinates of quad corners 23 | ChessboardQuadPtr neighbors[4]; // Pointers of quad neighbors 24 | bool labeled; // Has this corner been labeled? 25 | }; 26 | 27 | } 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/gpl/EigenQuaternionParameterization.h: -------------------------------------------------------------------------------- 1 | #ifndef EIGENQUATERNIONPARAMETERIZATION_H 2 | #define EIGENQUATERNIONPARAMETERIZATION_H 3 | 4 | #include "ceres/local_parameterization.h" 5 | 6 | namespace camodocal 7 | { 8 | 9 | class EigenQuaternionParameterization : public ceres::LocalParameterization 10 | { 11 | public: 12 | virtual ~EigenQuaternionParameterization() {} 13 | virtual bool Plus(const double* x, 14 | const double* delta, 15 | double* x_plus_delta) const; 16 | virtual bool ComputeJacobian(const double* x, 17 | double* jacobian) const; 18 | virtual int GlobalSize() const { return 4; } 19 | virtual int LocalSize() const { return 3; } 20 | 21 | private: 22 | template 23 | void EigenQuaternionProduct(const T z[4], const T w[4], T zw[4]) const; 24 | }; 25 | 26 | 27 | template 28 | void 29 | EigenQuaternionParameterization::EigenQuaternionProduct(const T z[4], const T w[4], T zw[4]) const 30 | { 31 | zw[0] = z[3] * w[0] + z[0] * w[3] + z[1] * w[2] - z[2] * w[1]; 32 | zw[1] = z[3] * w[1] - z[0] * w[2] + z[1] * w[3] + z[2] * w[0]; 33 | zw[2] = z[3] * w[2] + z[0] * w[1] - z[1] * w[0] + z[2] * w[3]; 34 | zw[3] = z[3] * w[3] - z[0] * w[0] - z[1] * w[1] - z[2] * w[2]; 35 | } 36 | 37 | } 38 | 39 | #endif 40 | 41 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/gpl/gpl.h: -------------------------------------------------------------------------------- 1 | #ifndef GPL_H 2 | #define GPL_H 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | namespace camodocal 9 | { 10 | 11 | template 12 | const T clamp(const T& v, const T& a, const T& b) 13 | { 14 | return std::min(b, std::max(a, v)); 15 | } 16 | 17 | double hypot3(double x, double y, double z); 18 | float hypot3f(float x, float y, float z); 19 | 20 | template 21 | const T normalizeTheta(const T& theta) 22 | { 23 | T normTheta = theta; 24 | 25 | while (normTheta < - M_PI) 26 | { 27 | normTheta += 2.0 * M_PI; 28 | } 29 | while (normTheta > M_PI) 30 | { 31 | normTheta -= 2.0 * M_PI; 32 | } 33 | 34 | return normTheta; 35 | } 36 | 37 | double d2r(double deg); 38 | float d2r(float deg); 39 | double r2d(double rad); 40 | float r2d(float rad); 41 | 42 | double sinc(double theta); 43 | 44 | template 45 | const T square(const T& x) 46 | { 47 | return x * x; 48 | } 49 | 50 | template 51 | const T cube(const T& x) 52 | { 53 | return x * x * x; 54 | } 55 | 56 | template 57 | const T random(const T& a, const T& b) 58 | { 59 | return static_cast(rand()) / RAND_MAX * (b - a) + a; 60 | } 61 | 62 | template 63 | const T randomNormal(const T& sigma) 64 | { 65 | T x1, x2, w; 66 | 67 | do 68 | { 69 | x1 = 2.0 * random(0.0, 1.0) - 1.0; 70 | x2 = 2.0 * random(0.0, 1.0) - 1.0; 71 | w = x1 * x1 + x2 * x2; 72 | } 73 | while (w >= 1.0 || w == 0.0); 74 | 75 | w = sqrt((-2.0 * log(w)) / w); 76 | 77 | return x1 * w * sigma; 78 | } 79 | 80 | unsigned long long timeInMicroseconds(void); 81 | 82 | double timeInSeconds(void); 83 | 84 | void colorDepthImage(cv::Mat& imgDepth, 85 | cv::Mat& imgColoredDepth, 86 | float minRange, float maxRange); 87 | 88 | bool colormap(const std::string& name, unsigned char idx, 89 | float& r, float& g, float& b); 90 | 91 | std::vector bresLine(int x0, int y0, int x1, int y1); 92 | std::vector bresCircle(int x0, int y0, int r); 93 | 94 | void fitCircle(const std::vector& points, 95 | double& centerX, double& centerY, double& radius); 96 | 97 | std::vector intersectCircles(double x1, double y1, double r1, 98 | double x2, double y2, double r2); 99 | 100 | void LLtoUTM(double latitude, double longitude, 101 | double& utmNorthing, double& utmEasting, 102 | std::string& utmZone); 103 | void UTMtoLL(double utmNorthing, double utmEasting, 104 | const std::string& utmZone, 105 | double& latitude, double& longitude); 106 | 107 | long int timestampDiff(uint64_t t1, uint64_t t2); 108 | 109 | } 110 | 111 | #endif 112 | -------------------------------------------------------------------------------- /camera_models/include/camodocal/sparse_graph/Transform.h: -------------------------------------------------------------------------------- 1 | #ifndef TRANSFORM_H 2 | #define TRANSFORM_H 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | namespace camodocal 9 | { 10 | 11 | class Transform 12 | { 13 | public: 14 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 15 | 16 | Transform(); 17 | Transform(const Eigen::Matrix4d& H); 18 | 19 | Eigen::Quaterniond& rotation(void); 20 | const Eigen::Quaterniond& rotation(void) const; 21 | double* rotationData(void); 22 | const double* const rotationData(void) const; 23 | 24 | Eigen::Vector3d& translation(void); 25 | const Eigen::Vector3d& translation(void) const; 26 | double* translationData(void); 27 | const double* const translationData(void) const; 28 | 29 | Eigen::Matrix4d toMatrix(void) const; 30 | 31 | private: 32 | Eigen::Quaterniond m_q; 33 | Eigen::Vector3d m_t; 34 | }; 35 | 36 | } 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /camera_models/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | camera_models 4 | 0.0.0 5 | The camera_models package 6 | 7 | 8 | 9 | 10 | dvorak 11 | 12 | 13 | 14 | 15 | 16 | TODO 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 | std_msgs 45 | roscpp 46 | std_msgs 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | -------------------------------------------------------------------------------- /camera_models/readme.md: -------------------------------------------------------------------------------- 1 | part of [camodocal](https://github.com/hengli/camodocal) 2 | 3 | [Google Ceres](http://ceres-solver.org) is needed. 4 | 5 | # Calibration: 6 | 7 | Use [intrinsic_calib.cc](https://github.com/dvorak0/camera_model/blob/master/src/intrinsic_calib.cc) to calibrate your camera. 8 | 9 | # Undistortion: 10 | 11 | See [Camera.h](https://github.com/dvorak0/camera_model/blob/master/include/camodocal/camera_models/Camera.h) for general interface: 12 | 13 | - liftProjective: Lift points from the image plane to the projective space. 14 | - spaceToPlane: Projects 3D points to the image plane (Pi function) 15 | 16 | -------------------------------------------------------------------------------- /camera_models/src/gpl/EigenQuaternionParameterization.cc: -------------------------------------------------------------------------------- 1 | #include "camodocal/gpl/EigenQuaternionParameterization.h" 2 | 3 | #include 4 | 5 | namespace camodocal 6 | { 7 | 8 | bool 9 | EigenQuaternionParameterization::Plus(const double* x, 10 | const double* delta, 11 | double* x_plus_delta) const 12 | { 13 | const double norm_delta = 14 | sqrt(delta[0] * delta[0] + delta[1] * delta[1] + delta[2] * delta[2]); 15 | if (norm_delta > 0.0) 16 | { 17 | const double sin_delta_by_delta = (sin(norm_delta) / norm_delta); 18 | double q_delta[4]; 19 | q_delta[0] = sin_delta_by_delta * delta[0]; 20 | q_delta[1] = sin_delta_by_delta * delta[1]; 21 | q_delta[2] = sin_delta_by_delta * delta[2]; 22 | q_delta[3] = cos(norm_delta); 23 | EigenQuaternionProduct(q_delta, x, x_plus_delta); 24 | } 25 | else 26 | { 27 | for (int i = 0; i < 4; ++i) 28 | { 29 | x_plus_delta[i] = x[i]; 30 | } 31 | } 32 | return true; 33 | } 34 | 35 | bool 36 | EigenQuaternionParameterization::ComputeJacobian(const double* x, 37 | double* jacobian) const 38 | { 39 | jacobian[0] = x[3]; jacobian[1] = x[2]; jacobian[2] = -x[1]; // NOLINT 40 | jacobian[3] = -x[2]; jacobian[4] = x[3]; jacobian[5] = x[0]; // NOLINT 41 | jacobian[6] = x[1]; jacobian[7] = -x[0]; jacobian[8] = x[3]; // NOLINT 42 | jacobian[9] = -x[0]; jacobian[10] = -x[1]; jacobian[11] = -x[2]; // NOLINT 43 | return true; 44 | } 45 | 46 | } 47 | -------------------------------------------------------------------------------- /camera_models/src/sparse_graph/Transform.cc: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | namespace camodocal 4 | { 5 | 6 | Transform::Transform() 7 | { 8 | m_q.setIdentity(); 9 | m_t.setZero(); 10 | } 11 | 12 | Transform::Transform(const Eigen::Matrix4d& H) 13 | { 14 | m_q = Eigen::Quaterniond(H.block<3,3>(0,0)); 15 | m_t = H.block<3,1>(0,3); 16 | } 17 | 18 | Eigen::Quaterniond& 19 | Transform::rotation(void) 20 | { 21 | return m_q; 22 | } 23 | 24 | const Eigen::Quaterniond& 25 | Transform::rotation(void) const 26 | { 27 | return m_q; 28 | } 29 | 30 | double* 31 | Transform::rotationData(void) 32 | { 33 | return m_q.coeffs().data(); 34 | } 35 | 36 | const double* const 37 | Transform::rotationData(void) const 38 | { 39 | return m_q.coeffs().data(); 40 | } 41 | 42 | Eigen::Vector3d& 43 | Transform::translation(void) 44 | { 45 | return m_t; 46 | } 47 | 48 | const Eigen::Vector3d& 49 | Transform::translation(void) const 50 | { 51 | return m_t; 52 | } 53 | 54 | double* 55 | Transform::translationData(void) 56 | { 57 | return m_t.data(); 58 | } 59 | 60 | const double* const 61 | Transform::translationData(void) const 62 | { 63 | return m_t.data(); 64 | } 65 | 66 | Eigen::Matrix4d 67 | Transform::toMatrix(void) const 68 | { 69 | Eigen::Matrix4d H; 70 | H.setIdentity(); 71 | H.block<3,3>(0,0) = m_q.toRotationMatrix(); 72 | H.block<3,1>(0,3) = m_t; 73 | 74 | return H; 75 | } 76 | 77 | } 78 | -------------------------------------------------------------------------------- /extrinsic.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/extrinsic.png -------------------------------------------------------------------------------- /imu.yaml: -------------------------------------------------------------------------------- 1 | ###PX4-mini 2 | #Accelerometers 3 | accelerometer_noise_density: 0.00333388 #Noise density (continuous-time) 4 | accelerometer_random_walk: 0.00047402 #Bias random walk 5 | 6 | #Gyroscopes 7 | gyroscope_noise_density: 0.00005770 #Noise density (continuous-time) 8 | gyroscope_random_walk: 0.00001565 #Bias random walk 9 | 10 | rostopic: /mavros/imu/data_raw #the IMU ROS topic 11 | update_rate: 100.0 #Hz (for discretization of the values above) 12 | 13 | ###T265 14 | #accelerometer_noise_density: 1.85e-03 #Noise density (continuous-time) 15 | #accelerometer_random_walk: 2.548e-05 #Bias random walk 16 | 17 | #Gyroscopes 18 | #gyroscope_noise_density: 1.094e-02 #Noise density (continuous-time) 19 | #gyroscope_random_walk: 5.897e-04 #Bias random walk 20 | 21 | #rostopic: /camera/imu #the IMU ROS topic 22 | #update_rate: 200.0 #Hz (for discretization of the values above) 23 | 24 | 25 | ###d435i 26 | ##Accelerometers 27 | #accelerometer_noise_density: 0.001865 #Noise density (continuous-time) 28 | #accelerometer_random_walk: 0.0002 #Bias random walk 29 | 30 | ##Gyroscopes 31 | #gyroscope_noise_density: 0.0018685 #Noise density (continuous-time) 32 | #gyroscope_random_walk: 0.000004 #Bias random walk 33 | 34 | #rostopic: /camera/imu #the IMU ROS topic 35 | #update_rate: 400.0 #Hz (for discretization of the values above) 36 | 37 | 38 | ###zed mini 39 | ##Accelerometers 40 | #accelerometer_noise_density: 1.4e-03 #Noise density (continuous-time) 41 | #accelerometer_random_walk: 8.0e-05 #Bias random walk 42 | 43 | ##Gyroscopes 44 | #gyroscope_noise_density: 8.6e-05 #Noise density (continuous-time) 45 | #gyroscope_random_walk: 2.2e-06 #Bias random walk 46 | 47 | #rostopic: /zed/zed_node/imu/data_raw #the IMU ROS topic 48 | #update_rate: 800.0 #Hz (for discretization of the values above) 49 | -------------------------------------------------------------------------------- /pitching.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/pitching.png -------------------------------------------------------------------------------- /s-msckf_flightgoggles/camchain-imucam-flightgoggles.yaml: -------------------------------------------------------------------------------- 1 | # The modifications of the output file from Kalibr: 2 | # 1. For each matrix (e.g. cam0/T_cam_imu), remove the brackets and minus sign for each line. Use one pair of brackets for each matrix. 3 | # 2. Add the T_imu_body at the end of the calibration file (usually set to identity). 4 | cam0: 5 | T_cam_imu: 6 | [0.0, -1.0, 0.0, 0.0, 7 | 0.0, 0.0, -1.0, 0.0, 8 | 1.0, 0.0, 0.0, 0.0, 9 | 0.0, 0.0, 0.0, 1.0] 10 | camera_model: pinhole 11 | distortion_coeffs: [0.0, 0.0, 0.0, 0.0] 12 | distortion_model: radtan 13 | intrinsics: [342.7555236816406, 320.0, 342.7555236816406, 240.0] 14 | resolution: [640, 480] 15 | timeshift_cam_imu: 0.0 16 | cam1: 17 | T_cam_imu: 18 | [0.0, -1.0, 0.0, -0.32, 19 | 0.0, 0.0, -1.0, 0.0, 20 | 1.0, 0.0, 0.0, 0.0, 21 | 0.0, 0.0, 0.0, 1.0] 22 | T_cn_cnm1: #T_c1_c0 : c0's points from c1's view 23 | [1.0, 0.0, 0.0, -0.32, 24 | 0.0, 1.0, 0.0, 0.0, 25 | 0.0, 0.0, 1.0, 0.0, 26 | 0.0, 0.0, 0.0, 1.0] 27 | camera_model: pinhole 28 | distortion_coeffs: [0.0, 0.0, 0.0, 0.0] 29 | distortion_model: radtan 30 | intrinsics: [342.7555236816406, 320.0, 342.7555236816406, 240.0] 31 | resolution: [640, 480] 32 | timeshift_cam_imu: 0.0 33 | T_imu_body: 34 | [1.0000, 0.0000, 0.0000, 0.0000, 35 | 0.0000, 1.0000, 0.0000, 0.0000, 36 | 0.0000, 0.0000, 1.0000, 0.0000, 37 | 0.0000, 0.0000, 0.0000, 1.0000] 38 | 39 | -------------------------------------------------------------------------------- /s-msckf_flightgoggles/flightgoggles.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 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 | -------------------------------------------------------------------------------- /s-msckf_flightgoggles/image_processor_flightgoggles.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 6 | 7 | 8 | 9 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /vins-fusion-px4/README.md: -------------------------------------------------------------------------------- 1 | ### VINS-Fusion for PX4 2 | + Edited ***frame_id*** from **world** to **map** for odometry, camera_pose, point cloud, and ... everythings! 3 | + Added ***Masking*** inside the feature tracker node, check ***yaml*** files 4 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(loop_fusion) 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 | nav_msgs 13 | camera_models 14 | cv_bridge 15 | roslib 16 | ) 17 | 18 | find_package(OpenCV) 19 | 20 | 21 | find_package(Ceres REQUIRED) 22 | 23 | set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) 24 | find_package(Eigen3) 25 | 26 | include_directories(${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIR}) 27 | 28 | catkin_package() 29 | 30 | add_executable(loop_fusion_node 31 | src/pose_graph_node.cpp 32 | src/pose_graph.cpp 33 | src/keyframe.cpp 34 | src/utility/CameraPoseVisualization.cpp 35 | src/ThirdParty/DBoW/BowVector.cpp 36 | src/ThirdParty/DBoW/FBrief.cpp 37 | src/ThirdParty/DBoW/FeatureVector.cpp 38 | src/ThirdParty/DBoW/QueryResults.cpp 39 | src/ThirdParty/DBoW/ScoringObject.cpp 40 | src/ThirdParty/DUtils/Random.cpp 41 | src/ThirdParty/DUtils/Timestamp.cpp 42 | src/ThirdParty/DVision/BRIEF.cpp 43 | src/ThirdParty/VocabularyBinary.cpp 44 | ) 45 | 46 | target_link_libraries(loop_fusion_node ${catkin_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) 47 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | loop_fusion 4 | 0.0.0 5 | loop_fusion package 6 | 7 | 8 | 9 | 10 | tony-ws 11 | 12 | 13 | 14 | 15 | 16 | TODO 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 | camera_models 44 | camera_models 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | 70 | /// BRIEF Vocabulary 71 | typedef DBoW2::TemplatedVocabulary 72 | BriefVocabulary; 73 | 74 | /// BRIEF Database 75 | typedef DBoW2::TemplatedDatabase 76 | BriefDatabase; 77 | 78 | #endif 79 | 80 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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 | extern camodocal::CameraPtr m_camera; 25 | extern Eigen::Vector3d tic; 26 | extern Eigen::Matrix3d qic; 27 | extern ros::Publisher pub_match_img; 28 | extern int VISUALIZATION_SHIFT_X; 29 | extern int VISUALIZATION_SHIFT_Y; 30 | extern std::string BRIEF_PATTERN_FILE; 31 | extern std::string POSE_GRAPH_SAVE_PATH; 32 | extern int ROW; 33 | extern int COL; 34 | extern std::string VINS_RESULT_PATH; 35 | extern int DEBUG_IMAGE; 36 | 37 | 38 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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); 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 | -------------------------------------------------------------------------------- /vins-fusion-px4/loop_fusion/src/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-fusion-px4/loop_fusion/src/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-fusion-px4/mask_img.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/vins-fusion-px4/mask_img.jpg -------------------------------------------------------------------------------- /vins-fusion-px4/masking.m: -------------------------------------------------------------------------------- 1 | left = imread('image.png'); 2 | right = imread('imager.png'); 3 | 4 | left_g = rgb2gray(left); 5 | right_g = rgb2gray(right); 6 | 7 | l_m = left_g < 100 ; 8 | r_m = right_g < 100 ; 9 | 10 | l_m = l_m*255; 11 | l_m = 255-l_m; 12 | 13 | r_m = r_m*255; 14 | r_m = 255-r_m; 15 | 16 | imwrite(l_m, 'left_masking.jpg'); 17 | imwrite(r_m, 'right_masking.jpg'); 18 | 19 | lr_m = l_m & r_m; 20 | mask=lr_m*255; 21 | 22 | imwrite(mask, 'mask_img.jpg'); 23 | -------------------------------------------------------------------------------- /vins-fusion-px4/support_files/brief_k10L6.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/engcang/vins-application/ba777bdf3fdd82baad3f7a179c7995b159681db6/vins-fusion-px4/support_files/brief_k10L6.bin -------------------------------------------------------------------------------- /vins-fusion-px4/vins_estimator/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(vins) 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 | 19 | find_package(OpenCV REQUIRED) 20 | 21 | # message(WARNING "OpenCV_VERSION: ${OpenCV_VERSION}") 22 | 23 | find_package(Ceres REQUIRED) 24 | 25 | include_directories(${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS}) 26 | 27 | set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) 28 | find_package(Eigen3) 29 | include_directories( 30 | ${catkin_INCLUDE_DIRS} 31 | ${EIGEN3_INCLUDE_DIR} 32 | ) 33 | 34 | catkin_package() 35 | 36 | add_library(vins_lib 37 | src/estimator/parameters.cpp 38 | src/estimator/estimator.cpp 39 | src/estimator/feature_manager.cpp 40 | src/factor/pose_local_parameterization.cpp 41 | src/factor/projectionTwoFrameOneCamFactor.cpp 42 | src/factor/projectionTwoFrameTwoCamFactor.cpp 43 | src/factor/projectionOneFrameTwoCamFactor.cpp 44 | src/factor/marginalization_factor.cpp 45 | src/utility/utility.cpp 46 | src/utility/visualization.cpp 47 | src/utility/CameraPoseVisualization.cpp 48 | src/initial/solve_5pts.cpp 49 | src/initial/initial_aligment.cpp 50 | src/initial/initial_sfm.cpp 51 | src/initial/initial_ex_rotation.cpp 52 | src/featureTracker/feature_tracker.cpp) 53 | target_link_libraries(vins_lib ${catkin_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) 54 | 55 | 56 | add_executable(vins_node src/rosNodeTest.cpp) 57 | target_link_libraries(vins_node vins_lib) 58 | 59 | add_executable(kitti_odom_test src/KITTIOdomTest.cpp) 60 | target_link_libraries(kitti_odom_test vins_lib) 61 | 62 | add_executable(kitti_gps_test src/KITTIGPSTest.cpp) 63 | target_link_libraries(kitti_gps_test vins_lib) 64 | 65 | -------------------------------------------------------------------------------- /vins-fusion-px4/vins_estimator/launch/vins_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /vins-fusion-px4/vins_estimator/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | vins 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 | -------------------------------------------------------------------------------- /vins-fusion-px4/vins_estimator/src/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 | const double FOCAL_LENGTH = 460.0; 24 | const int WINDOW_SIZE = 10; 25 | const int NUM_OF_F = 1000; 26 | //#define UNIT_SPHERE_ERROR 27 | 28 | extern double INIT_DEPTH; 29 | extern double MIN_PARALLAX; 30 | extern int ESTIMATE_EXTRINSIC; 31 | 32 | extern double ACC_N, ACC_W; 33 | extern double GYR_N, GYR_W; 34 | 35 | extern std::vector RIC; 36 | extern std::vector TIC; 37 | extern Eigen::Vector3d G; 38 | 39 | extern double BIAS_ACC_THRESHOLD; 40 | extern double BIAS_GYR_THRESHOLD; 41 | extern double SOLVER_TIME; 42 | extern int NUM_ITERATIONS; 43 | extern std::string EX_CALIB_RESULT_PATH; 44 | extern std::string VINS_RESULT_PATH; 45 | extern std::string OUTPUT_FOLDER; 46 | extern std::string IMU_TOPIC; 47 | extern double TD; 48 | extern int ESTIMATE_TD; 49 | extern int ROLLING_SHUTTER; 50 | extern int ROW, COL; 51 | extern int NUM_OF_CAM; 52 | extern int STEREO; 53 | extern int USE_IMU; 54 | extern int MULTIPLE_THREAD; 55 | // pts_gt for debug purpose; 56 | extern map pts_gt; 57 | 58 | extern std::string IMAGE0_TOPIC, IMAGE1_TOPIC; 59 | extern int MASKING; //added 60 | extern std::string MASKING_PATH; //added 61 | extern cv::Mat MASKING_IMG; //added 62 | extern std::vector CAM_NAMES; 63 | extern int MAX_CNT; 64 | extern int MIN_DIST; 65 | extern double F_THRESHOLD; 66 | extern int SHOW_TRACK; 67 | extern int FLOW_BACK; 68 | 69 | void readParameters(std::string config_file); 70 | 71 | enum SIZE_PARAMETERIZATION 72 | { 73 | SIZE_POSE = 7, 74 | SIZE_SPEEDBIAS = 9, 75 | SIZE_FEATURE = 1 76 | }; 77 | 78 | enum StateOrder 79 | { 80 | O_P = 0, 81 | O_R = 3, 82 | O_V = 6, 83 | O_BA = 9, 84 | O_BG = 12 85 | }; 86 | 87 | enum NoiseOrder 88 | { 89 | O_AN = 0, 90 | O_GN = 3, 91 | O_AW = 6, 92 | O_GW = 9 93 | }; 94 | -------------------------------------------------------------------------------- /vins-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/factor/projectionOneFrameTwoCamFactor.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 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-fusion-px4/vins_estimator/src/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> 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-fusion-px4/vins_estimator/src/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> 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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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 | 22 | #include "camodocal/camera_models/CameraFactory.h" 23 | #include "camodocal/camera_models/CataCamera.h" 24 | #include "camodocal/camera_models/PinholeCamera.h" 25 | #include "../estimator/parameters.h" 26 | #include "../utility/tic_toc.h" 27 | 28 | using namespace std; 29 | using namespace camodocal; 30 | using namespace Eigen; 31 | 32 | bool inBorder(const cv::Point2f &pt); 33 | void reduceVector(vector &v, vector status); 34 | void reduceVector(vector &v, vector status); 35 | 36 | class FeatureTracker 37 | { 38 | public: 39 | FeatureTracker(); 40 | map>>> trackImage(double _cur_time, const cv::Mat &_img, const cv::Mat &_img1 = cv::Mat()); 41 | void setMask(); 42 | void readIntrinsicParameter(const vector &calib_file); 43 | void showUndistortion(const string &name); 44 | void rejectWithF(); 45 | void undistortedPoints(); 46 | vector undistortedPts(vector &pts, camodocal::CameraPtr cam); 47 | vector ptsVelocity(vector &ids, vector &pts, 48 | map &cur_id_pts, map &prev_id_pts); 49 | void showTwoImage(const cv::Mat &img1, const cv::Mat &img2, 50 | vector pts1, vector pts2); 51 | void drawTrack(const cv::Mat &imLeft, const cv::Mat &imRight, 52 | vector &curLeftIds, 53 | vector &curLeftPts, 54 | vector &curRightPts, 55 | map &prevLeftPtsMap); 56 | void setPrediction(map &predictPts); 57 | double distance(cv::Point2f &pt1, cv::Point2f &pt2); 58 | void removeOutliers(set &removePtsIds); 59 | cv::Mat getTrackImage(); 60 | bool inBorder(const cv::Point2f &pt); 61 | 62 | int row, col; 63 | cv::Mat imTrack; 64 | cv::Mat mask; 65 | cv::Mat fisheye_mask; 66 | cv::Mat prev_img, cur_img; 67 | vector n_pts; 68 | vector predict_pts; 69 | vector predict_pts_debug; 70 | vector prev_pts, cur_pts, cur_right_pts; 71 | vector prev_un_pts, cur_un_pts, cur_un_right_pts; 72 | vector pts_velocity, right_pts_velocity; 73 | vector ids, ids_right; 74 | vector track_cnt; 75 | map cur_un_pts_map, prev_un_pts_map; 76 | map cur_un_right_pts_map, prev_un_right_pts_map; 77 | map prevLeftPtsMap; 78 | vector m_camera; 79 | double cur_time; 80 | double prev_time; 81 | bool stereo_cam; 82 | int n_id; 83 | bool hasPrediction; 84 | }; 85 | -------------------------------------------------------------------------------- /vins-fusion-px4/vins_estimator/src/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 | bool VisualIMUAlignment(map &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x); -------------------------------------------------------------------------------- /vins-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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-fusion-px4/vins_estimator/src/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 28 | #include "CameraPoseVisualization.h" 29 | #include 30 | #include "../estimator/estimator.h" 31 | #include "../estimator/parameters.h" 32 | #include 33 | 34 | extern ros::Publisher pub_odometry, pub_odometry_mavros; 35 | extern ros::Publisher pub_path, pub_pose; 36 | extern ros::Publisher pub_cloud, pub_map; 37 | extern ros::Publisher pub_key_poses; 38 | extern ros::Publisher pub_ref_pose, pub_cur_pose; 39 | extern ros::Publisher pub_key; 40 | extern nav_msgs::Path path; 41 | extern ros::Publisher pub_pose_graph; 42 | extern int IMAGE_ROW, IMAGE_COL; 43 | 44 | void registerPub(ros::NodeHandle &n); 45 | 46 | void pubLatestOdometry(const Eigen::Vector3d &P, const Eigen::Quaterniond &Q, const Eigen::Vector3d &V, double t); 47 | 48 | void pubTrackImage(const cv::Mat &imgTrack, const double t); 49 | 50 | void printStatistics(const Estimator &estimator, double t); 51 | 52 | void pubOdometry(const Estimator &estimator, const std_msgs::Header &header); 53 | 54 | void pubInitialGuess(const Estimator &estimator, const std_msgs::Header &header); 55 | 56 | void pubKeyPoses(const Estimator &estimator, const std_msgs::Header &header); 57 | 58 | void pubCameraPose(const Estimator &estimator, const std_msgs::Header &header); 59 | 60 | void pubPointCloud(const Estimator &estimator, const std_msgs::Header &header); 61 | 62 | void pubTF(const Estimator &estimator, const std_msgs::Header &header); 63 | 64 | void pubKeyframe(const Estimator &estimator); 65 | 66 | void pubRelocalization(const Estimator &estimator); 67 | 68 | void pubCar(const Estimator & estimator, const std_msgs::Header &header); 69 | -------------------------------------------------------------------------------- /vins_estimator/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(vins) 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 | 19 | find_package(OpenCV REQUIRED) 20 | 21 | # message(WARNING "OpenCV_VERSION: ${OpenCV_VERSION}") 22 | 23 | find_package(Ceres REQUIRED) 24 | 25 | include_directories(${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS}) 26 | 27 | set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) 28 | find_package(Eigen3) 29 | include_directories( 30 | ${catkin_INCLUDE_DIRS} 31 | ${EIGEN3_INCLUDE_DIR} 32 | ) 33 | 34 | catkin_package() 35 | 36 | add_library(vins_lib 37 | src/estimator/parameters.cpp 38 | src/estimator/estimator.cpp 39 | src/estimator/feature_manager.cpp 40 | src/factor/pose_local_parameterization.cpp 41 | src/factor/projectionTwoFrameOneCamFactor.cpp 42 | src/factor/projectionTwoFrameTwoCamFactor.cpp 43 | src/factor/projectionOneFrameTwoCamFactor.cpp 44 | src/factor/marginalization_factor.cpp 45 | src/utility/utility.cpp 46 | src/utility/visualization.cpp 47 | src/utility/CameraPoseVisualization.cpp 48 | src/initial/solve_5pts.cpp 49 | src/initial/initial_aligment.cpp 50 | src/initial/initial_sfm.cpp 51 | src/initial/initial_ex_rotation.cpp 52 | src/featureTracker/feature_tracker.cpp) 53 | target_link_libraries(vins_lib ${catkin_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES}) 54 | 55 | 56 | add_executable(vins_node src/rosNodeTest.cpp) 57 | target_link_libraries(vins_node vins_lib) 58 | -------------------------------------------------------------------------------- /vins_estimator/launch/vins_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /vins_estimator/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | vins 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 | -------------------------------------------------------------------------------- /vins_estimator/src/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 | const double FOCAL_LENGTH = 460.0; 24 | const int WINDOW_SIZE = 10; 25 | const int NUM_OF_F = 1000; 26 | //#define UNIT_SPHERE_ERROR 27 | 28 | extern double INIT_DEPTH; 29 | extern double MIN_PARALLAX; 30 | extern int ESTIMATE_EXTRINSIC; 31 | 32 | extern double ACC_N, ACC_W; 33 | extern double GYR_N, GYR_W; 34 | 35 | extern std::vector RIC; 36 | extern std::vector TIC; 37 | extern Eigen::Vector3d G; 38 | 39 | extern double BIAS_ACC_THRESHOLD; 40 | extern double BIAS_GYR_THRESHOLD; 41 | extern double SOLVER_TIME; 42 | extern int NUM_ITERATIONS; 43 | extern std::string EX_CALIB_RESULT_PATH; 44 | extern std::string VINS_RESULT_PATH; 45 | extern std::string OUTPUT_FOLDER; 46 | extern std::string IMU_TOPIC; 47 | extern double TD; 48 | extern int ESTIMATE_TD; 49 | extern int ROLLING_SHUTTER; 50 | extern int ROW, COL; 51 | extern int NUM_OF_CAM; 52 | extern int STEREO; 53 | extern int USE_IMU; 54 | extern int MULTIPLE_THREAD; 55 | // pts_gt for debug purpose; 56 | extern map pts_gt; 57 | 58 | extern std::string IMAGE0_TOPIC, IMAGE1_TOPIC; 59 | extern int MASKING; //added 60 | extern std::string MASKING_PATH; //added 61 | extern cv::Mat MASKING_IMG; //added 62 | extern std::vector CAM_NAMES; 63 | extern int MAX_CNT; 64 | extern int MIN_DIST; 65 | extern double F_THRESHOLD; 66 | extern int SHOW_TRACK; 67 | extern int FLOW_BACK; 68 | 69 | void readParameters(std::string config_file); 70 | 71 | enum SIZE_PARAMETERIZATION 72 | { 73 | SIZE_POSE = 7, 74 | SIZE_SPEEDBIAS = 9, 75 | SIZE_FEATURE = 1 76 | }; 77 | 78 | enum StateOrder 79 | { 80 | O_P = 0, 81 | O_R = 3, 82 | O_V = 6, 83 | O_BA = 9, 84 | O_BG = 12 85 | }; 86 | 87 | enum NoiseOrder 88 | { 89 | O_AN = 0, 90 | O_GN = 3, 91 | O_AW = 6, 92 | O_GW = 9 93 | }; 94 | -------------------------------------------------------------------------------- /vins_estimator/src/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/src/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/src/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/src/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/src/factor/projectionOneFrameTwoCamFactor.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 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/src/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> 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/src/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> 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/src/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/src/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 | 22 | #include "camodocal/camera_models/CameraFactory.h" 23 | #include "camodocal/camera_models/CataCamera.h" 24 | #include "camodocal/camera_models/PinholeCamera.h" 25 | #include "../estimator/parameters.h" 26 | #include "../utility/tic_toc.h" 27 | 28 | using namespace std; 29 | using namespace camodocal; 30 | using namespace Eigen; 31 | 32 | bool inBorder(const cv::Point2f &pt); 33 | void reduceVector(vector &v, vector status); 34 | void reduceVector(vector &v, vector status); 35 | 36 | class FeatureTracker 37 | { 38 | public: 39 | FeatureTracker(); 40 | map>>> trackImage(double _cur_time, const cv::Mat &_img, const cv::Mat &_img1 = cv::Mat()); 41 | void setMask(); 42 | void readIntrinsicParameter(const vector &calib_file); 43 | void showUndistortion(const string &name); 44 | void rejectWithF(); 45 | void undistortedPoints(); 46 | vector undistortedPts(vector &pts, camodocal::CameraPtr cam); 47 | vector ptsVelocity(vector &ids, vector &pts, 48 | map &cur_id_pts, map &prev_id_pts); 49 | void showTwoImage(const cv::Mat &img1, const cv::Mat &img2, 50 | vector pts1, vector pts2); 51 | void drawTrack(const cv::Mat &imLeft, const cv::Mat &imRight, 52 | vector &curLeftIds, 53 | vector &curLeftPts, 54 | vector &curRightPts, 55 | map &prevLeftPtsMap); 56 | void setPrediction(map &predictPts); 57 | double distance(cv::Point2f &pt1, cv::Point2f &pt2); 58 | void removeOutliers(set &removePtsIds); 59 | cv::Mat getTrackImage(); 60 | bool inBorder(const cv::Point2f &pt); 61 | 62 | int row, col; 63 | cv::Mat imTrack; 64 | cv::Mat mask; 65 | cv::Mat fisheye_mask; 66 | cv::Mat prev_img, cur_img; 67 | vector n_pts; 68 | vector predict_pts; 69 | vector predict_pts_debug; 70 | vector prev_pts, cur_pts, cur_right_pts; 71 | vector prev_un_pts, cur_un_pts, cur_un_right_pts; 72 | vector pts_velocity, right_pts_velocity; 73 | vector ids, ids_right; 74 | vector track_cnt; 75 | map cur_un_pts_map, prev_un_pts_map; 76 | map cur_un_right_pts_map, prev_un_right_pts_map; 77 | map prevLeftPtsMap; 78 | vector m_camera; 79 | double cur_time; 80 | double prev_time; 81 | bool stereo_cam; 82 | int n_id; 83 | bool hasPrediction; 84 | }; 85 | -------------------------------------------------------------------------------- /vins_estimator/src/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 | bool VisualIMUAlignment(map &all_image_frame, Vector3d* Bgs, Vector3d &g, VectorXd &x); -------------------------------------------------------------------------------- /vins_estimator/src/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/src/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/src/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/src/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/src/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/src/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/src/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 28 | #include "CameraPoseVisualization.h" 29 | #include 30 | #include "../estimator/estimator.h" 31 | #include "../estimator/parameters.h" 32 | #include 33 | 34 | extern ros::Publisher pub_odometry, pub_odometry_mavros; 35 | extern ros::Publisher pub_path, pub_pose; 36 | extern ros::Publisher pub_cloud, pub_map; 37 | extern ros::Publisher pub_key_poses; 38 | extern ros::Publisher pub_ref_pose, pub_cur_pose; 39 | extern ros::Publisher pub_key; 40 | extern nav_msgs::Path path; 41 | extern ros::Publisher pub_pose_graph; 42 | extern int IMAGE_ROW, IMAGE_COL; 43 | 44 | void registerPub(ros::NodeHandle &n); 45 | 46 | void pubLatestOdometry(const Eigen::Vector3d &P, const Eigen::Quaterniond &Q, const Eigen::Vector3d &V, double t); 47 | 48 | void pubTrackImage(const cv::Mat &imgTrack, const double t); 49 | 50 | void printStatistics(const Estimator &estimator, double t); 51 | 52 | void pubOdometry(const Estimator &estimator, const std_msgs::Header &header); 53 | 54 | void pubInitialGuess(const Estimator &estimator, const std_msgs::Header &header); 55 | 56 | void pubKeyPoses(const Estimator &estimator, const std_msgs::Header &header); 57 | 58 | void pubCameraPose(const Estimator &estimator, const std_msgs::Header &header); 59 | 60 | void pubPointCloud(const Estimator &estimator, const std_msgs::Header &header); 61 | 62 | void pubTF(const Estimator &estimator, const std_msgs::Header &header); 63 | 64 | void pubKeyframe(const Estimator &estimator); 65 | 66 | void pubRelocalization(const Estimator &estimator); 67 | 68 | void pubCar(const Estimator & estimator, const std_msgs::Header &header); 69 | --------------------------------------------------------------------------------