Code Monkey home page Code Monkey logo

dliom's Introduction

DLIOM

这份代码是基于direct_lidar_inertial_odometry,对论文Direct LiDAR-Inertial Odometry and Mapping: Perceptive and Connective SLAM的早期复现改进版本。

代码功能正在持续完善中,当前仍然存在较多bug,仍在努力测试修改


图1 : UrbanLoco dataset Dataset 5: HK-Data20190117测试效果


图2: 闭环前后的轨迹对比


图3: 基于3D Jaccard的submap构建

依赖

  • Ubuntu 20.04
  • ROS Noetic (roscpp, std_msgs, sensor_msgs, geometry_msgs, nav_msgs, pcl_ros)
  • C++ 14
  • CMake >= 3.12.4
  • OpenMP >= 4.5
  • Point Cloud Library >= 1.10.0
  • Eigen >= 3.3.7
  • GTSAM >= 4.0.2
sudo apt install libomp-dev libpcl-dev libeigen3-dev

编译

mkdir ws && cd ws && mkdir src && cd src
git clone https://github.com/YWL0720/DLIOM.git
cd ..
catkin_make

已经实现的功能

  • 基于GTSAM的后端
  • 基于3D Jaccard的子地图构建
  • 基于欧氏距离的回环检测

待实现的功能

  • 重力因子

更新日志:

  • 7.11 单独线程用于更新地图,解决回环后崩溃的问题
  • 7.12 更改了一些用于回环的参数
  • 7.13 修正了ulhk数据集重力的影响
  • 7.13 完成了回环后位姿在submap中的更新
  • 7.13 更新了readme
  • 7.14 更新了gtsam::pose3的旋转构造方式 此前的转换存在问题
  • 7.14 添加了对newer college数据集的测试 增加了保存回环后关键帧位姿的接口
  • 7.17 增加了utbm接口
  • 7.18 修正了fitness的bug
  • 8.1 增加GeographicLib的GPS预处理接口
  • 8.2 完成GPS回调 UTM与Lidar系的初始化对齐
  • 8.3 添加了GPS因子
  • 8.4 增加了一种引入GPS因子的方式 待测试
  • 8.11 添加了GNSS与Lidar外参增量式更新的方法

TODO:

  • IMU因子
  • 优化submap部分和地图更新部分的代码
  • 对部分环节进行加速
  • 精简可视化部分

参考

@misc{chen2023direct,
      title={Direct LiDAR-Inertial Odometry and Mapping: Perceptive and Connective SLAM}, 
      author={Kenny Chen and Ryan Nemiroff and Brett T. Lopez},
      year={2023},
      eprint={2305.01843},
      archivePrefix={arXiv},
      primaryClass={cs.RO}
}
@article{chen2022dlio,
  title={Direct LiDAR-Inertial Odometry: Lightweight LIO with Continuous-Time Motion Correction},
  author={Chen, Kenny and Nemiroff, Ryan and Lopez, Brett T},
  journal={2023 IEEE International Conference on Robotics and Automation (ICRA)},
  year={2023},
  pages={3983-3989},
  doi={10.1109/ICRA48891.2023.10160508}
}

dliom's People

Contributors

ywl0720 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar

dliom's Issues

启动命令问题

你好,我使用您的代码进行复现,但是我不知道要怎么进行数据集的使用,我launch文件是使用dlio.launch文件启动,我的数据集的节点是livox/lidar,livox/imu,我将launch文件进行修改并且运行代码也是按照dlio的格式写的,但是启动报错,请问是为什么?我启动的方式是不是有问题。正确的代码应该是什么

我的运行代码:
roslaunch direct_lidar_inertial_odometry dlio.launch pointcloud_topic:=/livox/lidar imu_topic:=/livox/imu

