imu data preprocessing?

1,161 views
Skip to first unread message

zyli...@gmail.com

unread,
Nov 4, 2016, 1:18:00 AM11/4/16
to google-cartographer
Hi,

First I want to thank the developers of cartographer for their awesome work! We tried to run it with an velodyne lidar and our imu to do 3D slam and the result looks good!

However, we noticed that during the process, our progressively built submaps were not as  well aligned as the demo 3d data, and I had to set scans_per_accumulation=40 (the default was 160) to increase the frequency of background loop-closure, which clearly helped re-aligning the submaps.

I'm suspecting that the imu data (gyro+accelerometer) data we fed into cartographer is the cause.

My question is, are we supposed to pre-process the imu data, such as de-biasing, or just provide raw data?

Also, would providing our own attitude estimation and the covariance (currently we only fed rates and accelerations, like the demo file) help with the SLAM performance?

Thanks!

Holger Rapp

unread,
Nov 4, 2016, 12:11:58 PM11/4/16
to zyli...@gmail.com, google-cartographer
On Thu, Nov 3, 2016 at 10:18 PM, <zyli...@gmail.com> wrote:
Hi,

First I want to thank the developers of cartographer for their awesome work! We tried to run it with an velodyne lidar and our imu to do 3D slam and the result looks good!

However, we noticed that during the process, our progressively built submaps were not as  well aligned as the demo 3d data, and I had to set scans_per_accumulation=40 (the default was 160) to increase the frequency of background loop-closure, which clearly helped re-aligning the submaps.

​This setting defines how many scans are accumulated before a scan-match is attempted. It therefore also affects local slam. All settings for loop closing are in sparse_pose_graph.lua​.

 

I'm suspecting that the imu data (gyro+accelerometer) data we fed into cartographer is the cause.

My question is, are we supposed to pre-process the imu data, such as de-biasing, or just provide raw data?

​Cartographer does no IMU bias estimation and no online sensor extrinsic calibration. So yes, you should probably remove IMU biases yourself. 


Also, would providing our own attitude estimation and the covariance (currently we only fed rates and accelerations, like the demo file) help with the SLAM performance?

​Maybe :). The kalman filter doing sensor fusion is a finicky beast, it is hard to know what appeases it. We are planing to remove it through a optimization based sensor fusion which is easier to tune and understand.​

 

Thanks!

--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsub...@googlegroups.com.
To post to this group, send email to google-cartographer@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/google-cartographer/570c396b-ef2f-431c-8d6a-85cf5841eda4%40googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Google Germany GmbH
Erika-Mann-Straße 33
80331 München

Registergericht und -nummer: Hamburg, HRB 86891
Sitz der Gesellschaft: Hamburg
Geschäftsführer: Matthew Scott Sucherman, Paul Terence Manicle


zyli...@gmail.com

unread,
Nov 4, 2016, 1:40:48 PM11/4/16
to google-cartographer, zyli...@gmail.com
Hi, Holger,

Thank you for your reply! That really helps!

A related question is that is there a tuning knob on how much I trust the imu? If I have a good imu I could trust it more in both mapping and localization, while if I have a bad imu I need to rely more heavily on the scan match.

Another question about 3D map creation, in one of the post you said the 3D map writing "only writes data that was kept in memory for SLAMing". Say, if I walk for a long distance,  do you mean the final map will only contain the final part of the map, or the final map removes/filters many repetitive points I collected on my way? I guess you meant the latter, right?

Thank you so much!
Zhiyuan


On Friday, November 4, 2016 at 9:11:58 AM UTC-7, Holger Rapp wrote:
On Thu, Nov 3, 2016 at 10:18 PM, <zyli...@gmail.com> wrote:
Hi,

First I want to thank the developers of cartographer for their awesome work! We tried to run it with an velodyne lidar and our imu to do 3D slam and the result looks good!

However, we noticed that during the process, our progressively built submaps were not as  well aligned as the demo 3d data, and I had to set scans_per_accumulation=40 (the default was 160) to increase the frequency of background loop-closure, which clearly helped re-aligning the submaps.

​This setting defines how many scans are accumulated before a scan-match is attempted. It therefore also affects local slam. All settings for loop closing are in sparse_pose_graph.lua​.

 

I'm suspecting that the imu data (gyro+accelerometer) data we fed into cartographer is the cause.

My question is, are we supposed to pre-process the imu data, such as de-biasing, or just provide raw data?

​Cartographer does no IMU bias estimation and no online sensor extrinsic calibration. So yes, you should probably remove IMU biases yourself. 


