LIO-SAM icon indicating copy to clipboard operation
LIO-SAM copied to clipboard

Is the statement about extrinsicRPY in the readme wrong?

Open inntoy opened this issue 2 years ago • 51 comments

Hi @TixiaoShan, thanks for your execllent work! However, after reading your answer in #6 and the explaination in the IMU alignment part of readme, I am still puzzled about the physical meaning of extrinsicRPY. In the IMU alignment part you said that "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", which implies that extrinsicRPY is q_l_b. But in the yaml file you gave, the physical meaning of extrinsicRPY is to transform the coordinates in the lidar coordinate system to the imu coordinate system, which is q_b_l.

What's more, in the function imuConverter(), the calculation of q_final also verifies that my statement is correct, q_final is q_w_lk, w is the world frame (usually the ENU coordinate system), lk is the lidar frame in time stamp k. Imu's orientation q_from is q_w_bk, bk is the imu frame in time stamp k. If the meaning of extRPY is according to the readme: ** q_from * extQRPY = q_w_bk * q_lk_bk ≠ q_final** If the meaning of extRPY is according to my statement: q_from * extQRPY = q_w_bk * q_bk_lk = q_final So, is the statement about extrinsicRPY in the readme wrong?

Finally, thanks again for your work. Below is a map created with lio-sam. What a nice and beautiful map! mapping

inntoy avatar Apr 23 '22 02:04 inntoy

@inntoy Thanks for pointing this out. When I wrote the readme and comments, there were some wrong descriptions about rotations. If you feel up to it, please free to send a push to the repo.

It's great to see the results like this.

TixiaoShan avatar Apr 23 '22 14:04 TixiaoShan

@TixiaoShan Thanks for such a quick reply. I'm glad my understanding is correct. I will submit a revised description of extrinsicRPY.

inntoy avatar Apr 25 '22 10:04 inntoy

@inntoy I also find in ImuConverter function that the q_final expression is wrong. But in my opinion, I preserve the yaml extrinsic rotation and transition which imply the convert a point from imu coordinate to lidar coordinate. And then, I change the q_final expression to Eigen::Quaterniond q_final = q_from * extQRPY.inverse(); and that's it. I infer that the usage of extQRPY and extTrans is right in preintegration and other parts. Is that right?

Richardson-Chong avatar Apr 26 '22 12:04 Richardson-Chong

@Richardson-Chong I think your approach is correct. extQRPY(extrinsicRPY) is only used to calculate q_final in the code.

inntoy avatar Apr 26 '22 14:04 inntoy

Have you ever noticed the imu2Lidar and lidar2Imu in imuPreintegration? In my mind, here the author want to predict states first in imu coordinate and then convert to lidar coor. However, the transition imu2Lidar and lidar2Imu are not right in the expression of gtsam::Pose3 imu2Lidar = gtsam::Pose3(gtsam::Rot3(1, 0, 0, 0), gtsam::Point3(-extTrans.x(), -extTrans.y(), -extTrans.z())); gtsam::Pose3 lidar2Imu = gtsam::Pose3(gtsam::Rot3(1, 0, 0, 0), gtsam::Point3(extTrans.x(), extTrans.y(), extTrans.z()));. In my mind they should be: Eigen::Quaterniond q = Eigen::Quaterniond(extRot); gtsam::Pose3 lidar2Imu = gtsam::Pose3(gtsam::Rot3(q.w(), q.x(), q.y(), q.z()), gtsam::Point3(extTrans.x(), extTrans.y(), extTrans.z())); gtsam::Pose3 imu2Lidar = lidar2Imu.inverse(); And here the IMU msgs will not be transformed by imuConverter because the IMU-Preintergration and IMU-predict work in imu coor. I don't know whether my opinion is right. @TixiaoShan @inntoy

Richardson-Chong avatar Apr 27 '22 02:04 Richardson-Chong

