Re: [GTSAM] a problem with fixedlag marginalization

846 views
Skip to first unread message

Brice Rebsamen

unread,
Sep 14, 2020, 12:00:03 PM9/14/20
to huanhexiao, gtsam users
Hello
This should work, so the first that comes to mind is that you made a mistake somewhere. Unfortunately it's hard to provide more help than the following advice: go back to studying the example for the IncrementalFixedLagSmoother and double check your code (a strategy is to trim your code to reduce the complexity as much as possible so that it's easier to grok what's going on). Good luck.

On Sun, Sep 13, 2020 at 8:47 AM huanhexiao <huanh...@gmail.com> wrote:
Hi, there.
I met a problem using IncrementalFixedLagSmoother, the following is a sketch of the factor graph:
Marg.png
The marginalization in IncrementalFixedLagSmoother has been done in the "update()" step, when it comes to the "calculateEstimate()", it throw an error :
"Requested variable 'x0' is not in this VectorValues."

I have checked all factors in the IncrementalFixedLagSmoother after the marginalization, "x0" has been removed from the variables,  and no factor contains "x0" at all. That makes me confused too much.
Any help!

--
You received this message because you are subscribed to the Google Groups "gtsam users" group.
To unsubscribe from this group and stop receiving emails from it, send an email to gtsam-users...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/gtsam-users/d588b2b4-6c54-4817-b1a2-657e60847a8an%40googlegroups.com.

navid km

unread,
Sep 15, 2021, 5:00:38 AM9/15/21
to gtsam users
I get the exact error when using ISAM2  IncrementalFixedLagSmoother marginalization, in update() step. My graph is very similar to the above picture, and I use BearingRangeFactor for the landmarks. 
Do you came into any conclusion or any solution found?
Best
Navid

Joel Truher

unread,
Aug 15, 2024, 2:12:02 PM8/15/24
to gtsam users
I experience this same behavior, messages like "IndexError: Requested variable 'x41' is not in this VectorValues."  from IncrementalFixedLagSmoother.update(), with a similar setup.

