Git Product home page Git Product logo

lego-loam's Introduction

LeGO-LOAM

This repository contains code for a lightweight and ground optimized lidar odometry and mapping (LeGO-LOAM) system for ROS compatible UGVs. The system takes in point cloud from a Velodyne VLP-16 Lidar (palced horizontally) and optional IMU data as inputs. It outputs 6D pose estimation in real-time. A demonstration of the system can be found here -> https://www.youtube.com/watch?v=O3tz_ftHV48

drawing

Lidar-inertial Odometry

An updated lidar-initial odometry package, LIO-SAM, has been open-sourced and available for testing.

Dependency

  • ROS (tested with indigo, kinetic, and melodic)
  • gtsam (Georgia Tech Smoothing and Mapping library, 4.0.0-alpha2)
    wget -O ~/Downloads/gtsam.zip https://github.com/borglab/gtsam/archive/4.0.0-alpha2.zip
    cd ~/Downloads/ && unzip gtsam.zip -d ~/Downloads/
    cd ~/Downloads/gtsam-4.0.0-alpha2/
    mkdir build && cd build
    cmake ..
    sudo make install
    

Compile

You can use the following commands to download and compile the package.

cd ~/catkin_ws/src
git clone https://github.com/RobustFieldAutonomyLab/LeGO-LOAM.git
cd ..
catkin_make -j1

When you compile the code for the first time, you need to add "-j1" behind "catkin_make" for generating some message types. "-j1" is not needed for future compiling.

The system

LeGO-LOAM is speficifally optimized for a horizontally placed VLP-16 on a ground vehicle. It assumes there is always a ground plane in the scan. The UGV we are using is Clearpath Jackal. It has a built-in IMU.

drawing

The package performs segmentation before feature extraction.

drawing

Lidar odometry performs two-step Levenberg Marquardt optimization to get 6D transformation.

drawing

New Lidar

The key thing to adapt the code to a new sensor is making sure the point cloud can be properly projected to an range image and ground can be correctly detected. For example, VLP-16 has a angular resolution of 0.2° and 2° along two directions. It has 16 beams. The angle of the bottom beam is -15°. Thus, the parameters in "utility.h" are listed as below. When you implement new sensor, make sure that the ground_cloud has enough points for matching. Before you post any issues, please read this.

extern const int N_SCAN = 16;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 15.0;
extern const int groundScanInd = 7;

Another example for Velodyne HDL-32e range image projection:

extern const int N_SCAN = 32;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 360.0/Horizon_SCAN;
extern const float ang_res_y = 41.333/float(N_Scan-1);
extern const float ang_bottom = 30.666666;
extern const int groundScanInd = 20;

New: a new useCloudRing flag has been added to help with point cloud projection (i.e., VLP-32C, VLS-128). Velodyne point cloud has "ring" channel that directly gives the point row id in a range image. Other lidars may have a same type of channel, i.e., "r" in Ouster. If you are using a non-Velodyne lidar but it has a similar "ring" channel, you can change the PointXYZIR definition in utility.h and the corresponding code in imageProjection.cpp.

For KITTI users, if you want to use our algorithm with HDL-64e, you need to write your own implementation for such projection. If the point cloud is not projected properly, you will lose many points and performance.

If you are using your lidar with an IMU, make sure your IMU is aligned properly with the lidar. The algorithm uses IMU data to correct the point cloud distortion that is cause by sensor motion. If the IMU is not aligned properly, the usage of IMU data will deteriorate the result. Ouster lidar IMU is not supported in the package as LeGO-LOAM needs a 9-DOF IMU.

Run the package

  1. Run the launch file:
roslaunch lego_loam run.launch

Notes: The parameter "/use_sim_time" is set to "true" for simulation, "false" to real robot usage.

  1. Play existing bag files:
rosbag play *.bag --clock --topic /velodyne_points /imu/data

Notes: Though /imu/data is optinal, it can improve estimation accuracy greatly if provided. Some sample bags can be downloaded from here.

New data-set

This dataset, Stevens data-set, is captured using a Velodyne VLP-16, which is mounted on an UGV - Clearpath Jackal, on Stevens Institute of Technology campus. The VLP-16 rotation rate is set to 10Hz. This data-set features over 20K scans and many loop-closures.

drawing

drawing

Cite LeGO-LOAM

Thank you for citing our LeGO-LOAM paper if you use any of this code:

@inproceedings{legoloam2018,
  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}
}

Loop Closure

The loop-closure method implemented in this package is a naive ICP-based method. It often fails when the odometry drift is too large. For more advanced loop-closure methods, there is a package called SC-LeGO-LOAM, which features utilizing point cloud descriptor.

Speed Optimization

An optimized version of LeGO-LOAM can be found here. All credits go to @facontidavide. Improvements in this directory include but not limited to:

