JokerJohn / LIO_SAM_6AXIS

LIO_SAM for 6-axis IMU and GNSS.
585 stars 116 forks source link

The IMU lidar coordinate frame transformation for the hilti slam dataset #22

Closed JzHuai0108 closed 1 year ago

JzHuai0108 commented 1 year ago

Hi @JokerJohn, thank you for sharing the work. I am running the codebase with the hiltislam dataset, e.g. exp01.

Can you please clarify how you compute the lidar IMU extrinsic parameters R_lidar_imu? The rotation part R_lidar_imu are given in here as

  extrinsicRot: [ 1, 0, 0;
                  0, 1, 0;
                  0, 0, -1 ].

From hiltislam calibration file, we have R_imu_pandar = [0, -1, 0; -1, 0, 0; 0, 0, -1] According to the pointcloud projection for hesai in here, we know that R_velodyne_pandar = [0, -1, 0; 1, 0, 0; 0, 0, 1];

To my understanding, extrinsicRot = R_velodyne_imu = R_velodyne_pandar * R_imu_pandar^T = [ 1, 0, 0; 0, -1, 0; 0, 0, -1 ]. But this is different from that given in here.

Can you please clarify this point?

FYI, I have tried both sets of parameters, the matrix given in params_pandar.yaml seems to work better, but still is not visually satisfactory.

JokerJohn commented 1 year ago

Hi, @JzHuai0108, Thanks for this question. For the hesai lidar in the HILTI dataset, I have adjusted its coordinate system in the codes of LIO_SAM_6axis, which is consistent with the REP105 convention, the same as the Velodyne lidar. For details, please refer to here image

Why do these adjustments are detailed in the following document. https://github.com/JokerJohn/LIO_SAM_6AXIS/blob/main/doc/adaption.md

JzHuai0108 commented 1 year ago

Hi @JokerJohn , I appreciate your quick reply. I perused the adaption doc and the source code of pcl moveFromROSMsg function. However, my derivation still leads me to extrinsicRot = R_velodyne_imu = R_velodyne_pandar * R_imu_pandar^T = [ 1, 0, 0; 0, -1, 0; 0, 0, -1 ].

  1. Apparently, the moveFromROSMsg does not do any coordinate transform.
  2. In the diagram, the math formula is correct to me, but the drawing of the pandar coordinate frame in red is problematic. Shouldn't the y axis be reversed? Otherwise, if we stick with the wrong drawing, then I arrive at extrinsicRot = [ 1, 0, 0; 0, 1, 0; 0, 0, -1 ] (as given in pandar.yaml) which will transform a right hand coordinate frame to a left handed coordinate frame. But we are not using any right handed coordinate frame. So this is a contradiction. Can you please resolve this inconsistency?
JokerJohn commented 1 year ago

I understand , you can refer to this issue in the following HILTI repo first. HILTI ISSUE

The coordinate system diagram provided by the organizer is actually problematic, although I am not sure which version you are looking at, I will update the code as soon as possible Making the configuration set in YAMLfile consistent with the configuration directly provided by HILTI. image

JokerJohn commented 1 year ago

Hi @JokerJohn , I appreciate your quick reply. I perused the adaption doc and the source code of pcl moveFromROSMsg function. However, my derivation still leads me to extrinsicRot = R_velodyne_imu = R_velodyne_pandar * R_imu_pandar^T = [ 1, 0, 0; 0, -1, 0; 0, 0, -1 ].

  1. Apparently, the moveFromROSMsg does not do any coordinate transform.
  2. In the diagram, the math formula is correct to me, but the drawing of the pandar coordinate frame in red is problematic. Shouldn't the y axis be reversed? Otherwise, if we stick with the wrong drawing, then I arrive at extrinsicRot = [ 1, 0, 0; 0, 1, 0; 0, 0, -1 ] (as given in pandar.yaml) which will transform a right hand coordinate frame to a left handed coordinate frame. But we are not using any right handed coordinate frame. So this is a contradiction. Can you please resolve this inconsistency?

I have solved the problem, let me explain as follows

  1. If the IMU and Pandar coordinate systems displayed in the CAD model provided by HILTI are correct and based on this, then some adjustments should be made to extrinsics in the calibration file provided by HILTI. This is because the axis order of Pandar is inconsistent with traditional Velodyne lidars(XYZ front-left-right). image

2.The extrinsicRot parameter in LIO-SAM is used to align the IMU data to the Pandar coordinate system, so it should be R_IMU_Pandar, and take the inverse matrix of the extrinsics (R_Pandar_IMU) provided in the HILTI calibration file. image

Look at my parameter settings below image

image

JzHuai0108 commented 1 year ago
  1. It is interesting to see that the transformation of laser points is removed in your last picture of the cachePointCloud function (though the main branch of the LIO_SAM_6AXIS has not been updated). This is what I am doing now. IMHO, I think we can safely ignore REP105 forward left up coordinate convention as long as the lidar sensor coordinate frame has z pointing upward because a) the velodyne lidar uses a right forward up sensor coordinate frame per its user manual and lio-sam does not transform its points, b) the Hesai lidar uses a left back up sensor coordinate frame per its user manual.
  2. As discussed in the Hilti issue, the lidar frame drawn in the diagram is not the Hesai lidar sensor frame. I did not take time to figure it out what it is because I honestly think it is largely irrelevant as long as we have the calibration files.
  3. I am not sure about the nomenclature for R_IMU_Pandar in "The extrinsicRot parameter in LIO-SAM is used to align the IMU data to the Pandar coordinate system, so it should be R_IMU_Pandar". It seems that in your diagram it means lidar relative to IMU. To my understanding, the extrinsicRot should be IMU relative to lidar, see here. And this value can be read off the lidar_calibration.yaml. A quaternion to rotation matrix conversion gives extrinsicRot = [ 0, -1, 0; -1, 0, 0; 0, 0, -1 ]. As for the extrinsicRot given in the second to last picture, [0, -1, 0; 1, 0, 0; 0, 0, -1], it will result in a left-hand coordinate frame, IMHO. As an aside, the extrinsicRPY should be the same as extrinsicRot for Hiltislam 2022 if the LIO-SAM's commit is merged. But so far, this commit is not reflected in this repo. That means, extrinsicRPY is the transpose of extrinsicRot per this codebase.
  4. Conclusion: with the above settings, lio-sam-6axis gives impressive results on hiltislam 2022. Kudos.