i'm using python, with a toy problem, a few fixed landmarks and a single moving state, using odometry and bearing/range factors.  there's an animated plot showing the covariance distributions.  the whole point is to teach high school kids the concepts, in preparation for the 2025 robotics season.  (messy code here if you're curious: https://github.com/truher/all24/blob/main/studies/factor_graph/factor_graph2.py)

Some observations, in case anyone is interested:

  • if a short lag is used, such that the number of active timestamps is small, the error disappears.  The specific number of allowed timestamps seems to vary; sometimes it's 5, sometimes 10
  • for medium levels of lag, i can catch the IndexError in update() and calculateEstimate() and proceed, and all is well for awhile (maybe ten iterations)
  • for longer lag, catching the IndexError results in a state that produces ValueErrors in update(), and then IndexErrors in every call to marginalCovariance(), like it forgets every key, and doesn't recover.  in this state, it also stops pruning timestamps, so the timestamp map grows without bound.

perhaps this is somehow related to the marginalization accounting issue described in https://github.com/borglab/gtsam/issues/1101?

Joel Truher

unread,
Aug 15, 2024, 3:14:12 PM8/15/24
to gtsam users
oh, another clue: initially i used a single set of "landmark" variables (e.g. "L(1)" and "L(2)", used them in every bearing-range factor, and updated their timestamps with each iteration.

it's ok to treat the landmarks as fixed, so i changed this so that every iteration creates a new set of "landmarks," and old "landmarks" are pruned just like old "robot" states, and viola!  the issues described above disappear!

i imagine that the problem has something to do with having many bearing-range factors linked to the same landmark variables.

Dellaert, Frank

unread,
Aug 15, 2024, 4:06:00 PM8/15/24
to Joel Truher, gtsam users

Hi Joel

 

You are at this point in time probably the best person to create a PR with the smallest possible unit tests that reproduces the issue, if in fact it is a bug in GTSAM and not in your code. Issue 1101 was resolved I think, and that was part user code/part GTSAM. I found that often even making the unit tests is informative. Happy to review a PR with a unit test and maybe even a possible fix? 😊

 

Frank

 

From: gtsam...@googlegroups.com <gtsam...@googlegroups.com> on behalf of Joel Truher <joel....@gmail.com>
Date: Thursday, August 15, 2024 at 12:14
PM
To: gtsam users <gtsam...@googlegroups.com>
Subject: Re: [GTSAM] a problem with fixedlag marginalization

You don't often get email from joel....@gmail.com. Learn why this is important

oh, another clue: initially i used a single set of "landmark" variables (e.g. "L(1)" and "L(2)", used them in every bearing-range factor, and updated their timestamps with each iteration.

 

it's ok to treat the landmarks as fixed, so i changed this so that every iteration creates a new set of "landmarks," and old "landmarks" are pruned just like old "robot" states, and viola!  the issues described above disappear!

 

i imagine that the problem has something to do with having many bearing-range factors linked to the same landmark variables.

 

On Thursday, August 15, 2024 at 11:12:02 AM UTC-7 Joel Truher wrote:

I experience this same behavior, messages like "IndexError: Requested variable 'x41' is not in this VectorValues."  from IncrementalFixedLagSmoother.update(), with a similar setup.

 

i'm using python, with a toy problem, a few fixed landmarks and a single moving state, using odometry and bearing/range factors.  there's an animated plot showing the covariance distributions.  the whole point is to teach high school kids the concepts, in preparation for the 2025 robotics season.  (messy code here if you're curious: https://github.com/truher/all24/blob/main/studies/factor_graph/factor_graph2.py)

 

Some observations, in case anyone is interested:

 

·      if a short lag is used, such that the number of active timestamps is small, the error disappears.  The specific number of allowed timestamps seems to vary; sometimes it's 5, sometimes 10

·      for medium levels of lag, i can catch the IndexError in update() and calculateEstimate() and proceed, and all is well for awhile (maybe ten iterations)

·      for longer lag, catching the IndexError results in a state that produces ValueErrors in update(), and then IndexErrors in every call to marginalCovariance(), like it forgets every key, and doesn't recover.  in this state, it also stops pruning timestamps, so the timestamp map grows without bound.

 

perhaps this is somehow related to the marginalization accounting issue described in https://github.com/borglab/gtsam/issues/1101?

 

 

 

 

On Wednesday, September 15, 2021 at 2:00:38 AM UTC-7 n.mah...@gmail.com wrote:

I get the exact error when using ISAM2  IncrementalFixedLagSmoother marginalization, in update() step. My graph is very similar to the above picture, and I use BearingRangeFactor for the landmarks. 

Do you came into any conclusion or any solution found?

Best

Navid

On Monday, 14 September 2020 at 18:00:03 UTC+2 brice.r...@gmail.com wrote:

Hello

This should work, so the first that comes to mind is that you made a mistake somewhere. Unfortunately it's hard to provide more help than the following advice: go back to studying the example for the IncrementalFixedLagSmoother and double check your code (a strategy is to trim your code to reduce the complexity as much as possible so that it's easier to grok what's going on). Good luck.

 

On Sun, Sep 13, 2020 at 8:47 AM huanhexiao <huanh...@gmail.com> wrote:

Hi, there.

I met a problem using IncrementalFixedLagSmoother, the following is a sketch of the factor graph:

The marginalization in IncrementalFixedLagSmoother has been done in the "update()" step, when it comes to the "calculateEstimate()", it throw an error :

"Requested variable 'x0' is not in this VectorValues."

 

I have checked all factors in the IncrementalFixedLagSmoother after the marginalization, "x0" has been removed from the variables,  and no factor contains "x0" at all. That makes me confused too much.

Any help!

--
You received this message because you are subscribed to the Google Groups "gtsam users" group.
To unsubscribe from this group and stop receiving emails from it, send an email to gtsam-users...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/gtsam-users/d588b2b4-6c54-4817-b1a2-657e60847a8an%40googlegroups.com.

--
You received this message because you are subscribed to the Google Groups "gtsam users" group.
To unsubscribe from this group and stop receiving emails from it, send an email to gtsam-users...@googlegroups.com.

Joel Truher

unread,
Aug 15, 2024, 8:37:05 PM8/15/24
to gtsam users
OK, I made a couple of tests, see https://github.com/borglab/gtsam/pull/1795

The proximate cause of the first issue appears to be the use of IncrementalFixedLagSmoother.update() more than once per timestamp (e.g. once for odometry, once for vision).  Are you supposed to only call update() once per timestamp?  If so, maybe the fix could be as simple as catching the issue on input.

While writing this first case, I came across a second case, a SEGV during marginalization of variables without any factors other than a prior, which isn't a realistic situation but it would still be really good to not SEGV, ever!
Reply all
Reply to author
Forward
0 new messages