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

Using Livox mid 70 get bad result #3

Closed
gongyue666 opened this issue Jan 5, 2022 · 9 comments
Closed

Using Livox mid 70 get bad result #3

gongyue666 opened this issue Jan 5, 2022 · 9 comments

Comments

@gongyue666
Copy link

Hi, I use Livox mid 70 with wheel odometry and IMU, but the localization result is not good, the robot pose always "jump" when running. any idea to make a better result (stable, smooth, continues path)

@fercabe
Copy link
Member

fercabe commented Jan 5, 2022

Hi,

Well, without more information regarding the environment, the map, or the sensor data I can only suggest to check the following aspects:

  • Be sure to properly initialize the position of the robot into the map.
  • Verify your odometry is accurate enough, and that it is properly published in TF. An easy way to check this is to visualize in rviz the laser with the parameter "Decay time" set to 10 for example, and with the "Fixed frame" set to your odom frame. If the odometry is good enough you should see how the laser scans more or less matching with slow drifting.
  • Try to run DLL using no odometry, does it stop jumping? To do it so, just add the following line to your launch file and set the right odom and base_link TF to DLL:
    <node pkg="tf" type="static_transform_publisher" name="odom_tf" args="0 0 0 0 0 0 odom base_link 10" />

That said, the field of view of the "Livox mid 70" is short in comparison to rotating lasers. Bigger FoV helps to estimate rotations better, and to deal with low texture scenarios. So I am not sure about the behaviour of DLL with such restricted FoV.

Please, verify the points above. If the problem persist, the only way to help you would be to get access to your rosbag and map in order to see in details what is going on.

Regards!
Fernando Caballero

@gongyue666
Copy link
Author

gongyue666 commented Jan 7, 2022

Hi thanks for your reply, I just saw it. My environment is Ubuntu 20.04, ros noetic, cpu intel 9700, 500G SSD. Here is my test data and launch file and alse my odometry I think is good enough, I have test it many times.https://drive.google.com/file/d/14H7SNDO2379i9mR0yc5_Plxm0A1Mdn1G/view?usp=sharing

@gongyue666
Copy link
Author

Information about Livox Mid 70 is here:https://www.livoxtech.com/mid-70

@fercabe
Copy link
Member

fercabe commented Jan 7, 2022

Hi,

Watching your data I can see that the Livox TF is tilted up like 35 degrees, is that correct? Because the sensor information make me feel that the sensor is just looking forward without tilt angle

Fernando

@gongyue666
Copy link
Author

yes,my lidar sensor is installed not forward, about 30 degree up to the floor

@gongyue666
Copy link
Author

3881641564705_ pic

@gongyue666
Copy link
Author

The silver cube is lidar sensor, Livox mid 70. and I tried to merge 5 frames of data into 1 frame to increase the number of point clouds, and then perform subsequent processing, but the effect did not improve much.

@gongyue666
Copy link
Author

any idea?

@fercabe
Copy link
Member

fercabe commented Mar 17, 2022

Hi,

I am sorry for the late answer, but it took me more than I expected finding the reason of the error, and together with IROS deadlines.....

So, there were some errors in the launch file you sent, and in the rosbag you are using to test. First, the easy thing, the launch file:

  • You have to set the use_sim_time flag to true. Otherwise, the TFs into the bags are all of them discarded because they are too old.
  • You also have to provide a good initial solution. DLL does not need centimetre accuracy for the initial solution, something approximate will be enough. But you were setting the initial position to (0,0,0,0), and the actual initial position was (7, 17, 0, 1).

It was easy to find theses errors, the complex part was to know why DLL did not work well with your data. And the reason behind was the odometry, as I mentioned in my first answer. Although your wheel odometry is very precise, a close look to the data shows that the base_link is tilted up about 20 degrees (see the image bellow). My guess is that your IMU or the part of the TF tree related with the IMU was biased.

giraffe_base_link

DLL makes use of the IMU to tilt compensate the point-cloud for roll and pitch, otherwise it makes use of the odomtry. But in this cae, both IMU and odometry were affected by the same bias. I programmed a quick patch to check this idea, you can find the source code attached. It basically creates a new frame called odomFixed that removes the roll and pitch angles from odom. Bellow you can see the map that is generated using odom (top), and using odomFixed (bottom). You can see how the data makes much more sense now.

giraffe_odom_map
giraffe_odomFixed_map

Using this patch and properly setting up the launch files, I was able to properly localize the robot with respect to the map, but it was a little jumpy. Probably, the patch is not perfect, so I recommend you to fix the IMU problem, so that you can use the data without patches. I also attach the launch file used into the zip.

patch_and_launch.zip

If everything is ok, please proceed to close this issue.

@fercabe fercabe closed this as completed Mar 21, 2022
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

2 participants