我的报错:
/home/hjy/dliom_ws/devel/lib/direct_lidar_inertial_odometry/dlio_odom_node: error while loading shared libraries: libmetis-gtsam.so: cannot open shared object file: No such file or directory
process[robot/dlio_map-3]: started with pid [17503]
/home/hjy/dliom_ws/devel/lib/direct_lidar_inertial_odometry/dlio_map_node: error while loading shared libraries: libmetis-gtsam.so: cannot open shared object file: No such file or directory
process[dlio_rviz-4]: started with pid [17504]
[robot/dlio_odom-2] process has died [pid 17502, exit code 127, cmd /home/hjy/dliom_ws/devel/lib/direct_lidar_inertial_odometry/dlio_odom_node ~pointcloud:=/livox/lidar ~imu:=/livox/imu ~odom:=dlio/odom_node/odom ~pose:=dlio/odom_node/pose ~path:=path ~kf_pose:=dlio/odom_node/keyframes ~kf_cloud:=dlio/odom_node/pointcloud/keyframe ~deskewed:=dlio/odom_node/pointcloud/deskewed __name:=dlio_odom __log:=/home/hjy/.ros/log/1a523bb0-4995-11ef-a0ef-0242ac110003/robot-dlio_odom-2.log].
log file: /home/hjy/.ros/log/1a523bb0-4995-11ef-a0ef-0242ac110003/robot-dlio_odom-2*.log
[robot/dlio_map-3] process has died [pid 17503, exit code 127, cmd /home/hjy/dliom_ws/devel/lib/direct_lidar_inertial_odometry/dlio_map_node ~keyframes:=dlio/odom_node/pointcloud/keyframe ~map:=dlio/map_node/map __name:=dlio_map __log:=/home/hjy/.ros/log/1a523bb0-4995-11ef-a0ef-0242ac110003/robot-dlio_map-3.log].
log file: /home/hjy/.ros/log/1a523bb0-4995-11ef-a0ef-0242ac110003/robot-dlio_map-3*.log

疑问:keyframes 中的点云是否也需要在全局优化后进行矫正

keyframes中的pose 每次全局优化后会进行矫正,而cloud从未矫正过。也就是说这些cloud各自在不同的坐标系下(它们经历过不同次数的后端优化,也就是产生该keyframe时里程计被矫正过的次数,有的可能在没有经过任何后端优化时的坐标系,有的可能处在经过若干次后端优化的坐标系)。然而代码中的构建jaccard submap时 使用这些实际上处于不同坐标系的点云进行knn计算相似度。

Process has died error (exit code -11)

Hi, really appreciate this work. I'm getting the following error as soon as the IMU calibration completes:

+-------------------------------------------------------------------+
| Direct LiDAR-Inertial Odometry and Mapping v1.0 |
+-------------------------------------------------------------------+

Calibrating IMU for 3 seconds... done

Accel biases [xyz]: 0.31946748, -0.10318823, -19.60602570
Gyro biases [xyz]: 0.00086732, 0.00014013, -0.00075244

DLIO initialized!
[robot/dlio_odom-2] process has died [pid 20903, exit code -11, cmd /home/bil/ws/devel/lib/direct_lidar_inertial_odometry/dlio_odom_node ~pointcloud:=/robosense/helios/right ~imu:=/sbg/imu_data ~gps:=/sbg/ekf_nav_fix ~odom:=robot/odom ~pose:=robot/pose ~path:=path ~kf_pose:=robot/kf_pose ~kf_cloud:=robot/kf_cloud ~deskewed:=robot/deskewed ~kf_connect:=robot/kf_connect ~loop_constraint:=robot/loop_constraint ~global_map:=robot/global_map ~global_odom:=robot/global_odom ~odom_gps:=robot/odom_gps __name:=dlio_odom __log:=/home/bil/.ros/log/2a02dbca-5645-11ef-b970-a733887e9e32/robot-dlio_odom-2.log].
log file: /home/bil/.ros/log/2a02dbca-5645-11ef-b970-a733887e9e32/robot-dlio_odom-2*.log

Sadly, there are no informative logs.

Do you know a possible solution to this? Thank you!

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.