Hello,
I am using a Husky robot with a realsense D435 camera in Gazebo. The problem I am facing is that after running for some time the cloud_map changes suddenly to become warped. I have put my launch file in this github repo: https://github.com/RishavGH/husky_error/tree/main Here is a video of what happened: And here is the bag file: https://drive.google.com/file/d/1FZ42Y11xBVPzrMp5xiGkhP7A0MCU6wwH/view?usp=sharing I cannot figure out why this is happening. Please help and let me know if any further information is needed. Thank you in advance!! |
Administrator
|
Hi, it is preferred to share the resulting database (default ~/.ros/rtabmap.db) instead the bag for fast review.
It seems that a loop closure happened. With the database it will be easier to see why it did a wrong loop closure or why it accepted it. |
Thank you for your quick reply. Unfortunately I don't have the rtabmap db for that instance. However I could reproduce the event and here are the corresponding files.
RtabMap DB Bag file The video is attached below (it happens at about 4:03): Thank you in advance |
Administrator
|
This post was updated on .
Hi,
I was looking at this kind of problem (easier to see with the database): The ground has the same repetitive texture. The robot moves some distance and see exactly the same texture on the ground with enough features matching to accept the loop closure. We can set Kp/RoiRatios to ignore the bottom parts of the images for feature extractions. The STM size can be also increased to avoid loop closures on just seen locations. rtabmap-reprocess Mem/UseOdomFeatures false Mem/DepthAsMask false Kp/RoiRatios "0 0 0 0.25" Mem/STMSize 50 rtabmap.db output.db The odometry covariance seems varying a lot. Do you have more than one odometry subscribed to rtabmap? Well, if we fix the covariance and add RGBD/OptimizeMaxError under rtabmap node: <param name="odom_frame_id" value="odom"/> <param name="odom_tf_linear_variance" value="0.0001"/> <param name="odom_tf_angular_variance" value="0.0003"/> <param name="RGBD/OptimizeMaxError" value="2"/>the wrong loop closures are correctly rejected. With the all the changes under rtabmap node: . <param name="odom_frame_id" value="odom"/> <param name="odom_tf_linear_variance" value="0.0001"/> <param name="odom_tf_angular_variance" value="0.0003"/> <param name="Mem/DepthAsMask" type="string" value="false"/> <param name="Mem/STMSize" type="string" value="50"/> <param name="Kp/RoiRatios" type="string" value="0 0 0 0.25"/> <param name="RGBD/OptimizeMaxError" type="string" value="2"/> cheers, Mathieu |
Thanks, Mathieu, I took you suggested parameters and it worked but it occurred at another location. But this time it was because of the wall texture. I tried by removing the wall and increased the ROI to 45% and it has worked.
I wanted to ask: 1) I think these problems are mostly because it's a simulated world (causing repeated textures). So, these should not occur in the real-world, right? 2) Also, do these settings need to be present during localization mode as well? 3) I did not understand the comment you made regarding the STM size. What is it you meant by "seen locations"? Thank you again for your valuable time and help. Regards, Rishav |
Administrator
|
Hi Rishav,
Normally you would not have to set 45% with the fixed variance. I think I forgot that odom_frame_id should also be set so that odom_tf_linear_variance and odom_tf_angular_variance can work. I edited my answer above. I set odom_frame_id to "odom", but adjust to one written in your odometry topic header. 1) In real world, it could happen. See for example: https://github.com/introlab/rtabmap/wiki/IROS-2014-Kinect-Challenge#contest-environment. It is why setting correctly the odomety covariance and using RGBD/OptimizeMaxError gives a much more robust loop closure detection. 2) In localization it is trickier, by default we don't do graph deformation check (as the map is not re-optimized, just the pose is teleported at the right location). However, this can be enabled with RGBD/MaxOdomCacheSize, for example by setting it to 1000. It will check if odometry path has deformed too much or not from the last localization. 3) It is more "just seen locations", I was referring the images the robot just saw. For example, it is likely that consecutive images look very similar. We don't want to compare the current frame to past 10 frames for example. To do so, we can increase Mem/STMSize so we don't compare with previous frames that we just saw. For loop closure detection, we want to compare with images from old locations. cheers, Mathieu |
Free forum by Nabble | Edit this page |