LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping

Overview

LIO-SAM

A real-time lidar-inertial odometry package. We strongly recommend the users read this document thoroughly and test the package with the provided dataset first. A video of the demonstration of the method can be found on YouTube.

drawing

drawing drawing drawing drawing

Menu

System architecture

drawing

We design a system that maintains two graphs and runs up to 10x faster than real-time.

  • The factor graph in "mapOptimization.cpp" optimizes lidar odometry factor and GPS factor. This factor graph is maintained consistently throughout the whole test.
  • The factor graph in "imuPreintegration.cpp" optimizes IMU and lidar odometry factor and estimates IMU bias. This factor graph is reset periodically and guarantees real-time odometry estimation at IMU frequency.

Dependency

  • ROS (tested with Kinetic and Melodic)
    sudo apt-get install -y ros-kinetic-navigation
    sudo apt-get install -y ros-kinetic-robot-localization
    sudo apt-get install -y ros-kinetic-robot-state-publisher
    
  • gtsam (Georgia Tech Smoothing and Mapping library)
    wget -O ~/Downloads/gtsam.zip https://github.com/borglab/gtsam/archive/4.0.2.zip
    cd ~/Downloads/ && unzip gtsam.zip -d ~/Downloads/
    cd ~/Downloads/gtsam-4.0.2/
    mkdir build && cd build
    cmake -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF ..
    sudo make install -j8
    

Install

Use the following commands to download and compile the package.

cd ~/catkin_ws/src
git clone https://github.com/TixiaoShan/LIO-SAM.git
cd ..
catkin_make

Prepare lidar data

The user needs to prepare the point cloud data in the correct format for cloud deskewing, which is mainly done in "imageProjection.cpp". The two requirements are:

  • Provide point time stamp. LIO-SAM uses IMU data to perform point cloud deskew. Thus, the relative point time in a scan needs to be known. The up-to-date Velodyne ROS driver should output this information directly. Here, we assume the point time channel is called "time." The definition of the point type is located at the top of the "imageProjection.cpp." "deskewPoint()" function utilizes this relative time to obtain the transformation of this point relative to the beginning of the scan. When the lidar rotates at 10Hz, the timestamp of a point should vary between 0 and 0.1 seconds. If you are using other lidar sensors, you may need to change the name of this time channel and make sure that it is the relative time in a scan.
  • Provide point ring number. LIO-SAM uses this information to organize the point correctly in a matrix. The ring number indicates which channel of the sensor that this point belongs to. The definition of the point type is located at the top of "imageProjection.cpp." The up-to-date Velodyne ROS driver should output this information directly. Again, if you are using other lidar sensors, you may need to rename this information. Note that only mechanical lidars are supported by the package currently.

Prepare IMU data

  • IMU requirement. Like the original LOAM implementation, LIO-SAM only works with a 9-axis IMU, which gives roll, pitch, and yaw estimation. The roll and pitch estimation is mainly used to initialize the system at the correct attitude. The yaw estimation initializes the system at the right heading when using GPS data. Theoretically, an initialization procedure like VINS-Mono will enable LIO-SAM to work with a 6-axis IMU. The performance of the system largely depends on the quality of the IMU measurements. The higher the IMU data rate, the better the system accuracy. We use Microstrain 3DM-GX5-25, which outputs data at 500Hz. We recommend using an IMU that gives at least a 200Hz output rate. Note that the internal IMU of Ouster lidar is an 6-axis IMU.

  • IMU alignment. LIO-SAM transforms IMU raw data from the IMU frame to the Lidar frame, which follows the ROS REP-105 convention (x - forward, y - left, z - upward). To make the system function properly, the correct extrinsic transformation needs to be provided in "params.yaml" file. The reason why there are two extrinsics is that my IMU (Microstrain 3DM-GX5-25) acceleration and attitude have different cooridinates. Depend on your IMU manufacturer, the two extrinsics for your IMU may or may not be the same. Using our setup as an example:

    • we need to set the readings of x-z acceleration and gyro negative to transform the IMU data in the lidar frame, which is indicated by "extrinsicRot" in "params.yaml."
    • The transformation of attitude readings is slightly different. We rotate the attitude measurements by -90 degrees around "lidar-z" axis and get the corresponding roll, pitch, and yaw readings in the lidar frame. This transformation is indicated by "extrinsicRPY" in "params.yaml."
  • IMU debug. It's strongly recommended that the user uncomment the debug lines in "imuHandler()" of "imageProjection.cpp" and test the output of the transformed IMU data. The user can rotate the sensor suite to check whether the readings correspond to the sensor's movement. A YouTube video that shows the corrected IMU data can be found here (link to YouTube).

drawing

drawing

Sample datasets

  • Download some sample datasets to test the functionality of the package. The datasets below is configured to run using the default settings:

  • The datasets below need the parameters to be configured. In these datasets, the point cloud topic is "points_raw." The IMU topic is "imu_correct," which gives the IMU data in ROS REP105 standard. Because no IMU transformation is needed for this dataset, the following configurations need to be changed to run this dataset successfully:

    • The "imuTopic" parameter in "config/params.yaml" needs to be set to "imu_correct".
    • The "extrinsicRot" and "extrinsicRPY" in "config/params.yaml" needs to be set as identity matrices.
  • Ouster (OS1-128) dataset. No extrinsics need to be changed for this dataset if you are using the default settings. Please follow the Ouster notes below to configure the package to run with Ouster data. A video of the dataset can be found on YouTube:

  • KITTI dataset. The extrinsics can be found in the Notes KITTI section below. To generate more bags using other KITTI raw data, you can use the python script provided in "config/doc/kitti2bag".

Run the package

  1. Run the launch file:
roslaunch lio_sam run.launch
  1. Play existing bag files:
rosbag play your-bag.bag -r 3

Other notes

  • Loop closure: The loop function here gives an example of proof of concept. It is directly adapted from LeGO-LOAM loop closure. For more advanced loop closure implementation, please refer to ScanContext. Set the "loopClosureEnableFlag" in "params.yaml" to "true" to test the loop closure function. In Rviz, uncheck "Map (cloud)" and check "Map (global)". This is because the visualized map - "Map (cloud)" - is simply a stack of point clouds in Rviz. Their postion will not be updated after pose correction. The loop closure function here is simply adapted from LeGO-LOAM, which is an ICP-based method. Because ICP runs pretty slow, it is suggested that the playback speed is set to be "-r 1". You can try the Garden dataset for testing.

