Giter VIP home page Giter VIP logo

lio-livox's Introduction

LIO-Livox (A Robust LiDAR-Inertial Odometry for Livox LiDAR)

This respository implements a robust LiDAR-inertial odometry system for Livox LiDAR. The system uses only a single Livox LiDAR with a built-in IMU. It has a robust initialization module, which is independent to the sensor motion. It can be initialized with the static state, dynamic state, and the mixture of static and dynamic state. The system achieves super robust performance. It can pass through a 4km-tunnel and run on the highway with a very high speed (about 80km/h) using a single Livox Horizon. Moreover, it is also robust to dynamic objects, such as cars, bicycles, and pedestrains. It obtains high precision of localization even in traffic jams. The mapping result is precise even most of the FOV is occluded by vehicles. Videos of the demonstration of the system can be found on Youtube and Bilibili. NOTE: Images are only used for demonstration, not used in the system.

Developer: Livox

## System achritecture

The system consists of two ros nodes: ScanRegistartion and PoseEstimation.

  • The class "LidarFeatureExtractor" of the node "ScanRegistartion" extracts corner features, surface features, and irregular features from the raw point cloud.
  • In the node "PoseEstimation", the main thread aims to estimate sensor poses, while another thread in the class "Estimator" uses the class "MapManager" to build and manage feature maps.

The system is mainly designed for car platforms in the large scale outdoor environment. Users can easily run the system with a Livox Horizon or HAP LiDAR. It is still stable in indoor,we also support Mid-360 which is designed for robots now.

The system starts with the node "ScanRegistartion", where feature points are extracted. Before the feature extraction, dynamic objects are removed from the raw point cloud, since in urban scenes there are usually many dynamic objects, which affect system robustness and precision. For the dynamic objects filter, we use a fast point cloud segmentation method. The Euclidean clustering is applied to group points into some clusters. The raw point cloud is divided into ground points, background points, and foreground points. Foreground points are considered as dynamic objects, which are excluded form the feature extraction process. Due to the dynamic objects filter, the system obtains high robustness in dynamic scenes.

In open scenarios, usually few features can be extracted, leading to degeneracy on certain degrees of freedom. To tackle this problem, we developed a feature extraction process to make the distribution of feature points wide and uniform. A uniform and wide distribution provides more constraints on all 6 degrees of freedom, which is helpful for eliminating degeneracy. Besides, some irregular points also provides information in feature-less scenes. Therefore, we also extract irregular features as a class for the point cloud registration. Feature points are classifed into three types, corner features, surface features, and irregular features, according to their local geometry properties. We first extract points with large curvature and isolated points on each scan line as corner points. Then principal components analysis (PCA) is performed to classify surface features and irregular features, as shown in the following figure. For points with different distance, thresholds are set to different values, in order to make the distribution of points in space as uniform as possible.

In the node "PoseEstimation", the motion distortion of the point cloud is compensated using IMU preintegration or constant velocity model. Then the IMU initialization module is performed. If the Initialization is successfully finished, the system will switch to the LIO mode. Otherwise, it run with LO mode and initialize IMU states. In the LO mode, we use a frame-to-model point cloud registration to estimate the sensor pose. Inspired by ORB-SLAM3, a maximum a posteriori (MAP) estimation method is adopted to jointly initialize IMU biases, velocities, and the gravity direction. This method doesn't need a careful initialization process. The system can be initialized with an arbitrary motion. This method takes into account sensor uncertainty, which obtains the optimum in the sense of maximum posterior probability. It achieves efficient, robust, and accurate performance. After the initialization, a tightly coupled slding window based sensor fusion module is performed to estimate IMU poses, biases, and velocities within the sliding window. Simultaneously, an extra thread builds and maintains the global map in parallel.

Prerequisites

Compilation

cd ~/catkin_ws/src
git clone https://github.com/Livox-SDK/LIO-Livox
cd ..
catkin_make

Run with bag files:

Run the launch file:

cd ~/catkin_ws
source devel/setup.bash
roslaunch lio_livox horizon.launch

Play your bag files:

rosbag play YOUR_ROSBAG.bag

Run with your device:

Run your LiDAR with livox_ros_driver

cd ~/catkin_ws
source devel/setup.bash
roslaunch livox_ros_driver livox_lidar_msg.launch

