Comments (7)
Hey @weisongwen!
I assume you mean (unary) priors on individual poses? If so, then you're in luck :-)! It is actually possible to express these priors directly in the model that SE-Sync already employs: you can simply introduce a single distinguished pose x_w that represents the "world" coordinate system that you want to use, and then express priors as relative measurements against x_w. To transform the estimates returned by SE-Sync back into this distinguished world frame when you're done, you'll then just need to multiply everything by x_w^{-1}, where x_w is the estimate for the "world" pose returned by SE-Sync.
Note that while this construction may at first glance appear somewhat contrived, it's actually a straightforward mathematical reflection of the fact that there is no such thing as an "absolute" coordinate system. That is, even when we are using measurements that we typically think of as "absolute" (e.g. GPS measurements of position), what we are actually doing is measuring position relative to a commonly-adopted "standard" reference frame (in the case of GPS measurements, the lines of latitude and longitude that are laid out on the surface of the Earth). The construction that I described above simply expresses this fact in a more concrete way than we typically do :-).
from se-sync.
Closing this issue, as I've not heard anything further.
from se-sync.
@david-m-rosen , Thanks for your detailed reply and sorry for my late reply.
Yes, I mean the unary constraint, such as the GPS positioning. I am still looking into the algorithm as it is really quite tough to fully understand. I will let you know if I have any updates based on your comments. :-)
from se-sync.
Hey @weisongwen,
No worries -- I just want to stay on top of any reported issues to keep the repo in good working order :-).
A couple of additional comments that might help to clarify the discussion:
-
The construction that I outlined in my previous post (for encoding unary priors in a particular coordinate frame using relative constraints) actually has nothing to do with the SE-Sync algorithm itself: this is ultimately just a statement about what it means to transform between different coordinate frames. So one shouldn't need to dig into the guts of the SE-Sync algorithm itself to understand this construction :-).
-
While some of the math involved in deriving the SE-Sync algorithm is admittedly perhaps a bit exotic, the actual algorithm itself turns out not to be very different from "standard" pose-graph SLAM. One way to see this is by comparing Problems 3 and 9 in the paper. Problem 3 is equivalent to a totally standard formulation of pose-graph SLAM (my colleague Kasra Khosoussi has a very nice paper that investigates this form of the problem in more detail, including how to find (local) solutions of it using standard NLS libraries like e.g. GTSAM and g2o). Problem 9 is the optimization problem that SE-Sync actually uses to search for global solutions. If you compare Problem 3 and Problem 9, you'll see that the only difference between these two problems is that Problem 9 replaces the original rotation variables Ri in SO(d) with elements Yi from the Stiefel manifold St(d,r), which is just a higher-dimensional manifold containing SO(d) itself. So all we're really doing in passing from Problem 3 to Problem 9 is giving ourselves a bit more room to move around in the search space, in order to avoid becoming stuck in bad local minima. So 90% of what SE-Sync is doing is just solving a (slightly) higher-dimensional generalization of "standard" pose-graph SLAM :-). [As an aside: this is also why SE-Sync is so fast, especially compared to prior approaches for global optimization: the subproblems that it's solving are very close to the "standard" problem that current state-of-the-art local search methods like GTSAM solve, and so we can achieve comparable numerical performance -- in fact, better performance if we're a bit more clever about designing the optimization method in the right way :-)]. This is really the core idea of the method. The rest of the paper is just devoted to (1) proving that this approach will actually succeed in finding the right answer, and (2) deriving a condition that one can check to determine whether a given critical point for Problem 9 is a global solution (so we can stop), or whether we need to keep searching.
Hope this helps :-)!
from se-sync.
Hi @david-m-rosen , Many thanks for your detailed explanation. Based on your explanation, my understanding is that: a higher-dimensional manifold is employed for searching in SE-Sync to approach the global optimal. I highly believe that your work can have a pretty deep impact on the state estimation field.
Currently, I am doing collaborative positioning based on camera, imu, GNSS, and inter-ranging measurements from multiple agents. I will try to compare your SE-Sync to this case. I will let you know if I got any interesting findings,
Thanks a lot :-)
Weisong,
from se-sync.
Hey @weisongwen,
That's the right intuition. If you'd like an alternative take on this, you might also be interested in checking out the video for our recent paper that shows how to adapt the SE-Sync approach to solve rotation averaging problems using GTSAM -- it has some nice visualizations in it that attempt to convey what the algorithm is doing a bit more transparently :-).
And please do keep me posted on the project! It's always super fun to see how folks are using this :-).
from se-sync.
@david-m-rosen , Many thanks for your video and paper link. This is really very very interesting.
Sure, I will keep you updated!
Best,
Weisong,
from se-sync.
Related Issues (20)
- Synchronizing 2D rotations in 3D space HOT 1
- Sequence of recording vertices and edges in g2o file HOT 6
- liblapack.so.3: undefined references HOT 3
- Question regarding SE-Sync vs. Shonan Rotation Averaging HOT 4
- Where can I find the optimized pose? HOT 2
- Where is the ground truth poses for the data folder? HOT 1
- G2o parsing code incorrectly names a variable as covariance instead of info matrix. HOT 1
- sometimes sesync may output incorrect results HOT 2
- Question regarding prior constraints HOT 8
- Documentation on how to start HOT 5
- can se-sync work with factor graph generated with GSAM ? HOT 1
- Unable to enter visual mode
- The newest/accelerating version compiled in ubuntu 20.04... HOT 3
- How to optimize a least square problem, where there is only one node with multiple prior factors?
- Python binding installation and Inference
- SESync results matrix sometimes flips HOT 1
- can se sync solve BA or PnP?
- Cross compile for other platforms
- Which version of Pangolin should I use
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from se-sync.