drawing drawing

  • Using GPS: The park dataset is provided for testing LIO-SAM with GPS data. This dataset is gathered by Yewei Huang. To enable the GPS function, change "gpsTopic" in "params.yaml" to "odometry/gps". In Rviz, uncheck "Map (cloud)" and check "Map (global)". Also check "Odom GPS", which visualizes the GPS odometry. "gpsCovThreshold" can be adjusted to filter bad GPS readings. "poseCovThreshold" can be used to adjust the frequency of adding GPS factor to the graph. For example, you will notice the trajectory is constantly corrected by GPS whey you set "poseCovThreshold" to 1.0. Because of the heavy iSAM optimization, it's recommended that the playback speed is "-r 1".

drawing

  • KITTI: Since LIO-SAM needs a high-frequency IMU for function properly, we need to use KITTI raw data for testing. One problem remains unsolved is that the intrinsics of the IMU are unknown, which has a big impact on the accuracy of LIO-SAM. Download the provided sample data and make the following changes in "params.yaml":
    • extrinsicTrans: [-8.086759e-01, 3.195559e-01, -7.997231e-01]
    • extrinsicRot: [9.999976e-01, 7.553071e-04, -2.035826e-03, -7.854027e-04, 9.998898e-01, -1.482298e-02, 2.024406e-03, 1.482454e-02, 9.998881e-01]
    • extrinsicRPY: [9.999976e-01, 7.553071e-04, -2.035826e-03, -7.854027e-04, 9.998898e-01, -1.482298e-02, 2.024406e-03, 1.482454e-02, 9.998881e-01]
    • N_SCAN: 64
    • downsampleRate: 2 or 4
    • loopClosureEnableFlag: true or false

drawing drawing

  • Ouster lidar: To make LIO-SAM work with Ouster lidar, some preparations needs to be done on hardware and software level.
    • Hardware:
      • Use an external IMU. LIO-SAM does not work with the internal 6-axis IMU of Ouster lidar. You need to attach a 9-axis IMU to the lidar and perform data-gathering.
      • Configure the driver. Change "timestamp_mode" in your Ouster launch file to "TIME_FROM_PTP_1588" so you can have ROS format timestamp for the point clouds.
    • Config:
      • Change "sensor" in "params.yaml" to "ouster".
      • Change "N_SCAN" and "Horizon_SCAN" in "params.yaml" according to your lidar, i.e., N_SCAN=128, Horizon_SCAN=1024.
    • Gen 1 and Gen 2 Ouster: It seems that the point coordinate definition might be different in different generations. Please refer to Issue #94 for debugging.

drawing drawing

Service

  • /lio_sam/save_map
    • save map as a PCD file.
        rosservice call [service] [resolution] [destination]
      • Example:
        $ rosservice call /lio_sam/save_map 0.2 "/Downloads/LOAM/"