Run the launch file:

cd ~/catkin_ws
source devel/setup.bash
roslaunch lio_livox horizon.launch

Notes:

The current version of the system is only adopted for Livox Horizon and Livox HAP. In theory, it should be able to run directly with a Livox Avia, but we haven't done enough tests. Besides, the system doesn't provide a interface of Livox mid series. If you want use mid-40 or mid-70, you can try livox_mapping.

The topic of point cloud messages is /livox/lidar and its type is livox_ros_driver/CustomMsg.
The topic of IMU messages is /livox/imu and its type is sensor_msgs/Imu.

There are some parameters in launch files:

  • IMU_Mode: choose IMU information fusion strategy, there are 3 modes:
    • 0 - without using IMU information, pure LiDAR odometry, motion distortion is removed using a constant velocity model
    • 1 - using IMU preintegration to remove motion distortion
    • 2 - tightly coupling IMU and LiDAR information
  • Extrinsic_Tlb: extrinsic parameter between LiDAR and IMU, which uses SE3 form. If you want to use an external IMU, you need to calibrate your own sensor suite and change this parameter to your extrinsic parameter.

There are also some parameters in the config file:

  • Use_seg: choose the segmentation mode for dynamic objects filtering, there are 2 modes:
    • 0 - without using the segmentation method, you can choose this mode if there is few dynamic objects in your data
    • 1 - using the segmentation method to remove dynamic objects

Acknowledgements

Thanks for following work:

  • LOAM (LOAM: Lidar Odometry and Mapping in Real-time)
  • VINS-Mono (VINS-Mono: A Robust and Versatile Monocular Visual-Inertial State Estimator)
  • LIO-mapping (Tightly Coupled 3D Lidar Inertial Odometry and Mapping)
  • ORB-SLAM3 (ORB-SLAM3: An Accurate Open-Source Library for Visual, Visual-Inertial and Multi-Map SLAM)
  • LiLi-OM (Towards High-Performance Solid-State-LiDAR-Inertial Odometry and Mapping)
  • MSCKF_VIO (Robust Stereo Visual Inertial Odometry for Fast Autonomous Flight)
  • horizon_highway_slam
  • livox_mapping
  • livox_horizon_loam

Support

You can get support from Livox with the following methods:

  • Send email to [email protected] with a clear description of your problem and your setup
  • Report issues on github

lio-livox's People

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

lio-livox's Issues

catkin_make issue

[ 98%] Built target livox_ros_driver_node
make[2]: *** [LIO-Livox/CMakeFiles/PoseEstimation.dir/build.make:63: LIO-Livox/CMakeFiles/PoseEstimation.dir/src/lio/PoseEstimation.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
make[1]: *** [CMakeFiles/Makefile2:3646: LIO-Livox/CMakeFiles/PoseEstimation.dir/all] Error 2
make: *** [Makefile:141: all] Error 2

Missing Launch file

Hi, I believe you forgot to add the launch file for the mid360 and put instead another copy of LidarFeatureExtractor.h in the launch folder

Error in evaluating the ResidualBlock.

Hi all

I try to generate a map with LIO-LIVOX using HAP.
I ran my custom rosbag files, and it works well with this error.
I think memory leak is occurred due to this problem, but I do not have an idea to solve this problem

Any solutions?

Hello,
I'm trying to build a map with Livox-Horizon, but LIO-LIVOX doesn't work properly.
The terminal prompts the following error, has anyone encountered a similar error, or is there any solution?
Thank you all very much!

[ INFO] [1683814134.886824369]: Frame: 92

[ INFO] [1683814135.955633539]: Frame: 93

[ INFO] [1683814137.024720123]: Frame: 94

**************Start MAP Initialization!!!******************
WARNING: Logging before InitGoogleLogging() is written to STDERR
W0511 22:08:57.031163 24555 residual_block.cc:131] 

Error in evaluating the ResidualBlock.

There are two possible reasons. Either the CostFunction did not evaluate and fill all    
residual and jacobians that were requested or there was a non-finite value (nan/infinite)
generated during the or jacobian computation. 

Residual Block size: 1 parameter blocks x 3 residuals

