Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

when online refinement start working, the lidar lost direction #43

Open
Marshall-Hu opened this issue Nov 25, 2022 · 20 comments
Open

when online refinement start working, the lidar lost direction #43

Marshall-Hu opened this issue Nov 25, 2022 · 20 comments

Comments

@Marshall-Hu
Copy link

Thanks your nice work. I get some confused thing when I try myself IMU.

I try run this code with Avia Lidar with internal IMU. That is works fine.
When I change imu topic to my external IMU. It seems works well when Init and move around Lidar. When the online refinement Or switch to FastLIO, it jusr break up. There is a video and result image:
Kazam_screenshot_00002

1.mp4
@Marshall-Hu
Copy link
Author

After using Livox_ros_lidar modified by your team. "Time Lag IMU to LiDAR " seems to be okay while the result is still so bad.

result:
[Final Result] Rotation LiDAR to IMU = -7.986911 -28.632727 0.648854 deg
[Final Result] Translation LiDAR to IMU = -0.030898 0.007697 -0.130860 m
[Final Result] Time Lag IMU to LiDAR = -0.06435479 s
[Final Result] Bias of Gyroscope = -1.946176 -0.298351 0.533426 rad/s
[Final Result] Bias of Accelerometer = -0.419254 0.025881 0.195204 m/s^2
[Final Result] Gravity in World Frame = -0.156993 0.171372 -9.402240 m/s^2

@zfc-zfc
Copy link
Collaborator

zfc-zfc commented Nov 25, 2022

After using Livox_ros_lidar modified by your team. "Time Lag IMU to LiDAR " seems to be okay while the result is still so bad.

result: [Final Result] Rotation LiDAR to IMU = -7.986911 -28.632727 0.648854 deg [Final Result] Translation LiDAR to IMU = -0.030898 0.007697 -0.130860 m [Final Result] Time Lag IMU to LiDAR = -0.06435479 s [Final Result] Bias of Gyroscope = -1.946176 -0.298351 0.533426 rad/s [Final Result] Bias of Accelerometer = -0.419254 0.025881 0.195204 m/s^2 [Final Result] Gravity in World Frame = -0.156993 0.171372 -9.402240 m/s^2

image
Is this parameter correct?

@Marshall-Hu
Copy link
Author

I set 9.805 for sure

@zfc-zfc
Copy link
Collaborator

zfc-zfc commented Nov 25, 2022

the

I recommend verifying the output data of your external IMU, to see if the acceleration and gyroscope are normal. The calibrated gyroscope bias seems abnormal.

@Marshall-Hu
Copy link
Author

Marshall-Hu commented Nov 25, 2022

It seems work fine as usual until X Y Z get 100% to online refinement. And then the lidar do that confusing rotation

After using Livox_ros_lidar modified by your team. "Time Lag IMU to LiDAR " seems to be okay while the result is still so bad.
result: [Final Result] Rotation LiDAR to IMU = -7.986911 -28.632727 0.648854 deg [Final Result] Translation LiDAR to IMU = -0.030898 0.007697 -0.130860 m [Final Result] Time Lag IMU to LiDAR = -0.06435479 s [Final Result] Bias of Gyroscope = -1.946176 -0.298351 0.533426 rad/s [Final Result] Bias of Accelerometer = -0.419254 0.025881 0.195204 m/s^2 [Final Result] Gravity in World Frame = -0.156993 0.171372 -9.402240 m/s^2

image Is this parameter correct?

It seems work fine as usual until X Y Z get 100% to online refinement. And then the lidar do that confusing rotation.

I will try it with other IMU.

@zfc-zfc
Copy link
Collaborator

zfc-zfc commented Nov 25, 2022

It seems work fine as usual until X Y Z get 100% to online refinement. And then the lidar do that confusing rotation

After using Livox_ros_lidar modified by your team. "Time Lag IMU to LiDAR " seems to be okay while the result is still so bad.
result: [Final Result] Rotation LiDAR to IMU = -7.986911 -28.632727 0.648854 deg [Final Result] Translation LiDAR to IMU = -0.030898 0.007697 -0.130860 m [Final Result] Time Lag IMU to LiDAR = -0.06435479 s [Final Result] Bias of Gyroscope = -1.946176 -0.298351 0.533426 rad/s [Final Result] Bias of Accelerometer = -0.419254 0.025881 0.195204 m/s^2 [Final Result] Gravity in World Frame = -0.156993 0.171372 -9.402240 m/s^2

image Is this parameter correct?

It seems work fine as usual until X Y Z get 100% to online refinement. And then the lidar do that confusing rotation

Or you can share a bag by uploading it to onedrive and then give me a link.

@Marshall-Hu
Copy link
Author

It seems work fine as usual until X Y Z get 100% to online refinement. And then the lidar do that confusing rotation

After using Livox_ros_lidar modified by your team. "Time Lag IMU to LiDAR " seems to be okay while the result is still so bad.
result: [Final Result] Rotation LiDAR to IMU = -7.986911 -28.632727 0.648854 deg [Final Result] Translation LiDAR to IMU = -0.030898 0.007697 -0.130860 m [Final Result] Time Lag IMU to LiDAR = -0.06435479 s [Final Result] Bias of Gyroscope = -1.946176 -0.298351 0.533426 rad/s [Final Result] Bias of Accelerometer = -0.419254 0.025881 0.195204 m/s^2 [Final Result] Gravity in World Frame = -0.156993 0.171372 -9.402240 m/s^2