@Richardson-Chong In imuHandler, with the ImuConverter function, imu raw data (acceleration and angular velocity) has been converted to another coordinate system b*. There is only a translation relationship between the coordinate system b* and the lidar coordinate system. Let's label the transformation represented imu2Lidar as T_b*_l, and I guesses that the transformation represented by the variable imuPose is T_w_b*. In this situation, lidarPose = imuPose.compose(imu2Lidar); can be expressed as T_w_l = T_w_b* x T_b*_l. So the author is correct

inntoy avatar Apr 27 '22 04:04 inntoy

You are right. Now the only thing I don't figure out is the gravity acceleration setting of Gtsam. boost::shared_ptr<gtsam::PreintegrationParams> p = gtsam::PreintegrationParams::MakeSharedU(imuGravity); Should it be the gravity vector of initial Body coordinate? If it's true, the whole process should be in Body coor, not the changed B* coor.

Richardson-Chong avatar Apr 27 '22 06:04 Richardson-Chong

@Richardson-Chong In my opinion, the gravity vector should be in the world coordinate (i.e. (0,0,-9.8)). That's why the author said to use a nine-axis IMU, because it can give us the quaternion q_wb.

inntoy avatar Apr 27 '22 07:04 inntoy

What I mean is that if author use B* as coordinate, should the gravity acceleration also be transformed to B*? But in the code, imuGravity is just equal to g in B.

Richardson-Chong avatar Apr 27 '22 08:04 Richardson-Chong

@Richardson-Chong Actually, the initial body coordinate (B0) is not necessarily the world coordinate. It can be a rotation between them, which is q_wb0 (get from imu attitude). I think the imu-integration process is carried out in the world coordinate. I also find that initialization in function updateInitialGuess will save the information of q_wb0. But I have not fully understood this part. If you understand this part, please let me know.

inntoy avatar Apr 27 '22 09:04 inntoy

不好意思,这里为了理解的更清楚点,就直接中文给您回复了: 关于这里IMU的测量和外参的转换,我还是有点不理解:为什么在imu_handler当中会把IMU的测量值转换到lidar坐标系下,但是在预积分的时候,IMU还需要在自身的坐标系下进行积分呢?我的理解是:整体在状态估计的时候应该是以Lidar作为body系主体,依次向下进行状态递推的

Gatsby23 avatar May 04 '22 12:05 Gatsby23

imuConverter那个函数只是把imu测量值转换到了一个和lidar坐标系只有平移而没有旋转关系的坐标系b*。那预积分其实都是在b*下进行的,那肯定是要加上平移关系才能转换到lidar坐标系下(imu2Lidar里只有平移)。

inntoy avatar May 05 '22 05:05 inntoy

imuConverter那个函数只是把imu测量值转换到了一个和lidar坐标系只有平移而没有旋转关系的坐标系b*。那预积分其实都是在b*下进行的,那肯定是要加上平移关系才能转换到lidar坐标系下(imu2Lidar里只有平移)。

OK,我大致明白了,我仔细看下源码,后面再和您详细交流下

Gatsby23 avatar May 05 '22 05:05 Gatsby23

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

stale[bot] avatar Nov 02 '22 04:11 stale[bot]

您好,您的邮件我已收到。————祝您每天都有个好心情!

inntoy avatar Nov 02 '22 04:11 inntoy

您好,您的邮件我已收到。————祝您每天都有个好心情!

can i ask you something?

himhan34 avatar Dec 08 '22 08:12 himhan34

您好,您的邮件我已收到。————祝您每天都有个好心情!

inntoy avatar Dec 08 '22 08:12 inntoy

Thanks for replying . i am trying to know how to implement the 45 degree tilted velodyne lidar(vlp16) with the imu(3DM-GQ7 GNSS). i just tried to modify extrinsic matrix in the params.yaml.. is there a method that i can do?

2022년 12월 8일 (목) 오후 5:49, Omega_lin @.***>님이 작성:

您好,您的邮件我已收到。————祝您每天都有个好心情!

— Reply to this email directly, view it on GitHub https://github.com/TixiaoShan/LIO-SAM/issues/335#issuecomment-1342283905, or unsubscribe https://github.com/notifications/unsubscribe-auth/ALFL7JY7M36LLVHWXNOERR3WMGOKXANCNFSM5UD6S6PA . You are receiving this because you commented.Message ID: @.***>