For each parameter block, the value of the parameters are printed in the first column   
and the value of the jacobian under the corresponding residual. If a ParameterBlock was 
held constant then the corresponding jacobian is printed as 'Not Computed'. If an entry 
of the Jacobian/residual array was requested but was not written to by user code, it is 
indicated by 'Uninitialized'. This is an error. Residuals or Jacobian values evaluating 
to Inf or NaN is also an error.  

Residuals:              nan          nan          nan 

Parameter Block 0, size: 4

           1 |            0            0            0 
           0 |            0        19.61            0 
           0 |       -19.61            0            0 
           0 |            0            0            0 


E0511 22:08:57.031241 24555 trust_region_minimizer.cc:72] Terminating: Residual and Jacobian evaluation failed.
W0511 22:08:57.031497 24632 residual_block.cc:131] 

Error in evaluating the ResidualBlock.

There are two possible reasons. Either the CostFunction did not evaluate and fill all    
residual and jacobians that were requested or there was a non-finite value (nan/infinite)
generated during the or jacobian computation. 

Residual Block size: 5 parameter blocks x 9 residuals

For each parameter block, the value of the parameters are printed in the first column   
and the value of the jacobian under the corresponding residual. If a ParameterBlock was 
held constant then the corresponding jacobian is printed as 'Not Computed'. If an entry 
of the Jacobian/residual array was requested but was not written to by user code, it is 
indicated by 'Uninitialized'. This is an error. Residuals or Jacobian values evaluating 
to Inf or NaN is also an error.  

Residuals:             -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 

Parameter Block 0, size: 3

           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 

Parameter Block 1, size: 3

  0.00156916 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
   0.0147306 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
  -0.0786896 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 

Parameter Block 2, size: 3

  0.00156916 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
   0.0147306 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
  -0.0786896 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 

Parameter Block 3, size: 3

           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 

Parameter Block 4, size: 3

           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 
           0 |         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan         -nan 

Are all Livox lidars supported out of the box?

Are all the different Livox lidars supported out of the box, such as the tele?

I've noticed the config file has a parameter where one can specify the lidar type. Where can I find a list of what each is referenced to. 0 references to the horizon

Stand-alone app

Please Integrate this with the Livox-SDK for stand-alone mapping as an app. Drop the reliance on ROS/ROS2.

IMU预积分公式推导引用自何处?与vins-mono中imu预积分推导不一样呢?

Eigen::Matrix<double,15,15> A = Eigen::Matrix<double,15,15>::Identity();
A.block<3,3>(0,3) = -0.5*dq.matrix()*Sophus::SO3d::hat(acc)*dt2;
A.block<3,3>(0,6) = Eigen::Matrix3d::Identity()*dt;
A.block<3,3>(0,12) = -0.5*dq.matrix()*dt2;
A.block<3,3>(3,3) = dR.transpose();
A.block<3,3>(3,9) = - Jr*dt;
A.block<3,3>(6,3) = -dq.matrix()*Sophus::SO3d::hat(acc)*dt;
A.block<3,3>(6,12) = -dq.matrix()*dt;
Eigen::Matrix<double,15,12> B = Eigen::Matrix<double,15,12>::Zero();
B.block<3,3>(0,3) = 0.5*dq.matrix()*dt2;
B.block<3,3>(3,0) = Jr*dt;
B.block<3,3>(6,3) = dq.matrix()*dt;
B.block<3,3>(9,6) = Eigen::Matrix3d::Identity()*dt;
B.block<3,3>(12,9) = Eigen::Matrix3d::Identity()*dt;

如何保存计算出的点云

测试的效果不错,请问livox如何设置可以保存rviz计算出来的点云文件呢,是对哪个文件进行设置吗