image Is this parameter correct?

It seems work fine as usual until X Y Z get 100% to online refinement. And then the lidar do that confusing rotation

Or you can share a bag by uploading it to onedrive and then give me a link.

lidar topic: /livox/lidar
IMU topic: /imu/data_raw
https://tjueducn-my.sharepoint.com/:u:/g/personal/h_shengfeng_tju_edu_cn/EXVjHxXoDGlIs6SotO384TUBi12h7Sw2Lz0VzdVO3mdtrw?e=5yXsnf

@zfc-zfc
Copy link
Collaborator

zfc-zfc commented Nov 25, 2022

The angular velocity of your bag is too large, I guess it's because the unit is degree/s but our code needs rad/s. By converting the input angular velocity to rad/s, the calibration is OK.
image

Converting degree/s to rad/s:
image

Result:

111-2022-11-25_18.39.06.mp4

@Marshall-Hu
Copy link
Author

ngular velocity of your bag is too large, I guess it's because the unit is degree/s but our code needs rad/s

That solved this problem. Thanks to you zfc helping me out.
Have a nice day...

ps:
Add code to laserMapping.cpp line 423

@edwardes2201
Copy link

Hello, can you share the laserMapping.cpp file, I tried to add the lines to pass to rad/sec but I get the same error as you at the beginning.

@Marshall-Hu
Copy link
Author

Hello, can you share the laserMapping.cpp file, I tried to add the lines to pass to rad/sec but I get the same error as you at the beginning.

can u just post your code( executed function) here? My .cpp file dropped long time ago.

@xbnz-1997
Copy link

@Marshall-Hu Hi,could you tell me the avia calibration parameter which you get with the built-in IMU? Thank you very much. I get the parameters I got are not consistent with the avia documentation.

@Marshall-Hu
Copy link
Author

@Marshall-Hu Hi,could you tell me the avia calibration parameter which you get with the built-in IMU? Thank you very much. I get the parameters I got are not consistent with the avia documentation.

IMU 坐标原点 O' 在点云坐标系 O-XYZ 上的坐标为(-41.65,-23.26,28.40)(单位:mm)。https://terra-1-g.djicdn.com/65c028cd298f4669a7f0e40e50ba1131/Download/Avia/Livox%20Avia%20用户手册中文.pdf

@xbnz-1997
Copy link

(-41.65,-23.26,28.40)
您好,请问您通过lidar_imu_init算法标出来的结果和avia 用户手册一样?我标了好多次都不一样,用作者提供的bag跑结果也不是。如果您标出来的和avia用户手册一样那可能是我操作有误了。

@Marshall-Hu
Copy link
Author

(-41.65,-23.26,28.40)
您好,请问您通过lidar_imu_init算法标出来的结果和avia 用户手册一样?我标了好多次都不一样,用作者提供的bag跑结果也不是。如果您标出来的和avia用户手册一样那可能是我操作有误了。

你是外置imu还是怎么,这个值可以拿来做参考啊,不会一样的。但如果差的很多我感觉,可以检查下xyz轴是不是朝向一致的

@xbnz-1997
Copy link

你是外置imu还是怎么
我是用的avia的内置IMU,直接跑的作者给的bag包,加速度也设置为1,但是结果偏差较大,标定结果与用户手册正负号都不一样

@Marshall-Hu
Copy link
Author

你是外置imu还是怎么
我是用的avia的内置IMU,直接跑的作者给的bag包,加速度也设置为1,但是结果偏差较大,标定结果与用户手册正负号都不一样

没明白,你要跑自己的bag包才能有自己的imu和lidar的转换关系。你跑作者的出来也是他搭建的设备的标定结果。

假如你直接用avia和内置其内置的imu的bag包出来的标定,也不会和手册一样的。
这个标定结果,我是结合r3live另一个项目配合使用自己的外置imu,能够保证2者比较好的工作。不清楚你的需求,只能说这么多了

@Marshall-Hu Marshall-Hu reopened this Dec 26, 2023
@xbnz-1997
Copy link

我是自采了bag包,但结果不对,所以用了下作者上传的用avia和其内置IMU采集的bag包进行验证,发现都与手册相差很多。想验证下这个标定精度能有多高,谢谢您的耐心解答,再次感谢!

@LiSi0205
Copy link

现在这个代码是不是优化了?是不是已经删除了,我并没有找到里面有这三行代码

@Shidabot
Copy link

Shidabot commented Sep 4, 2024

ngular velocity of your bag is too large, I guess it's because the unit is degree/s but our code needs rad/s

That solved this problem. Thanks to you zfc helping me out. Have a nice day...

ps: Add code to laserMapping.cpp line 423

The angular velocity of your bag is too large, I guess it's because the unit is degree/s but our code needs rad/s. By converting the input angular velocity to rad/s, the calibration is OK. image

Converting degree/s to rad/s: image

Result:

111-2022-11-25_18.39.06.mp4

Thank you so much for your suggestion! I applied the method you provided, and it successfully resolved this trouble. I really appreciate your help!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

6 participants