How to create a map using tagslam

374 views
Skip to first unread message

Suman Saurav Panda

unread,
Feb 5, 2020, 11:03:11 AM2/5/20
to tagslam

Hi all,
I am trying to create a map using tagslam. As input I have a rosbag which publishes raw image. I don't have any prior estimate of the map file and I intend to create a map using the slam technique provided by tagslam. But I am facing issue to achieve this task.  What I have done so far is creating a launch file consisting of  an april tag detector node and a tagslam node. I am providing the camera.yaml file which has camera intrinsic, camera_pose.yaml  and tagslam.yaml as  described in project page. I give only one apriltags pose as origin similar to example file described in the project page. I am attaching the tagslam.yaml for reference

Screenshot from 2020-02-05 21-00-40.png

In first case I have tried this in online mode with "amnesia = false" the program runs but each time shows "sum of subgraph error = 0" and "full graph error = 0" and finally when I dump the output, I can only see one tag in the pose.yaml file same as the pose provided in the tagslam.yaml. The terminal output is shown in the screenshot.

Screenshot from 2020-02-05 21-22-21.png

Second case if I run it with amnesia = true then tagslam outputs this error.

Note - in the tagslam.yaml file if I add all the tags and their pose(some initial estimate) then this error does not show up. I am struggling to understand what is the proper way to give input. If anyone can help us regarding this it would be great for us.
tagslam.yaml

Bernd Pfrommer

unread,
Feb 5, 2020, 6:19:47 PM2/5/20
to tagslam
From the TagSLAM output it looks like the tags are detected fine, and tagslam is trying to put them into the graph. Good!

If I understand correctly, you are trying to do a mapping run: i.e. determine the pose of all tags, except for tag 0, for which you have provided a position. In order for this to work, at some point your camera needs to see tag 0. Once tag 0 is detected (and if it's a good detection, not too small, not too shallow an angle etc), only then can the position of the camera be determined. Question: is tag 0 ever detected? What does the output of TagSLAM look like when that happens?

Even if tag 0 is detected, that does not mean you are home free. In order to determine the pose of other tags, they need to be seen simultaneously with tag 0. Then the position of *those* tags can be determined as well. This increases the set of known tags, so now it's sufficient to see any of them, and new tags can be added. Note that tag 0 does not have to be the first tag to be seen: TagSLAM will go back in time to find all tags that are somehow connected in the graph.

About "amnesia". As the name says, in this mode TagSLAM forgets all earlier observations. So that is definitely *not* to be used when you want to do mapping. In mapping, you want to remember what tags have been seen before. So switch amnesia to false for mapping. Once you have the poses of all tags, then you can use amnesia to find the camera pose as you move the camera around within a universe of tags with known poses that have been pre-defined in the tagslam.yaml. You should use amnesia really only if you have to: when you want to run real-time in a world with known tags.

Suman Saurav Panda

unread,
Feb 6, 2020, 3:22:32 AM2/6/20
to tagslam
Thanks Bernd for your excellent explanation. I see my mistake now. Thank you very much for reaching out.
Message has been deleted

jianxin huang

unread,
Apr 21, 2021, 4:31:52 AM4/21/21
to tagslam
Hi  bernd,
I have some questions about this sentence  "Even if tag 0 is detected, that does not mean you are home free. In order to determine the pose of other tags, they need to be seen simultaneously with tag 0. Then the position of *those* tags can be determined as well. This increases the set of known tags, so now it's sufficient to see any of them, and new tags can be added."
which means that I first detect the tag 0 and the next tag such as tag 1 at the same time, then tag 1 will be added, but when I detect tag 3 I just need to see the tag 2 and tag 3 and don't need to see tag 0. Is it right? Should I need odometry when I map tags?

Bernd Pfrommer

unread,
Apr 21, 2021, 7:29:34 AM4/21/21
to tagslam
"which means that I first detect the tag 0 and the next tag such as tag 1 at the same time, then tag 1 will be added,"
This part of your sentence is correct. From now on tag 1 is known, and it is sufficient to either see tag 0 or tag 1 to discover additional tags (2, 3, 4).

", but when I detect tag 3 I just need to see the tag 2 and tag 3 and don't need to see tag 0. Is it right?"
I cannot answer this part because you have not stated whether tag 2 has been discovered (only tag 0 and tag 1 have been discovered).

" Should I need odometry when I map tags?" If you have odometry, then there is no longer need for seeing tags simultaneously for mapping. The odometry "bridges" the camera movement during the time when no tags are simultaneously visible. So odometry helps, but if you have enough tags such that there is always some overlap, you will strictly not need it. Odometry however helps stabilize and improves the results of the mapping no matter what.
Reply all
Reply to author
Forward
0 new messages