himhan34 avatar Dec 08 '22 09:12 himhan34

@himhan34 It should be enough to provide extrinsic matrix directly. I guess you are using KAIST dataset? I haven't tested LIO-SAM on this dataset, can you share the running results?

inntoy avatar Dec 08 '22 11:12 inntoy

wow thanks for replying. i am using my own dataset which is recorded in my lab's corridor .

this is a extrinsic matrix that i used

extrinsicRot: [1,0,0, 0,1,0, 0,0,1]

extrinsicRPY: [0,1,0, 1,0,0, 0,0,-1]

and this is a results. Screenshot from 2022-12-08 20-12-27

really thanks for your reply. i am handling this problem in 3 weeks

himhan34 avatar Dec 08 '22 11:12 himhan34

wow thanks for replying. i am using my own dataset which is recorded in my lab's corridor .

this is a extrinsic matrix that i used

extrinsicRot: [1,0,0, 0,1,0, 0,0,1]

extrinsicRPY: [0,1,0, 1,0,0, 0,0,-1]

really thanks for your reply. i am handling this problem in 3 weeks

Um, is the coordinate system of each sensor the same as in the picture I drew? att means the attitude, acc means the acceleration. @himhan34

device

inntoy avatar Dec 08 '22 11:12 inntoy

2022년 12월 8일 (목) 오후 8:59, Omega_lin @.***>님이 작성:

wow thanks for replying. i am using my own dataset which is recorded in my lab's corridor .

this is a extrinsic matrix that i used

extrinsicRot: [1,0,0, 0,1,0, 0,0,1]

extrinsicRPY: [0,1,0, 1,0,0, 0,0,-1]

really thanks for your reply. i am handling this problem in 3 weeks

Um, is the coordinate system of each sensor the same as in the picture I drew? att means the attitude, acc means the acceleration. @himhan34 https://github.com/himhan34

[image: device] https://user-images.githubusercontent.com/39400163/206441116-46d1a2a6-cfcf-4eae-ba9b-3e0edfc1e680.png

— Reply to this email directly, view it on GitHub https://github.com/TixiaoShan/LIO-SAM/issues/335#issuecomment-1342619868, or unsubscribe https://github.com/notifications/unsubscribe-auth/ALFL7J6UABWHCYDBPCRMPODWMHES3ANCNFSM5UD6S6PA . You are receiving this because you were mentioned.Message ID: @.***>

himhan34 avatar Dec 08 '22 12:12 himhan34

20221208_210241.jpg

himhan34 avatar Dec 08 '22 12:12 himhan34

for the not 45 degree tilted i think the coordinate is like this.

himhan34 avatar Dec 08 '22 12:12 himhan34

I found that extrinsicRPY seem to be wrong, it should be the unit matrix, that is: [1,0,0, 0,1,0, 0,0,1] @himhan34

inntoy avatar Dec 08 '22 12:12 inntoy

20221208_211610.jpg

himhan34 avatar Dec 08 '22 12:12 himhan34

the pic that i uploaded first was the flat situation, the real one is the next pic

himhan34 avatar Dec 08 '22 12:12 himhan34

interestingly this is a default pointcloud when i play the rosbag in the rviz Screenshot from 2022-12-08 21-24-52

himhan34 avatar Dec 08 '22 12:12 himhan34

and when i set the parameter like this Screenshot from 2022-12-08 21-27-50

and the pointcloud is like this, Screenshot from 2022-12-08 21-27-27

himhan34 avatar Dec 08 '22 12:12 himhan34

Oh, I see. It looks like your extrinsics are wrong. Maybe you can use a calibration tool to get the extrinsics between LiDAR and IMU. I advise this: https://github.com/hku-mars/LiDAR_IMU_Init. But please note that the extrinsic matrix obtained by using this method is T_imu_lidar. And LIO-SAM uses T_lidar_imu, which can be obtained by taking the inverse of the matrix T_imu_lidar. @himhan34

inntoy avatar Dec 08 '22 12:12 inntoy