Query regarding under-constrained variables

189 views
Skip to first unread message

Aswin Gururaj

unread,
Jan 26, 2021, 1:19:29 PM1/26/21
to tagslam
Hi Bernd, 
                 Thanks a lot for your help in solving the synchronization issue last time. Now I am trying to run TagSLAM with bags of length 2 to 3 minutes with around 9000 frames of data. I am using sync_and_detect.launch to detect the tags first and running them offline so that I can extract the tag poses and use them in real-time with the amnesia feature. While running TagSLAM with longer bags(in offline mode), I am getting the following error after approximately 100 seconds( till then it seems to be working fine)

[ERROR] [1611676955.428701901]: /tagslam: 
Indeterminant linear system detected while working near variable
1 (Symbol: 1).Thrown when a linear system is ill-posed. The most common cause for this
error is having underconstrained variables. Mathematically, the system is
underdetermined. See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.

What could be the reason for this? Also, I could notice that tagslam was giving a much better estimate of the trajectory when using two cameras and visual odometry instead of just a single camera and odometry( in offline mode after a while). Is there any reason for this? Should I always prefer two cameras and visual odometry in that case? 

I tried running tagslam with two cameras and visual odometry in online mode ( without all the tag poses) but the processing was very slow right from the beginning. Is this expected? Will it give better performance when tag poses are already specified in the config file? I have attached the config files that I am using. It would be great if you can have a look at them and let me know what could be the issue.

Thanks!
camera_poses.yaml
tagslam.yaml
cameras.yaml

Bernd Pfrommer

unread,
Jan 26, 2021, 2:26:19 PM1/26/21
to tagslam
OK, so you are getting the error when first doing a mapping run (without amnesia) to extract the tag poses, right?
The first question is: how does the trajectory look up until it bombs out? And does anything special happen right before you get the error?
Visualize it in RVIZ (you can limit the maximum number of frames played so it stops right before the error). Any suspicious output on the console? Warning messages about large subgraph errors?
Sometimes the errors you see happen when loop closure occurs after drift, and the error is unexpectedly big. There are safeguards in place to avoid that, but still, that's one thing to look for.
Another possibility is maybe duplicate tag ids or wrong tag size specified.
About two vs one cameras: this buys you something only when the second camera sees tags that the first one doesn't. For small baseline cameras (T265) that is rarely the case, so I'm somewhat surprised. Sometimes there are cases where the tag corners are misdetected. Then also you may get better results with two cameras because there will be some error correction due to having two observations. The odometry obviously always uses both cameras.
I would not expect two cameras running much slower than one, at least not on tagslam's side. Check if it's a problem with the tag detector. If you run two detectors and each drops e.g. 2 of 3 frames due to high CPU load, then you have to be lucky for them to decode frames with the same time stamp, because if not, tagslam will drop them (the time stamps must agree).
Config files look good, 8cm baseline for the T265 is also about right. Make sure that file is good, i.e. first do a clean calibration run in front of your base tags such that tagslam can generate a good camera_poses.yaml. Then use that file subsequently as input, otherwise tagslam will have to recompute the calibration. It's better to have it beforehand, because it additionally constrains the system and allows for better outlier rejection.
If you can't figure it out, please send me the bag (just with the extracted tags, that's enough).

Aswin Gururaj

unread,
Jan 29, 2021, 1:47:12 PM1/29/21
to tagslam
Hi Bernd,
                There were two tags with the same tag ID. That was the reason for the error. After removing the tag, it worked fine offline. However, the taglslam odometry frequency while running online is very less(around 1 Hz). As you mentioned earlier, it looks like it is because of the apriltag detector. I am getting images at 30 Hz and visual odometry data at 200 Hz, while the detector output is around 15 Hz. I have the use_approximate_sync parameter set to true in tagslam.yaml but I think the low-frequency output from the detector results in not many messages having an identical timestamp and hence getting ignored by tagslam. Are there any options in the detector which I can try out to get a higher frequency?

Thanks.

Bernd Pfrommer

unread,
Jan 29, 2021, 2:04:05 PM1/29/21
to tagslam
Can you try using just one camera for tagslam and see what frequency you get then?
I'm a bit surprised that you would get such low frequency despite the detector operating at 15Hz. The approximate time sync should work.
If you collect the detector output and run offline, do you also see tagslam just producing data at about 1Hz?

Aswin Gururaj

unread,
Jan 30, 2021, 1:32:57 AM1/30/21
to tagslam
With single camera and visual odometry data, I am getting a maximum of  2 Hz output (online mode with detector running at 15 Hz). When operating in offline mode it's much better. I have mentioned the poses of 19 tags in the config file. In offline mode, it(tagslam odometry) starts at 60 Hz and slowly drops to 30 Hz by the end of the bag. I thought that increasing the detector frequency would help increase the frequency of the tagslam output as it would result in more messages having closer timestamps which can be processed by tagslam with approximate time sync set to true. Could approximate time sync be the issue here?

Bernd Pfrommer

unread,
Jan 30, 2021, 11:16:22 AM1/30/21
to tagslam
Looked at your bag. The sensor header and recording (bag) time stamps are off by 39h! This means the clock of your recording device is not synchronized with that running the camera driver. You should really synchronize those reasonably well (running ntp daemon for example).

Everything else looks good. I got mediocre results when running offline, but it worked, and it looks like every frame is used.
However, if I run online, I'm also just getting about 2Hz. This is because the synchronization queues are too short. For online running they are hard coded to length 5, for playing from bag directly the are determined by a config parameter that defaults to 100. I think this qualifies as a bug. Thanks for reporting. I pushed the fix for it to the master branch.

Please give it a try.

Reply all
Reply to author
Forward
0 new messages