Also, would providing our own attitude estimation and the covariance (currently we only fed rates and accelerations, like the demo file) help with the SLAM performance?

​Maybe :). The kalman filter doing sensor fusion is a finicky beast, it is hard to know what appeases it. We are planing to remove it through a optimization based sensor fusion which is easier to tune and understand.​

 

Thanks!

--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsub...@googlegroups.com.
To post to this group, send email to google-ca...@googlegroups.com.

Holger Rapp

unread,
Nov 4, 2016, 1:54:22 PM11/4/16
to zyli...@gmail.com, google-cartographer
On Fri, Nov 4, 2016 at 10:40 AM, <zyli...@gmail.com> wrote:
Hi, Holger,

Thank you for your reply! That really helps!

A related question is that is there a tuning knob on how much I trust the imu? If I have a good imu I could trust it more in both mapping and localization, while if I have a bad imu I need to rely more heavily on the scan match.

​Yes, there are such knobs and tuning them will greatly impact the SLAM performance for a set of sensors. Unfortunately there are quite a lot of these parameters to tune (we will try to reduce them) and they are not yet well documented (we will fix this by EOY). The weights for scan matching, the covariances for the kalman filter and how often and how aggressively to loop close are among the most important ones. The local SLAM parameters are tuned in 'trajectory_builder_3d.lua' and the loop closing ones in 'sparse_pose_graph.lua'. Cranking up 'position_model_variance' and 'velocity_model_variance' means to trust the IMU less - also increasing the scan matcher weights means to trust the IMU less. Tuning is a lot of trial and error - once you found a reasonable setting for your sensors, the system is quite robust though, i.e. if you have 2 similar robots, tuning one and using the parameters on the other will work nicely.


Another question about 3D map creation, in one of the post you said the 3D map writing "only writes data that was kept in memory for SLAMing". Say, if I walk for a long distance,  do you mean the final map will only contain the final part of the map,

​No. ​

 
or the final map removes/filters many repetitive points I collected on my way? I guess you meant the latter, right?

​Yes, sorta. While SLAMIng we throw a lot away: most scans completely, and from scans most points. We only use the points you see in the visualization for SLAMing. The job of SLAM is just to get a correct timestamped trajectory. Therefore, when the trajectory is ended through the service call to the node, the generated assets only contain the points that we decided to keep in memory. 

However, once you have a nice trajectory, you can replay your sensor data into this trajectory and create nice stuff. We provide an asset writer to do just that. It can generate XRays (like the one attached, which is from the deutsche museum) and points in various data types.

 

Thank you so much!
Zhiyuan

On Friday, November 4, 2016 at 9:11:58 AM UTC-7, Holger Rapp wrote:
On Thu, Nov 3, 2016 at 10:18 PM, <zyli...@gmail.com> wrote:
Hi,

First I want to thank the developers of cartographer for their awesome work! We tried to run it with an velodyne lidar and our imu to do 3D slam and the result looks good!

However, we noticed that during the process, our progressively built submaps were not as  well aligned as the demo 3d data, and I had to set scans_per_accumulation=40 (the default was 160) to increase the frequency of background loop-closure, which clearly helped re-aligning the submaps.

​This setting defines how many scans are accumulated before a scan-match is attempted. It therefore also affects local slam. All settings for loop closing are in sparse_pose_graph.lua​.

 

I'm suspecting that the imu data (gyro+accelerometer) data we fed into cartographer is the cause.

My question is, are we supposed to pre-process the imu data, such as de-biasing, or just provide raw data?

​Cartographer does no IMU bias estimation and no online sensor extrinsic calibration. So yes, you should probably remove IMU biases yourself. 


Also, would providing our own attitude estimation and the covariance (currently we only fed rates and accelerations, like the demo file) help with the SLAM performance?

​Maybe :). The kalman filter doing sensor fusion is a finicky beast, it is hard to know what appeases it. We are planing to remove it through a optimization based sensor fusion which is easier to tune and understand.​

 

Thanks!

--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsubscribe...@googlegroups.com.
Google Germany GmbH
Erika-Mann-Straße 33
80331 München

Registergericht und -nummer: Hamburg, HRB 86891
Sitz der Gesellschaft: Hamburg
Geschäftsführer: Matthew Scott Sucherman, Paul Terence Manicle


--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsub...@googlegroups.com.

For more options, visit https://groups.google.com/d/optout.
xray_xy (1).png

zyli...@gmail.com

unread,
Nov 4, 2016, 2:07:11 PM11/4/16
to google-cartographer, zyli...@gmail.com
Hi, Holger,