Issues

  • Zigzag or jerking behavior: if your lidar and IMU data formats are consistent with the requirement of LIO-SAM, this problem is likely caused by un-synced timestamp of lidar and IMU data.

  • Jumpping up and down: if you start testing your bag file and the base_link starts to jump up and down immediately, it is likely your IMU extrinsics are wrong. For example, the gravity acceleration has negative value.

  • mapOptimization crash: it is usually caused by GTSAM. Please install the GTSAM specified in the README.md. More similar issues can be found here.

  • gps odometry unavailable: it is generally caused due to unavailable transform between message frame_ids and robot frame_id (for example: transform should be available from "imu_frame_id" and "gps_frame_id" to "base_link" frame. Please read the Robot Localization documentation found here.

Paper

Thank you for citing LIO-SAM (IROS-2020) if you use any of this code.

@inproceedings{liosam2020shan,
  title={LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping},
  author={Shan, Tixiao and Englot, Brendan and Meyers, Drew and Wang, Wei and Ratti, Carlo and Rus Daniela},
  booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  pages={5135-5142},
  year={2020},
  organization={IEEE}
}

Part of the code is adapted from LeGO-LOAM.

@inproceedings{legoloam2018shan,
  title={LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain},
  author={Shan, Tixiao and Englot, Brendan},
  booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  pages={4758-4765},
  year={2018},
  organization={IEEE}
}

TODO

Related Package

Acknowledgement

  • LIO-SAM is based on LOAM (J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time).
Comments
  • Ouster lidar - IMU error?

    Ouster lidar - IMU error?

    Hello here, the IMU am using have the same coordinate definition with ouster os1-64, which is front-left-up, thus I change the "extrinsicRot" and "extrinsicRPY" to identity matrices, and debug IMU according to the video, everything's fine. However, when I play my recorded bag, the result is a disaster, which seems to be IMU error. Screenshot from 2020-09-01 21-10-43 And the terminal gives me Screenshot from 2020-09-01 21-11-03 Do you have any suggestions? By the way, I've tested the same IMU with ouster using Lego-Loam, which is fine. If you are interested, the recorded bag is https://drive.google.com/file/d/10zUV7I8Mh7suLumHvFeLKOO-yTBr19wj/view?usp=sharing

    Ouster 
    opened by YushengWHU 51
  • Point cloud is not in dense format, please remove NaN points first!

    Point cloud is not in dense format, please remove NaN points first!

    I used RSLIDAR to make bag, and modified config/params.yaml pointcoudtopic. When I run this bag with lio-sam, the following problem occur.

    [ERROR] [1608623674.483017189]: Point cloud is not in dense format, please remove NaN points first!

    How to solve this problem, please

    stale 
    opened by heirenlop 35
  • KITTI Dataset

    KITTI Dataset

    Hi @TixiaoShan , I noticed that you update KITTI data several days ago. And I tried new KITTI data. Lidar and IMU data are ok. But GPS data seems to have some problems.You can see below picture. The red path is the result of lio sam and another one is gps path tranformed to local cartesian coordinate. Another question is lio sam will drift a lot without loop closure. Does IMU noises cause that ? image

    stale 
    opened by LeisureLei 22
  • Ouster + External IMU inconsistent rendering and frequent jumps

    Ouster + External IMU inconsistent rendering and frequent jumps

    I have been trying to integrate my Ouster OS1-16 (Gen1) with an XSENS MTi-680G and here's how I set them up:

    • Ouster OS1 is connected to the Ethernet port of laptop
    • MTi IMU sensor is connected to a USB port
    • I have set the Ouster to timestamp in PTP 1588 mode, and issued the command sudo ptpd -i enp3s0 -M in a Terminal to make the Ethernet chip broadcast timings (thanks to @px4Li for the tip here)

    Tested and it seems PTP timestamps are working correctly but when I input the bag file data into LIO-SAM I get the following result with jumps and displacements:

    Peek 2021-03-01 21-31

    I have read the README.md and un-synced timestamps are stated as a cause for these issues but I here's a sample output from the 3 first messages of topics for LiDAR, internal IMU and XSENS IMU in the bag and as you can see the timings are pretty close, are these considered out of sync? Or am I missing something else?

    LiDAR (t) timestamp: 		1614616639310819517 - March 1, 2021 4:37:19.310 PM
    LiDAR (msg.header) timestamp: 	1614616639254676480 - March 1, 2021 4:37:19.254 PM
    LiDAR (t) timestamp: 		1614616639374563536 - March 1, 2021 4:37:19.374 PM
    LiDAR (msg.header) timestamp: 	1614616639304678400 - March 1, 2021 4:37:19.304 PM
    LiDAR (t) timestamp: 		1614616639423463862 - March 1, 2021 4:37:19.423 PM
    LiDAR (msg.header) timestamp: 	1614616639354687744 - March 1, 2021 4:37:19.354 PM
    
    
    Internal IMU (t) timestamp: 		1614616639282313498 - March 1, 2021 4:37:19.282 PM
    Internal IMU (msg.header) timestamp: 	1614616639280500775 - March 1, 2021 4:37:19.280 PM
    Internal IMU (t) timestamp: 		1614616639291110001 - March 1, 2021 4:37:19.291 PM
    Internal IMU (msg.header) timestamp: 	1614616639290500695 - March 1, 2021 4:37:19.290 PM
    Internal IMU (t) timestamp: 		1614616639301079360 - March 1, 2021 4:37:19.301 PM
    Internal IMU (msg.header) timestamp: 	1614616639300518531 - March 1, 2021 4:37:19.300 PM
    
    
    XSENS IMU (t) timestamp: 		1614616639298836081 - March 1, 2021 4:37:19.298 PM
    XSENS IMU (msg.header) timestamp: 	1614616639298028272 - March 1, 2021 4:37:19.298 PM
    XSENS IMU (t) timestamp: 		1614616639299337757 - March 1, 2021 4:37:19.299 PM
    XSENS IMU (msg.header) timestamp: 	1614616639298052150 - March 1, 2021 4:37:19.298 PM
    XSENS IMU (t) timestamp: 		1614616639299362726 - March 1, 2021 4:37:19.299 PM
    XSENS IMU (msg.header) timestamp: 	1614616639298077029 - March 1, 2021 4:37:19.298 PM
    

    rosbag info of the bag:

    version:     2.0
    duration:    21.5s
    start:       Mar 01 2021 20:07:19.28 (1614616639.28)
    end:         Mar 01 2021 20:07:40.78 (1614616660.78)
    size:        327.3 MB
    messages:    17140
    compression: none [431/431 chunks]
    types:       sensor_msgs/Imu         [6a62c6daae103f4ff57a132d6f95cec2]
                 sensor_msgs/NavSatFix   [2d3a8cd499b9b4a0249fb98fd05cfa48]
                 sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181]
                 tf2_msgs/TFMessage      [94810edda583a504dfda3829e70d7eec]
    topics:      /gnss                     72 msgs @   3.9 Hz : sensor_msgs/NavSatFix  
                 /imu/data               7243 msgs @ 33.8 kHz : sensor_msgs/Imu        
                 /os_cloud_node/imu      2151 msgs @ 100.0 Hz : sensor_msgs/Imu        
                 /os_cloud_node/points    430 msgs @  21.1 Hz : sensor_msgs/PointCloud2
                 /tf                     7243 msgs @ 35.5 kHz : tf2_msgs/TFMessage     
                 /tf_static                 1 msg             : tf2_msgs/TFMessage
    
    

    Here's LIO-SAM's output:

    [ WARN] [1614621691.228977708, 1614616643.476415178]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621696.328799517, 1614616648.572775929]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621698.231852286, 1614616650.479392595]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621698.950174892, 1614616651.201077672]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621699.709356978, 1614616651.953501557]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621700.532156937, 1614616652.786435385]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621701.204714765, 1614616653.455877594]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621701.948003696, 1614616654.195174552]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621703.001573379, 1614616655.247956986]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621704.086892839, 1614616656.075745433]: Large velocity, reset IMU-preintegration!
    [ WARN] [1614621728.522772966, 1614616844.864422705]: Failed to meet update rate! Took 188.80210920700000088
    [ WARN] [1614621728.524362000, 1614616844.864422705]: Failed to meet update rate! Took 188.78210920699999065
    
    

    And here's my params.yaml:

    lio_sam:
    
      # Topics
      pointCloudTopic: "/os_cloud_node/points"               # Point cloud data
      imuTopic: "/imu/data"                         # IMU data
      odomTopic: "odometry/imu"                   # IMU pre-preintegration odometry, same frequency as IMU
      gpsTopic: "odometry/gpsz"                   # GPS odometry topic from navsat, see module_navsat.launch file
    
      # Frames
      lidarFrame: "os_lidar"
      baselinkFrame: "base_link"
      odometryFrame: "odom"
      mapFrame: "map"
    
      # GPS Settings
      useImuHeadingInitialization: false           # if using GPS data, set to "true"
      useGpsElevation: false                      # if GPS elevation is bad, set to "false"
      gpsCovThreshold: 2.0                        # m^2, threshold for using GPS data
      poseCovThreshold: 25.0                      # m^2, threshold for using GPS data
      
      # Export settings
      savePCD: true                              # https://github.com/TixiaoShan/LIO-SAM/issues/3
      savePCDDirectory: "/Documents/PointClouds"        # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation
    
      # Sensor Settings
      sensor: ouster                            # lidar sensor type, either 'velodyne' or 'ouster'
      N_SCAN: 16                                  # number of lidar channel (i.e., 16, 32, 64, 128)
      Horizon_SCAN: 1024                          # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048)
      downsampleRate: 1                           # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1
      lidarMinRange: 1.0                          # default: 1.0, minimum lidar range to be used
      lidarMaxRange: 1000.0                       # default: 1000.0, maximum lidar range to be used
    
      # IMU Settings
      imuAccNoise: 3.9939570888238808e-03
      imuGyrNoise: 1.5636343949698187e-03
      imuAccBiasN: 6.4356659353532566e-05
      imuGyrBiasN: 3.5640318696367613e-05
      imuGravity: 9.80511
      imuRPYWeight: 0.01
    
      # Extrinsics (lidar -> IMU)
      extrinsicTrans: [0.0, 0.0, 0.0]
    
      extrinsicRot: [1, 0, 0,
                     0, 1, 0,
                     0, 0, 1]
    
      extrinsicRPY: [1, 0, 0,
                     0, 1, 0,
                     0, 0, 1]
    
      # LOAM feature threshold
      edgeThreshold: 1.0
      surfThreshold: 0.1
      edgeFeatureMinValidNum: 10
      surfFeatureMinValidNum: 100
    
      # voxel filter paprams
      odometrySurfLeafSize: 0.4                     # default: 0.4 - outdoor, 0.2 - indoor
      mappingCornerLeafSize: 0.2                    # default: 0.2 - outdoor, 0.1 - indoor
      mappingSurfLeafSize: 0.4                      # default: 0.4 - outdoor, 0.2 - indoor
    
      # robot motion constraint (in case you are using a 2D robot)
      z_tollerance: 1000                            # meters
      rotation_tollerance: 1000                     # radians
    
      # CPU Params
      numberOfCores: 4                              # number of cores for mapping optimization
      mappingProcessInterval: 0.15                  # seconds, regulate mapping frequency
    
      # Surrounding map
      surroundingkeyframeAddingDistThreshold: 1.0   # meters, regulate keyframe adding threshold
      surroundingkeyframeAddingAngleThreshold: 0.2  # radians, regulate keyframe adding threshold
      surroundingKeyframeDensity: 2.0               # meters, downsample surrounding keyframe poses   
      surroundingKeyframeSearchRadius: 50.0         # meters, within n meters scan-to-map optimization (when loop closure disabled)
    
      # Loop closure
      loopClosureEnableFlag: true
      loopClosureFrequency: 1.0                     # Hz, regulate loop closure constraint add frequency
      surroundingKeyframeSize: 50                   # submap size (when loop closure enabled)
      historyKeyframeSearchRadius: 15.0             # meters, key frame that is within n meters from current pose will be considerd for loop closure
      historyKeyframeSearchTimeDiff: 30.0           # seconds, key frame that is n seconds older will be considered for loop closure
      historyKeyframeSearchNum: 25                  # number of hostory key frames will be fused into a submap for loop closure
      historyKeyframeFitnessScore: 0.3              # icp threshold, the smaller the better alignment
    
      # Visualization
      globalMapVisualizationSearchRadius: 1000.0    # meters, global map visualization radius
      globalMapVisualizationPoseDensity: 10.0       # meters, global map visualization keyframe density
      globalMapVisualizationLeafSize: 1.0           # meters, global map visualization cloud density
    
    
    
    
    # Navsat (convert GPS coordinates to Cartesian)
    navsat:
      frequency: 50
      wait_for_datum: false
      delay: 0.0
      magnetic_declination_radians: 0
      yaw_offset: 0
      zero_altitude: true
      broadcast_utm_transform: false
      broadcast_utm_transform_as_parent_frame: false
      publish_filtered_gps: false
    
    # EKF for Navsat
    ekf_gps:
      publish_tf: false
      map_frame: map
      odom_frame: odom
      base_link_frame: base_link
      world_frame: odom
    
      frequency: 50
      two_d_mode: false
      sensor_timeout: 0.01
      # -------------------------------------
      # External IMU:
      # -------------------------------------
      imu0: imu_correct
      # make sure the input is aligned with ROS REP105. "imu_correct" is manually transformed by myself. EKF can also transform the data using tf between your imu and base_link
      imu0_config: [false, false, false,
                    true,  true,  true,
                    false, false, false,
                    false, false, true,
                    true,  true,  true]
      imu0_differential: false
      imu0_queue_size: 50 
      imu0_remove_gravitational_acceleration: true
      # -------------------------------------
      # Odometry (From Navsat):
      # -------------------------------------
      odom0: odometry/gps
      odom0_config: [true,  true,  true,
                     false, false, false,
                     false, false, false,
                     false, false, false,
                     false, false, false]
      odom0_differential: false
      odom0_queue_size: 10
    
      #                            x     y     z     r     p     y   x_dot  y_dot  z_dot  r_dot p_dot y_dot x_ddot y_ddot z_ddot
      process_noise_covariance: [  1.0,  0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,    0,    0,      0,
                                   0,    1.0,  0,    0,    0,    0,    0,     0,     0,     0,    0,    0,    0,    0,      0,
                                   0,    0,    10.0, 0,    0,    0,    0,     0,     0,     0,    0,    0,    0,    0,      0,
                                   0,    0,    0,    0.03, 0,    0,    0,     0,     0,     0,    0,    0,    0,    0,      0,
                                   0,    0,    0,    0,    0.03, 0,    0,     0,     0,     0,    0,    0,    0,    0,      0,
                                   0,    0,    0,    0,    0,    0.1,  0,     0,     0,     0,    0,    0,    0,    0,      0,
                                   0,    0,    0,    0,    0,    0,    0.25,  0,     0,     0,    0,    0,    0,    0,      0,
                                   0,    0,    0,    0,    0,    0,    0,     0.25,  0,     0,    0,    0,    0,    0,      0,
                                   0,    0,    0,    0,    0,    0,    0,     0,     0.04,  0,    0,    0,    0,    0,      0,
                                   0,    0,    0,    0,    0,    0,    0,     0,     0,     0.01, 0,    0,    0,    0,      0,
                                   0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0.01, 0,    0,    0,      0,
                                   0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0.5,  0,    0,      0,
                                   0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,    0.01, 0,      0,
                                   0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,    0,    0.01,   0,
                                   0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,    0,    0,      0.015]
    
    

    A couple of things to note:

    • I have upgraded the firmware on both sensors, Ouster recently released version 2.0 (changelog available here), not sure if this is causing incompatibility issues with the current version of LIO-SAM.
    • One strange thing in the rosbag info output of the ros bag is that /imu/data frequency is stated as 33 kHz while I set it to 400 MHz inside the device settings manager!

    If anyone could give me some pointers, I'd be grateful.

    stale 
    opened by 0xLem0nade 21
  • "Large velocity, reset IMU-preintegration!"

    Hi @TixiaoShan, Thanks for sharing your excellent work.

    1. I am testing the lio-sam system but I got a warning for "Large velocity, reset IMU-preintegration!". And the trajectory result is very bad.

    lio-sam

    1. My IMU data is from INS570D and lidar data is from RS-LIDAR 16, the default coordinate of IMU is "x-forward, y-right, z-down" and the default coordinate of RS-LIDAR is "x-right, y-forward, z-up", i have changed both of them to "x-forward, y-left, z-up", but the result is still bad.

    imu修改 lidar修改

    As shown in the two figures, I modified the code for IMU and LIDAR to complete coordinate transformation.

    3.I used lidar_imu_calib to calib LIDAR and IMU. I did it in a small room, but when I put the extrinsicRot and extrinsicRPY into the yaml, the result did not change, still very bad.

    biaoding

    1. I don't know which part I did wrong. I hope someone can give me some advice,such as whether I need to calibrate IMU with IMU_utils?
    opened by heirenlop 18
  • Ouster OS1 IMU Filter 9-DOF

    Ouster OS1 IMU Filter 9-DOF

    I've been trying to make this work with a bag recorded from an Ouster OS1 by putting it through the imu_complementary_filter I managed to simulate a 9-DOF and get the LIO-SAM up and running but I'm still having some issues as indicated in the screenshot attached:

    Screenshot from 2020-09-12 23-58-09

    rviz_screenshot_2020_09_13-00_01_43 A closeup of TF frames.

    Here's a summary of what I did:

    • Added imu_complementary_filter to the module_navsat.launch and set it's output topic "imu/data" as the default imu topic everywhere in params.yaml .
    • Copied OS1's URDF definition from here inside config directory and set it as the "robot_description" inside module_robot_state_publisher.launch
    • Edited the files for Ouster as instructed in the repository's ReadMe.

    My params.yaml config: params.yaml.zip

    And here are the issues I'm having so far:

    1. The "base_link" jumps around like a rabbit as you saw in the screenshot!
    2. Terminal output is flooded by the following warnings:
    • Large velocity, reset IMU-preintegration!
    • Not enough features! Only X edge and X planar features available warnings.

    Here are some sample messages from the topics I thought were useful for debugging, if you need any other one's output let me know.

    ============= rostopic echo /imu/data
    ---
    header: 
      seq: 555
      stamp: 
        secs: 254
        nsecs: 425792160
      frame_id: "os1_imu"
    orientation: 
      x: 0.00163514830366
      y: 0.0127232187101
      z: -0.0541508667033
      w: 0.99845036413
    orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    angular_velocity: 
      x: -0.015845808486
      y: -0.00652474467069
      z: -0.0217047628841
    angular_velocity_covariance: [0.0006, 0.0, 0.0, 0.0, 0.0006, 0.0, 0.0, 0.0, 0.0006]
    linear_acceleration: 
      x: -0.471657727051
      y: -0.126892687988
      z: 10.4171714233
    linear_acceleration_covariance: [0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.01]
    ---
    header: 
      seq: 556
      stamp: 
        secs: 254
        nsecs: 435791780
      frame_id: "os1_imu"
    orientation: 
      x: 0.00157110857345
      y: 0.0127486267498
      z: -0.0542472996735
      w: 0.998444908151
    orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    angular_velocity: 
      x: -0.0119842249054
      y: -0.00958737992429
      z: -0.0194410759576
    angular_velocity_covariance: [0.0006, 0.0, 0.0, 0.0, 0.0006, 0.0, 0.0, 0.0, 0.0006]
    linear_acceleration: 
      x: -0.407014282227
      y: 0.00957680664062
      z: 10.314220752
    linear_acceleration_covariance: [0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.01]
    
    
    =============== rostopic echo /odometry/filtered
    header: 
      seq: 2727
      stamp: 
        secs: 282
        nsecs: 685791880
      frame_id: "odom"
    child_frame_id: "odom_imu"
    pose: 
      pose: 
        position: 
          x: 59.9538993835
          y: 155.108230591
          z: -316.268127441
        orientation: 
          x: -0.104433353511
          y: -0.0709931170876
          z: -0.987199786026
          w: 0.0974178344639
      covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    twist: 
      twist: 
        linear: 
          x: -17.1956308801
          y: -8.17372760457
          z: -9.09247474523
        angular: 
          x: 0.00922697018836
          y: -0.00576473529493
          z: 0.0199309978722
      covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    ---
    header: 
      seq: 2728
      stamp: 
        secs: 282
        nsecs: 695791820
      frame_id: "odom"
    child_frame_id: "odom_imu"
    pose: 
      pose: 
        position: 
          x: 59.7730751038
          y: 155.045776367
          z: -316.358398438
        orientation: 
          x: -0.104430462055
          y: -0.0711071328993
          z: -0.987180695484
          w: 0.0975311678855
      covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    twist: 
      twist: 
        linear: 
          x: -17.2124348969
          y: -8.19215127303
          z: -9.28984803679
        angular: 
          x: 0.0252059367288
          y: -0.000438413114768
          z: 0.0203304720357
      covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    ---
    
    =================== rostopic echo /diagnostics
    header: 
      seq: 22
      stamp: 
        secs: 1597567219
        nsecs: 348634297
      frame_id: ''
    status: 
      - 
        level: 1
        name: "ekf_gps: Filter diagnostic updater"
        message: "Potentially erroneous data or settings detected for a robot_localization state estimation\
      \ node."
        hardware_id: "none"
        values: 
          - 
            key: "imu0_pose_covariance"
            value: "The covariance at position (35), which corresponds to YAW variance, was zero. This\
      \ will be replaced with a small value to maintain filter stability, but should be\
      \ corrected at the message origin node."
      - 
        level: 0
        name: "ekf_gps: odometry/filtered topic status"
        message: ''
        hardware_id: "none"
        values: 
          - 
            key: "Events in window"
            value: "507"
          - 
            key: "Events since startup"
            value: "1062"
          - 
            key: "Duration of window (s)"
            value: "10.143589"
          - 
            key: "Actual frequency (Hz)"
            value: "49.982307"
          - 
            key: "Minimum acceptable frequency (Hz)"
            value: "43.200000"
          - 
            key: "Maximum acceptable frequency (Hz)"
            value: "57.200000"
    ---
    
    stale 
    opened by 0xLem0nade 18
  • with gps fator,  the map optimization node crashed  when encountering a big loop

    with gps fator, the map optimization node crashed when encountering a big loop

    Thanks for your hard work! I run LIO-SAM with my own dataset, the sensors are velodyne 16, steam 300 and F9P GPS.

    when the scene is very small(small loop) or the trajectory distance is very short, the LIO-SAM system runs well with GPS.

    But when encountering a big closed loop, the mapOptimization node died and the lio_sam_udi_imuPreintegration process restart.how can i solve this problem?

    I was confused by this problem for several weeks and it made me really frustrated. I would be grateful if anyone could help me

    I recorded a vedio : vedio

    image

    ERROR:

    Thrown when a linear system is ill-posed.  The most common cause for this
    error is having underconstrained variables.  Mathematically, the system is
    underdetermined.  See the GTSAM Doxygen documentation at
    http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
    more information.
    [lio_sam_udi_imuPreintegration-1] process has died [pid 4210, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
    log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
    [lio_sam_udi_imuPreintegration-1] restarting process
    process[lio_sam_udi_imuPreintegration-1]: started with pid [4240]
    [ INFO] [1640275367.369310875]: ----> IMU Preintegration Started.
    system initialization. 
    currlidar pose: 17.2032814025879, -30.5312538146973, -48.5863075256348
    currGPS position: 13.8068151473999, 7.92838048934937, 5.14798021316528
    currGPS cov: 11.0224, 11.0224, 176.3584
    terminate called after throwing an instance of 'gtsam::IndeterminantLinearSystemException'
      what():  
    Indeterminant linear system detected while working near variable
    7061644215716937728 (Symbol: b0).
    
    Thrown when a linear system is ill-posed.  The most common cause for this
    error is having underconstrained variables.  Mathematically, the system is
    underdetermined.  See the GTSAM Doxygen documentation at
    http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
    more information.
    [lio_sam_udi_imuPreintegration-1] process has died [pid 4240, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
    log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
    [lio_sam_udi_imuPreintegration-1] restarting process
    process[lio_sam_udi_imuPreintegration-1]: started with pid [4268]
    [ INFO] [1640275367.905634176]: ----> IMU Preintegration Started.
    currlidar pose: 16.9986457824707, -29.6455020904541, -48.5315475463867
    currGPS position: 13.9584197998047, 8.71054935455322, 4.71397876739502
    currGPS cov: 11.0224, 11.0224, 176.3584
    system initialization. 
    terminate called after throwing an instance of 'gtsam::IndeterminantLinearSystemException'
      what():  
    Indeterminant linear system detected while working near variable
    7061644215716937728 (Symbol: b0).
    
    Thrown when a linear system is ill-posed.  The most common cause for this
    error is having underconstrained variables.  Mathematically, the system is
    underdetermined.  See the GTSAM Doxygen documentation at
    http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
    more information.
    [lio_sam_udi_imuPreintegration-1] process has died [pid 4268, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
    log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
    [lio_sam_udi_imuPreintegration-1] restarting process
    process[lio_sam_udi_imuPreintegration-1]: started with pid [4310]
    [ INFO] [1640275368.605006835]: ----> IMU Preintegration Started.
    system initialization. 
    currlidar pose: 16.4861240386963, -28.6083831787109, -48.5112152099609
    currGPS position: 13.9197864532471, 9.7651309967041, 4.2459774017334
    currGPS cov: 11.0224, 11.0224, 176.3584
    terminate called after throwing an instance of 'gtsam::IndeterminantLinearSystemException'
      what():  
    Indeterminant linear system detected while working near variable
    7061644215716937728 (Symbol: b0).
    
    Thrown when a linear system is ill-posed.  The most common cause for this
    error is having underconstrained variables.  Mathematically, the system is
    underdetermined.  See the GTSAM Doxygen documentation at
    http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
    more information.
    [lio_sam_udi_imuPreintegration-1] process has died [pid 4310, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
    log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
    
    stale 
    opened by JokerJohn 17
  • IMU to LiDAR transform bug

    IMU to LiDAR transform bug

    Hi @TixiaoShan, I think I have found a bug in the transformation from IMU frame to LiDAR frame. From what I have seen, LIO-SAM uses the IMU data in the following way:

    1. Rotate IMU data into LiDAR frame
    2. Integrate IMU data

    However, this does not account for IMU acceleration that is tangential to the LiDAR->IMU lever arm. This error is proportional to the the extrinsic translation between LiDAR and IMU (a.k.a. the lever arm) and the rotation speed of the LiDAR (not the RPM).

    If we look at the following image showing a simplified 2D representation of the LiDAR+IMU at time 0 and time 1 we can see that the linear acceleration of the LiDAR and the integrated IMU data do not match If we follow the same process as LIO-SAM:

    1. Rotate the IMU frame around its own origin so that its frame matches the orientation of the LiDAR frame
    2. Integrate the new acceleration vector. We start at 0 velocity and have a time difference of 1s, giving us [6, -2] in the rotated IMU frame. However, it should be [4, 0] in the LiDAR frame

    This would be particularly bad if you had pure rotation around the LiDAR origin, because the IMU data would say that there is translation occurring even though the LiDAR is stationary in xyz

    I tried to implement a fix but I wasn't able to just yet, so I am reporting the issue, in case you or someone else can do it faster than me.

    stale 
    opened by HMellor 17
  • ImuPreintegration and ImageProjection crashing and restarting

    ImuPreintegration and ImageProjection crashing and restarting

    Hi, I've been trying to make this work with a Bosch BNO055 chip until now, but recently I managed to get a Microstrain 3DM-GX5-25, like @TixiaoShan is using, but after switching to it and changing the topics around, I've noticed I started getting a lot more errors and crashes of my system with output similar to this:

    terminate called after throwing an instance of 'std::runtime_error' what(): PreintegratedImuMeasurements::integrateMeasurement: dt <=0 [lio_sam_imuPreintegration-1] process has died [pid 574, exit code -6, cmd /home/gl/catkin_ws/devel/lib/lio_sam/lio_sam_imuPreintegration __name:=lio_sam_imuPreintegration __log:=/home/gl/.ros/log/1415f1e0-bd6d-11eb-b877-64bc5855aa9b/lio_sam_imuPreintegration-1.log]. log file: /home/gl/.ros/log/1415f1e0-bd6d-11eb-b877-64bc5855aa9b/lio_sam_imuPreintegration-1*.log [lio_sam_imuPreintegration-1] restarting process process[lio_sam_imuPreintegration-1]: started with pid [691] [ INFO] [1621956396.629035437]: ----> IMU Preintegration Started. terminate called after throwing an instance of 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injectorboost::lock_error >' what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument [lio_sam_imageProjection-2] process has died [pid 575, exit code -6, cmd /home/gl/catkin_ws/devel/lib/lio_sam/lio_sam_imageProjection __name:=lio_sam_imageProjection __log:=/home/gl/.ros/log/1415f1e0-bd6d-11eb-b877-64bc5855aa9b/lio_sam_imageProjection-2.log]. log file: /home/gl/.ros/log/1415f1e0-bd6d-11eb-b877-64bc5855aa9b/lio_sam_imageProjection-2*.log [lio_sam_imageProjection-2] restarting process process[lio_sam_imageProjection-2]: started with pid [717] [ INFO] [1621956403.494835027]: ----> Image Projection Started.

    I am using an Ouster OS1-128 lidar, does anyone have any suggestions how to fix these errors? thanks

    stale 
    opened by Jaetriel 16
  • Having issues with my own data.

    Having issues with my own data.

    This is not a error in the code its a lack of understanding by me. I did not know where else to post this so please forgive if I did in the wrong place. I am new to ROS and Linux. So please bear with me. Setup is: Jetson AGX, Ubuntu 18, ROS Melodic. Velodyne VLP-16 with Garmin antenna and a XSENS MTI-7 Development Kit 9 axis IMU with GPS and antenna. I installed LIO_SAM and can read and play back your sample bag files. I can see data from my Velodyne VLP-16 in rviz using" roslaunch velodyne_pointcloud VLP16_points.launch calibration:=/home/lbackpack/Downloads/VLP-16.yaml" and Then I launch LIO_SAM: roslaunch lio_sam run.launch If I select Fixed frame in rviz as velodyne and under point cloud select /velodyne_points as the topic I can see the point cloud live. I obviously am doing something wrong but searching for more than a week I cannot figure out the proper way to set this up. My IMU data is showing up in the sample code that comes with the MTi IMU. Its topic is imu_link. I think I need to edit the params.yaml file Topics section to the topic names velodyne_points and imu_link but it did not change anything. Could you offer some suggestions or links to where I can learn more about setting this up to work with LIO_SAM.

    thanks for your time and software

    stale 
    opened by Rotoslider 16
  • the map will be bad when the car turning

    the map will be bad when the car turning

    The imu data is in ENU(x-forword y-left z-up), so the two matrices are identity matrix. Once my car makes a turnning, the map will be overlap or flying. lidar: velodyne-16 IMU: UM7 why?

    A396ACAE67B26A1EEB7ECA6170C9993A @TixiaoShan

    stale 
    opened by llxClover 15
  • "Large velocity, reset IMU-preintegration!"

    I tried to run this algorithm with livox mid70 lidar. The error "Large velocity, reset IMU preintegration!" appeared, and the trajectory could be seen flying in rviz. The parameters related to the lidar are set according to the Livox Horizon lidar in README.md. The livox_ros_driver used is also the version that can publish the correct message type after the author modifying it. The imu I used is ibc-nav40. This imu will not make mistakes when running the lio-sam with the velodyne vlp16 lidar. Therefore, I guess it is a problem that the mid70 solid-state laser radar is not supported. I want to ask the author and everyone for help, is there a way to solve this problem by modifying the parameter file or part of the code

    opened by wwdlh 0
  • Question; How to replay ouster .bag file and capture it via LIO-SAM the model?

    Question; How to replay ouster .bag file and capture it via LIO-SAM the model?

    I am a NOOBE with the ROS/ouster platform, so forgive me if I ask questions which probably were asked before in one way or another.

    • I am trying to generate a global 3d model using LIO-SAM package (I've succeeded doing that using the package, then used "rosbag play" command when the rviz with the LIO-SAM pointcloud sample datasets).
    • I've succeeded using the ouster-ros package to play the ouster .bag - and visualize the data. (that was done using the ouster-ros package and not the "rosbag" command).

    What is the best practice here to follow inorder to use "rosbag play {an ouster bag file}" as pointcloud visualization (like the package ouster-ros does) and capture the model using the LIO-SAM package, Using the ouster .bag files supplied on ouster sample datasets?

    on the README.md there were some guide lines to follow in order to prepare ouster hardware, and software. Do I need to modify in a way the ouster .bag files, in order for such process to take place?

    opened by nighthawk2032 0
  • Questions about export each frame point cloud

    Questions about export each frame point cloud

    Your project is great!

    I'm new to slam and point cloud processing, and I'm also new to C++. In my project, I am using point clouds from KITTI Raw data, and after SLAM, I need to do other processing on the point clouds for each frame.

    I have successfully exported the whole map .pcd file and by modifying the code I have exported the key frame pcd. but as I said I need the point cloud of all the frames and at the moment I am stuck here, if you can help me or give me some advice I would appreciate it!

    For example, in the 2011_09_26_drive_0084 data I'm currently using, the original point cloud has 383 frames, but the exported keyframes only have 142 frames.

    opened by ooooohhhhhxxx 4
  • so how to know RPY  axis with the 9 dof imu?

    so how to know RPY axis with the 9 dof imu?

    https://github.com/TixiaoShan/LIO-SAM/issues/108

    i have seen this comment in this github issue, as i am using the 9 Dof imu which is equipped with the acceleometer, gyroscope, magnetometer, how can i know the roll pitch yaw axis?

    opened by himhan34 0
  • About the groundtruth of datasets

    About the groundtruth of datasets

    First, thank you very much for the excellent work! i am testing related algorithms on the datasets as you mentioned, such as: Walking dataset Park dataset Garden dataset But, i check the relative issues, the topic published by park.bag and the Google Drive sharing, did not find any groundtruth information. The groundtruth of datasets is important for quantitative analysis, could you provide some information about your datasets? Thank you again for your work! Thanks for any help!

    opened by MoonSheepJx 0
  • Questions about degradation in mapOptimization.cp →LMOptimization

    Questions about degradation in mapOptimization.cp →LMOptimization

    First of all, thank you very much for your great work. The isDegenerate is only calculated in the first iteration. If the isDegenerate is true in the first iteration, but in subsequent iterations, it may be false; And matP is only calculated once. Is that reasonable? As the iteration continues, A will change → V will change → matP will change; So matP needs to be calculated each time when isDegenerate is true.

    opened by michaelqiuyu 0
Owner
Tixiao Shan
Tixiao Shan
SSL_SLAM2: Lightweight 3-D Localization and Mapping for Solid-State LiDAR (mapping and localization separated) ICRA 2021

SSL_SLAM2 Lightweight 3-D Localization and Mapping for Solid-State LiDAR (Intel Realsense L515 as an example) This repo is an extension work of SSL_SL

Wang Han 王晗 337 Dec 27, 2022
RP-VIO: Robust Plane-based Visual-Inertial Odometry for Dynamic Environments (Code & Dataset)

RP-VIO: Robust Plane-based Visual-Inertial Odometry for Dynamic Environments RP-VIO is a monocular visual-inertial odometry (VIO) system that uses onl

Karnik Ram 167 Jan 6, 2023
A Modular Framework for LiDAR-based Lifelong Mapping

LT-mapper News July 2021 A preprint manuscript is available (download the preprint). LT-SLAM module is released.

Giseop Kim 300 Dec 30, 2022
This robot lcoalisation package for lidar-map based localisation using multi-sensor state estimation.

A ROS-based NDT localizer with multi-sensor state estimation This repo is a ROS based multi-sensor robot localisation. An NDT localizer is loosely-cou

null 49 Dec 15, 2022
Scalable, Portable and Distributed Gradient Boosting (GBDT, GBRT or GBM) Library, for Python, R, Java, Scala, C++ and more. Runs on single machine, Hadoop, Spark, Dask, Flink and DataFlow

eXtreme Gradient Boosting Community | Documentation | Resources | Contributors | Release Notes XGBoost is an optimized distributed gradient boosting l

Distributed (Deep) Machine Learning Community 23.6k Dec 30, 2022
Distributed (Deep) Machine Learning Community 682 Dec 28, 2022
A toolkit for making real world machine learning and data analysis applications in C++

dlib C++ library Dlib is a modern C++ toolkit containing machine learning algorithms and tools for creating complex software in C++ to solve real worl

Davis E. King 11.6k Dec 31, 2022
A lightweight C++ machine learning library for embedded electronics and robotics.

Fido Fido is an lightweight, highly modular C++ machine learning library for embedded electronics and robotics. Fido is especially suited for robotic

The Fido Project 413 Dec 17, 2022
A RGB-D SLAM system for structural scenes, which makes use of point-line-plane features and the Manhattan World assumption.

This repo proposes a RGB-D SLAM system specifically designed for structured environments and aimed at improved tracking and mapping accuracy by relying on geometric features that are extracted from the surrounding.

Yanyan Li 269 Jan 2, 2023
MITIE: library and tools for information extraction

MITIE: MIT Information Extraction This project provides free (even for commercial use) state-of-the-art information extraction tools. The current rele

null 2.8k Dec 29, 2022
Yggdrasil Decision Forests (YDF) is a collection of state-of-the-art algorithms for the training, serving and interpretation of Decision Forest models.

Yggdrasil Decision Forests (YDF) is a collection of state-of-the-art algorithms for the training, serving and interpretation of Decision Forest models. The library is developed in C++ and available in C++, CLI (command-line-interface, i.e. shell commands) and in TensorFlow under the name TensorFlow Decision Forests (TF-DF).

Google 268 Jan 9, 2023
MATLAB and C++ implementations of sideslip angle estimators

sideslip-angle-vehicle-estimation MATLAB and C++ implementations of sideslip angle estimators Factor graph sideslip angle estimator Papers: "A Factor

Libraries for Multibody Dynamics Simulation (MBDS) 10 Oct 15, 2022
LVI-SAM: Tightly-coupled Lidar-Visual-Inertial Odometry via Smoothing and Mapping

LVI-SAM This repository contains code for a lidar-visual-inertial odometry and mapping system, which combines the advantages of LIO-SAM and Vins-Mono

Tixiao Shan 1.1k Jan 8, 2023
IA-LIO-SAM is enhanced LIO-SAM using Intensity and Ambient channel from OUSTER LiDAR.

IA-LIO-SAM Construction monitoring is one of the key modules in smart construction. Unlike structured urban environment, construction site mapping is

Kevin Jung 82 Dec 13, 2022
R3live - A Robust, Real-time, RGB-colored, LiDAR-Inertial-Visual tightly-coupled state Estimation and mapping package

R3LIVE A Robust, Real-time, RGB-colored, LiDAR-Inertial-Visual tightly-coupled state Estimation and mapping package News [Dec 31, 2021] Release of cod

HKU-Mars-Lab 1.3k Jan 4, 2023
A real-time, direct and tightly-coupled LiDAR-Inertial SLAM for high velocities with spinning LiDARs

LIMO-Velo [Alpha] ?? [16 February 2022] ?? The project is on alpha stage, so be sure to open Issues and Discussions and give all the feedback you can!

Andreu Huguet 150 Dec 28, 2022
R2LIVE is a robust, real-time tightly-coupled multi-sensor fusion framework, which fuses the measurement from the LiDAR, inertial sensor, visual camera to achieve robust, accurate state estimation.

R2LIVE is a robust, real-time tightly-coupled multi-sensor fusion framework, which fuses the measurement from the LiDAR, inertial sensor, visual camera to achieve robust, accurate state estimation.

HKU-Mars-Lab 602 Jan 5, 2023
Livox-Mapping - An all-in-one and ready-to-use LiDAR-inertial odometry system for Livox LiDAR

Livox-Mapping This repository implements an all-in-one and ready-to-use LiDAR-inertial odometry system for Livox LiDAR. The system is developed based

null 257 Dec 27, 2022
A Multi-sensor Fusion Odometry via Smoothing and Mapping.

LVIO-SAM A multi-sensor fusion odometry, LVIO-SAM, which fuses LiDAR, stereo camera and inertial measurement unit (IMU) via smoothing and mapping. The

Xinliang Zhong 152 Dec 24, 2022