+ To improve the quality of the code, making it more readable, consistent and easier to understand and modify.
+ To remove hard-coded values and use proper configuration files to describe the hardware.
+ To improve performance, in terms of amount of CPU used to calculate the same result.
+ To convert a multi-process application into a single-process / multi-threading one; this makes the algorithm more deterministic and slightly faster.
+ To make it easier and faster to work with rosbags: processing a rosbag should be done at maximum speed allowed by the CPU and in a deterministic way.
+ As a consequence of the previous point, creating unit and regression tests will be easier.

lego-loam's People

Contributors

eddy-w avatar tixiaoshan avatar vwvw 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  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  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  avatar

lego-loam's Issues

About Kitti Experiment

Hi! congratulations for your great work.

I was curious about the performance of the algorithm in Kitti. Apart from the speed over the Jetson, do you know how the performance would be affected if we use the full HDL64 pointcloud?

I would love to do some more experiments over this dataset with the full pointcloud (as if real-time would not be a requirement). Maybe you could comment the parameters configuration that you use on the Kitti benchmark, and even share the results you obtained with your downsampled pointclouds?

Thank you very much in advance.

Best

VLP-32C changes

What would need to be changed to have it work on a 32 layer puck? const int N_SCAN = 32, i assume in utility.h, but what else? currently it's not working at all

Odometry output

Hi Tixiao

Thanks for sharing this work,
I have a question regarding the odometry. Which topic should I subscribe to, in order to get the correct odometry? the topic /aft_mapped_to_init seems correct but the problem is I cannot filter this message as the time stamp is not synced to /scan topic which I obtain using pointcloud_to_laserscan package. The other odometry messages (/laser_odom_to_init and /integrated_to_init) are well aligned with this.
Seems like the publishing rate of topic /aft_mapped_to_init is slower (1.449Hz) as compared to /laser_odom_to_init (2.9Hz)
Any suggestion?

scan_sub = message_filters.Subscriber("/scan", LaserScan) odom_sub = message_filters.Subscriber("/aft_mapped_to_init", Odometry) ts = message_filters.TimeSynchronizer([scan_sub,odom_sub],10) ts.registerCallback(callback_rx_data)

Best Regards
Myron

How do I test LeGO-LOAM with rosbag

Hi ,
I tried to use LeGO-LOAM with my rosbag with Velodyne-16 data, but I cant visualize it on rviz neither the topics are being published.
Any clue about this?
Thanks,
Bruno

problem with rviz?

hi, I am really sorry to bother you. However, i happen to a weird problem. When I try to roslaunch the run.launch(your provided ) and the bag (your provided), the rviz will crash. The error messages are listed as following: I am using ubuntu 16.04 with ros kinect version

rviz: /build/ogre-1.9-mqY1wq/ogre-1.9-1.9.0+dfsg1/OgreMain/src/OgreNode.cpp:405: virtual void Ogre::Node::setPosition(const Ogre::Vector3&): Assertion !pos.isNaN() && "Invalid vector supplied as parameter"' failed.
[rviz-2] process has died [pid 26222, exit code -6, cmd /opt/ros/kinetic/lib/rviz/rviz -d /home/machozhao/zhao_ws/src/LeGO-LOAM/LeGO-LOAM/launch/test.rviz __name:=rviz __log:=/home/machozhao/.ros/log/f88fc50a-a5bd-11e8-9edc-70f11c0dd839/rviz-2.log].
log file: /home/machozhao/.ros/log/f88fc50a-a5bd-11e8-9edc-70f11c0dd839/rviz-2*.log

rviz: /build/ogre-1.9-mqY1wq/ogre-1.9-1.9.0+dfsg1/OgreMain/include/OgreAxisAlignedBox.h:252: void Ogre::AxisAlignedBox::setExtents(const Ogre::Vector3&, const Ogre::Vector3&): Assertion (min.x <= max.x && min.y <= max.y && min.z <= max.z) && "The minimum corner of the box must be less than or equal to maximum corner"' failed. [rviz-2] process has died [pid 25433, exit code -6, cmd /opt/ros/kinetic/lib/rviz/rviz -d /home/machozhao/zhao_ws/src/LeGO-LOAM/LeGO-LOAM/launch/test2.rviz __name:=rviz __log:=/home/machozhao/.ros/log/8be59486-a5bb-11e8-9edc-70f11c0dd839/rviz-2.log]. log file: /home/machozhao/.ros/log/8be59486-a5bb-11e8-9edc-70f11c0dd839/rviz-2*.log

I guess the test.rviz may have some problems, so I use my configured rviz file. Unfortunately, the rviz also crashes. The most weird thing is that there will be fine if i run other ros packages with rviz file. Can you give me some suggestions?

related problems:ros-visualization/rviz#808
useful information:https://forums.ogre3d.org/viewtopic.php?t=70549

catkin_make error on ubuntu 16.04 + ROS kinetic

I try to make this package and get the following error:

