├── .gitignore ├── CMakeLists.txt ├── Log ├── dbg.txt ├── fast_lio_time_log.csv ├── fast_lio_time_log_analysis.m ├── guide.md ├── imu.txt ├── mat_out.txt ├── mat_pre.txt ├── plot.py └── pos_log.txt ├── README.md ├── config ├── avia.yaml ├── hesai32.yaml ├── horizon.yaml ├── mid360.yaml ├── ouster128_malioCity.yaml ├── ouster32.yaml ├── ouster64.yaml ├── velodyne16_kaist.yaml └── velodyne32_UrbanNav.yaml ├── include ├── Exp_mat.h ├── IKFoM_toolkit │ ├── esekfom │ │ ├── esekfom.hpp │ │ └── util.hpp │ └── mtk │ │ ├── build_manifold.hpp │ │ ├── src │ │ ├── SubManifold.hpp │ │ ├── mtkmath.hpp │ │ └── vectview.hpp │ │ ├── startIdx.hpp │ │ └── types │ │ ├── S2.hpp │ │ ├── SOn.hpp │ │ ├── vect.hpp │ │ └── wrapped_cv_mat.hpp ├── common_lib.h ├── ikd-Tree │ ├── README.md │ ├── ikd_Tree.cpp │ └── ikd_Tree.h ├── matplotlibcpp.h ├── so3_math.h └── use-ikfom.hpp ├── launch ├── gdb_debug_example.launch ├── mapping_avia.launch ├── mapping_hesai32.launch ├── mapping_horizon.launch ├── mapping_mid360.launch ├── mapping_ouster128_malioCity.launch ├── mapping_ouster32.launch ├── mapping_ouster64.launch ├── mapping_velodyne16_kaist.launch └── mapping_velodyne32_UrbanNav.launch ├── msg └── Pose6D.msg ├── package.xml ├── rviz_cfg ├── .gitignore └── loam_livox.rviz └── src ├── GNSS_Processing.hpp ├── IMU_Processing.hpp ├── laserMapping.cpp ├── preprocess.cpp └── preprocess.h /.gitignore: -------------------------------------------------------------------------------- 1 | config/.idea 2 | .idea 3 | /Log/ 4 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(fast_lio_msf) 3 | 4 | SET(CMAKE_BUILD_TYPE "Release") 5 | 6 | ADD_COMPILE_OPTIONS(-std=c++14 ) 7 | ADD_COMPILE_OPTIONS(-std=c++14 ) 8 | set( CMAKE_CXX_FLAGS "-std=c++14 -O3" ) 9 | 10 | add_definitions(-DROOT_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/\") 11 | 12 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fexceptions" ) 13 | set(CMAKE_CXX_STANDARD 14) 14 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 15 | set(CMAKE_CXX_EXTENSIONS OFF) 16 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -pthread -std=c++0x -std=c++14 -fexceptions") 17 | 18 | message("Current CPU archtecture: ${CMAKE_SYSTEM_PROCESSOR}") 19 | if(CMAKE_SYSTEM_PROCESSOR MATCHES "(x86)|(X86)|(amd64)|(AMD64)" ) 20 | include(ProcessorCount) 21 | ProcessorCount(N) 22 | message("Processer number: ${N}") 23 | if(N GREATER 4) 24 | add_definitions(-DMP_EN) 25 | add_definitions(-DMP_PROC_NUM=3) 26 | message("core for MP: 3") 27 | elseif(N GREATER 3) 28 | add_definitions(-DMP_EN) 29 | add_definitions(-DMP_PROC_NUM=2) 30 | message("core for MP: 2") 31 | else() 32 | add_definitions(-DMP_PROC_NUM=1) 33 | endif() 34 | else() 35 | add_definitions(-DMP_PROC_NUM=1) 36 | endif() 37 | 38 | find_package(OpenMP QUIET) 39 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") 40 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") 41 | 42 | find_package(PythonLibs REQUIRED) 43 | find_path(MATPLOTLIB_CPP_INCLUDE_DIRS "matplotlibcpp.h") 44 | 45 | find_package(catkin REQUIRED COMPONENTS 46 | geometry_msgs 47 | nav_msgs 48 | sensor_msgs 49 | roscpp 50 | rospy 51 | std_msgs 52 | pcl_ros 53 | tf 54 | livox_ros_driver 55 | message_generation 56 | eigen_conversions 57 | ) 58 | 59 | find_package(Eigen3 REQUIRED) 60 | find_package(PCL 1.8 REQUIRED) 61 | 62 | set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "/usr/share/cmake/geographiclib/") 63 | find_package (GeographicLib REQUIRED) 64 | 65 | message(Eigen: ${EIGEN3_INCLUDE_DIR}) 66 | 67 | include_directories( 68 | ${catkin_INCLUDE_DIRS} 69 | ${EIGEN3_INCLUDE_DIR} 70 | ${PCL_INCLUDE_DIRS} 71 | ${PYTHON_INCLUDE_DIRS} 72 | ${GeographicLib_INCLUDE_DIRS} 73 | include) 74 | 75 | add_message_files( 76 | FILES 77 | Pose6D.msg 78 | ) 79 | 80 | generate_messages( 81 | DEPENDENCIES 82 | geometry_msgs 83 | ) 84 | 85 | catkin_package( 86 | CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs message_runtime 87 | DEPENDS EIGEN3 PCL 88 | INCLUDE_DIRS 89 | ) 90 | 91 | add_executable(fastlio_msf_mapping src/laserMapping.cpp include/ikd-Tree/ikd_Tree.cpp src/preprocess.cpp) 92 | target_link_libraries(fastlio_msf_mapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${PYTHON_LIBRARIES} ${GeographicLib_LIBRARIES}) 93 | target_include_directories(fastlio_msf_mapping PRIVATE ${PYTHON_INCLUDE_DIRS} ${GeographicLib_INCLUDE_DIRS}) -------------------------------------------------------------------------------- /Log/dbg.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zhh2005757/FAST-LIO-Multi-Sensor-Fusion/a893e78becc200486e743d48e4f5a333e123f49b/Log/dbg.txt -------------------------------------------------------------------------------- /Log/fast_lio_time_log_analysis.m: -------------------------------------------------------------------------------- 1 | clear 2 | close all 3 | 4 | Color_red = [0.6350 0.0780 0.1840]; 5 | Color_blue = [0 0.4470 0.7410]; 6 | Color_orange = [0.8500 0.3250 0.0980]; 7 | Color_green = [0.4660 0.6740 0.1880]; 8 | Color_lightblue = [0.3010 0.7450 0.9330]; 9 | Color_purple = [0.4940 0.1840 0.5560]; 10 | Color_yellow = [0.9290 0.6940 0.1250]; 11 | 12 | fast_lio_ikdtree = csvread("./fast_lio_time_log.csv",1,0); 13 | timestamp_ikd = fast_lio_ikdtree(:,1); 14 | timestamp_ikd = timestamp_ikd - min(timestamp_ikd); 15 | total_time_ikd = fast_lio_ikdtree(:,2)*1e3; 16 | scan_num = fast_lio_ikdtree(:,3); 17 | incremental_time_ikd = fast_lio_ikdtree(:,4)*1e3; 18 | search_time_ikd = fast_lio_ikdtree(:,5)*1e3; 19 | delete_size_ikd = fast_lio_ikdtree(:,6); 20 | delete_time_ikd = fast_lio_ikdtree(:,7) * 1e3; 21 | tree_size_ikd_st = fast_lio_ikdtree(:,8); 22 | tree_size_ikd = fast_lio_ikdtree(:,9); 23 | add_points = fast_lio_ikdtree(:,10); 24 | 25 | fast_lio_forest = csvread("fast_lio_time_log.csv",1,0); 26 | fov_check_time_forest = fast_lio_forest(:,5)*1e3; 27 | average_time_forest = fast_lio_forest(:,2)*1e3; 28 | total_time_forest = fast_lio_forest(:,6)*1e3; 29 | incremental_time_forest = fast_lio_forest(:,3)*1e3; 30 | search_time_forest = fast_lio_forest(:,4)*1e3; 31 | timestamp_forest = fast_lio_forest(:,1); 32 | 33 | % Use slide window to calculate average 34 | L = 1; % Length of slide window 35 | for i = 1:length(timestamp_ikd) 36 | if (i 0); 78 | search_time_ikd = search_time_ikd(index_ikd); 79 | index_forest = find(search_time_forest > 0); 80 | search_time_forest = search_time_forest(index_forest); 81 | 82 | t = nexttile; 83 | hold on; 84 | boxplot_data_ikd = [incremental_time_ikd,total_time_ikd]; 85 | boxplot_data_forest = [incremental_time_forest,total_time_forest]; 86 | Colors_ikd = [Color_blue;Color_blue;Color_blue]; 87 | Colors_forest = [Color_orange;Color_orange;Color_orange]; 88 | % xticks([3,8,13]) 89 | h_search_ikd = boxplot(search_time_ikd,'Whisker',50,'Positions',1,'Colors',Color_blue,'Widths',0.3); 90 | h_search_forest = boxplot(search_time_forest,'Whisker',50,'Positions',1.5,'Colors',Color_orange,'Widths',0.3); 91 | h_ikd = boxplot(boxplot_data_ikd,'Whisker',50,'Positions',[3,5],'Colors',Color_blue,'Widths',0.3); 92 | h_forest = boxplot(boxplot_data_forest,'Whisker',50,'Positions',[3.5,5.5],'Colors',Color_orange,'Widths',0.3); 93 | ax2 = gca; 94 | ax2.YAxis.Scale = 'log'; 95 | xlim([0.5,6.0]) 96 | ylim([0.0008,100]) 97 | xticks([1.25 3.25 5.25]) 98 | xticklabels({'Nearest Search',' Incremental Updates','Total Time'}); 99 | yticks([1e-3,1e-2,1e-1,1e0,1e1,1e2]) 100 | ax2.YAxis.FontSize = 12; 101 | ax2.XAxis.FontSize = 14.5; 102 | % ax.XAxis.FontWeight = 'bold'; 103 | ylabel('Run Time/ms','FontSize',14,'FontName','Times New Roman') 104 | box_vars = [findall(h_search_ikd,'Tag','Box');findall(h_ikd,'Tag','Box');findall(h_search_forest,'Tag','Box');findall(h_forest,'Tag','Box')]; 105 | for j=1:length(box_vars) 106 | if (j<=3) 107 | Color = Color_blue; 108 | else 109 | Color = Color_orange; 110 | end 111 | patch(get(box_vars(j),'XData'),get(box_vars(j),'YData'),Color,'FaceAlpha',0.25,'EdgeColor',Color); 112 | end 113 | Lg = legend(box_vars([1,4]), {'ikd-Tree','ikd-Forest'},'Location',[0.6707 0.4305 0.265 0.07891],'fontsize',14,'fontname','Times New Roman'); 114 | grid on 115 | set(gca,'YMinorGrid','off') 116 | nexttile; 117 | hold on; 118 | grid on; 119 | box on; 120 | set(gca,'FontSize',12,'FontName','Times New Roman') 121 | plot(timestamp_ikd, alpha_bal_ikd,'-','Color',Color_blue,'LineWidth',1.2); 122 | plot(timestamp_ikd, alpha_del_ikd,'--','Color',Color_orange, 'LineWidth', 1.2); 123 | plot(timestamp_ikd, 0.6*ones(size(alpha_bal_ikd)), ':','Color','black','LineWidth',1.2); 124 | lg = legend("\alpha_{bal}", "\alpha_{del}",'location',[0.7871 0.1131 0.1433 0.069],'fontsize',14,'fontname','Times New Roman') 125 | title("Re-balancing Criterion",'FontSize',16,'FontName','Times New Roman') 126 | xlabel("time/s",'FontSize',16,'FontName','Times New Roman') 127 | yl = ylabel("\alpha",'FontSize',15, 'Position',[285.7 0.4250 -1]) 128 | xlim([32,390]); 129 | ylim([0,0.85]); 130 | ax3 = gca; 131 | ax3.YAxis.FontSize = 12; 132 | ax3.XAxis.FontSize = 12; 133 | % print('./Figures/fastlio_exp_combine','-depsc','-r1200') 134 | % exportgraphics(f,'./Figures/fastlio_exp_combine_1.pdf','ContentType','vector') 135 | 136 | -------------------------------------------------------------------------------- /Log/guide.md: -------------------------------------------------------------------------------- 1 | Here saved the debug records which can be drew by the ../Log/plot.py. The record function can be found frm the MACRO: DEBUG_FILE_DIR(name) in common_lib.h. 2 | -------------------------------------------------------------------------------- /Log/imu.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zhh2005757/FAST-LIO-Multi-Sensor-Fusion/a893e78becc200486e743d48e4f5a333e123f49b/Log/imu.txt -------------------------------------------------------------------------------- /Log/plot.py: -------------------------------------------------------------------------------- 1 | # import matplotlib 2 | # matplotlib.use('Agg') 3 | import numpy as np 4 | import matplotlib.pyplot as plt 5 | 6 | 7 | #######for ikfom 8 | fig, axs = plt.subplots(4,2) 9 | lab_pre = ['', 'pre-x', 'pre-y', 'pre-z'] 10 | lab_out = ['', 'out-x', 'out-y', 'out-z'] 11 | plot_ind = range(7,10) 12 | a_pre=np.loadtxt('mat_pre.txt') 13 | a_out=np.loadtxt('mat_out.txt') 14 | time=a_pre[:,0] 15 | axs[0,0].set_title('Attitude') 16 | axs[1,0].set_title('Translation') 17 | axs[2,0].set_title('Extrins-R') 18 | axs[3,0].set_title('Extrins-T') 19 | axs[0,1].set_title('Velocity') 20 | axs[1,1].set_title('bg') 21 | axs[2,1].set_title('ba') 22 | axs[3,1].set_title('Gravity') 23 | for i in range(1,4): 24 | for j in range(8): 25 | axs[j%4, j/4].plot(time, a_pre[:,i+j*3],'.-', label=lab_pre[i]) 26 | axs[j%4, j/4].plot(time, a_out[:,i+j*3],'.-', label=lab_out[i]) 27 | for j in range(8): 28 | # axs[j].set_xlim(386,389) 29 | axs[j%4, j/4].grid() 30 | axs[j%4, j/4].legend() 31 | plt.grid() 32 | #######for ikfom####### 33 | 34 | 35 | #### Draw IMU data 36 | # fig, axs = plt.subplots(2) 37 | # imu=np.loadtxt('imu.txt') 38 | # time=imu[:,0] 39 | # axs[0].set_title('Gyroscope') 40 | # axs[1].set_title('Accelerameter') 41 | # lab_1 = ['gyr-x', 'gyr-y', 'gyr-z'] 42 | # lab_2 = ['acc-x', 'acc-y', 'acc-z'] 43 | # for i in range(3): 44 | # # if i==1: 45 | # axs[0].plot(time, imu[:,i+1],'.-', label=lab_1[i]) 46 | # axs[1].plot(time, imu[:,i+4],'.-', label=lab_2[i]) 47 | # for i in range(2): 48 | # # axs[i].set_xlim(386,389) 49 | # axs[i].grid() 50 | # axs[i].legend() 51 | # plt.grid() 52 | 53 | # #### Draw time calculation 54 | # plt.figure(3) 55 | # fig = plt.figure() 56 | # font1 = {'family' : 'Times New Roman', 57 | # 'weight' : 'normal', 58 | # 'size' : 12, 59 | # } 60 | # c="red" 61 | # a_out1=np.loadtxt('Log/mat_out_time_indoor1.txt') 62 | # a_out2=np.loadtxt('Log/mat_out_time_indoor2.txt') 63 | # a_out3=np.loadtxt('Log/mat_out_time_outdoor.txt') 64 | # # n = a_out[:,1].size 65 | # # time_mean = a_out[:,1].mean() 66 | # # time_se = a_out[:,1].std() / np.sqrt(n) 67 | # # time_err = a_out[:,1] - time_mean 68 | # # feat_mean = a_out[:,2].mean() 69 | # # feat_err = a_out[:,2] - feat_mean 70 | # # feat_se = a_out[:,2].std() / np.sqrt(n) 71 | # ax1 = fig.add_subplot(111) 72 | # ax1.set_ylabel('Effective Feature Numbers',font1) 73 | # ax1.boxplot(a_out1[:,2], showfliers=False, positions=[0.9]) 74 | # ax1.boxplot(a_out2[:,2], showfliers=False, positions=[1.9]) 75 | # ax1.boxplot(a_out3[:,2], showfliers=False, positions=[2.9]) 76 | # ax1.set_ylim([0, 3000]) 77 | 78 | # ax2 = ax1.twinx() 79 | # ax2.spines['right'].set_color('red') 80 | # ax2.set_ylabel('Compute Time (ms)',font1) 81 | # ax2.yaxis.label.set_color('red') 82 | # ax2.tick_params(axis='y', colors='red') 83 | # ax2.boxplot(a_out1[:,1]*1000, showfliers=False, positions=[1.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) 84 | # ax2.boxplot(a_out2[:,1]*1000, showfliers=False, positions=[2.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) 85 | # ax2.boxplot(a_out3[:,1]*1000, showfliers=False, positions=[3.1],boxprops=dict(color=c),capprops=dict(color=c),whiskerprops=dict(color=c)) 86 | # ax2.set_xlim([0.5, 3.5]) 87 | # ax2.set_ylim([0, 100]) 88 | 89 | # plt.xticks([1,2,3], ('Outdoor Scene', 'Indoor Scene 1', 'Indoor Scene 2')) 90 | # # # print(time_se) 91 | # # # print(a_out3[:,2]) 92 | # plt.grid() 93 | # plt.savefig("time.pdf", dpi=1200) 94 | plt.show() 95 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## FAST-LIO-Multi-Sensor-Fusion 2 | Fusing GNSS and wheel measurements based on FAST-LIO and IKFOM 3 | 1. Fusing GNSS measurement and support GNSS heading auto-initialization. 4 | 2. Fusing wheel measurement and support the estimation of wheel extrinsic parameters and wheel scale factor meanwhile. 5 | 3. Tested on the Kaist Complex Urban Dataset. 6 | 7 | **Related paper and codes**: 8 | GNSS data handling part refers to [FAST_LIO_SAM](https://github.com/kahowang/FAST_LIO_SAM). 9 | Wheel fusion part refers to [Vehicle-Motion-Constraint-Based Visual-Inertial-Odometer Fusion With Online Extrinsic Calibration](https://ieeexplore.ieee.org/abstract/document/10272296). If you'd like to use this wheel fusion part of this package for academic research please cite this paper. 10 | 11 | --- 12 | @ARTICLE{10272296, 13 | author={Zhao, Hang and Ji, Xinchun and Wei, Dongyan}, 14 | journal={IEEE Sensors Journal}, 15 | title={Vehicle-Motion-Constraint-Based Visual-Inertial-Odometer Fusion With Online Extrinsic Calibration}, 16 | year={2023}, 17 | volume={23}, 18 | number={22}, 19 | pages={27895-27908}, 20 | keywords={Odometers;Calibration;Wheels;Velocity measurement;Sensors;Cameras;Visualization;Extrinsic calibration;robust initialization;vehicle motion constraint;visual-inertial-odometer fusion}, 21 | doi={10.1109/JSEN.2023.3319345}} 22 | --- 23 | 24 | ## FAST-LIO 25 | **FAST-LIO** (Fast LiDAR-Inertial Odometry) is a computationally efficient and robust LiDAR-inertial odometry package. It fuses LiDAR feature points with IMU data using a tightly-coupled iterated extended Kalman filter to allow robust navigation in fast-motion, noisy or cluttered environments where degeneration occurs. Our package address many key issues: 26 | 1. Fast iterated Kalman filter for odometry optimization; 27 | 2. Automaticaly initialized at most steady environments; 28 | 3. Parallel KD-Tree Search to decrease the computation; 29 | 30 | ## FAST-LIO 2.0 (2021-07-05 Update) 31 | 32 | 33 |
34 | 35 | 36 |
37 | 38 | **Related video:** [FAST-LIO2](https://youtu.be/2OvjGnxszf8), [FAST-LIO1](https://youtu.be/iYCY6T79oNU) 39 | 40 | **Pipeline:** 41 |
42 | 43 |
44 | 45 | **New Features:** 46 | 1. Incremental mapping using [ikd-Tree](https://github.com/hku-mars/ikd-Tree), achieve faster speed and over 100Hz LiDAR rate. 47 | 2. Direct odometry (scan to map) on Raw LiDAR points (feature extraction can be disabled), achieving better accuracy. 48 | 3. Since no requirements for feature extraction, FAST-LIO2 can support many types of LiDAR including spinning (Velodyne, Ouster) and solid-state (Livox Avia, Horizon, MID-70) LiDARs, and can be easily extended to support more LiDARs. 49 | 4. Support external IMU. 50 | 5. Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry Pi 4B(8G RAM). 51 | 52 | **Related papers**: 53 | 54 | [FAST-LIO2: Fast Direct LiDAR-inertial Odometry](doc/Fast_LIO_2.pdf) 55 | 56 | [FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter](https://arxiv.org/abs/2010.08196) 57 | 58 | **Contributors** 59 | 60 | [Wei Xu 徐威](https://github.com/XW-HKU),[Yixi Cai 蔡逸熙](https://github.com/Ecstasy-EC),[Dongjiao He 贺东娇](https://github.com/Joanna-HE),[Fangcheng Zhu 朱方程](https://github.com/zfc-zfc),[Jiarong Lin 林家荣](https://github.com/ziv-lin),[Zheng Liu 刘政](https://github.com/Zale-Liu), [Borong Yuan](https://github.com/borongyuan) 61 | 62 | 66 | 67 | ## 1. Prerequisites 68 | ### 1.1 **Ubuntu** and **ROS** 69 | **Ubuntu >= 16.04** 70 | 71 | For **Ubuntu 18.04 or higher**, the **default** PCL and Eigen is enough for FAST-LIO to work normally. 72 | 73 | ROS >= Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation) 74 | 75 | ### 1.2. **PCL && Eigen** 76 | PCL >= 1.8, Follow [PCL Installation](http://www.pointclouds.org/downloads/linux.html). 77 | 78 | Eigen >= 3.3.4, Follow [Eigen Installation](http://eigen.tuxfamily.org/index.php?title=Main_Page). 79 | 80 | ### 1.3. **livox_ros_driver** 81 | Follow [livox_ros_driver Installation](https://github.com/Livox-SDK/livox_ros_driver). 82 | 83 | *Remarks:* 84 | - Since the FAST-LIO must support Livox serials LiDAR firstly, so the **livox_ros_driver** must be installed and **sourced** before run any FAST-LIO luanch file. 85 | - How to source? The easiest way is add the line ``` source $Livox_ros_driver_dir$/devel/setup.bash ``` to the end of file ``` ~/.bashrc ```, where ``` $Livox_ros_driver_dir$ ``` is the directory of the livox ros driver workspace (should be the ``` ws_livox ``` directory if you completely followed the livox official document). 86 | 87 | 88 | ## 2. Build 89 | If you want to use docker conatiner to run fastlio2, please install the docker on you machine. 90 | Follow [Docker Installation](https://docs.docker.com/engine/install/ubuntu/). 91 | ### 2.1 Docker Container 92 | User can create a new script with anyname by the following command in linux: 93 | ``` 94 | touch .sh 95 | ``` 96 | Place the following code inside the ``` .sh ``` script. 97 | ``` 98 | #!/bin/bash 99 | mkdir docker_ws 100 | # Script to run ROS Kinetic with GUI support in Docker 101 | 102 | # Allow X server to be accessed from the local machine 103 | xhost +local: 104 | 105 | # Container name 106 | CONTAINER_NAME="fastlio2" 107 | 108 | # Run the Docker container 109 | docker run -itd \ 110 | --name=$CONTAINER_NAME \ 111 | --user mars_ugv \ 112 | --network host \ 113 | --ipc=host \ 114 | -v /home/$USER/docker_ws:/home/mars_ugv/docker_ws \ 115 | --privileged \ 116 | --env="QT_X11_NO_MITSHM=1" \ 117 | --volume="/etc/localtime:/etc/localtime:ro" \ 118 | -v /dev/bus/usb:/dev/bus/usb \ 119 | --device=/dev/dri \ 120 | --group-add video \ 121 | -v /tmp/.X11-unix:/tmp/.X11-unix \ 122 | --env="DISPLAY=$DISPLAY" \ 123 | kenny0407/marslab_fastlio2:latest \ 124 | /bin/bash 125 | ``` 126 | execute the following command to grant execute permissions to the script, making it runnable: 127 | ``` 128 | sudo chmod +x .sh 129 | ``` 130 | execute the following command to download the image and create the container. 131 | ``` 132 | ./.sh 133 | ``` 134 | 135 | *Script explanation:* 136 | - The docker run command provided below creates a container with a tag, using an image from Docker Hub. The download duration for this image can differ depending on the user's network speed. 137 | - This command also establishes a new workspace called ``` docker_ws ```, which serves as a shared folder between the Docker container and the host machine. This means that if users wish to run the rosbag example, they need to download the rosbag file and place it in the ``` docker_ws ``` directory on their host machine. 138 | - Subsequently, a folder with the same name inside the Docker container will receive this file. Users can then easily play the file within Docker. 139 | - In this example, we've shared the network of the host machine with the Docker container. Consequently, if users execute the ``` rostopic list ``` command, they will observe identical output whether they run it on the host machine or inside the Docker container." 140 | ### 2.2 Build from source 141 | Clone the repository and catkin_make: 142 | 143 | ``` 144 | cd ~/$A_ROS_DIR$/src 145 | git clone https://github.com/hku-mars/FAST_LIO.git 146 | cd FAST_LIO 147 | git submodule update --init 148 | cd ../.. 149 | catkin_make 150 | source devel/setup.bash 151 | ``` 152 | - Remember to source the livox_ros_driver before build (follow 1.3 **livox_ros_driver**) 153 | - If you want to use a custom build of PCL, add the following line to ~/.bashrc 154 | ```export PCL_ROOT={CUSTOM_PCL_PATH}``` 155 | ## 3. Directly run 156 | Noted: 157 | 158 | A. Please make sure the IMU and LiDAR are **Synchronized**, that's important. 159 | 160 | B. The warning message "Failed to find match for field 'time'." means the timestamps of each LiDAR points are missed in the rosbag file. That is important for the forward propagation and backwark propagation. 161 | 162 | C. We recommend to set the **extrinsic_est_en** to false if the extrinsic is give. As for the extrinsic initiallization, please refer to our recent work: [**Robust Real-time LiDAR-inertial Initialization**](https://github.com/hku-mars/LiDAR_IMU_Init). 163 | 164 | ### 3.1 For Avia 165 | Connect to your PC to Livox Avia LiDAR by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then 166 | ``` 167 | cd ~/$FAST_LIO_ROS_DIR$ 168 | source devel/setup.bash 169 | roslaunch fast_lio_msf mapping_avia.launch 170 | roslaunch livox_ros_driver livox_lidar_msg.launch 171 | ``` 172 | - For livox serials, FAST-LIO only support the data collected by the ``` livox_lidar_msg.launch ``` since only its ``` livox_ros_driver/CustomMsg ``` data structure produces the timestamp of each LiDAR point which is very important for the motion undistortion. ``` livox_lidar.launch ``` can not produce it right now. 173 | - If you want to change the frame rate, please modify the **publish_freq** parameter in the [livox_lidar_msg.launch](https://github.com/Livox-SDK/livox_ros_driver/blob/master/livox_ros_driver/launch/livox_lidar_msg.launch) of [Livox-ros-driver](https://github.com/Livox-SDK/livox_ros_driver) before make the livox_ros_driver pakage. 174 | 175 | ### 3.2 For Livox serials with external IMU 176 | 177 | mapping_avia.launch theratically supports mid-70, mid-40 or other livox serial LiDAR, but need to setup some parameters befor run: 178 | 179 | Edit ``` config/avia.yaml ``` to set the below parameters: 180 | 181 | 1. LiDAR point cloud topic name: ``` lid_topic ``` 182 | 2. IMU topic name: ``` imu_topic ``` 183 | 3. Translational extrinsic: ``` extrinsic_T ``` 184 | 4. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix) 185 | - The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame). They can be found in the official manual. 186 | - FAST-LIO produces a very simple software time sync for livox LiDAR, set parameter ```time_sync_en``` to ture to turn on. But turn on **ONLY IF external time synchronization is really not possible**, since the software time sync cannot make sure accuracy. 187 | 188 | ### 3.3 For Velodyne or Ouster (Velodyne as an example) 189 | 190 | Step A: Setup before run 191 | 192 | Edit ``` config/velodyne.yaml ``` to set the below parameters: 193 | 194 | 1. LiDAR point cloud topic name: ``` lid_topic ``` 195 | 2. IMU topic name: ``` imu_topic ``` (both internal and external, 6-aixes or 9-axies are fine) 196 | 3. Set the parameter ```timestamp_unit``` based on the unit of **time** (Velodyne) or **t** (Ouster) field in PoindCloud2 rostopic 197 | 4. Line number (we tested 16, 32 and 64 line, but not tested 128 or above): ``` scan_line ``` 198 | 5. Translational extrinsic: ``` extrinsic_T ``` 199 | 6. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix) 200 | - The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame). 201 | 202 | Step B: Run below 203 | ``` 204 | cd ~/$FAST_LIO_ROS_DIR$ 205 | source devel/setup.bash 206 | roslaunch fast_lio_msf mapping_velodyne.launch 207 | ``` 208 | 209 | Step C: Run LiDAR's ros driver or play rosbag. 210 | 211 | ### 3.4 PCD file save 212 | 213 | Set ``` pcd_save_enable ``` in launchfile to ``` 1 ```. All the scans (in global frame) will be accumulated and saved to the file ``` FAST_LIO/PCD/scans.pcd ``` after the FAST-LIO is terminated. ```pcl_viewer scans.pcd``` can visualize the point clouds. 214 | 215 | *Tips for pcl_viewer:* 216 | - change what to visualize/color by pressing keyboard 1,2,3,4,5 when pcl_viewer is running. 217 | ``` 218 | 1 is all random 219 | 2 is X values 220 | 3 is Y values 221 | 4 is Z values 222 | 5 is intensity 223 | ``` 224 | 225 | ## 4. Rosbag Example 226 | ### 4.1 Livox Avia Rosbag 227 |
228 | 229 | 230 | 231 | Files: Can be downloaded from [google drive](https://drive.google.com/drive/folders/1CGYEJ9-wWjr8INyan6q1BZz_5VtGB-fP?usp=sharing) 232 | 233 | Run: 234 | ``` 235 | roslaunch fast_lio_msf mapping_avia.launch 236 | rosbag play YOUR_DOWNLOADED.bag 237 | 238 | ``` 239 | 240 | ### 4.2 Velodyne HDL-32E Rosbag 241 | 242 | **NCLT Dataset**: Original bin file can be found [here](http://robots.engin.umich.edu/nclt/). 243 | 244 | We produce [Rosbag Files](https://drive.google.com/drive/folders/1blQJuAB4S80NwZmpM6oALyHWvBljPSOE?usp=sharing) and [a python script](https://drive.google.com/file/d/1QC9IRBv2_-cgo_AEvL62E1ml1IL9ht6J/view?usp=sharing) to generate Rosbag files: ```python3 sensordata_to_rosbag_fastlio.py bin_file_dir bag_name.bag``` 245 | 246 | Run: 247 | ``` 248 | roslaunch fast_lio_msf mapping_velodyne.launch 249 | rosbag play YOUR_DOWNLOADED.bag 250 | ``` 251 | 252 | ## 5.Implementation on UAV 253 | In order to validate the robustness and computational efficiency of FAST-LIO in actual mobile robots, we build a small-scale quadrotor which can carry a Livox Avia LiDAR with 70 degree FoV and a DJI Manifold 2-C onboard computer with a 1.8 GHz Intel i7-8550U CPU and 8 G RAM, as shown in below. 254 | 255 | The main structure of this UAV is 3d printed (Aluminum or PLA), the .stl file will be open-sourced in the future. 256 | 257 |
258 | 259 | 260 |
261 | 262 | ## 6.Acknowledgments 263 | 264 | Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), [Livox_Mapping](https://github.com/Livox-SDK/livox_mapping), [LINS](https://github.com/ChaoqinRobotics/LINS---LiDAR-inertial-SLAM) and [Loam_Livox](https://github.com/hku-mars/loam_livox). 265 | -------------------------------------------------------------------------------- /config/avia.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/livox/lidar" 3 | imu_topic: "/livox/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 6 11 | blind: 4 12 | 13 | mapping: 14 | acc_cov: 0.1 15 | gyr_cov: 0.1 16 | b_acc_cov: 0.0001 17 | b_gyr_cov: 0.0001 18 | fov_degree: 90 19 | det_range: 450.0 20 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 21 | extrinsic_T: [ 0.04165, 0.02326, -0.0284 ] 22 | extrinsic_R: [ 1, 0, 0, 23 | 0, 1, 0, 24 | 0, 0, 1] 25 | 26 | publish: 27 | path_en: false 28 | scan_publish_en: true # false: close all the point cloud output 29 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 30 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 31 | 32 | pcd_save: 33 | pcd_save_en: true 34 | interval: -1 # how many LiDAR frames saved in each pcd file; 35 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 36 | -------------------------------------------------------------------------------- /config/hesai32.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/hesai/pandar" 3 | imu_topic: "/alphasense/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 4 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 4 for hesai Lidar 10 | scan_line: 32 11 | scan_rate: 10 # only need to be set for velodyne, unit: Hz, 12 | timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. 13 | blind: 0.3 14 | 15 | mapping: 16 | acc_cov: 0.37999999999999995 17 | gyr_cov: 0.37999999999999995 18 | b_acc_cov: 0.0043 19 | b_gyr_cov: 0.000266 20 | fov_degree: 180 21 | det_range: 150.0 22 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 23 | extrinsic_T: [ -0.001, -0.00855, 0.055 ] 24 | extrinsic_R: [ 0, -1, 0, 25 | -1, 0, 0, 26 | 0, 0, -1 ] 27 | 28 | publish: 29 | path_en: true 30 | scan_publish_en: true # false: close all the point cloud output 31 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 32 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 33 | 34 | pcd_save: 35 | pcd_save_en: true 36 | interval: -1 # how many LiDAR frames saved in each pcd file; 37 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 38 | -------------------------------------------------------------------------------- /config/horizon.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/livox/lidar" 3 | imu_topic: "/livox/imu" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 6 11 | blind: 4 12 | 13 | mapping: 14 | acc_cov: 0.1 15 | gyr_cov: 0.1 16 | b_acc_cov: 0.0001 17 | b_gyr_cov: 0.0001 18 | fov_degree: 100 19 | det_range: 260.0 20 | extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic 21 | extrinsic_T: [ 0.05512, 0.02226, -0.0297 ] 22 | extrinsic_R: [ 1, 0, 0, 23 | 0, 1, 0, 24 | 0, 0, 1] 25 | 26 | publish: 27 | path_en: false 28 | scan_publish_en: true # false: close all the point cloud output 29 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 30 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 31 | 32 | pcd_save: 33 | pcd_save_en: true 34 | interval: -1 # how many LiDAR frames saved in each pcd file; 35 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 36 | -------------------------------------------------------------------------------- /config/mid360.yaml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zhh2005757/FAST-LIO-Multi-Sensor-Fusion/a893e78becc200486e743d48e4f5a333e123f49b/config/mid360.yaml -------------------------------------------------------------------------------- /config/ouster128_malioCity.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/os_cloud_node/points" 3 | imu_topic: "/xsens_imu_data" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 128 11 | timestamp_unit: 3 # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. 12 | blind: 4 13 | 14 | mapping: 15 | acc_cov: 0.011197412605492375 16 | gyr_cov: 0.010270904839480961 17 | b_acc_cov: 0.00011751767903346351 18 | b_gyr_cov: 0.000091355383994881894 19 | fov_degree: 180 20 | det_range: 100.0 21 | extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic, 22 | extrinsic_T: [ 0.215, 0, 0.018] 23 | extrinsic_R: [ 1, 0, 0, 24 | 0, 1, 0, 25 | 0, 0, 1 ] 26 | 27 | publish: 28 | path_en: true 29 | scan_publish_en: true # false: close all the point cloud output 30 | dense_publish_en: false # false: low down the points number in a global-frame point clouds scan. 31 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 32 | 33 | pcd_save: 34 | pcd_save_en: false 35 | interval: -1 # how many LiDAR frames saved in each pcd file; 36 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 37 | -------------------------------------------------------------------------------- /config/ouster32.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/ouster/points" 3 | imu_topic: "/ouster/imu" 4 | wheel_topic: "/odom" 5 | use_wheel: false 6 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 7 | time_offset_lidar_to_imu: -0.014057 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 8 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 9 | 10 | preprocess: 11 | lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 12 | scan_line: 32 13 | timestamp_unit: 3 # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. 14 | blind: 4 15 | 16 | wheel: 17 | wheel_cov: 0.01 18 | nhc_y_cov: 0.01 19 | nhc_z_cov: 0.01 20 | extrinsic_T: [ 0.0, 0.0, -0.5 ] 21 | extrinsic_R: [ 1, 0, 0, 22 | 0, 1, 0, 23 | 0, 0, 1 ] 24 | 25 | mapping: 26 | acc_cov: 0.1 27 | gyr_cov: 0.1 28 | b_acc_cov: 0.0001 29 | b_gyr_cov: 0.0001 30 | fov_degree: 180 31 | det_range: 150.0 32 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 33 | extrinsic_T: [ 0.063169, -0.014907, -0.316769 ] 34 | extrinsic_R: [0.999017, 0.036432, 0.025237, 35 | -0.036084, 0.999249, -0.014119, 36 | -0.025733, 0.013194, 0.999582] 37 | 38 | publish: 39 | path_en: true 40 | scan_publish_en: true # false: close all the point cloud output 41 | dense_publish_en: false # false: low down the points number in a global-frame point clouds scan. 42 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 43 | 44 | pcd_save: 45 | pcd_save_en: true 46 | interval: -1 # how many LiDAR frames saved in each pcd file; 47 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 48 | -------------------------------------------------------------------------------- /config/ouster64.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/chinook/ouster/points" 3 | imu_topic: "/chinook/imu/data" 4 | wheel_topic: "/chinook/husky_velocity_controller/odom" 5 | use_wheel: use 6 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 7 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 8 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 9 | 10 | preprocess: 11 | lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 12 | scan_line: 64 13 | timestamp_unit: 3 # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. 14 | blind: 4 15 | 16 | wheel: 17 | wheel_cov: 0.01 18 | nhc_y_cov: 0.01 19 | nhc_z_cov: 0.01 20 | extrinsic_T: [ 0.217, 0.000, 0.196 ] 21 | extrinsic_R: [-0.9999660, 0.0080227, 0.0019037, 22 | 0.0079747, 0.9996800, -0.0240041, 23 | -0.0020957, -0.0239881, -0.9997100] 24 | 25 | mapping: 26 | acc_cov: 0.1 27 | gyr_cov: 0.1 28 | b_acc_cov: 0.0001 29 | b_gyr_cov: 0.0001 30 | fov_degree: 180 31 | det_range: 150.0 32 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 33 | extrinsic_T: [ -0.03, 0.1, 0.0 ] 34 | extrinsic_R: [-1, 0, 0, 35 | 0, 1, 0, 36 | 0, 0, -1] 37 | 38 | publish: 39 | path_en: true 40 | scan_publish_en: true # false: close all the point cloud output 41 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 42 | scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame 43 | 44 | pcd_save: 45 | pcd_save_en: false 46 | interval: -1 # how many LiDAR frames saved in each pcd file; 47 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 48 | -------------------------------------------------------------------------------- /config/velodyne16_kaist.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic_left: "/ns2/velodyne_points" 3 | lid_topic_right: "/ns1/velodyne_points" 4 | imu_topic: "/imu/data_raw" 5 | wheel_topic: "/odom" 6 | gnss_topic: "/gps/fix" 7 | use_wheel: true 8 | use_gnss: true 9 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 10 | 11 | preprocess: 12 | lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 13 | scan_line: 16 14 | scan_rate: 10 # only need to be set for velodyne, unit: Hz, 15 | blind: 1 16 | 17 | wheel: 18 | wheel_cov: 0.01 19 | nhc_y_cov: 0.01 20 | nhc_z_cov: 0.001 21 | extrinsic_est_wheel: false 22 | scale_est_wheel: false 23 | extrinsic_T: [ 0.07, 0.0, -1.7 ] 24 | extrinsic_R: [ 1, 0, 0, 25 | 0, 1, 0, 26 | 0, 0, 1 ] 27 | wheel_scale: [1.0] 28 | 29 | mapping: 30 | acc_cov: 0.04 31 | gyr_cov: 0.004 32 | b_acc_cov: 0.002 33 | b_gyr_cov: 4.0e-5 34 | fov_degree: 180 35 | det_range: 100.0 36 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic 37 | extrinsic_T: [ 0.0, 0.0, 0.0 ] 38 | extrinsic_R: [1, 0, 0, 39 | 0, 1, 0, 40 | 0, 0, 1] 41 | 42 | right_lidar_to_imu: [ -0.514521, 0.701075, -0.493723, -0.263596, 43 | -0.492472, -0.712956, -0.499164, -0.373928, 44 | -0.701954, -0.0136853, 0.712091, 0.24377, 45 | 0, 0, 0, 1 ] 46 | 47 | left_lidar_to_imu: [ -0.516377, -0.702254, -0.490096, -0.264623, 48 | 0.491997, -0.711704, 0.501414, 0.431973, 49 | -0.700923, 0.0177927, 0.713015, 0.24043, 50 | 0, 0, 0, 1 ] 51 | 52 | extrinT_Gnss2IMU: [ -0.25, 0, 0.0 ] 53 | extrinR_Gnss2IMU: [ 1, 0, 0, 54 | 0, 1, 0, 55 | 0, 0, 1 ] 56 | 57 | publish: 58 | path_en: true 59 | scan_publish_en: true # false: close all the point cloud output 60 | dense_publish_en: false # false: low down the points number in a global-frame point clouds scan. 61 | scan_bodyframe_pub_en: false # true: output the point cloud scans in IMU-body-frame 62 | 63 | pcd_save: 64 | pcd_save_en: true 65 | interval: 3000 # how many LiDAR frames saved in each pcd file; 66 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. -------------------------------------------------------------------------------- /config/velodyne32_UrbanNav.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lid_topic: "/velodyne_points" 3 | imu_topic: "/imu/data" 4 | time_sync_en: false # ONLY turn on when external time synchronization is really not possible 5 | time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). 6 | # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 7 | 8 | preprocess: 9 | lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 10 | scan_line: 32 11 | timestamp_unit: 3 # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. 12 | blind: 4 13 | 14 | mapping: 15 | acc_cov: 0.011197412605492375 16 | gyr_cov: 0.010270904839480961 17 | b_acc_cov: 0.00011751767903346351 18 | b_gyr_cov: 0.000091355383994881894 19 | fov_degree: 180 20 | det_range: 100.0 21 | extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic, 22 | extrinsic_T: [ 0, 0, 0.28] 23 | extrinsic_R: [ 1, 0, 0, 24 | 0, 1, 0, 25 | 0, 0, 1 ] 26 | 27 | publish: 28 | path_en: true 29 | scan_publish_en: true # false: close all the point cloud output 30 | dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. 31 | scan_bodyframe_pub_en: false # true: output the point cloud scans in IMU-body-frame 32 | 33 | pcd_save: 34 | pcd_save_en: false 35 | interval: -1 # how many LiDAR frames saved in each pcd file; 36 | # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames. 37 | -------------------------------------------------------------------------------- /include/Exp_mat.h: -------------------------------------------------------------------------------- 1 | #ifndef EXP_MAT_H 2 | #define EXP_MAT_H 3 | 4 | #include 5 | #include 6 | #include 7 | // #include 8 | 9 | #define SKEW_SYM_MATRX(v) 0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0 10 | 11 | template 12 | Eigen::Matrix Exp(const Eigen::Matrix &&ang) 13 | { 14 | T ang_norm = ang.norm(); 15 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 16 | if (ang_norm > 0.0000001) 17 | { 18 | Eigen::Matrix r_axis = ang / ang_norm; 19 | Eigen::Matrix K; 20 | K << SKEW_SYM_MATRX(r_axis); 21 | /// Roderigous Tranformation 22 | return Eye3 + std::sin(ang_norm) * K + (1.0 - std::cos(ang_norm)) * K * K; 23 | } 24 | else 25 | { 26 | return Eye3; 27 | } 28 | } 29 | 30 | template 31 | Eigen::Matrix Exp(const Eigen::Matrix &ang_vel, const Ts &dt) 32 | { 33 | T ang_vel_norm = ang_vel.norm(); 34 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 35 | 36 | if (ang_vel_norm > 0.0000001) 37 | { 38 | Eigen::Matrix r_axis = ang_vel / ang_vel_norm; 39 | Eigen::Matrix K; 40 | 41 | K << SKEW_SYM_MATRX(r_axis); 42 | 43 | T r_ang = ang_vel_norm * dt; 44 | 45 | /// Roderigous Tranformation 46 | return Eye3 + std::sin(r_ang) * K + (1.0 - std::cos(r_ang)) * K * K; 47 | } 48 | else 49 | { 50 | return Eye3; 51 | } 52 | } 53 | 54 | template 55 | Eigen::Matrix Exp(const T &v1, const T &v2, const T &v3) 56 | { 57 | T &&norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); 58 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 59 | if (norm > 0.00001) 60 | { 61 | T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; 62 | Eigen::Matrix K; 63 | K << SKEW_SYM_MATRX(r_ang); 64 | 65 | /// Roderigous Tranformation 66 | return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; 67 | } 68 | else 69 | { 70 | return Eye3; 71 | } 72 | } 73 | 74 | /* Logrithm of a Rotation Matrix */ 75 | template 76 | Eigen::Matrix Log(const Eigen::Matrix &R) 77 | { 78 | T &&theta = std::acos(0.5 * (R.trace() - 1)); 79 | Eigen::Matrix K(R(2,1) - R(1,2), R(0,2) - R(2,0), R(1,0) - R(0,1)); 80 | return (std::abs(theta) < 0.001) ? (0.5 * K) : (0.5 * theta / std::sin(theta) * K); 81 | } 82 | 83 | // template 84 | // cv::Mat Exp(const T &v1, const T &v2, const T &v3) 85 | // { 86 | 87 | // T norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); 88 | // cv::Mat Eye3 = cv::Mat::eye(3, 3, CV_32F); 89 | // if (norm > 0.0000001) 90 | // { 91 | // T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; 92 | // cv::Mat K = (cv::Mat_(3,3) << SKEW_SYM_MATRX(r_ang)); 93 | 94 | // /// Roderigous Tranformation 95 | // return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; 96 | // } 97 | // else 98 | // { 99 | // return Eye3; 100 | // } 101 | // } 102 | 103 | #endif 104 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/esekfom/util.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2019--2023, The University of Hong Kong 3 | * All rights reserved. 4 | * 5 | * Author: Dongjiao HE 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of the Universitaet Bremen nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | */ 34 | 35 | #ifndef __MEKFOM_UTIL_HPP__ 36 | #define __MEKFOM_UTIL_HPP__ 37 | 38 | #include 39 | #include "../mtk/src/mtkmath.hpp" 40 | namespace esekfom { 41 | 42 | template 43 | class is_same { 44 | public: 45 | operator bool() { 46 | return false; 47 | } 48 | }; 49 | template 50 | class is_same { 51 | public: 52 | operator bool() { 53 | return true; 54 | } 55 | }; 56 | 57 | template 58 | class is_double { 59 | public: 60 | operator bool() { 61 | return false; 62 | } 63 | }; 64 | 65 | template<> 66 | class is_double { 67 | public: 68 | operator bool() { 69 | return true; 70 | } 71 | }; 72 | 73 | template 74 | static T 75 | id(const T &x) 76 | { 77 | return x; 78 | } 79 | 80 | } // namespace esekfom 81 | 82 | #endif // __MEKFOM_UTIL_HPP__ 83 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/build_manifold.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/build_manifold.hpp 75 | * @brief Macro to automatically construct compound manifolds. 76 | * 77 | */ 78 | #ifndef MTK_AUTOCONSTRUCT_HPP_ 79 | #define MTK_AUTOCONSTRUCT_HPP_ 80 | 81 | #include 82 | 83 | #include 84 | #include 85 | #include 86 | 87 | #include "src/SubManifold.hpp" 88 | #include "startIdx.hpp" 89 | 90 | #ifndef PARSED_BY_DOXYGEN 91 | //////// internals ////// 92 | 93 | #define MTK_APPLY_MACRO_ON_TUPLE(r, macro, tuple) macro tuple 94 | 95 | #define MTK_TRANSFORM_COMMA(macro, entries) BOOST_PP_SEQ_ENUM(BOOST_PP_SEQ_TRANSFORM_S(1, MTK_APPLY_MACRO_ON_TUPLE, macro, entries)) 96 | 97 | #define MTK_TRANSFORM(macro, entries) BOOST_PP_SEQ_FOR_EACH_R(1, MTK_APPLY_MACRO_ON_TUPLE, macro, entries) 98 | 99 | #define MTK_CONSTRUCTOR_ARG( type, id) const type& id = type() 100 | #define MTK_CONSTRUCTOR_COPY( type, id) id(id) 101 | #define MTK_BOXPLUS( type, id) id.boxplus(MTK::subvector(__vec, &self::id), __scale); 102 | #define MTK_OPLUS( type, id) id.oplus(MTK::subvector_(__vec, &self::id), __scale); 103 | #define MTK_BOXMINUS( type, id) id.boxminus(MTK::subvector(__res, &self::id), __oth.id); 104 | #define MTK_S2_hat( type, id) if(id.IDX == idx){id.S2_hat(res);} 105 | #define MTK_S2_Nx_yy( type, id) if(id.IDX == idx){id.S2_Nx_yy(res);} 106 | #define MTK_S2_Mx( type, id) if(id.IDX == idx){id.S2_Mx(res, dx);} 107 | #define MTK_OSTREAM( type, id) << __var.id << " " 108 | #define MTK_ISTREAM( type, id) >> __var.id 109 | #define MTK_S2_state( type, id) if(id.TYP == 1){S2_state.push_back(std::make_pair(id.IDX, id.DIM));} 110 | #define MTK_SO3_state( type, id) if(id.TYP == 2){(SO3_state).push_back(std::make_pair(id.IDX, id.DIM));} 111 | #define MTK_vect_state( type, id) if(id.TYP == 0){(vect_state).push_back(std::make_pair(std::make_pair(id.IDX, id.DIM), type::DOF));} 112 | 113 | #define MTK_SUBVARLIST(seq, S2state, SO3state) \ 114 | BOOST_PP_FOR_1( \ 115 | ( \ 116 | BOOST_PP_SEQ_SIZE(seq), \ 117 | BOOST_PP_SEQ_HEAD(seq), \ 118 | BOOST_PP_SEQ_TAIL(seq) (~), \ 119 | 0,\ 120 | 0,\ 121 | S2state,\ 122 | SO3state ),\ 123 | MTK_ENTRIES_TEST, MTK_ENTRIES_NEXT, MTK_ENTRIES_OUTPUT) 124 | 125 | #define MTK_PUT_TYPE(type, id, dof, dim, S2state, SO3state) \ 126 | MTK::SubManifold id; 127 | #define MTK_PUT_TYPE_AND_ENUM(type, id, dof, dim, S2state, SO3state) \ 128 | MTK_PUT_TYPE(type, id, dof, dim, S2state, SO3state) \ 129 | enum {DOF = type::DOF + dof}; \ 130 | enum {DIM = type::DIM+dim}; \ 131 | typedef type::scalar scalar; 132 | 133 | #define MTK_ENTRIES_OUTPUT(r, state) MTK_ENTRIES_OUTPUT_I state 134 | #define MTK_ENTRIES_OUTPUT_I(s, head, seq, dof, dim, S2state, SO3state) \ 135 | MTK_APPLY_MACRO_ON_TUPLE(~, \ 136 | BOOST_PP_IF(BOOST_PP_DEC(s), MTK_PUT_TYPE, MTK_PUT_TYPE_AND_ENUM), \ 137 | ( BOOST_PP_TUPLE_REM_2 head, dof, dim, S2state, SO3state)) 138 | 139 | #define MTK_ENTRIES_TEST(r, state) MTK_TUPLE_ELEM_4_0 state 140 | 141 | //! this used to be BOOST_PP_TUPLE_ELEM_4_0: 142 | #define MTK_TUPLE_ELEM_4_0(a,b,c,d,e,f, g) a 143 | 144 | #define MTK_ENTRIES_NEXT(r, state) MTK_ENTRIES_NEXT_I state 145 | #define MTK_ENTRIES_NEXT_I(len, head, seq, dof, dim, S2state, SO3state) ( \ 146 | BOOST_PP_DEC(len), \ 147 | BOOST_PP_SEQ_HEAD(seq), \ 148 | BOOST_PP_SEQ_TAIL(seq), \ 149 | dof + BOOST_PP_TUPLE_ELEM_2_0 head::DOF,\ 150 | dim + BOOST_PP_TUPLE_ELEM_2_0 head::DIM,\ 151 | S2state,\ 152 | SO3state) 153 | 154 | #endif /* not PARSED_BY_DOXYGEN */ 155 | 156 | 157 | /** 158 | * Construct a manifold. 159 | * @param name is the class-name of the manifold, 160 | * @param entries is the list of sub manifolds 161 | * 162 | * Entries must be given in a list like this: 163 | * @code 164 | * typedef MTK::trafo > Pose; 165 | * typedef MTK::vect Vec3; 166 | * MTK_BUILD_MANIFOLD(imu_state, 167 | * ((Pose, pose)) 168 | * ((Vec3, vel)) 169 | * ((Vec3, acc_bias)) 170 | * ) 171 | * @endcode 172 | * Whitespace is optional, but the double parentheses are necessary. 173 | * Construction is done entirely in preprocessor. 174 | * After construction @a name is also a manifold. Its members can be 175 | * accessed by names given in @a entries. 176 | * 177 | * @note Variable types are not allowed to have commas, thus types like 178 | * @c vect need to be typedef'ed ahead. 179 | */ 180 | #define MTK_BUILD_MANIFOLD(name, entries) \ 181 | struct name { \ 182 | typedef name self; \ 183 | std::vector > S2_state;\ 184 | std::vector > SO3_state;\ 185 | std::vector, int> > vect_state;\ 186 | MTK_SUBVARLIST(entries, S2_state, SO3_state) \ 187 | name ( \ 188 | MTK_TRANSFORM_COMMA(MTK_CONSTRUCTOR_ARG, entries) \ 189 | ) : \ 190 | MTK_TRANSFORM_COMMA(MTK_CONSTRUCTOR_COPY, entries) {}\ 191 | int getDOF() const { return DOF; } \ 192 | void boxplus(const MTK::vectview & __vec, scalar __scale = 1 ) { \ 193 | MTK_TRANSFORM(MTK_BOXPLUS, entries)\ 194 | } \ 195 | void oplus(const MTK::vectview & __vec, scalar __scale = 1 ) { \ 196 | MTK_TRANSFORM(MTK_OPLUS, entries)\ 197 | } \ 198 | void boxminus(MTK::vectview __res, const name& __oth) const { \ 199 | MTK_TRANSFORM(MTK_BOXMINUS, entries)\ 200 | } \ 201 | friend std::ostream& operator<<(std::ostream& __os, const name& __var){ \ 202 | return __os MTK_TRANSFORM(MTK_OSTREAM, entries); \ 203 | } \ 204 | void build_S2_state(){\ 205 | MTK_TRANSFORM(MTK_S2_state, entries)\ 206 | }\ 207 | void build_vect_state(){\ 208 | MTK_TRANSFORM(MTK_vect_state, entries)\ 209 | }\ 210 | void build_SO3_state(){\ 211 | MTK_TRANSFORM(MTK_SO3_state, entries)\ 212 | }\ 213 | void S2_hat(Eigen::Matrix &res, int idx) {\ 214 | MTK_TRANSFORM(MTK_S2_hat, entries)\ 215 | }\ 216 | void S2_Nx_yy(Eigen::Matrix &res, int idx) {\ 217 | MTK_TRANSFORM(MTK_S2_Nx_yy, entries)\ 218 | }\ 219 | void S2_Mx(Eigen::Matrix &res, Eigen::Matrix dx, int idx) {\ 220 | MTK_TRANSFORM(MTK_S2_Mx, entries)\ 221 | }\ 222 | friend std::istream& operator>>(std::istream& __is, name& __var){ \ 223 | return __is MTK_TRANSFORM(MTK_ISTREAM, entries); \ 224 | } \ 225 | }; 226 | 227 | 228 | 229 | #endif /*MTK_AUTOCONSTRUCT_HPP_*/ 230 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/src/SubManifold.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/src/SubManifold.hpp 75 | * @brief Defines the SubManifold class 76 | */ 77 | 78 | 79 | #ifndef SUBMANIFOLD_HPP_ 80 | #define SUBMANIFOLD_HPP_ 81 | 82 | 83 | #include "vectview.hpp" 84 | 85 | 86 | namespace MTK { 87 | 88 | /** 89 | * @ingroup SubManifolds 90 | * Helper class for compound manifolds. 91 | * This class wraps a manifold T and provides an enum IDX refering to the 92 | * index of the SubManifold within the compound manifold. 93 | * 94 | * Memberpointers to a submanifold can be used for @ref SubManifolds "functions accessing submanifolds". 95 | * 96 | * @tparam T The manifold type of the sub-type 97 | * @tparam idx The index of the sub-type within the compound manifold 98 | */ 99 | template 100 | struct SubManifold : public T 101 | { 102 | enum {IDX = idx, DIM = dim /*!< index of the sub-type within the compound manifold */ }; 103 | //! manifold type 104 | typedef T type; 105 | 106 | //! Construct from derived type 107 | template 108 | explicit 109 | SubManifold(const X& t) : T(t) {}; 110 | 111 | //! Construct from internal type 112 | //explicit 113 | SubManifold(const T& t) : T(t) {}; 114 | 115 | //! inherit assignment operator 116 | using T::operator=; 117 | 118 | }; 119 | 120 | } // namespace MTK 121 | 122 | 123 | #endif /* SUBMANIFOLD_HPP_ */ 124 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/src/mtkmath.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/src/mtkmath.hpp 75 | * @brief several math utility functions. 76 | */ 77 | 78 | #ifndef MTKMATH_H_ 79 | #define MTKMATH_H_ 80 | 81 | #include 82 | 83 | #include 84 | 85 | #include "../types/vect.hpp" 86 | 87 | #ifndef M_PI 88 | #define M_PI 3.1415926535897932384626433832795 89 | #endif 90 | 91 | 92 | namespace MTK { 93 | 94 | namespace internal { 95 | 96 | template 97 | struct traits { 98 | typedef typename Manifold::scalar scalar; 99 | enum {DOF = Manifold::DOF}; 100 | typedef vect vectorized_type; 101 | typedef Eigen::Matrix matrix_type; 102 | }; 103 | 104 | template<> 105 | struct traits : traits > {}; 106 | template<> 107 | struct traits : traits > {}; 108 | 109 | } // namespace internal 110 | 111 | /** 112 | * \defgroup MTKMath Mathematical helper functions 113 | */ 114 | //@{ 115 | 116 | //! constant @f$ \pi @f$ 117 | const double pi = M_PI; 118 | 119 | template inline scalar tolerance(); 120 | 121 | template<> inline float tolerance() { return 1e-5f; } 122 | template<> inline double tolerance() { return 1e-11; } 123 | 124 | 125 | /** 126 | * normalize @a x to @f$[-bound, bound] @f$. 127 | * 128 | * result for @f$ x = bound + 2\cdot n\cdot bound @f$ is arbitrary @f$\pm bound @f$. 129 | */ 130 | template 131 | inline scalar normalize(scalar x, scalar bound){ //not used 132 | if(std::fabs(x) <= bound) return x; 133 | int r = (int)(x *(scalar(1.0)/ bound)); 134 | return x - ((r + (r>>31) + 1) & ~1)*bound; 135 | } 136 | 137 | /** 138 | * Calculate cosine and sinc of sqrt(x2). 139 | * @param x2 the squared angle must be non-negative 140 | * @return a pair containing cos and sinc of sqrt(x2) 141 | */ 142 | template 143 | std::pair cos_sinc_sqrt(const scalar &x2){ 144 | using std::sqrt; 145 | using std::cos; 146 | using std::sin; 147 | static scalar const taylor_0_bound = boost::math::tools::epsilon(); 148 | static scalar const taylor_2_bound = sqrt(taylor_0_bound); 149 | static scalar const taylor_n_bound = sqrt(taylor_2_bound); 150 | 151 | assert(x2>=0 && "argument must be non-negative"); 152 | 153 | // FIXME check if bigger bounds are possible 154 | if(x2>=taylor_n_bound) { 155 | // slow fall-back solution 156 | scalar x = sqrt(x2); 157 | return std::make_pair(cos(x), sin(x)/x); // x is greater than 0. 158 | } 159 | 160 | // FIXME Replace by Horner-Scheme (4 instead of 5 FLOP/term, numerically more stable, theoretically cos and sinc can be calculated in parallel using SSE2 mulpd/addpd) 161 | // TODO Find optimal coefficients using Remez algorithm 162 | static scalar const inv[] = {1/3., 1/4., 1/5., 1/6., 1/7., 1/8., 1/9.}; 163 | scalar cosi = 1., sinc=1; 164 | scalar term = -1/2. * x2; 165 | for(int i=0; i<3; ++i) { 166 | cosi += term; 167 | term *= inv[2*i]; 168 | sinc += term; 169 | term *= -inv[2*i+1] * x2; 170 | } 171 | 172 | return std::make_pair(cosi, sinc); 173 | 174 | } 175 | 176 | template 177 | Eigen::Matrix hat(const Base& v) { 178 | Eigen::Matrix res; 179 | res << 0, -v[2], v[1], 180 | v[2], 0, -v[0], 181 | -v[1], v[0], 0; 182 | return res; 183 | } 184 | 185 | template 186 | Eigen::Matrix A_inv_trans(const Base& v){ 187 | Eigen::Matrix res; 188 | if(v.norm() > MTK::tolerance()) 189 | { 190 | res = Eigen::Matrix::Identity() + 0.5 * hat(v) + (1 - v.norm() * std::cos(v.norm() / 2) / 2 / std::sin(v.norm() / 2)) * hat(v) * hat(v) / v.squaredNorm(); 191 | 192 | } 193 | else 194 | { 195 | res = Eigen::Matrix::Identity(); 196 | } 197 | 198 | return res; 199 | } 200 | 201 | template 202 | Eigen::Matrix A_inv(const Base& v){ 203 | Eigen::Matrix res; 204 | if(v.norm() > MTK::tolerance()) 205 | { 206 | res = Eigen::Matrix::Identity() - 0.5 * hat(v) + (1 - v.norm() * std::cos(v.norm() / 2) / 2 / std::sin(v.norm() / 2)) * hat(v) * hat(v) / v.squaredNorm(); 207 | 208 | } 209 | else 210 | { 211 | res = Eigen::Matrix::Identity(); 212 | } 213 | 214 | return res; 215 | } 216 | 217 | template 218 | Eigen::Matrix S2_w_expw_( Eigen::Matrix v, scalar length) 219 | { 220 | Eigen::Matrix res; 221 | scalar norm = std::sqrt(v[0]*v[0] + v[1]*v[1]); 222 | if(norm < MTK::tolerance()){ 223 | res = Eigen::Matrix::Zero(); 224 | res(0, 1) = 1; 225 | res(1, 2) = 1; 226 | res /= length; 227 | } 228 | else{ 229 | res << -v[0]*(1/norm-1/std::tan(norm))/std::sin(norm), norm/std::sin(norm), 0, 230 | -v[1]*(1/norm-1/std::tan(norm))/std::sin(norm), 0, norm/std::sin(norm); 231 | res /= length; 232 | } 233 | } 234 | 235 | template 236 | Eigen::Matrix A_matrix(const Base & v){ 237 | Eigen::Matrix res; 238 | double squaredNorm = v[0] * v[0] + v[1] * v[1] + v[2] * v[2]; 239 | double norm = std::sqrt(squaredNorm); 240 | if(norm < MTK::tolerance()){ 241 | res = Eigen::Matrix::Identity(); 242 | } 243 | else{ 244 | res = Eigen::Matrix::Identity() + (1 - std::cos(norm)) / squaredNorm * hat(v) + (1 - std::sin(norm) / norm) / squaredNorm * hat(v) * hat(v); 245 | } 246 | return res; 247 | } 248 | 249 | template 250 | scalar exp(vectview result, vectview vec, const scalar& scale = 1) { 251 | scalar norm2 = vec.squaredNorm(); 252 | std::pair cos_sinc = cos_sinc_sqrt(scale*scale * norm2); 253 | scalar mult = cos_sinc.second * scale; 254 | result = mult * vec; 255 | return cos_sinc.first; 256 | } 257 | 258 | 259 | /** 260 | * Inverse function to @c exp. 261 | * 262 | * @param result @c vectview to the result 263 | * @param w scalar part of input 264 | * @param vec vector part of input 265 | * @param scale scale result by this value 266 | * @param plus_minus_periodicity if true values @f$[w, vec]@f$ and @f$[-w, -vec]@f$ give the same result 267 | */ 268 | template 269 | void log(vectview result, 270 | const scalar &w, const vectview vec, 271 | const scalar &scale, bool plus_minus_periodicity) 272 | { 273 | // FIXME implement optimized case for vec.squaredNorm() <= tolerance() * (w*w) via Rational Remez approximation ~> only one division 274 | scalar nv = vec.norm(); 275 | if(nv < tolerance()) { 276 | if(!plus_minus_periodicity && w < 0) { 277 | // find the maximal entry: 278 | int i; 279 | nv = vec.cwiseAbs().maxCoeff(&i); 280 | result = scale * std::atan2(nv, w) * vect::Unit(i); 281 | return; 282 | } 283 | nv = tolerance(); 284 | } 285 | scalar s = scale / nv * (plus_minus_periodicity ? std::atan(nv / w) : std::atan2(nv, w) ); 286 | 287 | result = s * vec; 288 | } 289 | 290 | 291 | } // namespace MTK 292 | 293 | 294 | #endif /* MTKMATH_H_ */ 295 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/src/vectview.hpp: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Copyright (c) 2008--2011, Universitaet Bremen 4 | * All rights reserved. 5 | * 6 | * Author: Christoph Hertzberg 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Universitaet Bremen nor the names of its 19 | * contributors may be used to endorse or promote products derived 20 | * from this software without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | * POSSIBILITY OF SUCH DAMAGE. 34 | */ 35 | /** 36 | * @file mtk/src/vectview.hpp 37 | * @brief Wrapper class around a pointer used as interface for plain vectors. 38 | */ 39 | 40 | #ifndef VECTVIEW_HPP_ 41 | #define VECTVIEW_HPP_ 42 | 43 | #include 44 | 45 | namespace MTK { 46 | 47 | /** 48 | * A view to a vector. 49 | * Essentially, @c vectview is only a pointer to @c scalar but can be used directly in @c Eigen expressions. 50 | * The dimension of the vector is given as template parameter and type-checked when used in expressions. 51 | * Data has to be modifiable. 52 | * 53 | * @tparam scalar Scalar type of the vector. 54 | * @tparam dim Dimension of the vector. 55 | * 56 | * @todo @c vectview can be replaced by simple inheritance of @c Eigen::Map, as soon as they get const-correct 57 | */ 58 | namespace internal { 59 | template 60 | struct CovBlock { 61 | typedef typename Eigen::Block, T1::DOF, T2::DOF> Type; 62 | typedef typename Eigen::Block, T1::DOF, T2::DOF> ConstType; 63 | }; 64 | 65 | template 66 | struct CovBlock_ { 67 | typedef typename Eigen::Block, T1::DIM, T2::DIM> Type; 68 | typedef typename Eigen::Block, T1::DIM, T2::DIM> ConstType; 69 | }; 70 | 71 | template 72 | struct CrossCovBlock { 73 | typedef typename Eigen::Block, T1::DOF, T2::DOF> Type; 74 | typedef typename Eigen::Block, T1::DOF, T2::DOF> ConstType; 75 | }; 76 | 77 | template 78 | struct CrossCovBlock_ { 79 | typedef typename Eigen::Block, T1::DIM, T2::DIM> Type; 80 | typedef typename Eigen::Block, T1::DIM, T2::DIM> ConstType; 81 | }; 82 | 83 | template 84 | struct VectviewBase { 85 | typedef Eigen::Matrix matrix_type; 86 | typedef typename matrix_type::MapType Type; 87 | typedef typename matrix_type::ConstMapType ConstType; 88 | }; 89 | 90 | template 91 | struct UnalignedType { 92 | typedef T type; 93 | }; 94 | } 95 | 96 | template 97 | class vectview : public internal::VectviewBase::Type { 98 | typedef internal::VectviewBase VectviewBase; 99 | public: 100 | //! plain matrix type 101 | typedef typename VectviewBase::matrix_type matrix_type; 102 | //! base type 103 | typedef typename VectviewBase::Type base; 104 | //! construct from pointer 105 | explicit 106 | vectview(scalar* data, int dim_=dim) : base(data, dim_) {} 107 | //! construct from plain matrix 108 | vectview(matrix_type& m) : base(m.data(), m.size()) {} 109 | //! construct from another @c vectview 110 | vectview(const vectview &v) : base(v) {} 111 | //! construct from Eigen::Block: 112 | template 113 | vectview(Eigen::VectorBlock block) : base(&block.coeffRef(0), block.size()) {} 114 | template 115 | vectview(Eigen::Block block) : base(&block.coeffRef(0), block.size()) {} 116 | 117 | //! inherit assignment operator 118 | using base::operator=; 119 | //! data pointer 120 | scalar* data() {return const_cast(base::data());} 121 | }; 122 | 123 | /** 124 | * @c const version of @c vectview. 125 | * Compared to @c Eigen::Map this implementation is const correct, i.e., 126 | * data will not be modifiable using this view. 127 | * 128 | * @tparam scalar Scalar type of the vector. 129 | * @tparam dim Dimension of the vector. 130 | * 131 | * @sa vectview 132 | */ 133 | template 134 | class vectview : public internal::VectviewBase::ConstType { 135 | typedef internal::VectviewBase VectviewBase; 136 | public: 137 | //! plain matrix type 138 | typedef typename VectviewBase::matrix_type matrix_type; 139 | //! base type 140 | typedef typename VectviewBase::ConstType base; 141 | //! construct from const pointer 142 | explicit 143 | vectview(const scalar* data, int dim_ = dim) : base(data, dim_) {} 144 | //! construct from column vector 145 | template 146 | vectview(const Eigen::Matrix& m) : base(m.data()) {} 147 | //! construct from row vector 148 | template 149 | vectview(const Eigen::Matrix& m) : base(m.data()) {} 150 | //! construct from another @c vectview 151 | vectview(vectview x) : base(x.data()) {} 152 | //! construct from base 153 | vectview(const base &x) : base(x) {} 154 | /** 155 | * Construct from Block 156 | * @todo adapt this, when Block gets const-correct 157 | */ 158 | template 159 | vectview(Eigen::VectorBlock block) : base(&block.coeffRef(0)) {} 160 | template 161 | vectview(Eigen::Block block) : base(&block.coeffRef(0)) {} 162 | 163 | }; 164 | 165 | 166 | } // namespace MTK 167 | 168 | #endif /* VECTVIEW_HPP_ */ 169 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/startIdx.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/startIdx.hpp 75 | * @brief Tools to access sub-elements of compound manifolds. 76 | */ 77 | #ifndef GET_START_INDEX_H_ 78 | #define GET_START_INDEX_H_ 79 | 80 | #include 81 | 82 | #include "src/SubManifold.hpp" 83 | #include "src/vectview.hpp" 84 | 85 | namespace MTK { 86 | 87 | 88 | /** 89 | * \defgroup SubManifolds Accessing Submanifolds 90 | * For compound manifolds constructed using MTK_BUILD_MANIFOLD, member pointers 91 | * can be used to get sub-vectors or matrix-blocks of a corresponding big matrix. 92 | * E.g. for a type @a pose consisting of @a orient and @a trans the member pointers 93 | * @c &pose::orient and @c &pose::trans give all required information and are still 94 | * valid if the base type gets extended or the actual types of @a orient and @a trans 95 | * change (e.g. from 2D to 3D). 96 | * 97 | * @todo Maybe require manifolds to typedef MatrixType and VectorType, etc. 98 | */ 99 | //@{ 100 | 101 | /** 102 | * Determine the index of a sub-variable within a compound variable. 103 | */ 104 | template 105 | int getStartIdx( MTK::SubManifold Base::*) 106 | { 107 | return idx; 108 | } 109 | 110 | template 111 | int getStartIdx_( MTK::SubManifold Base::*) 112 | { 113 | return dim; 114 | } 115 | 116 | /** 117 | * Determine the degrees of freedom of a sub-variable within a compound variable. 118 | */ 119 | template 120 | int getDof( MTK::SubManifold Base::*) 121 | { 122 | return T::DOF; 123 | } 124 | template 125 | int getDim( MTK::SubManifold Base::*) 126 | { 127 | return T::DIM; 128 | } 129 | 130 | /** 131 | * set the diagonal elements of a covariance matrix corresponding to a sub-variable 132 | */ 133 | template 134 | void setDiagonal(Eigen::Matrix &cov, 135 | MTK::SubManifold Base::*, const typename Base::scalar &val) 136 | { 137 | cov.diagonal().template segment(idx).setConstant(val); 138 | } 139 | 140 | template 141 | void setDiagonal_(Eigen::Matrix &cov, 142 | MTK::SubManifold Base::*, const typename Base::scalar &val) 143 | { 144 | cov.diagonal().template segment(dim).setConstant(val); 145 | } 146 | 147 | /** 148 | * Get the subblock of corresponding to two members, i.e. 149 | * \code 150 | * Eigen::Matrix m; 151 | * MTK::subblock(m, &Pose::orient, &Pose::trans) = some_expression; 152 | * MTK::subblock(m, &Pose::trans, &Pose::orient) = some_expression.trans(); 153 | * \endcode 154 | * lets you modify mixed covariance entries in a bigger covariance matrix. 155 | */ 156 | template 157 | typename MTK::internal::CovBlock::Type 158 | subblock(Eigen::Matrix &cov, 159 | MTK::SubManifold Base::*, MTK::SubManifold Base::*) 160 | { 161 | return cov.template block(idx1, idx2); 162 | } 163 | 164 | template 165 | typename MTK::internal::CovBlock_::Type 166 | subblock_(Eigen::Matrix &cov, 167 | MTK::SubManifold Base::*, MTK::SubManifold Base::*) 168 | { 169 | return cov.template block(dim1, dim2); 170 | } 171 | 172 | template 173 | typename MTK::internal::CrossCovBlock::Type 174 | subblock(Eigen::Matrix &cov, MTK::SubManifold Base1::*, MTK::SubManifold Base2::*) 175 | { 176 | return cov.template block(idx1, idx2); 177 | } 178 | 179 | template 180 | typename MTK::internal::CrossCovBlock_::Type 181 | subblock_(Eigen::Matrix &cov, MTK::SubManifold Base1::*, MTK::SubManifold Base2::*) 182 | { 183 | return cov.template block(dim1, dim2); 184 | } 185 | /** 186 | * Get the subblock of corresponding to a member, i.e. 187 | * \code 188 | * Eigen::Matrix m; 189 | * MTK::subblock(m, &Pose::orient) = some_expression; 190 | * \endcode 191 | * lets you modify covariance entries in a bigger covariance matrix. 192 | */ 193 | template 194 | typename MTK::internal::CovBlock_::Type 195 | subblock_(Eigen::Matrix &cov, 196 | MTK::SubManifold Base::*) 197 | { 198 | return cov.template block(dim, dim); 199 | } 200 | 201 | template 202 | typename MTK::internal::CovBlock::Type 203 | subblock(Eigen::Matrix &cov, 204 | MTK::SubManifold Base::*) 205 | { 206 | return cov.template block(idx, idx); 207 | } 208 | 209 | template 210 | class get_cov { 211 | public: 212 | typedef Eigen::Matrix type; 213 | typedef const Eigen::Matrix const_type; 214 | }; 215 | 216 | template 217 | class get_cov_ { 218 | public: 219 | typedef Eigen::Matrix type; 220 | typedef const Eigen::Matrix const_type; 221 | }; 222 | 223 | template 224 | class get_cross_cov { 225 | public: 226 | typedef Eigen::Matrix type; 227 | typedef const type const_type; 228 | }; 229 | 230 | template 231 | class get_cross_cov_ { 232 | public: 233 | typedef Eigen::Matrix type; 234 | typedef const type const_type; 235 | }; 236 | 237 | 238 | template 239 | vectview 240 | subvector_impl_(vectview vec, SubManifold Base::*) 241 | { 242 | return vec.template segment(dim); 243 | } 244 | 245 | template 246 | vectview 247 | subvector_impl(vectview vec, SubManifold Base::*) 248 | { 249 | return vec.template segment(idx); 250 | } 251 | 252 | /** 253 | * Get the subvector corresponding to a sub-manifold from a bigger vector. 254 | */ 255 | template 256 | vectview 257 | subvector_(vectview vec, SubManifold Base::* ptr) 258 | { 259 | return subvector_impl_(vec, ptr); 260 | } 261 | 262 | template 263 | vectview 264 | subvector(vectview vec, SubManifold Base::* ptr) 265 | { 266 | return subvector_impl(vec, ptr); 267 | } 268 | 269 | /** 270 | * @todo This should be covered already by subvector(vectview vec,SubManifold Base::*) 271 | */ 272 | template 273 | vectview 274 | subvector(Eigen::Matrix& vec, SubManifold Base::* ptr) 275 | { 276 | return subvector_impl(vectview(vec), ptr); 277 | } 278 | 279 | template 280 | vectview 281 | subvector_(Eigen::Matrix& vec, SubManifold Base::* ptr) 282 | { 283 | return subvector_impl_(vectview(vec), ptr); 284 | } 285 | 286 | template 287 | vectview 288 | subvector_(const Eigen::Matrix& vec, SubManifold Base::* ptr) 289 | { 290 | return subvector_impl_(vectview(vec), ptr); 291 | } 292 | 293 | template 294 | vectview 295 | subvector(const Eigen::Matrix& vec, SubManifold Base::* ptr) 296 | { 297 | return subvector_impl(vectview(vec), ptr); 298 | } 299 | 300 | 301 | /** 302 | * const version of subvector(vectview vec,SubManifold Base::*) 303 | */ 304 | template 305 | vectview 306 | subvector_impl(const vectview cvec, SubManifold Base::*) 307 | { 308 | return cvec.template segment(idx); 309 | } 310 | 311 | template 312 | vectview 313 | subvector_impl_(const vectview cvec, SubManifold Base::*) 314 | { 315 | return cvec.template segment(dim); 316 | } 317 | 318 | template 319 | vectview 320 | subvector(const vectview cvec, SubManifold Base::* ptr) 321 | { 322 | return subvector_impl(cvec, ptr); 323 | } 324 | 325 | 326 | } // namespace MTK 327 | 328 | #endif // GET_START_INDEX_H_ 329 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/S2.hpp: -------------------------------------------------------------------------------- 1 | // This is a NEW implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/types/S2.hpp 75 | * @brief Unit vectors on the sphere, or directions in 3D. 76 | */ 77 | #ifndef S2_H_ 78 | #define S2_H_ 79 | 80 | 81 | #include "vect.hpp" 82 | 83 | #include "SOn.hpp" 84 | #include "../src/mtkmath.hpp" 85 | 86 | 87 | 88 | 89 | namespace MTK { 90 | 91 | /** 92 | * Manifold representation of @f$ S^2 @f$. 93 | * Used for unit vectors on the sphere or directions in 3D. 94 | * 95 | * @todo add conversions from/to polar angles? 96 | */ 97 | template 98 | struct S2 { 99 | 100 | typedef _scalar scalar; 101 | typedef vect<3, scalar> vect_type; 102 | typedef SO3 SO3_type; 103 | typedef typename vect_type::base vec3; 104 | scalar length = scalar(den)/scalar(num); 105 | enum {DOF=2, TYP = 1, DIM = 3}; 106 | 107 | //private: 108 | /** 109 | * Unit vector on the sphere, or vector pointing in a direction 110 | */ 111 | vect_type vec; 112 | 113 | public: 114 | S2() { 115 | if(S2_typ == 3) vec=length * vec3(0, 0, std::sqrt(1)); 116 | if(S2_typ == 2) vec=length * vec3(0, std::sqrt(1), 0); 117 | if(S2_typ == 1) vec=length * vec3(std::sqrt(1), 0, 0); 118 | } 119 | S2(const scalar &x, const scalar &y, const scalar &z) : vec(vec3(x, y, z)) { 120 | vec.normalize(); 121 | vec = vec * length; 122 | } 123 | 124 | S2(const vect_type &_vec) : vec(_vec) { 125 | vec.normalize(); 126 | vec = vec * length; 127 | } 128 | 129 | void oplus(MTK::vectview delta, scalar scale = 1) 130 | { 131 | SO3_type res; 132 | res.w() = MTK::exp(res.vec(), delta, scalar(scale/2)); 133 | vec = res.toRotationMatrix() * vec; 134 | } 135 | 136 | void boxplus(MTK::vectview delta, scalar scale=1) { 137 | Eigen::Matrix Bx; 138 | S2_Bx(Bx); 139 | vect_type Bu = Bx*delta;SO3_type res; 140 | res.w() = MTK::exp(res.vec(), Bu, scalar(scale/2)); 141 | vec = res.toRotationMatrix() * vec; 142 | } 143 | 144 | void boxminus(MTK::vectview res, const S2& other) const { 145 | scalar v_sin = (MTK::hat(vec)*other.vec).norm(); 146 | scalar v_cos = vec.transpose() * other.vec; 147 | scalar theta = std::atan2(v_sin, v_cos); 148 | if(v_sin < MTK::tolerance()) 149 | { 150 | if(std::fabs(theta) > MTK::tolerance() ) 151 | { 152 | res[0] = 3.1415926; 153 | res[1] = 0; 154 | } 155 | else{ 156 | res[0] = 0; 157 | res[1] = 0; 158 | } 159 | } 160 | else 161 | { 162 | S2 other_copy = other; 163 | Eigen::MatrixBx; 164 | other_copy.S2_Bx(Bx); 165 | res = theta/v_sin * Bx.transpose() * MTK::hat(other.vec)*vec; 166 | } 167 | } 168 | 169 | void S2_hat(Eigen::Matrix &res) 170 | { 171 | Eigen::Matrix skew_vec; 172 | skew_vec << scalar(0), -vec[2], vec[1], 173 | vec[2], scalar(0), -vec[0], 174 | -vec[1], vec[0], scalar(0); 175 | res = skew_vec; 176 | } 177 | 178 | 179 | void S2_Bx(Eigen::Matrix &res) 180 | { 181 | if(S2_typ == 3) 182 | { 183 | if(vec[2] + length > tolerance()) 184 | { 185 | 186 | res << length - vec[0]*vec[0]/(length+vec[2]), -vec[0]*vec[1]/(length+vec[2]), 187 | -vec[0]*vec[1]/(length+vec[2]), length-vec[1]*vec[1]/(length+vec[2]), 188 | -vec[0], -vec[1]; 189 | res /= length; 190 | } 191 | else 192 | { 193 | res = Eigen::Matrix::Zero(); 194 | res(1, 1) = -1; 195 | res(2, 0) = 1; 196 | } 197 | } 198 | else if(S2_typ == 2) 199 | { 200 | if(vec[1] + length > tolerance()) 201 | { 202 | 203 | res << length - vec[0]*vec[0]/(length+vec[1]), -vec[0]*vec[2]/(length+vec[1]), 204 | -vec[0], -vec[2], 205 | -vec[0]*vec[2]/(length+vec[1]), length-vec[2]*vec[2]/(length+vec[1]); 206 | res /= length; 207 | } 208 | else 209 | { 210 | res = Eigen::Matrix::Zero(); 211 | res(1, 1) = -1; 212 | res(2, 0) = 1; 213 | } 214 | } 215 | else 216 | { 217 | if(vec[0] + length > tolerance()) 218 | { 219 | 220 | res << -vec[1], -vec[2], 221 | length - vec[1]*vec[1]/(length+vec[0]), -vec[2]*vec[1]/(length+vec[0]), 222 | -vec[2]*vec[1]/(length+vec[0]), length-vec[2]*vec[2]/(length+vec[0]); 223 | res /= length; 224 | } 225 | else 226 | { 227 | res = Eigen::Matrix::Zero(); 228 | res(1, 1) = -1; 229 | res(2, 0) = 1; 230 | } 231 | } 232 | } 233 | 234 | void S2_Nx(Eigen::Matrix &res, S2& subtrahend) 235 | { 236 | if((vec+subtrahend.vec).norm() > tolerance()) 237 | { 238 | Eigen::Matrix Bx; 239 | S2_Bx(Bx); 240 | if((vec-subtrahend.vec).norm() > tolerance()) 241 | { 242 | scalar v_sin = (MTK::hat(vec)*subtrahend.vec).norm(); 243 | scalar v_cos = vec.transpose() * subtrahend.vec; 244 | 245 | res = Bx.transpose() * (std::atan2(v_sin, v_cos)/v_sin*MTK::hat(vec)+MTK::hat(vec)*subtrahend.vec*((-v_cos/v_sin/v_sin/length/length/length/length+std::atan2(v_sin, v_cos)/v_sin/v_sin/v_sin)*subtrahend.vec.transpose()*MTK::hat(vec)*MTK::hat(vec)-vec.transpose()/length/length/length/length)); 246 | } 247 | else 248 | { 249 | res = 1/length/length*Bx.transpose()*MTK::hat(vec); 250 | } 251 | } 252 | else 253 | { 254 | std::cerr << "No N(x, y) for x=-y" << std::endl; 255 | std::exit(100); 256 | } 257 | } 258 | 259 | void S2_Nx_yy(Eigen::Matrix &res) 260 | { 261 | Eigen::Matrix Bx; 262 | S2_Bx(Bx); 263 | res = 1/length/length*Bx.transpose()*MTK::hat(vec); 264 | } 265 | 266 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 267 | { 268 | Eigen::Matrix Bx; 269 | S2_Bx(Bx); 270 | if(delta.norm() < tolerance()) 271 | { 272 | res = -MTK::hat(vec)*Bx; 273 | } 274 | else{ 275 | vect_type Bu = Bx*delta; 276 | SO3_type exp_delta; 277 | exp_delta.w() = MTK::exp(exp_delta.vec(), Bu, scalar(1/2)); 278 | res = -exp_delta.toRotationMatrix()*MTK::hat(vec)*MTK::A_matrix(Bu).transpose()*Bx; 279 | } 280 | } 281 | 282 | operator const vect_type&() const{ 283 | return vec; 284 | } 285 | 286 | const vect_type& get_vect() const { 287 | return vec; 288 | } 289 | 290 | friend S2 operator*(const SO3& rot, const S2& dir) 291 | { 292 | S2 ret; 293 | ret.vec = rot * dir.vec; 294 | return ret; 295 | } 296 | 297 | scalar operator[](int idx) const {return vec[idx]; } 298 | 299 | friend std::ostream& operator<<(std::ostream &os, const S2& vec){ 300 | return os << vec.vec.transpose() << " "; 301 | } 302 | friend std::istream& operator>>(std::istream &is, S2& vec){ 303 | for(int i=0; i<3; ++i) 304 | is >> vec.vec[i]; 305 | vec.vec.normalize(); 306 | vec.vec = vec.vec * vec.length; 307 | return is; 308 | 309 | } 310 | }; 311 | 312 | 313 | } // namespace MTK 314 | 315 | 316 | #endif /*S2_H_*/ 317 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/SOn.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/types/SOn.hpp 75 | * @brief Standard Orthogonal Groups i.e.\ rotatation groups. 76 | */ 77 | #ifndef SON_H_ 78 | #define SON_H_ 79 | 80 | #include 81 | 82 | #include "vect.hpp" 83 | #include "../src/mtkmath.hpp" 84 | 85 | 86 | namespace MTK { 87 | 88 | 89 | /** 90 | * Two-dimensional orientations represented as scalar. 91 | * There is no guarantee that the representing scalar is within any interval, 92 | * but the result of boxminus will always have magnitude @f$\le\pi @f$. 93 | */ 94 | template 95 | struct SO2 : public Eigen::Rotation2D<_scalar> { 96 | enum {DOF = 1, DIM = 2, TYP = 3}; 97 | 98 | typedef _scalar scalar; 99 | typedef Eigen::Rotation2D base; 100 | typedef vect vect_type; 101 | 102 | //! Construct from angle 103 | SO2(const scalar& angle = 0) : base(angle) { } 104 | 105 | //! Construct from Eigen::Rotation2D 106 | SO2(const base& src) : base(src) {} 107 | 108 | /** 109 | * Construct from 2D vector. 110 | * Resulting orientation will rotate the first unit vector to point to vec. 111 | */ 112 | SO2(const vect_type &vec) : base(atan2(vec[1], vec[0])) {}; 113 | 114 | 115 | //! Calculate @c this->inverse() * @c r 116 | SO2 operator%(const base &r) const { 117 | return base::inverse() * r; 118 | } 119 | 120 | //! Calculate @c this->inverse() * @c r 121 | template 122 | vect_type operator%(const Eigen::MatrixBase &vec) const { 123 | return base::inverse() * vec; 124 | } 125 | 126 | //! Calculate @c *this * @c r.inverse() 127 | SO2 operator/(const SO2 &r) const { 128 | return *this * r.inverse(); 129 | } 130 | 131 | //! Gets the angle as scalar. 132 | operator scalar() const { 133 | return base::angle(); 134 | } 135 | void S2_hat(Eigen::Matrix &res) 136 | { 137 | res = Eigen::Matrix::Zero(); 138 | } 139 | //! @name Manifold requirements 140 | void S2_Nx_yy(Eigen::Matrix &res) 141 | { 142 | std::cerr << "wrong idx for S2" << std::endl; 143 | std::exit(100); 144 | res = Eigen::Matrix::Zero(); 145 | } 146 | 147 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 148 | { 149 | std::cerr << "wrong idx for S2" << std::endl; 150 | std::exit(100); 151 | res = Eigen::Matrix::Zero(); 152 | } 153 | 154 | void oplus(MTK::vectview vec, scalar scale = 1) { 155 | base::angle() += scale * vec[0]; 156 | } 157 | 158 | void boxplus(MTK::vectview vec, scalar scale = 1) { 159 | base::angle() += scale * vec[0]; 160 | } 161 | void boxminus(MTK::vectview res, const SO2& other) const { 162 | res[0] = MTK::normalize(base::angle() - other.angle(), scalar(MTK::pi)); 163 | } 164 | 165 | friend std::istream& operator>>(std::istream &is, SO2& ang){ 166 | return is >> ang.angle(); 167 | } 168 | 169 | }; 170 | 171 | 172 | /** 173 | * Three-dimensional orientations represented as Quaternion. 174 | * It is assumed that the internal Quaternion always stays normalized, 175 | * should this not be the case, call inherited member function @c normalize(). 176 | */ 177 | template 178 | struct SO3 : public Eigen::Quaternion<_scalar, Options> { 179 | enum {DOF = 3, DIM = 3, TYP = 2}; 180 | typedef _scalar scalar; 181 | typedef Eigen::Quaternion base; 182 | typedef Eigen::Quaternion Quaternion; 183 | typedef vect vect_type; 184 | 185 | //! Calculate @c this->inverse() * @c r 186 | template EIGEN_STRONG_INLINE 187 | Quaternion operator%(const Eigen::QuaternionBase &r) const { 188 | return base::conjugate() * r; 189 | } 190 | 191 | //! Calculate @c this->inverse() * @c r 192 | template 193 | vect_type operator%(const Eigen::MatrixBase &vec) const { 194 | return base::conjugate() * vec; 195 | } 196 | 197 | //! Calculate @c this * @c r.conjugate() 198 | template EIGEN_STRONG_INLINE 199 | Quaternion operator/(const Eigen::QuaternionBase &r) const { 200 | return *this * r.conjugate(); 201 | } 202 | 203 | /** 204 | * Construct from real part and three imaginary parts. 205 | * Quaternion is normalized after construction. 206 | */ 207 | SO3(const scalar& w, const scalar& x, const scalar& y, const scalar& z) : base(w, x, y, z) { 208 | base::normalize(); 209 | } 210 | 211 | /** 212 | * Construct from Eigen::Quaternion. 213 | * @note Non-normalized input may result result in spurious behavior. 214 | */ 215 | SO3(const base& src = base::Identity()) : base(src) {} 216 | 217 | /** 218 | * Construct from rotation matrix. 219 | * @note Invalid rotation matrices may lead to spurious behavior. 220 | */ 221 | template 222 | SO3(const Eigen::MatrixBase& matrix) : base(matrix) {} 223 | 224 | /** 225 | * Construct from arbitrary rotation type. 226 | * @note Invalid rotation matrices may lead to spurious behavior. 227 | */ 228 | template 229 | SO3(const Eigen::RotationBase& rotation) : base(rotation.derived()) {} 230 | 231 | //! @name Manifold requirements 232 | 233 | void boxplus(MTK::vectview vec, scalar scale=1) { 234 | // ROS_WARN_STREAM("vec " << vec); 235 | SO3 delta = exp(vec, scale); 236 | *this = *this * delta; 237 | } 238 | void boxminus(MTK::vectview res, const SO3& other) const { 239 | res = SO3::log(other.conjugate() * *this); 240 | } 241 | //} 242 | 243 | void oplus(MTK::vectview vec, scalar scale=1) { 244 | SO3 delta = exp(vec, scale); 245 | *this = *this * delta; 246 | } 247 | 248 | void S2_hat(Eigen::Matrix &res) 249 | { 250 | res = Eigen::Matrix::Zero(); 251 | } 252 | void S2_Nx_yy(Eigen::Matrix &res) 253 | { 254 | std::cerr << "wrong idx for S2" << std::endl; 255 | std::exit(100); 256 | res = Eigen::Matrix::Zero(); 257 | } 258 | 259 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 260 | { 261 | std::cerr << "wrong idx for S2" << std::endl; 262 | std::exit(100); 263 | res = Eigen::Matrix::Zero(); 264 | } 265 | 266 | friend std::ostream& operator<<(std::ostream &os, const SO3& q){ 267 | return os << q.coeffs().transpose() << " "; 268 | } 269 | 270 | friend std::istream& operator>>(std::istream &is, SO3& q){ 271 | vect<4,scalar> coeffs; 272 | is >> coeffs; 273 | q.coeffs() = coeffs.normalized(); 274 | return is; 275 | } 276 | 277 | //! @name Helper functions 278 | //{ 279 | /** 280 | * Calculate the exponential map. In matrix terms this would correspond 281 | * to the Rodrigues formula. 282 | */ 283 | // FIXME vectview<> can't be constructed from every MatrixBase<>, use const Vector3x& as workaround 284 | // static SO3 exp(MTK::vectview dvec, scalar scale = 1){ 285 | static SO3 exp(const Eigen::Matrix& dvec, scalar scale = 1){ 286 | SO3 res; 287 | // ROS_WARN_STREAM("dvec " << dvec); 288 | res.w() = MTK::exp(res.vec(), dvec, scalar(scale/2)); 289 | return res; 290 | } 291 | /** 292 | * Calculate the inverse of @c exp. 293 | * Only guarantees that exp(log(x)) == x 294 | */ 295 | static typename base::Vector3 log(const SO3 &orient){ 296 | typename base::Vector3 res; 297 | MTK::log(res, orient.w(), orient.vec(), scalar(2), true); 298 | return res; 299 | } 300 | }; 301 | 302 | namespace internal { 303 | template 304 | struct UnalignedType >{ 305 | typedef SO2 type; 306 | }; 307 | 308 | template 309 | struct UnalignedType >{ 310 | typedef SO3 type; 311 | }; 312 | 313 | } // namespace internal 314 | 315 | 316 | } // namespace MTK 317 | 318 | #endif /*SON_H_*/ 319 | 320 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/vect.hpp: -------------------------------------------------------------------------------- 1 | // This is an advanced implementation of the algorithm described in the 2 | // following paper: 3 | // C. Hertzberg, R. Wagner, U. Frese, and L. Schroder. Integratinggeneric sensor fusion algorithms with sound state representationsthrough encapsulation of manifolds. 4 | // CoRR, vol. abs/1107.1119, 2011.[Online]. Available: http://arxiv.org/abs/1107.1119 5 | 6 | /* 7 | * Copyright (c) 2019--2023, The University of Hong Kong 8 | * All rights reserved. 9 | * 10 | * Modifier: Dongjiao HE 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * * Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * * Redistributions in binary form must reproduce the above 19 | * copyright notice, this list of conditions and the following 20 | * disclaimer in the documentation and/or other materials provided 21 | * with the distribution. 22 | * * Neither the name of the Universitaet Bremen nor the names of its 23 | * contributors may be used to endorse or promote products derived 24 | * from this software without specific prior written permission. 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 28 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 29 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 30 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 31 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 32 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 33 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 34 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 36 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 37 | * POSSIBILITY OF SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | * Copyright (c) 2008--2011, Universitaet Bremen 42 | * All rights reserved. 43 | * 44 | * Author: Christoph Hertzberg 45 | * 46 | * Redistribution and use in source and binary forms, with or without 47 | * modification, are permitted provided that the following conditions 48 | * are met: 49 | * 50 | * * Redistributions of source code must retain the above copyright 51 | * notice, this list of conditions and the following disclaimer. 52 | * * Redistributions in binary form must reproduce the above 53 | * copyright notice, this list of conditions and the following 54 | * disclaimer in the documentation and/or other materials provided 55 | * with the distribution. 56 | * * Neither the name of the Universitaet Bremen nor the names of its 57 | * contributors may be used to endorse or promote products derived 58 | * from this software without specific prior written permission. 59 | * 60 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 61 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 62 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 63 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 64 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 65 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 66 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 67 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 68 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 69 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 70 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 71 | * POSSIBILITY OF SUCH DAMAGE. 72 | */ 73 | /** 74 | * @file mtk/types/vect.hpp 75 | * @brief Basic vectors interpreted as manifolds. 76 | * 77 | * This file also implements a simple wrapper for matrices, for arbitrary scalars 78 | * and for positive scalars. 79 | */ 80 | #ifndef VECT_H_ 81 | #define VECT_H_ 82 | 83 | #include 84 | #include 85 | #include 86 | 87 | #include "../src/vectview.hpp" 88 | 89 | namespace MTK { 90 | 91 | static const Eigen::IOFormat IO_no_spaces(Eigen::StreamPrecision, Eigen::DontAlignCols, ",", ",", "", "", "[", "]"); 92 | 93 | 94 | /** 95 | * A simple vector class. 96 | * Implementation is basically a wrapper around Eigen::Matrix with manifold 97 | * requirements added. 98 | */ 99 | template 100 | struct vect : public Eigen::Matrix<_scalar, D, 1, _Options> { 101 | typedef Eigen::Matrix<_scalar, D, 1, _Options> base; 102 | enum {DOF = D, DIM = D, TYP = 0}; 103 | typedef _scalar scalar; 104 | 105 | //using base::operator=; 106 | 107 | /** Standard constructor. Sets all values to zero. */ 108 | vect(const base &src = base::Zero()) : base(src) {} 109 | 110 | /** Constructor copying the value of the expression \a other */ 111 | template 112 | EIGEN_STRONG_INLINE vect(const Eigen::DenseBase& other) : base(other) {} 113 | 114 | /** Construct from memory. */ 115 | vect(const scalar* src, int size = DOF) : base(base::Map(src, size)) { } 116 | 117 | void boxplus(MTK::vectview vec, scalar scale=1) { 118 | *this += scale * vec; 119 | } 120 | void boxminus(MTK::vectview res, const vect& other) const { 121 | res = *this - other; 122 | } 123 | 124 | void oplus(MTK::vectview vec, scalar scale=1) { 125 | *this += scale * vec; 126 | } 127 | 128 | void S2_hat(Eigen::Matrix &res) 129 | { 130 | res = Eigen::Matrix::Zero(); 131 | } 132 | 133 | void S2_Nx_yy(Eigen::Matrix &res) 134 | { 135 | std::cerr << "wrong idx for S2" << std::endl; 136 | std::exit(100); 137 | res = Eigen::Matrix::Zero(); 138 | } 139 | 140 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 141 | { 142 | std::cerr << "wrong idx for S2" << std::endl; 143 | std::exit(100); 144 | res = Eigen::Matrix::Zero(); 145 | } 146 | 147 | friend std::ostream& operator<<(std::ostream &os, const vect& v){ 148 | // Eigen sometimes messes with the streams flags, so output manually: 149 | for(int i=0; i>(std::istream &is, vect& v){ 154 | char term=0; 155 | is >> std::ws; // skip whitespace 156 | switch(is.peek()) { 157 | case '(': term=')'; is.ignore(1); break; 158 | case '[': term=']'; is.ignore(1); break; 159 | case '{': term='}'; is.ignore(1); break; 160 | default: break; 161 | } 162 | if(D==Eigen::Dynamic) { 163 | assert(term !=0 && "Dynamic vectors must be embraced"); 164 | std::vector temp; 165 | while(is.good() && is.peek() != term) { 166 | scalar x; 167 | is >> x; 168 | temp.push_back(x); 169 | if(is.peek()==',') is.ignore(1); 170 | } 171 | v = vect::Map(temp.data(), temp.size()); 172 | } else 173 | for(int i=0; i> v[i]; 175 | if(is.peek()==',') { // ignore commas between values 176 | is.ignore(1); 177 | } 178 | } 179 | if(term!=0) { 180 | char x; 181 | is >> x; 182 | if(x!=term) { 183 | is.setstate(is.badbit); 184 | // assert(x==term && "start and end bracket do not match!"); 185 | } 186 | } 187 | return is; 188 | } 189 | 190 | template 191 | vectview tail(){ 192 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 193 | return base::template tail(); 194 | } 195 | template 196 | vectview tail() const{ 197 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 198 | return base::template tail(); 199 | } 200 | template 201 | vectview head(){ 202 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 203 | return base::template head(); 204 | } 205 | template 206 | vectview head() const{ 207 | BOOST_STATIC_ASSERT(0< dim && dim <= DOF); 208 | return base::template head(); 209 | } 210 | }; 211 | 212 | 213 | /** 214 | * A simple matrix class. 215 | * Implementation is basically a wrapper around Eigen::Matrix with manifold 216 | * requirements added, i.e., matrix is viewed as a plain vector for that. 217 | */ 218 | template::Options> 219 | struct matrix : public Eigen::Matrix<_scalar, M, N, _Options> { 220 | typedef Eigen::Matrix<_scalar, M, N, _Options> base; 221 | enum {DOF = M * N, TYP = 4, DIM=0}; 222 | typedef _scalar scalar; 223 | 224 | using base::operator=; 225 | 226 | /** Standard constructor. Sets all values to zero. */ 227 | matrix() { 228 | base::setZero(); 229 | } 230 | 231 | /** Constructor copying the value of the expression \a other */ 232 | template 233 | EIGEN_STRONG_INLINE matrix(const Eigen::MatrixBase& other) : base(other) {} 234 | 235 | /** Construct from memory. */ 236 | matrix(const scalar* src) : base(src) { } 237 | 238 | void boxplus(MTK::vectview vec, scalar scale = 1) { 239 | *this += scale * base::Map(vec.data()); 240 | } 241 | void boxminus(MTK::vectview res, const matrix& other) const { 242 | base::Map(res.data()) = *this - other; 243 | } 244 | 245 | void S2_hat(Eigen::Matrix &res) 246 | { 247 | res = Eigen::Matrix::Zero(); 248 | } 249 | 250 | void oplus(MTK::vectview vec, scalar scale = 1) { 251 | *this += scale * base::Map(vec.data()); 252 | } 253 | 254 | void S2_Nx_yy(Eigen::Matrix &res) 255 | { 256 | std::cerr << "wrong idx for S2" << std::endl; 257 | std::exit(100); 258 | res = Eigen::Matrix::Zero(); 259 | } 260 | 261 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 262 | { 263 | std::cerr << "wrong idx for S2" << std::endl; 264 | std::exit(100); 265 | res = Eigen::Matrix::Zero(); 266 | } 267 | 268 | friend std::ostream& operator<<(std::ostream &os, const matrix& mat){ 269 | for(int i=0; i>(std::istream &is, matrix& mat){ 275 | for(int i=0; i> mat.data()[i]; 277 | } 278 | return is; 279 | } 280 | };// @todo What if M / N = Eigen::Dynamic? 281 | 282 | 283 | 284 | /** 285 | * A simple scalar type. 286 | */ 287 | template 288 | struct Scalar { 289 | enum {DOF = 1, TYP = 5, DIM=0}; 290 | typedef _scalar scalar; 291 | 292 | scalar value; 293 | 294 | Scalar(const scalar& value = scalar(0)) : value(value) {} 295 | operator const scalar&() const { return value; } 296 | operator scalar&() { return value; } 297 | Scalar& operator=(const scalar& val) { value = val; return *this; } 298 | 299 | void S2_hat(Eigen::Matrix &res) 300 | { 301 | res = Eigen::Matrix::Zero(); 302 | } 303 | 304 | void S2_Nx_yy(Eigen::Matrix &res) 305 | { 306 | std::cerr << "wrong idx for S2" << std::endl; 307 | std::exit(100); 308 | res = Eigen::Matrix::Zero(); 309 | } 310 | 311 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 312 | { 313 | std::cerr << "wrong idx for S2" << std::endl; 314 | std::exit(100); 315 | res = Eigen::Matrix::Zero(); 316 | } 317 | 318 | void oplus(MTK::vectview vec, scalar scale=1) { 319 | value += scale * vec[0]; 320 | } 321 | 322 | void boxplus(MTK::vectview vec, scalar scale=1) { 323 | value += scale * vec[0]; 324 | } 325 | void boxminus(MTK::vectview res, const Scalar& other) const { 326 | res[0] = *this - other; 327 | } 328 | }; 329 | 330 | /** 331 | * Positive scalars. 332 | * Boxplus is implemented using multiplication by @f$x\boxplus\delta = x\cdot\exp(\delta) @f$. 333 | */ 334 | template 335 | struct PositiveScalar { 336 | enum {DOF = 1, TYP = 6, DIM=0}; 337 | typedef _scalar scalar; 338 | 339 | scalar value; 340 | 341 | PositiveScalar(const scalar& value = scalar(1)) : value(value) { 342 | assert(value > scalar(0)); 343 | } 344 | operator const scalar&() const { return value; } 345 | PositiveScalar& operator=(const scalar& val) { assert(val>0); value = val; return *this; } 346 | 347 | void boxplus(MTK::vectview vec, scalar scale = 1) { 348 | value *= std::exp(scale * vec[0]); 349 | } 350 | void boxminus(MTK::vectview res, const PositiveScalar& other) const { 351 | res[0] = std::log(*this / other); 352 | } 353 | 354 | void oplus(MTK::vectview vec, scalar scale = 1) { 355 | value *= std::exp(scale * vec[0]); 356 | } 357 | 358 | void S2_hat(Eigen::Matrix &res) 359 | { 360 | res = Eigen::Matrix::Zero(); 361 | } 362 | 363 | void S2_Nx_yy(Eigen::Matrix &res) 364 | { 365 | std::cerr << "wrong idx for S2" << std::endl; 366 | std::exit(100); 367 | res = Eigen::Matrix::Zero(); 368 | } 369 | 370 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 371 | { 372 | std::cerr << "wrong idx for S2" << std::endl; 373 | std::exit(100); 374 | res = Eigen::Matrix::Zero(); 375 | } 376 | 377 | 378 | friend std::istream& operator>>(std::istream &is, PositiveScalar& s){ 379 | is >> s.value; 380 | assert(s.value > 0); 381 | return is; 382 | } 383 | }; 384 | 385 | template 386 | struct Complex : public std::complex<_scalar>{ 387 | enum {DOF = 2, TYP = 7, DIM=0}; 388 | typedef _scalar scalar; 389 | 390 | typedef std::complex Base; 391 | 392 | Complex(const Base& value) : Base(value) {} 393 | Complex(const scalar& re = 0.0, const scalar& im = 0.0) : Base(re, im) {} 394 | Complex(const MTK::vectview &in) : Base(in[0], in[1]) {} 395 | template 396 | Complex(const Eigen::DenseBase &in) : Base(in[0], in[1]) {} 397 | 398 | void boxplus(MTK::vectview vec, scalar scale = 1) { 399 | Base::real() += scale * vec[0]; 400 | Base::imag() += scale * vec[1]; 401 | }; 402 | void boxminus(MTK::vectview res, const Complex& other) const { 403 | Complex diff = *this - other; 404 | res << diff.real(), diff.imag(); 405 | } 406 | 407 | void S2_hat(Eigen::Matrix &res) 408 | { 409 | res = Eigen::Matrix::Zero(); 410 | } 411 | 412 | void oplus(MTK::vectview vec, scalar scale = 1) { 413 | Base::real() += scale * vec[0]; 414 | Base::imag() += scale * vec[1]; 415 | }; 416 | 417 | void S2_Nx_yy(Eigen::Matrix &res) 418 | { 419 | std::cerr << "wrong idx for S2" << std::endl; 420 | std::exit(100); 421 | res = Eigen::Matrix::Zero(); 422 | } 423 | 424 | void S2_Mx(Eigen::Matrix &res, MTK::vectview delta) 425 | { 426 | std::cerr << "wrong idx for S2" << std::endl; 427 | std::exit(100); 428 | res = Eigen::Matrix::Zero(); 429 | } 430 | 431 | scalar squaredNorm() const { 432 | return std::pow(Base::real(),2) + std::pow(Base::imag(),2); 433 | } 434 | 435 | const scalar& operator()(int i) const { 436 | assert(0<=i && i<2 && "Index out of range"); 437 | return i==0 ? Base::real() : Base::imag(); 438 | } 439 | scalar& operator()(int i){ 440 | assert(0<=i && i<2 && "Index out of range"); 441 | return i==0 ? Base::real() : Base::imag(); 442 | } 443 | }; 444 | 445 | 446 | namespace internal { 447 | 448 | template 449 | struct UnalignedType >{ 450 | typedef vect type; 451 | }; 452 | 453 | } // namespace internal 454 | 455 | 456 | } // namespace MTK 457 | 458 | 459 | 460 | 461 | #endif /*VECT_H_*/ 462 | -------------------------------------------------------------------------------- /include/IKFoM_toolkit/mtk/types/wrapped_cv_mat.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2010--2011, Universitaet Bremen and DFKI GmbH 3 | * All rights reserved. 4 | * 5 | * Author: Rene Wagner 6 | * Christoph Hertzberg 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Universitaet Bremen nor the DFKI GmbH 19 | * nor the names of its contributors may be used to endorse or 20 | * promote products derived from this software without specific 21 | * prior written permission. 22 | * 23 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 24 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 25 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 26 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 27 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 28 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 29 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 30 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 32 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 33 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 34 | * POSSIBILITY OF SUCH DAMAGE. 35 | */ 36 | 37 | #ifndef WRAPPED_CV_MAT_HPP_ 38 | #define WRAPPED_CV_MAT_HPP_ 39 | 40 | #include 41 | #include 42 | 43 | namespace MTK { 44 | 45 | template 46 | struct cv_f_type; 47 | 48 | template<> 49 | struct cv_f_type 50 | { 51 | enum {value = CV_64F}; 52 | }; 53 | 54 | template<> 55 | struct cv_f_type 56 | { 57 | enum {value = CV_32F}; 58 | }; 59 | 60 | /** 61 | * cv_mat wraps a CvMat around an Eigen Matrix 62 | */ 63 | template 64 | class cv_mat : public matrix 65 | { 66 | typedef matrix base_type; 67 | enum {type_ = cv_f_type::value}; 68 | CvMat cv_mat_; 69 | 70 | public: 71 | cv_mat() 72 | { 73 | cv_mat_ = cvMat(rows, cols, type_, base_type::data()); 74 | } 75 | 76 | cv_mat(const cv_mat& oth) : base_type(oth) 77 | { 78 | cv_mat_ = cvMat(rows, cols, type_, base_type::data()); 79 | } 80 | 81 | template 82 | cv_mat(const Eigen::MatrixBase &value) : base_type(value) 83 | { 84 | cv_mat_ = cvMat(rows, cols, type_, base_type::data()); 85 | } 86 | 87 | template 88 | cv_mat& operator=(const Eigen::MatrixBase &value) 89 | { 90 | base_type::operator=(value); 91 | return *this; 92 | } 93 | 94 | cv_mat& operator=(const cv_mat& value) 95 | { 96 | base_type::operator=(value); 97 | return *this; 98 | } 99 | 100 | // FIXME: Maybe overloading operator& is not a good idea ... 101 | CvMat* operator&() 102 | { 103 | return &cv_mat_; 104 | } 105 | const CvMat* operator&() const 106 | { 107 | return &cv_mat_; 108 | } 109 | }; 110 | 111 | } // namespace MTK 112 | 113 | #endif /* WRAPPED_CV_MAT_HPP_ */ 114 | -------------------------------------------------------------------------------- /include/common_lib.h: -------------------------------------------------------------------------------- 1 | #ifndef COMMON_LIB_H 2 | #define COMMON_LIB_H 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | using namespace std; 15 | using namespace Eigen; 16 | 17 | #define USE_IKFOM 18 | 19 | #define PI_M (3.14159265358) 20 | #define G_m_s2 (9.8012) // Gravaty const in Beijing/China 21 | #define DIM_STATE (18) // Dimension of states (Let Dim(SO(3)) = 3) 22 | #define DIM_PROC_N (12) // Dimension of process noise (Let Dim(SO(3)) = 3) 23 | #define CUBE_LEN (6.0) 24 | #define LIDAR_SP_LEN (2) 25 | #define INIT_COV (1) 26 | #define NUM_MATCH_POINTS (5) 27 | #define MAX_MEAS_DIM (10000) 28 | 29 | #define VEC_FROM_ARRAY(v) v[0],v[1],v[2] 30 | #define MAT_FROM_ARRAY(v) v[0],v[1],v[2],v[3],v[4],v[5],v[6],v[7],v[8] 31 | #define CONSTRAIN(v,min,max) ((v>min)?((v (mat.data(), mat.data() + mat.rows() * mat.cols()) 34 | #define DEBUG_FILE_DIR(name) (string(string(ROOT_DIR) + "Log/"+ name)) 35 | 36 | typedef fast_lio_msf::Pose6D Pose6D; 37 | typedef pcl::PointXYZINormal PointType; 38 | typedef pcl::PointCloud PointCloudXYZI; 39 | typedef vector> PointVector; 40 | typedef Vector3d V3D; 41 | typedef Matrix3d M3D; 42 | typedef Vector3f V3F; 43 | typedef Matrix3f M3F; 44 | typedef Matrix V1D; 45 | 46 | #define MD(a,b) Matrix 47 | #define VD(a) Matrix 48 | #define MF(a,b) Matrix 49 | #define VF(a) Matrix 50 | 51 | M3D Eye3d(M3D::Identity()); 52 | M3F Eye3f(M3F::Identity()); 53 | V3D Zero3d(0, 0, 0); 54 | V3F Zero3f(0, 0, 0); 55 | 56 | bool USE_WHEEL = false; 57 | bool opt_with_wheel = false; 58 | double wheel_cov = 0.01, nhc_y_cov = 0.01, nhc_z_cov = 0.01; 59 | 60 | bool USE_GNSS = false; 61 | bool opt_with_gnss = false; 62 | 63 | // 储存一帧lidar数据及imu数据序列 64 | struct MeasureGroup // Lidar data and imu dates for the curent process 65 | { 66 | MeasureGroup() 67 | { 68 | lidar_beg_time = 0.0; 69 | this->lidar.reset(new PointCloudXYZI()); 70 | }; 71 | double lidar_beg_time; 72 | double lidar_end_time; 73 | PointCloudXYZI::Ptr lidar; 74 | deque imu; 75 | deque wheel; 76 | deque gnss; 77 | }; 78 | 79 | struct StatesGroup 80 | { 81 | StatesGroup() { 82 | this->rot_end = M3D::Identity(); 83 | this->pos_end = Zero3d; 84 | this->vel_end = Zero3d; 85 | this->bias_g = Zero3d; 86 | this->bias_a = Zero3d; 87 | this->gravity = Zero3d; 88 | this->cov = MD(DIM_STATE,DIM_STATE)::Identity() * INIT_COV; 89 | this->cov.block<9,9>(9,9) = MD(9,9)::Identity() * 0.00001; 90 | }; 91 | 92 | StatesGroup(const StatesGroup& b) { 93 | this->rot_end = b.rot_end; 94 | this->pos_end = b.pos_end; 95 | this->vel_end = b.vel_end; 96 | this->bias_g = b.bias_g; 97 | this->bias_a = b.bias_a; 98 | this->gravity = b.gravity; 99 | this->cov = b.cov; 100 | }; 101 | 102 | StatesGroup& operator=(const StatesGroup& b) 103 | { 104 | this->rot_end = b.rot_end; 105 | this->pos_end = b.pos_end; 106 | this->vel_end = b.vel_end; 107 | this->bias_g = b.bias_g; 108 | this->bias_a = b.bias_a; 109 | this->gravity = b.gravity; 110 | this->cov = b.cov; 111 | return *this; 112 | }; 113 | 114 | StatesGroup operator+(const Matrix &state_add) 115 | { 116 | StatesGroup a; 117 | a.rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0)); 118 | a.pos_end = this->pos_end + state_add.block<3,1>(3,0); 119 | a.vel_end = this->vel_end + state_add.block<3,1>(6,0); 120 | a.bias_g = this->bias_g + state_add.block<3,1>(9,0); 121 | a.bias_a = this->bias_a + state_add.block<3,1>(12,0); 122 | a.gravity = this->gravity + state_add.block<3,1>(15,0); 123 | a.cov = this->cov; 124 | return a; 125 | }; 126 | 127 | StatesGroup& operator+=(const Matrix &state_add) 128 | { 129 | this->rot_end = this->rot_end * Exp(state_add(0,0), state_add(1,0), state_add(2,0)); 130 | this->pos_end += state_add.block<3,1>(3,0); 131 | this->vel_end += state_add.block<3,1>(6,0); 132 | this->bias_g += state_add.block<3,1>(9,0); 133 | this->bias_a += state_add.block<3,1>(12,0); 134 | this->gravity += state_add.block<3,1>(15,0); 135 | return *this; 136 | }; 137 | 138 | Matrix operator-(const StatesGroup& b) 139 | { 140 | Matrix a; 141 | M3D rotd(b.rot_end.transpose() * this->rot_end); 142 | a.block<3,1>(0,0) = Log(rotd); 143 | a.block<3,1>(3,0) = this->pos_end - b.pos_end; 144 | a.block<3,1>(6,0) = this->vel_end - b.vel_end; 145 | a.block<3,1>(9,0) = this->bias_g - b.bias_g; 146 | a.block<3,1>(12,0) = this->bias_a - b.bias_a; 147 | a.block<3,1>(15,0) = this->gravity - b.gravity; 148 | return a; 149 | }; 150 | 151 | void resetpose() 152 | { 153 | this->rot_end = M3D::Identity(); 154 | this->pos_end = Zero3d; 155 | this->vel_end = Zero3d; 156 | } 157 | 158 | M3D rot_end; // the estimated attitude (rotation matrix) at the end lidar point 159 | V3D pos_end; // the estimated position at the end lidar point (world frame) 160 | V3D vel_end; // the estimated velocity at the end lidar point (world frame) 161 | V3D bias_g; // gyroscope bias 162 | V3D bias_a; // accelerator bias 163 | V3D gravity; // the estimated gravity acceleration 164 | Matrix cov; // states covariance 165 | }; 166 | 167 | template 168 | static std::string to_string_with_precision(T a_value, int n = 9); 169 | 170 | template 171 | std::string to_string_with_precision(const T a_value, const int n) 172 | { 173 | std::ostringstream out; 174 | out.precision(n); 175 | out << std::fixed << a_value; 176 | return out.str(); 177 | } 178 | 179 | template 180 | T rad2deg(T radians) 181 | { 182 | return radians * 180.0 / PI_M; 183 | } 184 | 185 | template 186 | T deg2rad(T degrees) 187 | { 188 | return degrees * PI_M / 180.0; 189 | } 190 | 191 | template 192 | auto set_pose6d(const double t, const Matrix &a, const Matrix &g, \ 193 | const Matrix &v, const Matrix &p, const Matrix &R) 194 | { 195 | Pose6D rot_kp; 196 | rot_kp.offset_time = t; 197 | for (int i = 0; i < 3; i++) 198 | { 199 | rot_kp.acc[i] = a(i); 200 | rot_kp.gyr[i] = g(i); 201 | rot_kp.vel[i] = v(i); 202 | rot_kp.pos[i] = p(i); 203 | for (int j = 0; j < 3; j++) rot_kp.rot[i*3+j] = R(i,j); 204 | } 205 | return move(rot_kp); 206 | } 207 | 208 | /* comment 209 | plane equation: Ax + By + Cz + D = 0 210 | convert to: A/D*x + B/D*y + C/D*z = -1 211 | solve: A0*x0 = b0 212 | where A0_i = [x_i, y_i, z_i], x0 = [A/D, B/D, C/D]^T, b0 = [-1, ..., -1]^T 213 | normvec: normalized x0 214 | */ 215 | template 216 | bool esti_normvector(Matrix &normvec, const PointVector &point, const T &threshold, const int &point_num) 217 | { 218 | MatrixXf A(point_num, 3); 219 | MatrixXf b(point_num, 1); 220 | b.setOnes(); 221 | b *= -1.0f; 222 | 223 | for (int j = 0; j < point_num; j++) 224 | { 225 | A(j,0) = point[j].x; 226 | A(j,1) = point[j].y; 227 | A(j,2) = point[j].z; 228 | } 229 | normvec = A.colPivHouseholderQr().solve(b); 230 | 231 | for (int j = 0; j < point_num; j++) 232 | { 233 | if (fabs(normvec(0) * point[j].x + normvec(1) * point[j].y + normvec(2) * point[j].z + 1.0f) > threshold) 234 | { 235 | return false; 236 | } 237 | } 238 | 239 | normvec.normalize(); 240 | return true; 241 | } 242 | 243 | float calc_dist(PointType p1, PointType p2){ 244 | float d = (p1.x - p2.x) * (p1.x - p2.x) + (p1.y - p2.y) * (p1.y - p2.y) + (p1.z - p2.z) * (p1.z - p2.z); 245 | return d; 246 | } 247 | 248 | template 249 | bool esti_plane(Matrix &pca_result, const PointVector &point, const T &threshold) 250 | { 251 | Matrix A; 252 | Matrix b; 253 | A.setZero(); 254 | b.setOnes(); 255 | b *= -1.0f; 256 | 257 | for (int j = 0; j < NUM_MATCH_POINTS; j++) 258 | { 259 | A(j,0) = point[j].x; 260 | A(j,1) = point[j].y; 261 | A(j,2) = point[j].z; 262 | } 263 | 264 | Matrix normvec = A.colPivHouseholderQr().solve(b); 265 | 266 | T n = normvec.norm(); 267 | pca_result(0) = normvec(0) / n; 268 | pca_result(1) = normvec(1) / n; 269 | pca_result(2) = normvec(2) / n; 270 | pca_result(3) = 1.0 / n; 271 | 272 | for (int j = 0; j < NUM_MATCH_POINTS; j++) 273 | { 274 | if (fabs(pca_result(0) * point[j].x + pca_result(1) * point[j].y + pca_result(2) * point[j].z + pca_result(3)) > threshold) 275 | { 276 | return false; 277 | } 278 | } 279 | return true; 280 | } 281 | 282 | #endif -------------------------------------------------------------------------------- /include/ikd-Tree/README.md: -------------------------------------------------------------------------------- 1 | # ikd-Tree 2 | ikd-Tree is an incremental k-d tree for robotic applications. 3 | -------------------------------------------------------------------------------- /include/ikd-Tree/ikd_Tree.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | #define EPSS 1e-6 14 | #define Minimal_Unbalanced_Tree_Size 10 15 | #define Multi_Thread_Rebuild_Point_Num 1500 16 | #define DOWNSAMPLE_SWITCH true 17 | #define ForceRebuildPercentage 0.2 18 | #define Q_LEN 1000000 19 | 20 | using namespace std; 21 | 22 | // typedef pcl::PointXYZINormal PointType; 23 | // typedef vector> PointVector; 24 | 25 | struct BoxPointType 26 | { 27 | float vertex_min[3]; 28 | float vertex_max[3]; 29 | }; 30 | 31 | enum operation_set 32 | { 33 | ADD_POINT, 34 | DELETE_POINT, 35 | DELETE_BOX, 36 | ADD_BOX, 37 | DOWNSAMPLE_DELETE, 38 | PUSH_DOWN 39 | }; 40 | 41 | enum delete_point_storage_set 42 | { 43 | NOT_RECORD, 44 | DELETE_POINTS_REC, 45 | MULTI_THREAD_REC 46 | }; 47 | 48 | template 49 | class KD_TREE 50 | { 51 | // using MANUAL_Q_ = MANUAL_Q; 52 | // using PointVector = std::vector; 53 | 54 | // using MANUAL_Q_ = MANUAL_Q; 55 | public: 56 | using PointVector = std::vector>; 57 | using Ptr = std::shared_ptr>; 58 | 59 | struct KD_TREE_NODE 60 | { 61 | PointType point; 62 | int division_axis; 63 | int TreeSize = 1; 64 | int invalid_point_num = 0; 65 | int down_del_num = 0; 66 | bool point_deleted = false; 67 | bool tree_deleted = false; 68 | bool point_downsample_deleted = false; 69 | bool tree_downsample_deleted = false; 70 | bool need_push_down_to_left = false; 71 | bool need_push_down_to_right = false; 72 | bool working_flag = false; 73 | pthread_mutex_t push_down_mutex_lock; 74 | float node_range_x[2], node_range_y[2], node_range_z[2]; 75 | float radius_sq; 76 | KD_TREE_NODE *left_son_ptr = nullptr; 77 | KD_TREE_NODE *right_son_ptr = nullptr; 78 | KD_TREE_NODE *father_ptr = nullptr; 79 | // For paper data record 80 | float alpha_del; 81 | float alpha_bal; 82 | }; 83 | 84 | struct Operation_Logger_Type 85 | { 86 | PointType point; 87 | BoxPointType boxpoint; 88 | bool tree_deleted, tree_downsample_deleted; 89 | operation_set op; 90 | }; 91 | // static const PointType zeroP; 92 | 93 | struct PointType_CMP 94 | { 95 | PointType point; 96 | float dist = 0.0; 97 | PointType_CMP(PointType p = PointType(), float d = INFINITY) 98 | { 99 | this->point = p; 100 | this->dist = d; 101 | }; 102 | bool operator<(const PointType_CMP &a) const 103 | { 104 | if (fabs(dist - a.dist) < 1e-10) 105 | return point.x < a.point.x; 106 | else 107 | return dist < a.dist; 108 | } 109 | }; 110 | 111 | class MANUAL_HEAP 112 | { 113 | 114 | public: 115 | MANUAL_HEAP(int max_capacity = 100) 116 | 117 | { 118 | cap = max_capacity; 119 | heap = new PointType_CMP[max_capacity]; 120 | heap_size = 0; 121 | } 122 | 123 | ~MANUAL_HEAP() 124 | { 125 | delete[] heap; 126 | } 127 | void pop() 128 | { 129 | if (heap_size == 0) 130 | return; 131 | heap[0] = heap[heap_size - 1]; 132 | heap_size--; 133 | MoveDown(0); 134 | return; 135 | } 136 | PointType_CMP top() 137 | { 138 | return heap[0]; 139 | } 140 | void push(PointType_CMP point) 141 | { 142 | if (heap_size >= cap) 143 | return; 144 | heap[heap_size] = point; 145 | FloatUp(heap_size); 146 | heap_size++; 147 | return; 148 | } 149 | int size() 150 | { 151 | return heap_size; 152 | } 153 | void clear() 154 | { 155 | heap_size = 0; 156 | return; 157 | } 158 | 159 | private: 160 | PointType_CMP *heap; 161 | void MoveDown(int heap_index) 162 | { 163 | int l = heap_index * 2 + 1; 164 | PointType_CMP tmp = heap[heap_index]; 165 | while (l < heap_size) 166 | { 167 | if (l + 1 < heap_size && heap[l] < heap[l + 1]) 168 | l++; 169 | if (tmp < heap[l]) 170 | { 171 | heap[heap_index] = heap[l]; 172 | heap_index = l; 173 | l = heap_index * 2 + 1; 174 | } 175 | else 176 | break; 177 | } 178 | heap[heap_index] = tmp; 179 | return; 180 | } 181 | void FloatUp(int heap_index) 182 | { 183 | int ancestor = (heap_index - 1) / 2; 184 | PointType_CMP tmp = heap[heap_index]; 185 | while (heap_index > 0) 186 | { 187 | if (heap[ancestor] < tmp) 188 | { 189 | heap[heap_index] = heap[ancestor]; 190 | heap_index = ancestor; 191 | ancestor = (heap_index - 1) / 2; 192 | } 193 | else 194 | break; 195 | } 196 | heap[heap_index] = tmp; 197 | return; 198 | } 199 | int heap_size = 0; 200 | int cap = 0; 201 | }; 202 | 203 | class MANUAL_Q 204 | { 205 | private: 206 | int head = 0, tail = 0, counter = 0; 207 | Operation_Logger_Type q[Q_LEN]; 208 | bool is_empty; 209 | 210 | public: 211 | void pop() 212 | { 213 | if (counter == 0) 214 | return; 215 | head++; 216 | head %= Q_LEN; 217 | counter--; 218 | if (counter == 0) 219 | is_empty = true; 220 | return; 221 | } 222 | Operation_Logger_Type front() 223 | { 224 | return q[head]; 225 | } 226 | Operation_Logger_Type back() 227 | { 228 | return q[tail]; 229 | } 230 | void clear() 231 | { 232 | head = 0; 233 | tail = 0; 234 | counter = 0; 235 | is_empty = true; 236 | return; 237 | } 238 | void push(Operation_Logger_Type op) 239 | { 240 | q[tail] = op; 241 | counter++; 242 | if (is_empty) 243 | is_empty = false; 244 | tail++; 245 | tail %= Q_LEN; 246 | } 247 | bool empty() 248 | { 249 | return is_empty; 250 | } 251 | int size() 252 | { 253 | return counter; 254 | } 255 | }; 256 | 257 | private: 258 | // Multi-thread Tree Rebuild 259 | bool termination_flag = false; 260 | bool rebuild_flag = false; 261 | pthread_t rebuild_thread; 262 | pthread_mutex_t termination_flag_mutex_lock, rebuild_ptr_mutex_lock, working_flag_mutex, search_flag_mutex; 263 | pthread_mutex_t rebuild_logger_mutex_lock, points_deleted_rebuild_mutex_lock; 264 | // queue Rebuild_Logger; 265 | MANUAL_Q Rebuild_Logger; 266 | PointVector Rebuild_PCL_Storage; 267 | KD_TREE_NODE **Rebuild_Ptr = nullptr; 268 | int search_mutex_counter = 0; 269 | static void *multi_thread_ptr(void *arg); 270 | void multi_thread_rebuild(); 271 | void start_thread(); 272 | void stop_thread(); 273 | void run_operation(KD_TREE_NODE **root, Operation_Logger_Type operation); 274 | // KD Tree Functions and augmented variables 275 | int Treesize_tmp = 0, Validnum_tmp = 0; 276 | float alpha_bal_tmp = 0.5, alpha_del_tmp = 0.0; 277 | float delete_criterion_param = 0.5f; 278 | float balance_criterion_param = 0.7f; 279 | float downsample_size = 0.2f; 280 | bool Delete_Storage_Disabled = false; 281 | KD_TREE_NODE *STATIC_ROOT_NODE = nullptr; 282 | PointVector Points_deleted; 283 | PointVector Downsample_Storage; 284 | PointVector Multithread_Points_deleted; 285 | void InitTreeNode(KD_TREE_NODE *root); 286 | void Test_Lock_States(KD_TREE_NODE *root); 287 | void BuildTree(KD_TREE_NODE **root, int l, int r, PointVector &Storage); 288 | void Rebuild(KD_TREE_NODE **root); 289 | int Delete_by_range(KD_TREE_NODE **root, BoxPointType boxpoint, bool allow_rebuild, bool is_downsample); 290 | void Delete_by_point(KD_TREE_NODE **root, PointType point, bool allow_rebuild); 291 | void Add_by_point(KD_TREE_NODE **root, PointType point, bool allow_rebuild, int father_axis); 292 | void Add_by_range(KD_TREE_NODE **root, BoxPointType boxpoint, bool allow_rebuild); 293 | void Search(KD_TREE_NODE *root, int k_nearest, PointType point, MANUAL_HEAP &q, float max_dist); //priority_queue 294 | void Search_by_range(KD_TREE_NODE *root, BoxPointType boxpoint, PointVector &Storage); 295 | void Search_by_radius(KD_TREE_NODE *root, PointType point, float radius, PointVector &Storage); 296 | bool Criterion_Check(KD_TREE_NODE *root); 297 | void Push_Down(KD_TREE_NODE *root); 298 | void Update(KD_TREE_NODE *root); 299 | void delete_tree_nodes(KD_TREE_NODE **root); 300 | void downsample(KD_TREE_NODE **root); 301 | bool same_point(PointType a, PointType b); 302 | float calc_dist(PointType a, PointType b); 303 | float calc_box_dist(KD_TREE_NODE *node, PointType point); 304 | static bool point_cmp_x(PointType a, PointType b); 305 | static bool point_cmp_y(PointType a, PointType b); 306 | static bool point_cmp_z(PointType a, PointType b); 307 | 308 | public: 309 | KD_TREE(float delete_param = 0.5, float balance_param = 0.6, float box_length = 0.2); 310 | ~KD_TREE(); 311 | void Set_delete_criterion_param(float delete_param) 312 | { 313 | delete_criterion_param = delete_param; 314 | } 315 | void Set_balance_criterion_param(float balance_param) 316 | { 317 | balance_criterion_param = balance_param; 318 | } 319 | void set_downsample_param(float downsample_param) 320 | { 321 | downsample_size = downsample_param; 322 | } 323 | void InitializeKDTree(float delete_param = 0.5, float balance_param = 0.7, float box_length = 0.2); 324 | int size(); 325 | int validnum(); 326 | void root_alpha(float &alpha_bal, float &alpha_del); 327 | void Build(PointVector point_cloud); 328 | void Nearest_Search(PointType point, int k_nearest, PointVector &Nearest_Points, vector &Point_Distance, float max_dist = INFINITY); 329 | void Box_Search(const BoxPointType &Box_of_Point, PointVector &Storage); 330 | void Radius_Search(PointType point, const float radius, PointVector &Storage); 331 | int Add_Points(PointVector &PointToAdd, bool downsample_on); 332 | void Add_Point_Boxes(vector &BoxPoints); 333 | void Delete_Points(PointVector &PointToDel); 334 | int Delete_Point_Boxes(vector &BoxPoints); 335 | void flatten(KD_TREE_NODE *root, PointVector &Storage, delete_point_storage_set storage_type); 336 | void acquire_removed_points(PointVector &removed_points); 337 | BoxPointType tree_range(); 338 | PointVector PCL_Storage; 339 | KD_TREE_NODE *Root_Node = nullptr; 340 | int max_queue_size = 0; 341 | }; 342 | 343 | // template 344 | // PointType KD_TREE::zeroP = PointType(0,0,0); 345 | -------------------------------------------------------------------------------- /include/so3_math.h: -------------------------------------------------------------------------------- 1 | #ifndef SO3_MATH_H 2 | #define SO3_MATH_H 3 | 4 | #include 5 | #include 6 | 7 | #define SKEW_SYM_MATRX(v) 0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0 8 | 9 | template 10 | Eigen::Matrix skew_sym_mat(const Eigen::Matrix &v) 11 | { 12 | Eigen::Matrix skew_sym_mat; 13 | skew_sym_mat<<0.0,-v[2],v[1],v[2],0.0,-v[0],-v[1],v[0],0.0; 14 | return skew_sym_mat; 15 | } 16 | 17 | template 18 | Eigen::Matrix Exp(const Eigen::Matrix &&ang) 19 | { 20 | T ang_norm = ang.norm(); 21 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 22 | if (ang_norm > 0.0000001) 23 | { 24 | Eigen::Matrix r_axis = ang / ang_norm; 25 | Eigen::Matrix K; 26 | K << SKEW_SYM_MATRX(r_axis); 27 | /// Roderigous Tranformation 28 | return Eye3 + std::sin(ang_norm) * K + (1.0 - std::cos(ang_norm)) * K * K; 29 | } 30 | else 31 | { 32 | return Eye3; 33 | } 34 | } 35 | 36 | template 37 | Eigen::Matrix Exp(const Eigen::Matrix &ang_vel, const Ts &dt) 38 | { 39 | T ang_vel_norm = ang_vel.norm(); 40 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 41 | 42 | if (ang_vel_norm > 0.0000001) 43 | { 44 | Eigen::Matrix r_axis = ang_vel / ang_vel_norm; 45 | Eigen::Matrix K; 46 | 47 | K << SKEW_SYM_MATRX(r_axis); 48 | 49 | T r_ang = ang_vel_norm * dt; 50 | 51 | /// Roderigous Tranformation 52 | return Eye3 + std::sin(r_ang) * K + (1.0 - std::cos(r_ang)) * K * K; 53 | } 54 | else 55 | { 56 | return Eye3; 57 | } 58 | } 59 | 60 | template 61 | Eigen::Matrix Exp(const T &v1, const T &v2, const T &v3) 62 | { 63 | T &&norm = sqrt(v1 * v1 + v2 * v2 + v3 * v3); 64 | Eigen::Matrix Eye3 = Eigen::Matrix::Identity(); 65 | if (norm > 0.00001) 66 | { 67 | T r_ang[3] = {v1 / norm, v2 / norm, v3 / norm}; 68 | Eigen::Matrix K; 69 | K << SKEW_SYM_MATRX(r_ang); 70 | 71 | /// Roderigous Tranformation 72 | return Eye3 + std::sin(norm) * K + (1.0 - std::cos(norm)) * K * K; 73 | } 74 | else 75 | { 76 | return Eye3; 77 | } 78 | } 79 | 80 | /* Logrithm of a Rotation Matrix */ 81 | template 82 | Eigen::Matrix Log(const Eigen::Matrix &R) 83 | { 84 | T theta = (R.trace() > 3.0 - 1e-6) ? 0.0 : std::acos(0.5 * (R.trace() - 1)); 85 | Eigen::Matrix K(R(2,1) - R(1,2), R(0,2) - R(2,0), R(1,0) - R(0,1)); 86 | return (std::abs(theta) < 0.001) ? (0.5 * K) : (0.5 * theta / std::sin(theta) * K); 87 | } 88 | 89 | template 90 | Eigen::Matrix RotMtoEuler(const Eigen::Matrix &rot) 91 | { 92 | T sy = sqrt(rot(0,0)*rot(0,0) + rot(1,0)*rot(1,0)); 93 | bool singular = sy < 1e-6; 94 | T x, y, z; 95 | if(!singular) 96 | { 97 | x = atan2(rot(2, 1), rot(2, 2)); 98 | y = atan2(-rot(2, 0), sy); 99 | z = atan2(rot(1, 0), rot(0, 0)); 100 | } 101 | else 102 | { 103 | x = atan2(-rot(1, 2), rot(1, 1)); 104 | y = atan2(-rot(2, 0), sy); 105 | z = 0; 106 | } 107 | Eigen::Matrix ang(x, y, z); 108 | return ang; 109 | } 110 | 111 | #endif 112 | -------------------------------------------------------------------------------- /include/use-ikfom.hpp: -------------------------------------------------------------------------------- 1 | #ifndef USE_IKFOM_H 2 | #define USE_IKFOM_H 3 | 4 | #include 5 | 6 | typedef MTK::vect<3, double> vect3; 7 | typedef MTK::SO3 SO3; 8 | typedef MTK::S2 S2; 9 | typedef MTK::vect<1, double> vect1; 10 | typedef MTK::vect<2, double> vect2; 11 | 12 | MTK_BUILD_MANIFOLD(state_ikfom, 13 | ((vect3, pos)) 14 | ((SO3, rot)) 15 | ((SO3, offset_R_L_I)) 16 | ((vect3, offset_T_L_I)) 17 | ((vect3, vel)) 18 | ((vect3, bg)) 19 | ((vect3, ba)) 20 | ((S2, grav)) //S2流形,grav为负值 21 | ((SO3, offset_R_W_I)) 22 | ((vect3, offset_T_W_I)) 23 | ((vect1, wheel_s)) 24 | ((SO3, offset_R_G_I)) 25 | ); 26 | 27 | MTK_BUILD_MANIFOLD(input_ikfom, 28 | ((vect3, acc)) 29 | ((vect3, gyro)) 30 | ); 31 | 32 | MTK_BUILD_MANIFOLD(process_noise_ikfom, 33 | ((vect3, ng)) 34 | ((vect3, na)) 35 | ((vect3, nbg)) 36 | ((vect3, nba)) 37 | ); 38 | 39 | MTK::get_cov::type process_noise_cov() 40 | { 41 | MTK::get_cov::type cov = MTK::get_cov::type::Zero(); 42 | MTK::setDiagonal(cov, &process_noise_ikfom::ng, 0.0001);// 0.03 43 | MTK::setDiagonal(cov, &process_noise_ikfom::na, 0.0001); // *dt 0.01 0.01 * dt * dt 0.05 44 | MTK::setDiagonal(cov, &process_noise_ikfom::nbg, 0.00001); // *dt 0.00001 0.00001 * dt *dt 0.3 //0.001 0.0001 0.01 45 | MTK::setDiagonal(cov, &process_noise_ikfom::nba, 0.00001); //0.001 0.05 0.0001/out 0.01 46 | return cov; 47 | } 48 | 49 | //double L_offset_to_I[3] = {0.04165, 0.02326, -0.0284}; // Avia 50 | //vect3 Lidar_offset_to_IMU(L_offset_to_I, 3); 51 | Eigen::Matrix get_f(state_ikfom &s, const input_ikfom &in) 52 | { 53 | Eigen::Matrix res = Eigen::Matrix::Zero(); 54 | vect3 omega; 55 | in.gyro.boxminus(omega, s.bg); 56 | vect3 a_inertial = s.rot * (in.acc-s.ba); 57 | for(int i = 0; i < 3; i++ ){ 58 | res(i) = s.vel[i]; 59 | res(i + 3) = omega[i]; 60 | res(i + 12) = a_inertial[i] + s.grav[i]; 61 | } 62 | return res; 63 | } 64 | 65 | Eigen::Matrix df_dx(state_ikfom &s, const input_ikfom &in) 66 | { 67 | Eigen::Matrix cov = Eigen::Matrix::Zero(); 68 | cov.template block<3, 3>(0, 12) = Eigen::Matrix3d::Identity(); // dp_ 69 | vect3 acc_; 70 | in.acc.boxminus(acc_, s.ba); 71 | vect3 omega; 72 | in.gyro.boxminus(omega, s.bg); 73 | cov.template block<3, 3>(12, 3) = -s.rot.toRotationMatrix()*MTK::hat(acc_); 74 | cov.template block<3, 3>(12, 18) = -s.rot.toRotationMatrix(); 75 | Eigen::Matrix vec = Eigen::Matrix::Zero(); 76 | Eigen::Matrix grav_matrix; 77 | s.S2_Mx(grav_matrix, vec, 21); 78 | cov.template block<3, 2>(12, 21) = grav_matrix; 79 | cov.template block<3, 3>(3, 15) = -Eigen::Matrix3d::Identity(); 80 | return cov; 81 | } 82 | 83 | 84 | Eigen::Matrix df_dw(state_ikfom &s, const input_ikfom &in) 85 | { 86 | Eigen::Matrix cov = Eigen::Matrix::Zero(); 87 | cov.template block<3, 3>(12, 3) = -s.rot.toRotationMatrix(); 88 | cov.template block<3, 3>(3, 0) = -Eigen::Matrix3d::Identity(); 89 | cov.template block<3, 3>(15, 6) = Eigen::Matrix3d::Identity(); 90 | cov.template block<3, 3>(18, 9) = Eigen::Matrix3d::Identity(); 91 | return cov; 92 | } 93 | 94 | vect3 SO3ToEuler(const SO3 &orient) 95 | { 96 | Eigen::Matrix _ang; 97 | Eigen::Vector4d q_data = orient.coeffs().transpose(); 98 | //scalar w=orient.coeffs[3], x=orient.coeffs[0], y=orient.coeffs[1], z=orient.coeffs[2]; 99 | double sqw = q_data[3]*q_data[3]; 100 | double sqx = q_data[0]*q_data[0]; 101 | double sqy = q_data[1]*q_data[1]; 102 | double sqz = q_data[2]*q_data[2]; 103 | double unit = sqx + sqy + sqz + sqw; // if normalized is one, otherwise is correction factor 104 | double test = q_data[3]*q_data[1] - q_data[2]*q_data[0]; 105 | 106 | if (test > 0.49999*unit) { // singularity at north pole 107 | 108 | _ang << 2 * std::atan2(q_data[0], q_data[3]), M_PI/2, 0; 109 | double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; 110 | vect3 euler_ang(temp, 3); 111 | return euler_ang; 112 | } 113 | if (test < -0.49999*unit) { // singularity at south pole 114 | _ang << -2 * std::atan2(q_data[0], q_data[3]), -M_PI/2, 0; 115 | double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; 116 | vect3 euler_ang(temp, 3); 117 | return euler_ang; 118 | } 119 | 120 | _ang << 121 | std::atan2(2*q_data[0]*q_data[3]+2*q_data[1]*q_data[2] , -sqx - sqy + sqz + sqw), 122 | std::asin (2*test/unit), 123 | std::atan2(2*q_data[2]*q_data[3]+2*q_data[1]*q_data[0] , sqx - sqy - sqz + sqw); 124 | double temp[3] = {_ang[0] * 57.3, _ang[1] * 57.3, _ang[2] * 57.3}; 125 | vect3 euler_ang(temp, 3); 126 | // euler_ang[0] = roll, euler_ang[1] = pitch, euler_ang[2] = yaw 127 | return euler_ang; 128 | } 129 | 130 | #endif -------------------------------------------------------------------------------- /launch/gdb_debug_example.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/mapping_avia.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/mapping_hesai32.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /launch/mapping_horizon.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /launch/mapping_mid360.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /launch/mapping_ouster128_malioCity.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/mapping_ouster32.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/mapping_ouster64.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/mapping_velodyne16_kaist.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/mapping_velodyne32_UrbanNav.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /msg/Pose6D.msg: -------------------------------------------------------------------------------- 1 | # the preintegrated Lidar states at the time of IMU measurements in a frame 2 | float64 offset_time # the offset time of IMU measurement w.r.t the first lidar point 3 | float64[3] acc # the preintegrated total acceleration (global frame) at the Lidar origin 4 | float64[3] gyr # the unbiased angular velocity (body frame) at the Lidar origin 5 | float64[3] vel # the preintegrated velocity (global frame) at the Lidar origin 6 | float64[3] pos # the preintegrated position (global frame) at the Lidar origin 7 | float64[9] rot # the preintegrated rotation (global frame) at the Lidar origin -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | fast_lio_msf 4 | 0.0.0 5 | 6 | 7 | This is a modified version of LOAM which is original algorithm 8 | is described in the following paper: 9 | J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time. 10 | Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014. 11 | 12 | 13 | claydergc 14 | 15 | BSD 16 | 17 | Ji Zhang 18 | 19 | catkin 20 | geometry_msgs 21 | nav_msgs 22 | roscpp 23 | rospy 24 | std_msgs 25 | sensor_msgs 26 | tf 27 | pcl_ros 28 | livox_ros_driver 29 | message_generation 30 | 31 | geometry_msgs 32 | nav_msgs 33 | sensor_msgs 34 | roscpp 35 | rospy 36 | std_msgs 37 | tf 38 | pcl_ros 39 | livox_ros_driver 40 | message_runtime 41 | 42 | rostest 43 | rosbag 44 | 45 | 46 | 47 | 48 | -------------------------------------------------------------------------------- /rviz_cfg/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/zhh2005757/FAST-LIO-Multi-Sensor-Fusion/a893e78becc200486e743d48e4f5a333e123f49b/rviz_cfg/.gitignore -------------------------------------------------------------------------------- /rviz_cfg/loam_livox.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 0 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /Global Options1 8 | - /mapping1/surround1 9 | - /mapping1/currPoints1 10 | - /mapping1/currPoints1/Autocompute Value Bounds1 11 | - /Odometry1/Odometry1 12 | - /Odometry1/Odometry1/Shape1 13 | - /Odometry1/Odometry1/Covariance1 14 | - /Odometry1/Odometry1/Covariance1/Position1 15 | - /Odometry1/Odometry1/Covariance1/Orientation1 16 | - /MarkerArray1/Namespaces1 17 | Splitter Ratio: 0.6432291865348816 18 | Tree Height: 1013 19 | - Class: rviz/Selection 20 | Name: Selection 21 | - Class: rviz/Tool Properties 22 | Expanded: 23 | - /2D Pose Estimate1 24 | - /2D Nav Goal1 25 | - /Publish Point1 26 | Name: Tool Properties 27 | Splitter Ratio: 0.5886790156364441 28 | - Class: rviz/Views 29 | Expanded: 30 | - /Current View1 31 | Name: Views 32 | Splitter Ratio: 0.5 33 | - Class: rviz/Time 34 | Experimental: false 35 | Name: Time 36 | SyncMode: 0 37 | SyncSource: currPoints 38 | Preferences: 39 | PromptSaveOnExit: true 40 | Toolbars: 41 | toolButtonStyle: 2 42 | Visualization Manager: 43 | Class: "" 44 | Displays: 45 | - Alpha: 1 46 | Cell Size: 1000 47 | Class: rviz/Grid 48 | Color: 160; 160; 164 49 | Enabled: false 50 | Line Style: 51 | Line Width: 0.029999999329447746 52 | Value: Lines 53 | Name: Grid 54 | Normal Cell Count: 0 55 | Offset: 56 | X: 0 57 | Y: 0 58 | Z: 0 59 | Plane: XY 60 | Plane Cell Count: 40 61 | Reference Frame: 62 | Value: false 63 | - Class: rviz/Axes 64 | Enabled: false 65 | Length: 0.699999988079071 66 | Name: Axes 67 | Radius: 0.05999999865889549 68 | Reference Frame: 69 | Value: false 70 | - Class: rviz/Group 71 | Displays: 72 | - Alpha: 1 73 | Autocompute Intensity Bounds: true 74 | Autocompute Value Bounds: 75 | Max Value: 10 76 | Min Value: -10 77 | Value: true 78 | Axis: Z 79 | Channel Name: intensity 80 | Class: rviz/PointCloud2 81 | Color: 238; 238; 236 82 | Color Transformer: Intensity 83 | Decay Time: 0 84 | Enabled: false 85 | Invert Rainbow: false 86 | Max Color: 255; 255; 255 87 | Min Color: 238; 238; 236 88 | Name: surround 89 | Position Transformer: XYZ 90 | Queue Size: 1 91 | Selectable: false 92 | Size (Pixels): 3 93 | Size (m): 0.05000000074505806 94 | Style: Points 95 | Topic: /cloud_registered 96 | Unreliable: false 97 | Use Fixed Frame: true 98 | Use rainbow: true 99 | Value: false 100 | - Alpha: 0.10000000149011612 101 | Autocompute Intensity Bounds: true 102 | Autocompute Value Bounds: 103 | Max Value: 15 104 | Min Value: -5 105 | Value: false 106 | Axis: Z 107 | Channel Name: intensity 108 | Class: rviz/PointCloud2 109 | Color: 255; 255; 255 110 | Color Transformer: Intensity 111 | Decay Time: 1000 112 | Enabled: true 113 | Invert Rainbow: true 114 | Max Color: 255; 255; 255 115 | Min Color: 0; 0; 0 116 | Name: currPoints 117 | Position Transformer: XYZ 118 | Queue Size: 100000 119 | Selectable: true 120 | Size (Pixels): 1 121 | Size (m): 0.009999999776482582 122 | Style: Points 123 | Topic: /cloud_registered 124 | Unreliable: false 125 | Use Fixed Frame: true 126 | Use rainbow: true 127 | Value: true 128 | - Alpha: 1 129 | Autocompute Intensity Bounds: true 130 | Autocompute Value Bounds: 131 | Max Value: 10 132 | Min Value: -10 133 | Value: true 134 | Axis: Z 135 | Channel Name: intensity 136 | Class: rviz/PointCloud2 137 | Color: 255; 0; 0 138 | Color Transformer: FlatColor 139 | Decay Time: 0 140 | Enabled: false 141 | Invert Rainbow: false 142 | Max Color: 255; 255; 255 143 | Min Color: 0; 0; 0 144 | Name: PointCloud2 145 | Position Transformer: XYZ 146 | Queue Size: 10 147 | Selectable: true 148 | Size (Pixels): 3 149 | Size (m): 0.10000000149011612 150 | Style: Flat Squares 151 | Topic: /Laser_map 152 | Unreliable: false 153 | Use Fixed Frame: true 154 | Use rainbow: true 155 | Value: false 156 | Enabled: true 157 | Name: mapping 158 | - Class: rviz/Group 159 | Displays: 160 | - Angle Tolerance: 0.009999999776482582 161 | Class: rviz/Odometry 162 | Covariance: 163 | Orientation: 164 | Alpha: 0.5 165 | Color: 255; 255; 127 166 | Color Style: Unique 167 | Frame: Local 168 | Offset: 1 169 | Scale: 1 170 | Value: true 171 | Position: 172 | Alpha: 0.30000001192092896 173 | Color: 204; 51; 204 174 | Scale: 1 175 | Value: true 176 | Value: true 177 | Enabled: true 178 | Keep: 1 179 | Name: Odometry 180 | Position Tolerance: 0.0010000000474974513 181 | Shape: 182 | Alpha: 1 183 | Axes Length: 1 184 | Axes Radius: 0.20000000298023224 185 | Color: 255; 85; 0 186 | Head Length: 0 187 | Head Radius: 0 188 | Shaft Length: 0.05000000074505806 189 | Shaft Radius: 0.05000000074505806 190 | Value: Axes 191 | Topic: /Odometry 192 | Unreliable: false 193 | Value: true 194 | Enabled: true 195 | Name: Odometry 196 | - Class: rviz/Axes 197 | Enabled: true 198 | Length: 0.699999988079071 199 | Name: Axes 200 | Radius: 0.10000000149011612 201 | Reference Frame: 202 | Value: true 203 | - Alpha: 0 204 | Buffer Length: 2 205 | Class: rviz/Path 206 | Color: 25; 255; 255 207 | Enabled: true 208 | Head Diameter: 0 209 | Head Length: 0 210 | Length: 0.30000001192092896 211 | Line Style: Billboards 212 | Line Width: 0.20000000298023224 213 | Name: Path 214 | Offset: 215 | X: 0 216 | Y: 0 217 | Z: 0 218 | Pose Color: 25; 255; 255 219 | Pose Style: None 220 | Radius: 0.029999999329447746 221 | Shaft Diameter: 0.4000000059604645 222 | Shaft Length: 0.4000000059604645 223 | Topic: /path 224 | Unreliable: false 225 | Value: true 226 | - Alpha: 1 227 | Buffer Length: 1 228 | Class: rviz/Path 229 | Color: 25; 255; 0 230 | Enabled: true 231 | Head Diameter: 0.30000001192092896 232 | Head Length: 0.20000000298023224 233 | Length: 0.30000001192092896 234 | Line Style: Lines 235 | Line Width: 0.029999999329447746 236 | Name: GNSSPath 237 | Offset: 238 | X: 0 239 | Y: 0 240 | Z: 0 241 | Pose Color: 255; 85; 255 242 | Pose Style: None 243 | Radius: 0.029999999329447746 244 | Shaft Diameter: 0.10000000149011612 245 | Shaft Length: 0.10000000149011612 246 | Topic: /gnss_path 247 | Unreliable: false 248 | Value: true 249 | - Alpha: 1 250 | Autocompute Intensity Bounds: false 251 | Autocompute Value Bounds: 252 | Max Value: 10 253 | Min Value: -10 254 | Value: true 255 | Axis: Z 256 | Channel Name: intensity 257 | Class: rviz/PointCloud2 258 | Color: 255; 255; 255 259 | Color Transformer: Intensity 260 | Decay Time: 0 261 | Enabled: false 262 | Invert Rainbow: false 263 | Max Color: 239; 41; 41 264 | Max Intensity: 0 265 | Min Color: 239; 41; 41 266 | Min Intensity: 0 267 | Name: PointCloud2 268 | Position Transformer: XYZ 269 | Queue Size: 10 270 | Selectable: true 271 | Size (Pixels): 4 272 | Size (m): 0.30000001192092896 273 | Style: Spheres 274 | Topic: /cloud_effected 275 | Unreliable: false 276 | Use Fixed Frame: true 277 | Use rainbow: true 278 | Value: false 279 | - Alpha: 1 280 | Autocompute Intensity Bounds: true 281 | Autocompute Value Bounds: 282 | Max Value: 13.139549255371094 283 | Min Value: -32.08251953125 284 | Value: true 285 | Axis: Z 286 | Channel Name: intensity 287 | Class: rviz/PointCloud2 288 | Color: 138; 226; 52 289 | Color Transformer: FlatColor 290 | Decay Time: 0 291 | Enabled: false 292 | Invert Rainbow: false 293 | Max Color: 138; 226; 52 294 | Min Color: 138; 226; 52 295 | Name: PointCloud2 296 | Position Transformer: XYZ 297 | Queue Size: 10 298 | Selectable: true 299 | Size (Pixels): 3 300 | Size (m): 0.10000000149011612 301 | Style: Flat Squares 302 | Topic: /Laser_map 303 | Unreliable: false 304 | Use Fixed Frame: true 305 | Use rainbow: true 306 | Value: false 307 | - Class: rviz/MarkerArray 308 | Enabled: false 309 | Marker Topic: /MarkerArray 310 | Name: MarkerArray 311 | Namespaces: 312 | {} 313 | Queue Size: 100 314 | Value: false 315 | Enabled: true 316 | Global Options: 317 | Background Color: 0; 0; 0 318 | Default Light: true 319 | Fixed Frame: camera_init 320 | Frame Rate: 10 321 | Name: root 322 | Tools: 323 | - Class: rviz/Interact 324 | Hide Inactive Objects: true 325 | - Class: rviz/MoveCamera 326 | - Class: rviz/Select 327 | - Class: rviz/FocusCamera 328 | - Class: rviz/Measure 329 | - Class: rviz/SetInitialPose 330 | Theta std deviation: 0.2617993950843811 331 | Topic: /initialpose 332 | X std deviation: 0.5 333 | Y std deviation: 0.5 334 | - Class: rviz/SetGoal 335 | Topic: /move_base_simple/goal 336 | - Class: rviz/PublishPoint 337 | Single click: true 338 | Topic: /clicked_point 339 | Value: true 340 | Views: 341 | Current: 342 | Class: rviz/Orbit 343 | Distance: 133.21060180664062 344 | Enable Stereo Rendering: 345 | Stereo Eye Separation: 0.05999999865889549 346 | Stereo Focal Distance: 1 347 | Swap Stereo Eyes: false 348 | Value: false 349 | Focal Point: 350 | X: 0 351 | Y: 0 352 | Z: 0 353 | Focal Shape Fixed Size: false 354 | Focal Shape Size: 0.05000000074505806 355 | Invert Z Axis: false 356 | Name: Current View 357 | Near Clip Distance: 0.009999999776482582 358 | Pitch: 0.2503986954689026 359 | Target Frame: body 360 | Value: Orbit (rviz) 361 | Yaw: 3.1735568046569824 362 | Saved: ~ 363 | Window Geometry: 364 | Displays: 365 | collapsed: false 366 | Height: 1314 367 | Hide Left Dock: false 368 | Hide Right Dock: false 369 | QMainWindow State: 000000ff00000000fd0000000400000000000001d70000044bfc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000008600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000560000044b0000012600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650000000297000001dc0000000000000000fb0000000a0049006d0061006700650000000394000001600000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c7000000000000000000000001000001520000044bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000560000044b000000ec00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009ca00000052fc0100000002fb0000000800540069006d00650100000000000009ca0000042b00fffffffb0000000800540069006d00650100000000000004500000000000000000000007ea0000044b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 370 | Selection: 371 | collapsed: false 372 | Time: 373 | collapsed: false 374 | Tool Properties: 375 | collapsed: false 376 | Views: 377 | collapsed: false 378 | Width: 2506 379 | X: 54 380 | Y: 41 381 | -------------------------------------------------------------------------------- /src/GNSS_Processing.hpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 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 "use-ikfom.hpp" 26 | 27 | #include // 调用GeographicLib库 28 | 29 | class GnssProcess 30 | { 31 | public: 32 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 33 | double time ; 34 | double latitude ; 35 | double longitude ; 36 | double altitude ; 37 | double local_E ; 38 | double local_N ; 39 | double local_U ; 40 | int status ; 41 | int service ; 42 | 43 | double origin_longitude; 44 | double origin_latitude; 45 | double origin_altitude; 46 | 47 | V3D pose_cov ; 48 | 49 | GnssProcess(); 50 | ~GnssProcess(); 51 | 52 | void InitOriginPosition(double latitude, double longitude, double altitude); 53 | void UpdateXYZ(double latitude, double longitude, double altitude); 54 | 55 | void Reverse( 56 | const double &local_E, const double &local_N, const double &local_U, 57 | double &lat, double &lon, double &alt 58 | ); 59 | 60 | void set_extrinsic(const V3D &transl, const M3D &rot); 61 | void set_extrinsic(const V3D &transl); 62 | void set_extrinsic(const MD(4,4) &T); 63 | 64 | private: 65 | GeographicLib::LocalCartesian geo_converter; 66 | 67 | M3D Gnss_R_wrt_Lidar ; 68 | V3D Gnss_T_wrt_Lidar; 69 | }; 70 | 71 | GnssProcess::GnssProcess() 72 | { 73 | time = 0.0; 74 | local_E = 0.0; 75 | local_N = 0.0; 76 | local_U = 0.0; 77 | status = 0; 78 | service = 0; 79 | 80 | origin_longitude = 0 ; 81 | origin_latitude = 0; 82 | origin_altitude = 0; 83 | pose_cov = Zero3d; 84 | Gnss_T_wrt_Lidar = Zero3d; 85 | Gnss_R_wrt_Lidar = Eye3d; 86 | } 87 | 88 | GnssProcess::~GnssProcess() {} 89 | 90 | // 初始化原点, WGS84 -> ENU ??? 调试结果好像是 NED 北东地 91 | void GnssProcess::InitOriginPosition(double latitude, double longitude, double altitude) 92 | { 93 | geo_converter.Reset(latitude, longitude, altitude); 94 | ROS_INFO("Init Gnss OriginPosition"); 95 | origin_latitude = latitude; 96 | origin_longitude = longitude; 97 | origin_altitude = altitude; 98 | } 99 | 100 | // 获取更新后的ENU坐标 101 | void GnssProcess::UpdateXYZ(double latitude, double longitude, double altitude) { 102 | geo_converter.Forward(latitude, longitude, altitude, local_E, local_N, local_U); 103 | } 104 | 105 | void GnssProcess::Reverse( 106 | const double &local_E, const double &local_N, const double &local_U, 107 | double &lat, double &lon, double &alt 108 | ) { 109 | geo_converter.Reverse(local_E, local_N, local_U, lat, lon, alt); 110 | } 111 | 112 | void GnssProcess::set_extrinsic(const MD(4,4) &T) 113 | { 114 | Gnss_T_wrt_Lidar = T.block<3,1>(0,3); 115 | Gnss_R_wrt_Lidar = T.block<3,3>(0,0); 116 | } 117 | 118 | void GnssProcess::set_extrinsic(const V3D &transl) 119 | { 120 | Gnss_T_wrt_Lidar = transl; 121 | Gnss_R_wrt_Lidar.setIdentity(); 122 | } 123 | 124 | void GnssProcess::set_extrinsic(const V3D &transl, const M3D &rot) 125 | { 126 | Gnss_T_wrt_Lidar = transl; 127 | Gnss_R_wrt_Lidar = rot; 128 | } 129 | 130 | 131 | -------------------------------------------------------------------------------- /src/IMU_Processing.hpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 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 "use-ikfom.hpp" 26 | 27 | /// *************Preconfiguration 28 | 29 | #define MAX_INI_COUNT (10) 30 | 31 | const bool time_list(PointType &x, PointType &y) {return (x.curvature < y.curvature);}; 32 | 33 | /// *************IMU Process and undistortion 34 | class ImuProcess 35 | { 36 | public: 37 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 38 | 39 | ImuProcess(); 40 | ~ImuProcess(); 41 | 42 | void Reset(); 43 | void Reset(double start_timestamp, const sensor_msgs::ImuConstPtr &lastimu); 44 | void set_extrinsic(const V3D &transl, const M3D &rot); 45 | void set_extrinsic(const V3D &transl); 46 | void set_extrinsic(const MD(4,4) &T); 47 | void set_gyr_cov(const V3D &scaler); 48 | void set_acc_cov(const V3D &scaler); 49 | void set_gyr_bias_cov(const V3D &b_g); 50 | void set_acc_bias_cov(const V3D &b_a); 51 | Eigen::Matrix Q; 52 | void Process(MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI::Ptr pcl_un_); 53 | 54 | void set_wheel_extrinsic(const V3D &transl, const M3D &rot); 55 | void set_wheel_nhc_cov(const V3D &scaler); 56 | void set_wheel_scale(const V1D &s); 57 | V3D cov_wheel_nhc; 58 | 59 | ofstream fout_imu; 60 | V3D cov_acc; 61 | V3D cov_gyr; 62 | V3D cov_acc_scale; 63 | V3D cov_gyr_scale; 64 | V3D cov_bias_gyr; 65 | V3D cov_bias_acc; 66 | double first_lidar_time; 67 | vector IMUpose; 68 | 69 | private: 70 | void IMU_init(MeasureGroup &meas, esekfom::esekf &kf_state, int &N); 71 | void UndistortPcl(MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI &pcl_in_out); 72 | 73 | PointCloudXYZI::Ptr cur_pcl_un_; 74 | sensor_msgs::ImuConstPtr last_imu_; 75 | deque v_imu_; 76 | vector v_rot_pcl_; 77 | M3D Lidar_R_wrt_IMU; 78 | V3D Lidar_T_wrt_IMU; 79 | V3D mean_acc; 80 | V3D mean_gyr; 81 | V3D angvel_last; 82 | V3D acc_s_last; 83 | double start_timestamp_; 84 | double last_lidar_end_time_; 85 | int init_iter_num = 1; 86 | bool b_first_frame_ = true; 87 | bool imu_need_init_ = true; 88 | bool gnss_heading_need_init_ = true; 89 | 90 | M3D Wheel_R_wrt_IMU; 91 | V3D Wheel_T_wrt_IMU; 92 | V1D wheel_s; 93 | 94 | M3D GNSS_Heading; 95 | }; 96 | 97 | ImuProcess::ImuProcess() 98 | : b_first_frame_(true), imu_need_init_(true), start_timestamp_(-1) 99 | { 100 | init_iter_num = 1; 101 | Q = process_noise_cov(); 102 | cov_acc = V3D(0.1, 0.1, 0.1); 103 | cov_gyr = V3D(0.1, 0.1, 0.1); 104 | cov_bias_gyr = V3D(0.0001, 0.0001, 0.0001); 105 | cov_bias_acc = V3D(0.0001, 0.0001, 0.0001); 106 | mean_acc = V3D(0, 0, -1.0); 107 | mean_gyr = V3D(0, 0, 0); 108 | angvel_last = Zero3d; 109 | Lidar_T_wrt_IMU = Zero3d; 110 | Lidar_R_wrt_IMU = Eye3d; 111 | last_imu_.reset(new sensor_msgs::Imu()); 112 | 113 | cov_wheel_nhc = V3D(0.01, 0.01, 0.01); 114 | Wheel_T_wrt_IMU = Zero3d; 115 | Wheel_R_wrt_IMU = Eye3d; 116 | wheel_s = V1D(1.0); 117 | 118 | GNSS_Heading = Eye3d; 119 | } 120 | 121 | ImuProcess::~ImuProcess() {} 122 | 123 | void ImuProcess::Reset() 124 | { 125 | // ROS_WARN("Reset ImuProcess"); 126 | mean_acc = V3D(0, 0, -1.0); 127 | mean_gyr = V3D(0, 0, 0); 128 | angvel_last = Zero3d; 129 | imu_need_init_ = true; 130 | start_timestamp_ = -1; 131 | init_iter_num = 1; 132 | v_imu_.clear(); 133 | IMUpose.clear(); 134 | last_imu_.reset(new sensor_msgs::Imu()); 135 | cur_pcl_un_.reset(new PointCloudXYZI()); 136 | } 137 | 138 | void ImuProcess::set_extrinsic(const MD(4,4) &T) 139 | { 140 | Lidar_T_wrt_IMU = T.block<3,1>(0,3); 141 | Lidar_R_wrt_IMU = T.block<3,3>(0,0); 142 | } 143 | 144 | void ImuProcess::set_extrinsic(const V3D &transl) 145 | { 146 | Lidar_T_wrt_IMU = transl; 147 | Lidar_R_wrt_IMU.setIdentity(); 148 | } 149 | 150 | void ImuProcess::set_extrinsic(const V3D &transl, const M3D &rot) 151 | { 152 | Lidar_T_wrt_IMU = transl; 153 | Lidar_R_wrt_IMU = rot; 154 | } 155 | 156 | void ImuProcess::set_gyr_cov(const V3D &scaler) 157 | { 158 | cov_gyr_scale = scaler; 159 | } 160 | 161 | void ImuProcess::set_acc_cov(const V3D &scaler) 162 | { 163 | cov_acc_scale = scaler; 164 | } 165 | 166 | void ImuProcess::set_gyr_bias_cov(const V3D &b_g) 167 | { 168 | cov_bias_gyr = b_g; 169 | } 170 | 171 | void ImuProcess::set_acc_bias_cov(const V3D &b_a) 172 | { 173 | cov_bias_acc = b_a; 174 | } 175 | 176 | void ImuProcess::set_wheel_extrinsic(const V3D &transl, const M3D &rot) 177 | { 178 | Wheel_T_wrt_IMU = transl; 179 | Wheel_R_wrt_IMU = rot; 180 | } 181 | 182 | void ImuProcess::set_wheel_scale(const V1D &s) 183 | { 184 | wheel_s = s; 185 | } 186 | 187 | void ImuProcess::set_wheel_nhc_cov(const V3D &scaler) 188 | { 189 | cov_wheel_nhc = scaler; 190 | } 191 | 192 | void ImuProcess::IMU_init(MeasureGroup &meas, esekfom::esekf &kf_state, int &N) 193 | { 194 | /** 1. initializing the gravity, gyro bias, acc and gyro covariance 195 | ** 2. normalize the acceleration measurenments to unit gravity **/ 196 | 197 | V3D cur_acc, cur_gyr; 198 | 199 | if (b_first_frame_) 200 | { 201 | Reset(); 202 | N = 1; 203 | b_first_frame_ = false; 204 | const auto &imu_acc = meas.imu.front()->linear_acceleration; 205 | const auto &gyr_acc = meas.imu.front()->angular_velocity; 206 | mean_acc << imu_acc.x, imu_acc.y, imu_acc.z; 207 | mean_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; 208 | first_lidar_time = meas.lidar_beg_time; 209 | } 210 | 211 | for (const auto &imu : meas.imu) 212 | { 213 | const auto &imu_acc = imu->linear_acceleration; 214 | const auto &gyr_acc = imu->angular_velocity; 215 | cur_acc << imu_acc.x, imu_acc.y, imu_acc.z; 216 | cur_gyr << gyr_acc.x, gyr_acc.y, gyr_acc.z; 217 | 218 | mean_acc += (cur_acc - mean_acc) / N; 219 | mean_gyr += (cur_gyr - mean_gyr) / N; 220 | 221 | cov_acc = cov_acc * (N - 1.0) / N + (cur_acc - mean_acc).cwiseProduct(cur_acc - mean_acc) * (N - 1.0) / (N * N); 222 | cov_gyr = cov_gyr * (N - 1.0) / N + (cur_gyr - mean_gyr).cwiseProduct(cur_gyr - mean_gyr) * (N - 1.0) / (N * N); 223 | 224 | // cout<<"acc norm: "<twist.twist.linear.x; 241 | V3D wheel_v_vec(wheel_velocity, 0.0, 0.0); 242 | M3D angv_crossmat; 243 | V3D real_gyr = cur_gyr - mean_gyr; 244 | angv_crossmat << SKEW_SYM_MATRX(real_gyr); 245 | init_state.vel = Wheel_R_wrt_IMU * (wheel_v_vec * wheel_s) - angv_crossmat * Wheel_T_wrt_IMU; // initial rot is identity matrix 246 | init_state.wheel_s = wheel_s; 247 | init_state.offset_R_W_I = Wheel_R_wrt_IMU; 248 | init_state.offset_T_W_I = Wheel_T_wrt_IMU; 249 | } 250 | kf_state.change_x(init_state); 251 | 252 | esekfom::esekf::cov init_P = kf_state.get_P(); 253 | init_P.setIdentity(); 254 | init_P(6,6) = init_P(7,7) = init_P(8,8) = 0.00001; 255 | init_P(9,9) = init_P(10,10) = init_P(11,11) = 0.00001; 256 | init_P(15,15) = init_P(16,16) = init_P(17,17) = 0.0001; 257 | init_P(18,18) = init_P(19,19) = init_P(20,20) = 0.001; 258 | init_P(21,21) = init_P(22,22) = 0.00001; 259 | init_P(23,23) = init_P(24,24) = init_P(25,25) = 0.00001; // Wheel_R_wrt_IMU 260 | init_P(26,26) = init_P(27,27) = init_P(28,28) = 0.00001; // Wheel_T_wrt_IMU 261 | init_P(29,29) = 0.0001; // wheel scale 262 | init_P(30,30) = init_P(31,31) = init_P(32,32) = 0.0001; // GNSS_Heading 263 | kf_state.change_P(init_P); 264 | last_imu_ = meas.imu.back(); 265 | 266 | } 267 | 268 | void ImuProcess::UndistortPcl(MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI &pcl_out) 269 | { 270 | /*** add the imu of the last frame-tail to the of current frame-head ***/ 271 | auto v_imu = meas.imu; 272 | v_imu.push_front(last_imu_); 273 | const double &imu_beg_time = v_imu.front()->header.stamp.toSec(); 274 | const double &imu_end_time = v_imu.back()->header.stamp.toSec(); 275 | const double &pcl_beg_time = meas.lidar_beg_time; 276 | const double &pcl_end_time = meas.lidar_end_time; 277 | 278 | /*** downsample wheel meas, only remain meas in the middle ***/ 279 | // if (meas.wheel.size() > 1){ 280 | // int pop_num = meas.wheel.size() / 2; 281 | // for (int i = 0; i < pop_num; i++){ 282 | // meas.wheel.pop_front(); 283 | // } 284 | // auto wheel_meas = meas.wheel.front(); 285 | // meas.wheel.clear(); 286 | // meas.wheel.push_back(wheel_meas); 287 | // } 288 | 289 | /*** sort point clouds by offset time ***/ 290 | pcl_out = *(meas.lidar); 291 | sort(pcl_out.points.begin(), pcl_out.points.end(), time_list); 292 | // cout<<"[ IMU Process ]: Process lidar from "<header.stamp.toSec() < last_lidar_end_time_) continue; 313 | 314 | angvel_avr<<0.5 * (head->angular_velocity.x + tail->angular_velocity.x), 315 | 0.5 * (head->angular_velocity.y + tail->angular_velocity.y), 316 | 0.5 * (head->angular_velocity.z + tail->angular_velocity.z); 317 | acc_avr <<0.5 * (head->linear_acceleration.x + tail->linear_acceleration.x), 318 | 0.5 * (head->linear_acceleration.y + tail->linear_acceleration.y), 319 | 0.5 * (head->linear_acceleration.z + tail->linear_acceleration.z); 320 | 321 | // fout_imu << setw(10) << head->header.stamp.toSec() - first_lidar_time << " " << angvel_avr.transpose() << " " << acc_avr.transpose() << endl; 322 | 323 | acc_avr = acc_avr * G_m_s2 / mean_acc.norm(); // - state_inout.ba; 324 | 325 | if(head->header.stamp.toSec() < last_lidar_end_time_) 326 | { 327 | dt = tail->header.stamp.toSec() - last_lidar_end_time_; 328 | // dt = tail->header.stamp.toSec() - pcl_beg_time; 329 | } 330 | else 331 | { 332 | dt = tail->header.stamp.toSec() - head->header.stamp.toSec(); 333 | } 334 | 335 | in.acc = acc_avr; 336 | in.gyro = angvel_avr; 337 | Q.block<3, 3>(0, 0).diagonal() = cov_gyr; 338 | Q.block<3, 3>(3, 3).diagonal() = cov_acc; 339 | Q.block<3, 3>(6, 6).diagonal() = cov_bias_gyr; 340 | Q.block<3, 3>(9, 9).diagonal() = cov_bias_acc; 341 | //向前传播 342 | kf_state.predict(dt, Q, in);// normal predict 343 | 344 | /*** update by gnss meas ***/ 345 | if (USE_GNSS && !meas.gnss.empty()) 346 | { 347 | double gnss_time = meas.gnss.front()->header.stamp.toSec(); 348 | if (gnss_time < head->header.stamp.toSec()){ 349 | meas.gnss.pop_front(); 350 | }else{ 351 | if (gnss_time < tail->header.stamp.toSec()){ // gnss位于两个imu之间 352 | opt_with_gnss = true; 353 | if (!gnss_heading_need_init_) 354 | { 355 | if (meas.gnss.front()->pose.covariance[0] < 200) // 航向初始化未完成或gnss水平噪声大于200不进行更新(遮挡区域) 356 | { 357 | kf_state.update_iterated_dyn_share(); // gnss更新 358 | ROS_WARN("gnss update !"); 359 | }else{ 360 | ROS_WARN("gnss too noise !"); 361 | } 362 | }else{ 363 | ROS_WARN("gnss not initialized !"); 364 | } 365 | opt_with_gnss = false; 366 | meas.gnss.pop_front(); 367 | } 368 | } 369 | } 370 | /*** update by wheel meas ***/ 371 | if (USE_WHEEL && !meas.wheel.empty()) 372 | { 373 | double wheel_time = meas.wheel.front()->header.stamp.toSec(); 374 | if (wheel_time < head->header.stamp.toSec()){ 375 | meas.wheel.pop_front(); 376 | }else{ 377 | if (wheel_time < tail->header.stamp.toSec()){ // wheel 位于两个imu之间 378 | opt_with_wheel = true; 379 | kf_state.update_iterated_dyn_share(); // wheel更新 380 | // cout << "wheel update !" << endl; 381 | opt_with_wheel = false; 382 | meas.wheel.pop_front(); 383 | } 384 | } 385 | } 386 | 387 | /* save the poses at each IMU measurements */ 388 | imu_state = kf_state.get_x(); 389 | angvel_last = angvel_avr - imu_state.bg; 390 | acc_s_last = imu_state.rot * (acc_avr - imu_state.ba); 391 | for(int i=0; i<3; i++) 392 | { 393 | acc_s_last[i] += imu_state.grav[i]; 394 | } 395 | double &&offs_t = tail->header.stamp.toSec() - pcl_beg_time; 396 | IMUpose.push_back(set_pose6d(offs_t, acc_s_last, angvel_last, imu_state.vel, imu_state.pos, imu_state.rot.toRotationMatrix())); 397 | } 398 | 399 | /*** calculated the pos and attitude prediction at the frame-end ***/ 400 | double note = pcl_end_time > imu_end_time ? 1.0 : -1.0; 401 | dt = note * (pcl_end_time - imu_end_time); 402 | kf_state.predict(dt, Q, in); 403 | 404 | imu_state = kf_state.get_x(); 405 | last_imu_ = meas.imu.back(); 406 | last_lidar_end_time_ = pcl_end_time; 407 | 408 | /*** undistort each lidar point (backward propagation) ***/ 409 | if (pcl_out.points.begin() == pcl_out.points.end()) return; 410 | auto it_pcl = pcl_out.points.end() - 1; 411 | for (auto it_kp = IMUpose.end() - 1; it_kp != IMUpose.begin(); it_kp--) 412 | { 413 | auto head = it_kp - 1; 414 | auto tail = it_kp; 415 | R_imu<rot); 416 | // cout<<"head imu acc: "<vel); 418 | pos_imu<pos); 419 | acc_imu<acc); 420 | angvel_avr<gyr); 421 | 422 | for(; it_pcl->curvature / double(1000) > head->offset_time; it_pcl --) 423 | { 424 | dt = it_pcl->curvature / double(1000) - head->offset_time; 425 | 426 | /* Transform to the 'end' frame, using only the rotation 427 | * Note: Compensation direction is INVERSE of Frame's moving direction 428 | * So if we want to compensate a point at timestamp-i to the frame-e 429 | * P_compensate = R_imu_e ^ T * (R_i * P_i + T_ei) where T_ei is represented in global frame */ 430 | M3D R_i(R_imu * Exp(angvel_avr, dt)); 431 | 432 | V3D P_i(it_pcl->x, it_pcl->y, it_pcl->z); 433 | V3D T_ei(pos_imu + vel_imu * dt + 0.5 * acc_imu * dt * dt - imu_state.pos); 434 | V3D P_compensate = imu_state.offset_R_L_I.conjugate() * (imu_state.rot.conjugate() * (R_i * (imu_state.offset_R_L_I * P_i + imu_state.offset_T_L_I) + T_ei) - imu_state.offset_T_L_I);// not accurate! 435 | 436 | // save Undistorted points and their rotation 437 | it_pcl->x = P_compensate(0); 438 | it_pcl->y = P_compensate(1); 439 | it_pcl->z = P_compensate(2); 440 | 441 | if (it_pcl == pcl_out.points.begin()) break; 442 | } 443 | } 444 | } 445 | 446 | void ImuProcess::Process(MeasureGroup &meas, esekfom::esekf &kf_state, PointCloudXYZI::Ptr cur_pcl_un_) 447 | { 448 | double t1,t2,t3; 449 | t1 = omp_get_wtime(); 450 | 451 | if(meas.imu.empty()) {return;}; 452 | ROS_ASSERT(meas.lidar != nullptr); 453 | 454 | if (imu_need_init_) 455 | { 456 | /// The very first lidar frame 457 | IMU_init(meas, kf_state, init_iter_num); 458 | 459 | imu_need_init_ = true; 460 | 461 | last_imu_ = meas.imu.back(); 462 | 463 | state_ikfom imu_state = kf_state.get_x(); 464 | if (init_iter_num > MAX_INI_COUNT) 465 | { 466 | cov_acc *= pow(G_m_s2 / mean_acc.norm(), 2); 467 | imu_need_init_ = false; 468 | 469 | cov_acc = cov_acc_scale; 470 | cov_gyr = cov_gyr_scale; 471 | ROS_INFO("IMU Initial Done"); 472 | // ROS_INFO("IMU Initial Done: Gravity: %.4f %.4f %.4f %.4f; state.bias_g: %.4f %.4f %.4f; acc covarience: %.8f %.8f %.8f; gry covarience: %.8f %.8f %.8f",\ 473 | // imu_state.grav[0], imu_state.grav[1], imu_state.grav[2], mean_acc.norm(), cov_bias_gyr[0], cov_bias_gyr[1], cov_bias_gyr[2], cov_acc[0], cov_acc[1], cov_acc[2], cov_gyr[0], cov_gyr[1], cov_gyr[2]); 474 | fout_imu.open(DEBUG_FILE_DIR("imu.txt"),ios::out); 475 | } 476 | 477 | return; 478 | } 479 | 480 | if (USE_GNSS && gnss_heading_need_init_){ 481 | if (!meas.gnss.empty()) 482 | { 483 | Eigen::Vector3d gnss_pose(meas.gnss.back()->pose.pose.position.x, meas.gnss.back()->pose.pose.position.y, 0.0); 484 | state_ikfom init_state = kf_state.get_x(); // 初始状态量 485 | cout << "gnss norm " << gnss_pose.norm() << endl; 486 | if (gnss_pose.norm() > 5) 487 | { // GNSS 水平位移大于5m 488 | Eigen::Vector3d tmp_vec(init_state.pos.x(), init_state.pos.y(), 0.0); 489 | GNSS_Heading = Eigen::Quaterniond::FromTwoVectors(gnss_pose, tmp_vec).toRotationMatrix(); 490 | SO3 so3(GNSS_Heading); 491 | V3D euler = SO3ToEuler(so3); 492 | ROS_WARN_STREAM("INITIAL GNSS HEADING " << euler.transpose()); 493 | init_state.offset_R_G_I = GNSS_Heading; 494 | kf_state.change_x(init_state); 495 | gnss_heading_need_init_ = false; 496 | } 497 | } 498 | } 499 | 500 | //畸变纠正 501 | UndistortPcl(meas, kf_state, *cur_pcl_un_); 502 | 503 | t2 = omp_get_wtime(); 504 | t3 = omp_get_wtime(); 505 | 506 | // cout<<"[ IMU Process ]: Time: "< 2 | #include 3 | #include 4 | #include 5 | 6 | using namespace std; 7 | 8 | #define IS_VALID(a) ((abs(a)>1e8) ? true : false) 9 | 10 | typedef pcl::PointXYZINormal PointType; 11 | typedef pcl::PointCloud PointCloudXYZI; 12 | 13 | enum LID_TYPE{AVIA = 1, VELO16, OUST64, HESAI32, RS128}; //{1, 2, 3, 4} 14 | enum TIME_UNIT{SEC = 0, MS = 1, US = 2, NS = 3}; 15 | enum Feature{Nor, Poss_Plane, Real_Plane, Edge_Jump, Edge_Plane, Wire, ZeroPoint}; 16 | enum Surround{Prev, Next}; 17 | enum E_jump{Nr_nor, Nr_zero, Nr_180, Nr_inf, Nr_blind}; 18 | 19 | struct orgtype 20 | { 21 | double range; 22 | double dista; 23 | double angle[2]; 24 | double intersect; 25 | E_jump edj[2]; 26 | Feature ftype; 27 | orgtype() 28 | { 29 | range = 0; 30 | edj[Prev] = Nr_nor; 31 | edj[Next] = Nr_nor; 32 | ftype = Nor; 33 | intersect = 2; 34 | } 35 | }; 36 | 37 | namespace velodyne_ros { 38 | struct EIGEN_ALIGN16 Point { 39 | PCL_ADD_POINT4D; 40 | float intensity; 41 | float time; 42 | uint16_t ring; 43 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 44 | }; 45 | } // namespace velodyne_ros 46 | POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_ros::Point, 47 | (float, x, x) 48 | (float, y, y) 49 | (float, z, z) 50 | (float, intensity, intensity) 51 | (float, time, time) 52 | (uint16_t, ring, ring) 53 | ) 54 | 55 | namespace rslidar_ros { 56 | struct EIGEN_ALIGN16 Point { 57 | PCL_ADD_POINT4D; 58 | float intensity; 59 | float time; 60 | uint16_t ring; 61 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 62 | }; 63 | } // namespace rslidar_ros 64 | POINT_CLOUD_REGISTER_POINT_STRUCT(rslidar_ros::Point, 65 | (float, x, x) 66 | (float, y, y) 67 | (float, z, z) 68 | (float, intensity, curvature) 69 | (float, time, normal_x) 70 | (uint16_t, ring, ring) 71 | ) 72 | 73 | namespace ouster_ros { 74 | struct EIGEN_ALIGN16 Point { 75 | PCL_ADD_POINT4D; 76 | float intensity; 77 | uint32_t t; 78 | uint16_t reflectivity; 79 | uint8_t ring; 80 | uint16_t ambient; 81 | uint32_t range; 82 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 83 | }; 84 | } // namespace ouster_ros 85 | 86 | // clang-format off 87 | POINT_CLOUD_REGISTER_POINT_STRUCT(ouster_ros::Point, 88 | (float, x, x) 89 | (float, y, y) 90 | (float, z, z) 91 | (float, intensity, intensity) 92 | // use std::uint32_t to avoid conflicting with pcl::uint32_t 93 | (std::uint32_t, t, t) 94 | (std::uint16_t, reflectivity, reflectivity) 95 | (std::uint16_t, ring, ring) 96 | (std::uint16_t, ambient, ambient) 97 | (std::uint32_t, range, range) 98 | ) 99 | 100 | class Preprocess 101 | { 102 | public: 103 | // EIGEN_MAKE_ALIGNED_OPERATOR_NEW 104 | 105 | Preprocess(); 106 | ~Preprocess(); 107 | 108 | void process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); 109 | void process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out); 110 | void set(bool feat_en, int lid_type, double bld, int pfilt_num); 111 | 112 | // sensor_msgs::PointCloud2::ConstPtr pointcloud; 113 | PointCloudXYZI pl_full, pl_corn, pl_surf; 114 | PointCloudXYZI pl_buff[128]; //maximum 128 line lidar 115 | vector typess[128]; //maximum 128 line lidar 116 | float time_unit_scale; 117 | int lidar_type, point_filter_num, N_SCANS, SCAN_RATE, time_unit; 118 | double blind; 119 | bool feature_enabled, given_offset_time; 120 | ros::Publisher pub_full, pub_surf, pub_corn; 121 | 122 | 123 | private: 124 | void avia_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg); 125 | void oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); 126 | void velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); 127 | void pandar_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); 128 | void rs_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); 129 | void give_feature(PointCloudXYZI &pl, vector &types); 130 | void pub_func(PointCloudXYZI &pl, const ros::Time &ct); 131 | int plane_judge(const PointCloudXYZI &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct); 132 | bool small_plane(const PointCloudXYZI &pl, vector &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct); 133 | bool edge_jump_judge(const PointCloudXYZI &pl, vector &types, uint i, Surround nor_dir); 134 | 135 | int group_size; 136 | double disA, disB, inf_bound; 137 | double limit_maxmid, limit_midmin, limit_maxmin; 138 | double p2l_ratio; 139 | double jump_up_limit, jump_down_limit; 140 | double cos160; 141 | double edgea, edgeb; 142 | double smallp_intersect, smallp_ratio; 143 | double vx, vy, vz; 144 | }; 145 | --------------------------------------------------------------------------------