[ScanRegistration-1] process has died [pid 15243

Converted lvx to bag file

roslaunch livox_ros_driver lvx_to_rosbag.launch lvx_file_path:=/home/arjun/Downloads/Horizon_.lvx xfer_format:=1 imu_bag:=true

Then I launch

roslaunch lio_livox horizon.launch
rosbag play Horizon_.bag

But I'm unable to run the package, it is giving an error as mentioned in the subject.

How to save final mapped point cloud

Hi all,

I tried to use pointcloud map which is generated by HAP.
Actually, I used to use loam livox with save map options and it was quite useful to me.
However, this package does not provide that options.

Is there any way to save generated pont cloud??

when I use the official rosbag named:hku_campus_seq_00.bag, still can't run horizon.launch

0 above ground points!
terminate called after throwing an instance of 'std::bad_alloc'
what(): std::bad_alloc
[ScanRegistration-2] process has died [pid 7634, exit code -6, cmd /home/arafat/lio-livox/devel/lib/lio_livox/ScanRegistration __name:=ScanRegistration __log:=/home/arafat/.ros/log/64b287f4-1d60-11ed-839f-e86a640f2b9b/ScanRegistration-2.log].
log file: /home/arafat/.ros/log/64b287f4-1d60-11ed-839f-e86a640f2b9b/ScanRegistration-2*.log

why imupreintegration multiply with gnorm ?

Hello, I notice that in void IMUIntegrator::PreIntegration(), it shows:

    Eigen::Vector3d acc; //为啥要乘以gnorm????
    acc <<  imu->linear_acceleration.x * gnorm,
            imu->linear_acceleration.y * gnorm,
            imu->linear_acceleration.z  * gnorm;

why do so? thanks!

请问大佬,为什么imu与积分这里的加速度要乘以g

Cannot create a KDTree with an empty input cloud!

Hi all,

I try to generate a map with LIO-LIVOX using HAP.
I ran my custom rosbag files, and it works well with this error.
I think memory leak is occurred due to this problem, but I do not have an idea to solve this problem

Any solutions?

image

Memory leak

I'm trying to play over 1500 secs with my rosbag files, but it almost over 500sec,
it uses all 32GB of memory and shut down. How can I solve this problem?

large bias

采用horizon雷达进行建图,出现一些警告。(能够正常建图)
ba_vec: 12.9835 ,bg_vec:0.000639327
[ WARN] [1684550033.362541359]: Too Large Biases! Initialization Failed!

可以看出是ba导致的数据较大。(雷达水平布置)
@Livox-SDK

Something wrong with spin lidar(ouster64)

Hi, friends,
I modify the feature extract moudle for my spin lidar--ouster,and the code is implemented based on lio_sam.
Now, the feature extract module is normal. And the result is good with the IMU_Mode is 0 and 1.
But there's something wrong when IMU_Mode is 2(Tightly Coupled IMU).

2022-03-10 17-33-21屏幕截图

As the picture above, when process "Frame:4654", the trajectory starts to shift.
The points and imu data record by ouster laser(OS1-64), so the transformation matrix of the laser and imu is the unit matrix. Other parameters are default.
The printing parameters are as follows:

微信截图_20220310174838
微信截图_20220310174913

What causes this? Someone has a similar situation?
Thanks again.

自己数据测试结果异常

您好,我们用地平线雷达录制了自己的数据测试,场景为手持雷达在室内行走,发现运行出来的结果很奇怪,运行开始还比较正常,但是很快地图就跑飞了,截图如下:
1628558516(1)

1628558542(1)

我看了下代码,似乎地面分割部分有一些固定的参数,是否需要根据我们的高度,手持场景进行调整呢?

另外是否和雷达的重复或者非重复扫描模式有关系?

请问下可能的原因在哪,需要怎么调整呢? 谢谢回复~

无法进行建图

图片
我使用msg_HAP.launch时,会出现这样的错误。
图片

我使用rviz_HAP.launch时,rviz_HAP打开的rviz可以看到点云数据,但是hap.launch打开的rviz无法进行建图

message not compatible when using lvx-converted bag file

1.download lvx file from 'https://www.livoxtech.com/downloads', Livox Horizon Point Cloud Data 1 2020-03-18
2.use ‘roslaunch livox_ros_driver lvx_to_rosbag.launch’ to convert the lvx file to bag file
3.run LIO-livox and rosbag play, error reported as:
[RUNNING] Bag Time: 3036.199661 Duration: 0.000000 / 94.499459
[ERROR] [1628220411.045738465]: Client [/ScanRegistration] wants topic /livox/lidar to have datatype/md5sum [livox_ros_driver/CustomMsg/e4d6829bdfe657cb6c21a746c86b21a6], but our version has [sensor_msgs/PointCloud2/1158d486dd51d683ce2f1be655c3c181]. Dropping connection.
[RUNNING] Bag Time: 3036.199742 Duration: 0.000081 / 94.499459
....

Unable to run with loam horizon data

Hi, i got the data of loam horizon from your own repo i.e 2020_open_road.bag from https://github.com/Livox-SDK/livox_horizon_loam

However i keep getting, [ScanRegistration-1] process has died and correspondingly a blank screen in RViz.

I have read other threads, but i already have Eigen version 3.3.7 and pcl version -> 1.10.0+dfsg-5ubuntu1.
I am using Ubuntu 20.04 but i meet dependency for the modules used (Eigen, pcl etc.)

Please tell me what suitable changes should i make. And where could i be possibly going wrong?

为什么要这样处理平均地面法线?

在pointcorrects.cpp CalGndPos_cor函数中

if(nNum>0)
{
for(int ii=0;ii<6;ii++)
{
gnd[ii]/=nNum; //得到平均法向量 & 地面点云的中心坐标
}
if(abs(gnd[0])<0.1)
{
gnd[0]=gnd[0]*(1-abs(gnd[0]))4.5;?????????
}
else if(abs(gnd[0])<0.2){
gnd[0]=gnd[0]
(1-abs(gnd[0]))3.2;?????????
}
else{
gnd[0]=gnd[0]
(1-abs(gnd[0]))*2.8;?????????
}
gnd[1] = gnd[1]*2.3;?????????

}

The dynamic objects filter not work

I have used horizon lidar dataset to test this algorithm, but i found when a moved car is also keep in the mapping result. I have set
Use_seg: 1 in config/horizon_config.yaml, and other params is keep as default. I have choose the moved car cloud in the picture.
202108041618

Multiple LiDARs

May we know if this supports multiple Horizon Lidars? what is the recommended setup for multiple Lidar data collection? Thanks

marginalization code question

2022-09-06_17-28

如图在Estimator.cpp执行完滑窗优化,对lidar特征factor作边缘化时,我理解这里是要对第0帧相关factor作边缘化操作,计算的transformTobeMapped应该对应是第0帧的pose,frame_curr应该切换到第0帧了,而这里的frame_curr似乎还是第1帧。不知是我理解错了还是这里漏了代码。
please correct me,thanks!

测试结果路径高程没有闭合,请问可能是什么原因?

我们使用默认的配置参数,以15km/h的速度,绕一个街区进行了测试。从最终的路径看,水平方向基本重合,但高程没有闭合,请问可能有哪些原因?

运行配置: MS Surface Pro i7/Ubuntu 18.04/PCL 1.8/Eigen 3.3.9
运行过程中点云融合延时比较严重,但是最终有正常结束。

路径截图:
rviz_screenshot_2021_08_09-18_35_23

Global Feature Maps not published

ive seen references to global feature maps in the code, but they are not published by any ros node, how can i get these global maps published in ROS?

Thanks.

catkin_make error

/home/pei/catkin_ws/src/LIO-Livox/src/lio/PoseEstimation.cpp: In function ‘bool TryMAPInitialization()’:
/home/pei/catkin_ws/src/LIO-Livox/src/lio/PoseEstimation.cpp:190:49: error: expected type-specifier
ceres::LocalParameterization quatParam = new ceres::QuaternionParameterization();
^~~~~
/home/pei/catkin_ws/src/LIO-Livox/src/lio/PoseEstimation.cpp:193:57: error: no matching function for call to ‘ceres::Problem::AddParameterBlock(double [4], int, ceres::LocalParameterization
&)’
problem_quat.AddParameterBlock(para_quat, 4, quatParam);
^
In file included from /usr/local/include/ceres/ceres.h:64:0,
from /home/pei/catkin_ws/src/LIO-Livox/include/utils/ceresfunc.h:3,
from /home/pei/catkin_ws/src/LIO-Livox/include/Estimator/Estimator.h:20,
from /home/pei/catkin_ws/src/LIO-Livox/src/lio/PoseEstimation.cpp:1:
/usr/local/include/ceres/problem.h:261:8: note: candidate: void ceres::Problem::AddParameterBlock(double*, int)
void AddParameterBlock(double* values, int size);
^~~~~~~~~~~~~~~~~
/usr/local/include/ceres/problem.h:261:8: note: candidate expects 2 arguments, 3 provided
/usr/local/include/ceres/problem.h:274:8: note: candidate: void ceres::Problem::AddParameterBlock(double*, int, ceres::Manifold*)
void AddParameterBlock(double* values, int size, Manifold* manifold);
^~~~~~~~~~~~~~~~~
/usr/local/include/ceres/problem.h:274:8: note: no known conversion for argument 3 from ‘ceres::LocalParameterization*’ to ‘ceres::Manifold*’
[ 91%] Linking CXX executable /home/pei/catkin_ws/devel/lib/lio_livox/ScanRegistration
[ 91%] Built target ScanRegistration
LIO-Livox/CMakeFiles/PoseEstimation.dir/build.make:75: recipe for target 'LIO-Livox/CMakeFiles/PoseEstimation.dir/src/lio/PoseEstimation.cpp.o' failed
make[2]: *** [LIO-Livox/CMakeFiles/PoseEstimation.dir/src/lio/PoseEstimation.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
CMakeFiles/Makefile2:3120: recipe for target 'LIO-Livox/CMakeFiles/PoseEstimation.dir/all' failed
make[1]: *** [LIO-Livox/CMakeFiles/PoseEstimation.dir/all] Error 2
Makefile:145: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j16 -l16" failed

build failed on ubuntu16.04

/home/user/qians/ws_livox/src/LIO-Livox/include/utils/ceresfunc.h:368:36: error: no match for ‘operator*’ (operand types are ‘Sophus::SO3<ceres::Jet<double, 30>, 0>’ and ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<ceres::Jet<double, 30> >, const Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<ceres::Jet<double, 30> >, const Eigen::Matrix<ceres::Jet<double, 30>, 3, 1, 0, 3, 1>, const Eigen::Matrix<ceres::Jet<double, 30>, 3, 1, 0, 3, 1> >, const Eigen::CwiseUnaryOp<Eigen::internal::scalar_multiple_op<ceres::Jet<double, 30> >, const Eigen::CwiseUnaryOp<Eigen::internal::scalar_cast_op<double, ceres::Jet<double, 30> >, const Eigen::Matrix<double, 3, 1> > > >’)
Eigen::Matrix<T, 3, 1> rVij = RiT*(Vj - Vi - GravityVec.cast()*dTij) -

/usr/include/eigen3/Eigen/src/Core/MathFunctions.h:365:34: error: invalid static_cast from type ‘const ceres::Jet<double, 3>’ to type ‘int’
return static_cast(x);

/usr/include/eigen3/Eigen/src/Core/MathFunctions.h:365:34: error: invalid static_cast from type ‘const ceres::Jet<double, 15>’ to type ‘int’
/usr/include/eigen3/Eigen/src/Core/MathFunctions.h: In instantiation of ‘static NewType Eigen::internal::cast_impl<OldType, NewType>::run(const OldType&) [with OldType = ceres::Jet<double, 6>; NewType = int]’:

/usr/include/eigen3/Eigen/src/Core/MathFunctions.h:365:34: error: invalid static_cast from type ‘const ceres::Jet<double, 30>’ to type ‘int’

PoseEstimation will crash

When I run PoseEstimation, will crash when ceres start to optimize, I guess it is related to pcl version, which pcl version, eigen version should be used?

or provide a docker file ?

@arjunskumar Hello. Solved, my friend.

@arjunskumar Hello. Solved, my friend.

What version of ROS are you using? I was using Kinetic.

Here'e what was going on:

The repo requires Eigen >= 3.3. Eigen is the dependency of PCL, and Ceres. The problem was mainly because 2 different versions of Eigen are existing in my system:

  • The Eigen >= 3.3 that I tried to build from source to meet the requirement.
  • The pre-built binary of Eigen (libeigen3-dev), which is 3.2.9 for Kinetic, as it is the dependency of pre-built PCL, which is 1.7.2 by sudo apt install libpcl-dev.

I tried to remove libpcl-devand libeigen3-dev. But believe me, this will mess things up.

Now 2 options are viable:

  1. Modify this line of CMakeLists.txt to tell LIO-Livox to use Eigen >= 3.3
  2. Switch to Melodic (docker, fresh install, ...), to take advantage of the pre-built binaries that already meet the requirement: Eigen 3.3.4 and PCL

Just pick one.

Originally posted by @congphase in #9 (comment)

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.