robot_mapping_demo.py << Please refer to the attached file.
Dear Mathieu I’m a ROS 2 Humble user and have a few questions about the RTAB-Map LandMark (Aruco) feature: 1. To enable LandMark detection, I’ve set ``` Optimizer/Strategy = 1 Optimizer/Robust = false RGBD/OptimizeMaxError = 0.0 ``` Is that correct, or am I missing something? 2. I’d like to deploy ArUco-based LandMarks over a large area so that, if the normal BoW-based loop-closure fails after environmental changes, I can still recover pose via the markers. Is that supported? 3. During runtime I constantly see: ``` [rtabmap-2] [ERROR] (…): createSignature() Invalid marker received! IDs should be > 0 (it is 0). Ignoring this marker. ``` In RViz I do see an orange “LandMark Match” pop up, and when I export poses via rtabmap-databaseViewer in RGBD-SLAM+ID format, I get lines like: 0.000000 -5.738327 6.787276 0.417891 -0.046690 0.052443 -0.158161 0.984914 -8 0.000000 -16.134329 -5.261295 0.316932 -0.137799 -0.010033 -0.113221 0.983917 -7 0.000000 -20.905924 -24.242378 0.395879 -0.092860 -0.049520 0.590613 0.800063 -6 0.000000 -13.607995 -35.448853 0.323346 -0.036050 -0.086696 0.990774 0.097733 -5 0.000000 3.894679 -40.469673 0.165100 -0.033594 -0.039766 0.600855 0.797661 -4 0.000000 18.757656 -8.988869 0.402318 -0.057973 0.027286 -0.797696 0.599646 -3 0.000000 14.164346 -28.256603 0.336725 -0.014094 -0.075720 0.990521 0.113740 -2 0.000000 14.298677 1.706668 0.190120 -0.033462 0.042391 -0.788115 0.613154 -1 So markers are being detected, but why is RTAB-Map reporting ID 0 as invalid? What’s causing that error? I would appreciate any help you can offer. Thanks, GGYU |
Administrator
|
1. These parameters are independent of marker detection: Optimizer/Strategy = 1 Optimizer/Robust = false RGBD/OptimizeMaxError = 0.0I don't recommend to set RGBD/OptimizeMaxError=0 (disabled) because it is used to reject bad loop closures. Optimizer/Strategy=1 or 2 can be used with markers. 2. Yes, rtabmap will re-localize on markers. The caveat is that they should be all unique. 3. Marker with ID=0 is just not supported. RTAB-Map uses ID=0 internally for invalid ID. For markers, we flip their ID to be negative, that's why you get negative IDs in the exported poses. |
1. I believe I saw on a GitHub issue that those parameters need to be set exactly as above for the RTAB-Map LandMark feature to work reliably. So you’re saying that if I enable (i.e., increase) `RGBD/OptimizeMaxError`, I can run both the BoW-based loop closure and the marker-based relocalization simultaneously?
2. Right—I want to deploy this Visual SLAM in an environment where the visual appearance changes daily, and if the BoW-based loop closure ever fails, I’d fall back on markers for robustness. You’re saying that’s possible as long as I use unique markers, correct? 3. I already knew from your GitHub issue that ID 0 isn’t supported. But the error I’m seeing only mentions IDs 1–8, so when I see that error I worry the marker wasn’t recognized properly as a LandMark. You’re saying that it could momentarily misidentify a marker and log that error, but if I then export the poses from the `.db` file in RGBD-SLAM+ID format and see the marker positions listed, everything is actually fine, right? |
Administrator
|
1. Yes
2. Yes, and that the markers don't move over time. 3. If you don't have tag ID=0 in the environment and you see that error, it could be a misdetection, though it should be pretty rare. I think there are some family of tags that are more robust to wrong identification / ghost tags. Do you mean you have errors like "createSignature() Invalid marker received!" for tags with ID > 0? The exported poses show the tags 1-8 are in the map, so they were detected. Is the error you are seeing more that the tag is seen again and there is a rejected loop closure / re-localization? |
It’s an honor to be able to speak with you in real time.
In the map I’m using, I employed the original ArUco markers for IDs 1 through 8, and I’ve been continuously testing with a rosbag file. However, I keep seeing error messages in the terminal log whenever IDs 1–8 are recognized. If you’d like, I can upload the video right now. I’m not entirely sure how to verify that re-localization occurred, but I can show it to you quickly in the video. |
In reply to this post by matlabbe
https://drive.google.com/file/d/14lqMH1UTFRGmvtLgFP7AqnPSs9EO7M-x/view?usp=drive_link
The yellow messages you see in the terminal are just due to the resolution mismatch between the depth and RGB topics, and the red messages are the “createSignature() Invalid marker received!” error I mentioned earlier. As you can see in the video, this error doesn’t occur exactly when every tag is detected—it comes and goes intermittently. Even when it appears, the landmarks still show up in RTAB-Map’s RViz. |
Administrator
|
You can set Mem/DepthAsMask to false to suppress that related warning.
Icp/MaxTranslation could be increased to accept closing local loop closures farther than 20 cm. I am impressed that even if rtabmap is using ~100 ms of processing, the delay is >3 sec. The input data may have huge delay. Could be debugged with `ros2 topic delay` tool. How are the markers detected? Are you using an external node? It seems to correctly detect your marker 1-8, but there are indeed some errors about ID=0. If the tag detector is external, you may check if the tag topic is sometime published with empty ID or set to 0. cheers, Mathieu |
Free forum by Nabble | Edit this page |