[ 66%] Building CXX object LeGO-LOAM/LeGO-LOAM/CMakeFiles/mapOptmization.dir/src/mapOptmization.cpp.o
In file included from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:36:0:
/usr/local/include/gtsam/geometry/Rot3.h: In static member function ‘static gtsam::Rot3 gtsam::Rot3::rodriguez(double, double, double)’:
/usr/local/include/gtsam/geometry/Rot3.h:197:51: error: no matching function for call to ‘gtsam::Rot3::rodriguez(Eigen::CommaInitializer<Eigen::Matrix<double, -1, 1> >&)’
{ return rodriguez((Vector(3) << wx, wy, wz));}
^
/usr/local/include/gtsam/geometry/Rot3.h:164:17: note: candidate: static gtsam::Rot3 gtsam::Rot3::rodriguez(const Vector&, double)
static Rot3 rodriguez(const Vector& w, double theta);
^
/usr/local/include/gtsam/geometry/Rot3.h:164:17: note: candidate expects 2 arguments, 1 provided
/usr/local/include/gtsam/geometry/Rot3.h:172:17: note: candidate: static gtsam::Rot3 gtsam::Rot3::rodriguez(const gtsam::Point3&, double)
static Rot3 rodriguez(const Point3& w, double theta);
^
/usr/local/include/gtsam/geometry/Rot3.h:172:17: note: candidate expects 2 arguments, 1 provided
/usr/local/include/gtsam/geometry/Rot3.h:180:17: note: candidate: static gtsam::Rot3 gtsam::Rot3::rodriguez(const gtsam::Unit3&, double)
static Rot3 rodriguez(const Unit3& w, double theta);
^
/usr/local/include/gtsam/geometry/Rot3.h:180:17: note: candidate expects 2 arguments, 1 provided
/usr/local/include/gtsam/geometry/Rot3.h:187:17: note: candidate: static gtsam::Rot3 gtsam::Rot3::rodriguez(const Vector&)
static Rot3 rodriguez(const Vector& v);
^
/usr/local/include/gtsam/geometry/Rot3.h:187:17: note: no known conversion for argument 1 from ‘Eigen::CommaInitializer<Eigen::Matrix<double, -1, 1> >’ to ‘const Vector& {aka const Eigen::Matrix<double, -1, 1>&}’
/usr/local/include/gtsam/geometry/Rot3.h:196:17: note: candidate: static gtsam::Rot3 gtsam::Rot3::rodriguez(double, double, double)
static Rot3 rodriguez(double wx, double wy, double wz)
^
/usr/local/include/gtsam/geometry/Rot3.h:196:17: note: candidate expects 3 arguments, 1 provided
In file included from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:37:0:
/usr/local/include/gtsam/geometry/Pose3.h: In static member function ‘static gtsam::Matrix gtsam::Pose3::wedge(double, double, double, double, double, double)’:
/usr/local/include/gtsam/geometry/Pose3.h:226:28: error: could not convert ‘(&(&(&(&(&(&(&(&(&(&(&(&(&(& Eigen::DenseBase::operator<<(const Scalar&) with Derived = Eigen::Matrix<double, -1, -1>; Eigen::DenseBase::Scalar = double.Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >((- wz)))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(wy))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(vx))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(wz))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(0.0))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >((- wx)))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(vy))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >((- wy)))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(wx))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(0.0))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(vz))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(0.0))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(0.0))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(0.0))->Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, -1> >(0.0)’ from ‘Eigen::CommaInitializer<Eigen::Matrix<double, -1, -1> >’ to ‘gtsam::Matrix {aka Eigen::Matrix<double, -1, -1>}’
0., 0., 0., 0.);
^
In file included from /usr/local/include/gtsam/nonlinear/NonlinearFactorGraph.h:24:0,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:40:
/usr/local/include/gtsam/geometry/Point2.h: In static member function ‘static gtsam::Vector gtsam::Point2::Logmap(const gtsam::Point2&)’:
/usr/local/include/gtsam/geometry/Point2.h:175:86: error: could not convert ‘Eigen::DenseBase::operator<<(const Scalar&) [with Derived = Eigen::Matrix<double, -1, 1>; Eigen::DenseBase::Scalar = double]((& dp)->gtsam::Point2::x()).Eigen::CommaInitializer::operator,<Eigen::Matrix<double, -1, 1> >((& dp)->gtsam::Point2::y())’ from ‘Eigen::CommaInitializer<Eigen::Matrix<double, -1, 1> >’ to ‘gtsam::Vector {aka Eigen::Matrix<double, -1, 1>}’
static inline Vector Logmap(const Point2& dp) { return (Vector(2) << dp.x(), dp.y()); }
^
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h: In instantiation of ‘class gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:118:62: required from here
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:62:59: error: no type named ‘Index’ in ‘struct Eigen::internal::traits<gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix >’
typedef typename Eigen::internal::traits::Index Index;
^
In file included from /usr/local/include/gtsam/linear/HessianFactor.h:21:0,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘gtsam::SymmetricBlockMatrix::Block gtsam::SymmetricBlockMatrix::operator()(gtsam::DenseIndex, gtsam::DenseIndex)’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:119:43: error: no matching function for call to ‘gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix::SymmetricBlockMatrixBlockExpr(gtsam::SymmetricBlockMatrix&, gtsam::DenseIndex&, gtsam::DenseIndex&)’
return Block(*this, i_block, j_block);
^
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate: constexpr gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix&)
class SymmetricBlockMatrixBlockExpr : public Eigen::EigenBase<SymmetricBlockMatrixBlockExpr >
^
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate expects 1 argument, 3 provided
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h: In instantiation of ‘class gtsam::SymmetricBlockMatrixBlockExpr’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:124:73: required from here
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:62:59: error: no type named ‘Index’ in ‘struct Eigen::internal::traits<gtsam::SymmetricBlockMatrixBlockExpr >’
typedef typename Eigen::internal::traits::Index Index;
^
In file included from /usr/local/include/gtsam/linear/HessianFactor.h:21:0,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘gtsam::SymmetricBlockMatrix::constBlock gtsam::SymmetricBlockMatrix::operator()(gtsam::DenseIndex, gtsam::DenseIndex) const’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:125:48: error: no matching function for call to ‘gtsam::SymmetricBlockMatrixBlockExpr::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrix&, gtsam::DenseIndex&, gtsam::DenseIndex&)’
return constBlock(*this, i_block, j_block);
^
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate: constexpr gtsam::SymmetricBlockMatrixBlockExpr::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrixBlockExpr&)
class SymmetricBlockMatrixBlockExpr : public Eigen::EigenBase<SymmetricBlockMatrixBlockExpr >
^
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate expects 1 argument, 3 provided
In file included from /usr/local/include/gtsam/linear/HessianFactor.h:21:0,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘gtsam::SymmetricBlockMatrix::Block gtsam::SymmetricBlockMatrix::range(gtsam::DenseIndex, gtsam::DenseIndex, gtsam::DenseIndex, gtsam::DenseIndex)’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:134:107: error: no matching function for call to ‘gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix::SymmetricBlockMatrixBlockExpr(gtsam::SymmetricBlockMatrix&, gtsam::DenseIndex&, gtsam::DenseIndex&, gtsam::DenseIndex, gtsam::DenseIndex)’
return Block(*this, i_startBlock, j_startBlock, i_endBlock - i_startBlock, j_endBlock - j_startBlock);
^
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate: constexpr gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix&)
class SymmetricBlockMatrixBlockExpr : public Eigen::EigenBase<SymmetricBlockMatrixBlockExpr >
^
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate expects 1 argument, 5 provided
In file included from /usr/local/include/gtsam/linear/HessianFactor.h:21:0,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘gtsam::SymmetricBlockMatrix::constBlock gtsam::SymmetricBlockMatrix::range(gtsam::DenseIndex, gtsam::DenseIndex, gtsam::DenseIndex, gtsam::DenseIndex) const’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:143:112: error: no matching function for call to ‘gtsam::SymmetricBlockMatrixBlockExpr::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrix&, gtsam::DenseIndex&, gtsam::DenseIndex&, gtsam::DenseIndex, gtsam::DenseIndex)’
return constBlock(*this, i_startBlock, j_startBlock, i_endBlock - i_startBlock, j_endBlock - j_startBlock);
^
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate: constexpr gtsam::SymmetricBlockMatrixBlockExpr::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrixBlockExpr&)
class SymmetricBlockMatrixBlockExpr : public Eigen::EigenBase<SymmetricBlockMatrixBlockExpr >
^
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate expects 1 argument, 5 provided
In file included from /usr/local/include/gtsam/linear/HessianFactor.h:21:0,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘gtsam::SymmetricBlockMatrix::Block gtsam::SymmetricBlockMatrix::full()’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:149:42: error: no matching function for call to ‘gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix::SymmetricBlockMatrixBlockExpr(gtsam::SymmetricBlockMatrix&, int, gtsam::DenseIndex, int)’
return Block(this, 0, nBlocks(), 0);
^
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate: constexpr gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix&)
class SymmetricBlockMatrixBlockExpr : public Eigen::EigenBase<SymmetricBlockMatrixBlockExpr >
^
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate expects 1 argument, 4 provided
In file included from /usr/local/include/gtsam/linear/HessianFactor.h:21:0,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘gtsam::SymmetricBlockMatrix::constBlock gtsam::SymmetricBlockMatrix::full() const’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:155:47: error: no matching function for call to ‘gtsam::SymmetricBlockMatrixBlockExpr::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrix&, int, gtsam::DenseIndex, int)’
return constBlock(this, 0, nBlocks(), 0);
^
In file included from /usr/local/include/gtsam/base/SymmetricBlockMatrix.h:22:0,
from /usr/local/include/gtsam/linear/HessianFactor.h:21,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate: constexpr gtsam::SymmetricBlockMatrixBlockExpr::SymmetricBlockMatrixBlockExpr(const gtsam::SymmetricBlockMatrixBlockExpr&)
class SymmetricBlockMatrixBlockExpr : public Eigen::EigenBase<SymmetricBlockMatrixBlockExpr >
^
/usr/local/include/gtsam/base/SymmetricBlockMatrixBlockExpr.h:46:9: note: candidate expects 1 argument, 4 provided
In file included from /usr/local/include/gtsam/linear/HessianFactor.h:21:0,
from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘Eigen::SelfAdjointView<const Eigen::Matrix<double, -1, -1>, 2u> gtsam::SymmetricBlockMatrix::matrix() const’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:161:14: error: could not convert ‘((const gtsam::SymmetricBlockMatrix
)this)->gtsam::SymmetricBlockMatrix::matrix_’ from ‘const Matrix {aka const Eigen::Matrix<double, -1, -1>}’ to ‘Eigen::SelfAdjointView<const Eigen::Matrix<double, -1, -1>, 2u>’
return matrix_;
^
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h: In member function ‘Eigen::SelfAdjointView<Eigen::Matrix<double, -1, -1>, 2u> gtsam::SymmetricBlockMatrix::matrix()’:
/usr/local/include/gtsam/base/SymmetricBlockMatrix.h:167:14: error: could not convert ‘((gtsam::SymmetricBlockMatrix
)this)->gtsam::SymmetricBlockMatrix::matrix_’ from ‘gtsam::Matrix {aka Eigen::Matrix<double, -1, -1>}’ to ‘Eigen::SelfAdjointView<Eigen::Matrix<double, -1, -1>, 2u>’
return matrix_;
^
In file included from /usr/local/include/gtsam/linear/GaussianFactorGraph.h:28:0,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizerParams.h:23,
from /usr/local/include/gtsam/nonlinear/NonlinearOptimizer.h:22,
from /usr/local/include/gtsam/nonlinear/LevenbergMarquardtOptimizer.h:21,
from /home/wangbx/catkin_ws/src/LeGO-LOAM/LeGO-LOAM/src/mapOptmization.cpp:41:
/usr/local/include/gtsam/linear/HessianFactor.h: In member function ‘double gtsam::HessianFactor::constantTerm() const’:
/usr/local/include/gtsam/linear/HessianFactor.h:287:79: error: no match for call to ‘(gtsam::SymmetricBlockMatrix::constBlock {aka gtsam::SymmetricBlockMatrixBlockExpr}) (int, int)’
double constantTerm() const { return info_(this->size(), this->size())(0,0); }
^
/usr/local/include/gtsam/linear/HessianFactor.h: In member function ‘double& gtsam::HessianFactor::constantTerm()’:
/usr/local/include/gtsam/linear/HessianFactor.h:292:74: error: no match for call to ‘(gtsam::SymmetricBlockMatrix::Block {aka gtsam::SymmetricBlockMatrixBlockExprgtsam::SymmetricBlockMatrix}) (int, int)’
double& constantTerm() { return info_(this->size(), this->size())(0,0); }
^
LeGO-LOAM/LeGO-LOAM/CMakeFiles/mapOptmization.dir/build.make:62: recipe for target 'LeGO-LOAM/LeGO-LOAM/CMakeFiles/mapOptmization.dir/src/mapOptmization.cpp.o' failed
make[2]: *** [LeGO-LOAM/LeGO-LOAM/CMakeFiles/mapOptmization.dir/src/mapOptmization.cpp.o] Error 1
CMakeFiles/Makefile2:3321: recipe for target 'LeGO-LOAM/LeGO-LOAM/CMakeFiles/mapOptmization.dir/all' failed
make[1]: *** [LeGO-LOAM/LeGO-LOAM/CMakeFiles/mapOptmization.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j1" failed

what's the problem and how to do?Thx

Setting up tf for LeGO-LOAM using VLP-16

Hi, all,

I am trying to get my Velodyne VLP-16 node(topic: velodyne_points) to work with LeGO-LOAM. I can compile the package and play sample bag files. I also have installed velodyne vlp16 and the lidar seems working properly. However, when I roslaunch velodyne node and LeGO-LOAM, I just can't get it right. My command lines are as follows:

$roscore
$roslaunch velodyne_pointcloud VLP16_points.launch
$roslaunch lego_loam run.launch

How to set up tf for LeGO-LOAM using VLP-16?THANKS A LOT.

Question about how to view the global map

Hi! I noticed that I can only view a partial map through rviz while running LeGO-LOAM. Is there any way to view the real-time global map in rviz?
By the way, I also noticed that the pointclouds sent by topic "/laser_cloud_surround" also only show part of the map. Is there a way to adjust the scale of it so that I can view the global map through that topic?
Thanks a lot!

Dense Final Cloud

Hi!
I would like to know if I can produce more dense final cloud.
Thank you.

lidar position is not stable

when the vehicle is stationary,the position is not stable。the error is about 0.4m .As time goes by, the error is getting bigger. The biggest position error is 1m.

PCL compilation issue

Hi,
I was compiling LeGO-LOAM and the following error show up:

 *** No rule to make target '/usr/local/lib/libpcl_common.so', needed by '/home/bruno/catkin_ws/devel/lib/lego_loam/featureAssociation'. Stop.
CMakeFiles/Makefile2:5390: recipe for target 'LeGO-LOAM/LeGO-LOAM/CMakeFiles/featureAssociation.dir/all' failed
make[1]: *** [LeGO-LOAM/LeGO-LOAM/CM

My pcl version is 1.7. Is that an issue?
Regards,
Bruno

IMU data error

My imu device is xsens mti-10 driver and driver http://wiki.ros.org/xsens_driver,

I opened run.launch first and then open velodyne VLP16, it showed pointcloud on rviz.
But, when i use imu it will be stoped and show MSG to TF : Quaternion Not Properly Normalized.

thx for help!

Utility Parameters for KITTI dataset testing ?

Hi,

Could you please provide the utility parameters to run LeGO-LOAM on KITTI dataset ?

When you implement new sensor, make sure that the ground_cloud has enough points for matching.

extern const int N_SCAN = 16;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 15.0;
extern const int groundScanInd = 7;

  1. What should the new parameters be ?

Here is a bag file that I am attaching.

https://transfer.pcloud.com/download.html?code=5Z61Ss7ZPV6UN87wU4kZAH3bZiIe8l4Y3IBJMUAHk9TSTmyAyT4Ek

  1. Could you tell me what other changes you made such as the topic name needs to be changed and so on.

  2. Any new static transform publishers need to be added ?

Thank you very much!

Drift in z direction

Hi Shan,

Thanks for your great job! However, I got some results which are not as good as yours in paper. Currently, I'm using VLP-16+imu to build the map in our campus, lidar is mounted at around 1.2m hight with imu attached to its top. In some situations LeGO-LOAM suffers significant drift in z direction (ex. ~7 meters after traveling around 400m), which didn't happen in x and y direction(x forward, y left, z up).

I have tried to change threshold in if (abs(angle - sensorMountAngle) <= 10) to 1,5,15,20 but got no good result.

I have also tried to change the map optimization update frequency in utility.h extern const double mappingProcessInterval = 0.1, but no luck.

Do you have any idea about this ? Could you take a look at my bag file ?

Looking forward to your reply.

Claude

bird view
birdview
z drift
drift_z
path
drift_z_path
bag link
https://drive.google.com/file/d/1LFKV-jA1yjSHvUUCYCarzFO2UQdPD_0_/view?usp=sharing

Adapt projecting pointcloud for different LIDAR sensor?

Hi @TixiaoShan,
Thanks for sharing this package.
I have a question about the function projectPointcloud. In this line, you hardcoded two numbers for identifying the column index of a point:

if (horizonAngle <= -90)
        columnIdn = -int(horizonAngle / ang_res_x) - 450;
      else if (horizonAngle >= 0)
        columnIdn = -int(horizonAngle / ang_res_x) + 1350;
      else
        columnIdn = 1350 - int(horizonAngle / ang_res_x);

If I understand correct, those numbers 450,1350 are somewhat related to the Velodyne VLP-16. They will probably not fit for other LIDAR, whose horizontal resolution is not 0.2 as the VLP-16. For example, the OS1-16 from Ouster has a horizontal resolution at 0.18, which creates a slightly bigger range image 16x2000.
I wonder if you could help me understand the logic behind this these number so that I can adapt them to different LIDAR sensor?
I appreciate your help!

How to modify parameters while using new lidar?

I'm using a different 16 lines lidar, and I've set N_SCAN,ang_res_x y, but it doesn't work.

What does Horizon_SCAN mean? frequency * 360? Your paper shows Velodyne is 10Hz,360°

And What does groundScanInd mean?
image
I set it to 16, and doesn't work.

Thanks for your work and help!

the wrong of roll and pitch

I got the roll,pitch and yawl of our robot .But the roll and pitch are around 0~180 degree.I think that my robot 's roll and pitch are around +/- 5 degree. Which reason lead to this problem? Could you tell me the reason?

                                Thanks.          

HDL-64E

Hello, I'm using kitti dataset to test your code, I have modified the params as follw:
extern const int N_SCAN = 64;
extern const int Horizon_SCAN = 1800; //1028~4500
extern const float ang_res_x = 360.0/float(Horizon_SCAN);
extern const float ang_res_y = 28.0/float(N_SCAN-1);
extern const float ang_bottom = 25.0;
extern const int groundScanInd = 60;

are they right? can you provide some advice?

parameters for Velodyne HDL-64E used in KITTI Raw Datasets

I will be grateful if you can help me figure out the set of parameters defined here:

// VLP-16
extern const int N_SCAN = 16;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 15.0+0.1;
extern const int groundScanInd = 7;

for Velodyne HDL-64E used in KITTI Raw Datasets. I know that N_SCAN = 64 but I don't know how to set the other parameters.

Coordinate transformation when use imu

Hi author, Thanks for your work!

  1. I am wonder how the coordinate transformation in point cloud distortion correction process. Did it firstly convert current point into the IMU coordinate(or world frame?), then integrate the measurements. Third calculated the relative pose and velocity (in world frame) between the current point and the first point . At last transform the relative measurements in Lidar coordinate, linear interpret and register every point in corresponding line? I don't know if I got the right order.
    2. I think before fusion these two kind of messages, it should firstly calibrate the sensor suite in temporal and spatial. I havn't seen any code to do this work both in LOAM and your project. Can you tell me what the influence of parameter of Rc and Pc (transformation between lidar and imu), or what should i be attention when use my own suite.
    Thank you very much!

About the leGO-LOAM paper

Hi! I'm really impressed by the speed and effect brought by LeGO-LOAM after playing my own rosbag.
Therefore, I really want to have some further understanding about how leGO-LOAM works. But I was unable to find the paper "LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain" online.
So could you please upload the paper or provide some information about where I can find it?
Thanks a lot and have a nice day!

Applicability for Quadcopter?

Hello,

Would LeGO-LOAM be suitable to use for aerial vehicle localization/pose estimation in indoor, gps-denied settings (say, using a VLP16)? I noticed from the readme that the requirement is that the ground plane always needs to be in view. Can this requirement be relaxed in any way?

Edit: Found the note about applying LeGO-LOAM to UAVs in the conclusion of your paper - any tips on how I could go about modifying the source to accomplish this?

Thanks!

Some problems about your paper and code

Hi,author! Thanks for your work.
I recently encountered some problems when reading your papers and code. In "Odometry" section, you added the "Label Matching" process, but I did not find this part in the code, I hope you can give me some advice. I think that since it is necessary to reduce the number of feature points and improve the accuracy of the system, this part is indispensable.

I am unable to drive LeGo-loam using pandar40

I changed the utility.h to:
extern const int N_SCAN = 40;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 7.0;
extern const int groundScanInd = 7;

I am unable to drive LeGo-loam using pandar40

pandar-40:
lower vertical bound (degress) :-16
upper vertical bound (degress) : 7
the number of scan rings 40

odometry drift and the odometry is not the same plane?

Hi. Thanks for your package.
I use the lego_loam with rslidar_points and changed the parameters in include file and the function in projectPointClolud, and there are some problems. First, the problem is the odometry always drift while our robot is static. Second, the problem is the odometry is not the same plane. Can you expain why these problems happen? And can you give me some advices how to resolve these problems?
Thank you very much!

Problems with VLP-16 dataset w/ IMU

Hi! Would you have a moment to take a look at the dataset provided here?
https://ferhr-my.sharepoint.com/:f:/g/personal/jorsulic_fer_hr/EvwbIJ1tVipLqAJi1ECinDcBLLwKVF0Vki1m4zQ6ye0Jwg?e=TqqWCu

To run Lego-LOAM with the dataset:

rosrun imu_filter_madgwick imu_filter_node /imu/data_raw:=imu _publish_tf:=false _use_mag:=false _gain:=0.005
roslaunch lego_loam run.launch
rosbag play processed_type1_traderjoes.bag  points2_1_VLP16:=/velodyne_points --clock

The trajectory sometimes looks okay piecewise, but often has jerky moments. Also, in the second part of processed_type1_traderjoes.bag, the trajectory goes crazy, up in the air, with an arbitrary pitch and roll - it looks like the gravity measured by the IMU is ignored. As far as I can tell, the IMU is well aligned to the lidar (~< 0.5 degrees). Do you maybe know what could be the cause?

(You may have to install the Madgwick filter with sudo apt install ros-melodic-imu-filter-madgwick.)

Also: the frequency is 20 Hz, which means the angular resolution is 0.4 degrees. However, If I tried adjusting for this (the angular resolution), I would get a crash.

Evaluation on kitti dataset and video production

Dear Author:
Very nice work!
1. I am wonder how you evaluate lego-loam on kitti dataset. I used the tool(https://pypi.org/project/kitti2bag/1.5/) to convert the raw data into rosbag. when I run the rosbag, there are msgs lost. Is this caused by hardware resources limitations? I saw your paper has evaluate the algorithm on tx2, have you encounter such problems?
2. The demo video is very interesting. How do you dynamically display trajectories to Google Maps in real time? Have you used any video production software ?
Thanks very much!

Sudden rotation occurs during mapping

Hi Shan,

I have tested your algorithm with my own datasets (VLP-16, no imu data), in dataset1, map is perfect with little drift (pic1, pic2). But in dataset2, it occurs a sudden rotation in the built map(pic3, pic4).
My lidar is mounted on the surface of handcart (1m height) which moves smoothly.
Do you have any idea about this ? Or do you have any suggestions about which parameters should be adjusted accordingly ?
1
2
3
4

Yours,
Claude

cloud_msgs/cloud_info.h: No such file or directory

Hi,
I am using ROS Kinect and Ubuntu 16.04. I compile this package using catkin_make and I am obtaining the following error:

/LeGO-LOAM/LeGO-LOAM/include/utility.h:11:35: fatal error: cloud_msgs/cloud_info.h: No such file or directory
compilation terminated.

Anybody with the same issue?

Comparing LeGO-LOAM and LOAM using the KITTI Dataset

Hello,

Maybe the most known LOAM implementation on Github is laboshinl's version, but when testing it with the KITTI Dataset, it doesn't reproduce the original results. I was working with the original code uploaded by J. Zhang http://docs.ros.org/indigo/api/loam_velodyne/html/files.html using the raw KITTI Dataset and; even though I get results near the original one, there are some sequences where the original LOAM diverges.

I tried LeGO-LOAM with the sequence 00 of the KITTI Dataset and it returns good results (better than original LOAM's code). I don't know if this occurs because of your algorithm or if the version of LOAM you based your code is the one that can reproduce the original LOAM results.

Since your work is based on LOAM, before starting to implement your code, did you get to reproduce original LOAM results with the KITTI Dataset?.

Thanks for your answer.

[run.launch] is neither a launch file in package [lego_loam] nor is [lego_loam] a launch file name The traceback for the exception was written to the log file

I made belo w commands
cd ~/catkin_ws/src
git clone https://github.com/RobustFieldAutonomyLab/LeGO-LOAM.git
cd ..
catkin_make -j1
In separate terminal i played below
rosbag play *.bag --clock --topic /velodyne_points /imu/data

But after exceuting
roslaunch lego_loam run.launch under "catkin_ws" directory, i got error below. Kindly help

[run.launch] is neither a launch file in package [lego_loam] nor is [lego_loam] a launch file name The traceback for the exception was written to the log file

Test in kitti dataset

Hello, If I want to test in kitti odometry dataset, Can all the functions about IMU be removed?

The kitti raw datasets's IMU data for your algorithm

Hi,I want to use the IMU data in kitti raw datasets to test lego ,just remap '/imu/data' to '/kitti/oxts/imu'
but it goes wrong when turn rotation on z axis. For example:
2018-09-12 16-20-35

And When not use IMU data,it will be ok:

2018-09-12 16-21-17

The kitti raw datasets coordinate transform between velodyne and imu like this:
2018-09-12 16-28-08

And in your datasets 2017-06-08-15-49-45_0.bag , the tf is like this:
2018-09-12 16-30-29

Can help me what's wrong?

By the way, is there any doc about featureAssociate.cpp's detail. Thanks

Relocalization in the previously built map?

Hi,
If I want to extend this system to have the ability to relocalise the robot in the previously built map, where should I start? I would be most grateful if anyone might be able to give me some advice. THX!!

catkin_make error on ubuntu 16.04

c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See file:///usr/share/doc/gcc-5/README.Bugs for instructions.
examples/CMakeFiles/Pose2SLAMExample_graph.dir/build.make:62: recipe for target 'examples/CMakeFiles/Pose2SLAMExample_graph.dir/Pose2SLAMExample_graph.cpp.o' failed
make[2]: *** [examples/CMakeFiles/Pose2SLAMExample_graph.dir/Pose2SLAMExample_graph.cpp.o] Error 4
CMakeFiles/Makefile2:14021: recipe for target 'examples/CMakeFiles/Pose2SLAMExample_graph.dir/all' failed
make[1]: *** [examples/CMakeFiles/Pose2SLAMExample_graph.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
[ 64%] Linking CXX executable Pose2SLAMwSPCG
[ 64%] Built target Pose2SLAMwSPCG
[ 64%] Linking CXX executable Pose2SLAMExample_lago
[ 64%] Built target Pose2SLAMExample_lago
[ 64%] Linking CXX executable SFMExample_bal_COLAMD_METIS
[ 64%] Built target SFMExample_bal_COLAMD_METIS
[ 66%] Linking CXX executable ImuFactorsExample
[ 66%] Built target ImuFactorsExample
[ 66%] Linking CXX executable SFMExampleExpressions
[ 66%] Built target SFMExampleExpressions
Makefile:160: recipe for target 'all' failed
make: *** [all] Error 2
<== Failed to process package 'gtsam':
Command '['/home/firefly/golo_ws/devel_isolated/golo_tools/env.sh', 'make', '-j6', '-l6']' returned non-zero exit status 2

Reproduce this error by running:
==> cd /home/firefly/golo_ws/build_isolated/gtsam && /home/firefly/golo_ws/devel_isolated/golo_tools/env.sh make -j6 -l6

the theory about transformation

Hi author, Thanks for your work!

When I read your code, I find there is so much code about transformation,such as in function "calculateTransformationSurf" and "calculateTransformationCorner", most of them are about imu, I didn't find the theory in your paper. Could you provide the related theory about this part?

Thank you very much!

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.