Hello Mathieu,
Recently I have been trying to create the Occupancy Grid from the RGBD camera, so I set Grid/FromDepth to be true. After I did that, mapping went great, but during localization this warning occured: [ WARN] (2020-09-11 17:11:06.056) RegistrationIcp.cpp:1251::computeTransformationImpl() Transform is found (xyz=0.134282,0.051967,0.000000 rpy=0.000000,-0.000000,-0.020067) but no correspondences has been found!? Variance is unknown! [ WARN] (2020-09-11 17:11:06.057) Rtabmap.cpp:2566::process() Rejected loop closure 358 -> 2008: Cannot compute transform (cor=0 corrRatio=0.000000/0.100000 maxLaserScans=388) And when I switched the Reg/Strategy to Vis, the error went away, and the robot is able to localize better. I am wondering if there is a way to use ICP or VIsICP for registration. Also, I wonder is this just a pose refinement for each node? I am using a t265 for odometry. Edit: I am using libpointmatcher and Point_to_plane. Sincerely, Sean |
Administrator
|
ICP won't add more accuracy for most RGB-D cameras, because of the small field of view and noise at longer range. The Icp warning is independent of choosing Grid/FromDepth or not. If we have "but no correspondences has been found!? Variance is unknown! " warning, something went wrong with ICP registration as the resulting transform didn't give any overlap (at least under Icp/CorrespondenceDistance). ICP would be used to refine the odometry (coming from T265, the wheels or other sources) with a long-range lidar to get a little more accuracy. If you don't have a lidar, stay with Reg/Strategy=0. cheers, Mathieu |
Thanks for the reply. Before I was using Grid/FromDepth: false, with a lidar, I was using Reg/Strategy to ICP, and there was no error. I think that means the ICP is using lidar data for refinement? Is it possible to use the lidar for ICP while setting Grid/FromDepth: true? Or is that what VisICP is for.
|
Administrator
|
To use ICP for refinement with a lidar, set Reg/Strategy to 1 (Icp). I don't generally recommend the use of Reg/Strategy=2 (VisIcp). Grid/FromDepth can be set to true when using a lidar, so that the occupancy grid is created from the camera's depth image instead. The ICP will still be done with the lidar. |
Oh I see, for some reason I thought ICP would be done with the pointcloud data. Would using libpointmatcher cause this warning?
[ WARN] (2020-09-16 16:59:39.664) RegistrationIcp.cpp:1251::computeTransformationImpl() Transform is found (xyz=0.005995,-0.007180,0.000000 rpy=0.000000,-0.000000,0.009494) but no correspondences has been found!? Variance is unknown! [ WARN] (2020-09-16 16:59:39.664) Rtabmap.cpp:2566::process() Rejected loop closure 158 -> 985: Cannot compute transform (cor=0 corrRatio=0.000000/0.100000 maxLaserScans=721) I am not sure if this would be a problem or not. |
This post was updated on .
Indeed it is the libpointmatcher, since I just started using it, not really familiar with the config files. I removed the data filter and the error went away.
Edit: I actually have this warning now even when the robot is looking at the exact location: [ WARN] (2020-09-16 18:12:48.725) Rtabmap.cpp:2566::process() Rejected loop closure 496 -> 700: libpointmatcher has failed: Field normals not found I couldn't find this error message in rtabmap, I am wondering if you know anything about this. Edit: It turns out PointToPlaneErrorMinimizer is not working for my setup, PointToPointErrorMinimizer works fine in my case |
Administrator
|
If you use Icp/PointToPlane = "true", Icp/PointToPlaneK should be set so that normals are computed.
|
This post was updated on .
I see, after I change set libpointmatcher to PointToPlaneErrorMinimizer, and Ico/PointToPlane: true, Icp/PointToPlaneK: 5. I am getting this error during mapping on loop closure:
[ WARN] (2020-09-17 16:39:54.225) Rtabmap.cpp:2566::process() Rejected loop closure 55 -> 146: libpointmatcher has failed: The existing field normals has dimension 3, different than requested dimension 2 But I think it is just due to me using SamplingSurfaceNormalPointsFilter. And also interestingly, the variance is unkown error still persists, and it only appears in localization mode, not mapping mode, I made sure the parameters are the same, any idea why this would be the case? Edit: I think it might have something to do with choosing GTSAM as the optimizer? I will check first thing on Monday. |
It's odd, I started over my rtabmap.launch and changed all the parameter that I wanted to change, and the error doesn't show up anymore. Maybe it is some parameters that I am not aware of. I did a diff, it didn't really show much difference.
|
Administrator
|
Which libpointmatcher version are you using? most of our tests were done with https://github.com/introlab/rtabmap/blob/c5158cade5f9b6f845c3df507c3032916d20ca20/docker/bionic/Dockerfile#L40
|
Free forum by Nabble | Edit this page |