Thank you so much for the detailed explanation!! Will spend more time and have more fun with it!

Best!

Thanks!

To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsub...@googlegroups.com.
Google Germany GmbH
Erika-Mann-Straße 33
80331 München

Registergericht und -nummer: Hamburg, HRB 86891
Sitz der Gesellschaft: Hamburg
Geschäftsführer: Matthew Scott Sucherman, Paul Terence Manicle


--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsub...@googlegroups.com.
To post to this group, send email to google-ca...@googlegroups.com.

Matt

unread,
Aug 20, 2017, 8:03:45 PM8/20/17
to google-cartographer
Hi all

@Zhiyuan, my setup may be somewhat similar to yours. Out of interest, what Velodyne LiDAR model did you use? and how have you got on with tuning? 

@Holger, I can't seem to find "position_model_variance" or "velocity_model_variance" in any of the .lua configuration files. Are these still exposed parameters?

Thanks as always for the help and feedback.

Matt

Damon Kohler

unread,
Aug 23, 2017, 6:34:12 AM8/23/17
to Matt, google-cartographer
Matt, this is a very old thread and those parameters no longer exist. There is a nascent tuning guide available here: https://google-cartographer-ros.readthedocs.io/en/latest/tuning.html

If you're having trouble with your setup, it's best if you file an issue on cartographer_ros.

HTH,
Damon

--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartogra...@googlegroups.com.

To post to this group, send email to google-ca...@googlegroups.com.

For more options, visit https://groups.google.com/d/optout.
--

Damon Kohler

Software Engineer

damon...@google.com

Google Germany GmbH

Erika-Mann-Straße 33

80636 München


Geschäftsführer: Paul Manicle, Halimah DeLaine Prado

Registergericht und -nummer: Hamburg, HRB 86891

Sitz der Gesellschaft: Hamburg


Diese E-Mail ist vertraulich. Falls sie diese fälschlicherweise erhalten haben sollten, leiten Sie diese bitte nicht an jemand anderes weiter, löschen Sie alle Kopien und Anhänge davon und lassen Sie mich bitte wissen, dass die E-Mail an die falsche Person gesendet wurde.

    

This e-mail is confidential. If you received this communication by mistake, please don't forward it to anyone else, please erase all copies and attachments, and please let me know that it has gone to the wrong person.

Matt

unread,
Aug 23, 2017, 10:43:59 PM8/23/17
to google-cartographer, mattfor...@gmail.com
Hi Damon

I suspected that was the case, thank you for the clarification!

I've already created an issue here, https://github.com/googlecartographer/cartographer_ros/issues/462, and both you and SirVer have already been very helpful.

Even though it's already been closed, it hasn't actually been resolved, so it should probably be re-opened (unfortunately I don't have the permissions to do this myself).

Matt 


On Wednesday, August 23, 2017 at 10:34:12 PM UTC+12, Damon Kohler wrote:
Matt, this is a very old thread and those parameters no longer exist. There is a nascent tuning guide available here: https://google-cartographer-ros.readthedocs.io/en/latest/tuning.html

If you're having trouble with your setup, it's best if you file an issue on cartographer_ros.

HTH,
Damon

On Mon, Aug 21, 2017 at 2:03 AM Matt <mattfor...@gmail.com> wrote:
Hi all

@Zhiyuan, my setup may be somewhat similar to yours. Out of interest, what Velodyne LiDAR model did you use? and how have you got on with tuning? 

@Holger, I can't seem to find "position_model_variance" or "velocity_model_variance" in any of the .lua configuration files. Are these still exposed parameters?

Thanks as always for the help and feedback.

Matt


On Friday, November 4, 2016 at 6:18:00 PM UTC+13, zyli...@gmail.com wrote:
Hi,

First I want to thank the developers of cartographer for their awesome work! We tried to run it with an velodyne lidar and our imu to do 3D slam and the result looks good!

However, we noticed that during the process, our progressively built submaps were not as  well aligned as the demo 3d data, and I had to set scans_per_accumulation=40 (the default was 160) to increase the frequency of background loop-closure, which clearly helped re-aligning the submaps.

I'm suspecting that the imu data (gyro+accelerometer) data we fed into cartographer is the cause.

My question is, are we supposed to pre-process the imu data, such as de-biasing, or just provide raw data?

Also, would providing our own attitude estimation and the covariance (currently we only fed rates and accelerations, like the demo file) help with the SLAM performance?

Thanks!

--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsub...@googlegroups.com.
Reply all
Reply to author
Forward
0 new messages