Comments (10)
We have not been testing on the EurocMav datasets. Can you please elaborate more on the problems that you're seeing?
Looking at your config file, this are the best guesses I can give you, short of trying to run and tune it myself.
- I notice that
X.td
is zero, and it is probably not zero. Since EuRoC and Kalibr are both published by ETH, you should be able to run the calibration dataset through Kalibr and get a better number. - Double-check numbers for
min_depth
andmax_depth
and any other standard deviation numbers. They are very specific to the environment. TUM-VI room sequences are entirely contained in a small room, so 5m might be too small. - If the datasets do not start from rest, set
gravity_init_counter
to 0 and make sure thatX.Wg
is correct. - Make the noise parameters in
Qimu
bigger.; For TUM-VI dataset, we inflated the numbers by three times. - If all that fails, edit
src/CMakeLists.txt
and turn on online calibration. (XIVO is under active development. I recently committed something that affects the radial-tangential distortion model, so please pull the latest copy of thedevel
branch.)
from xivo.
Have you been able to find a working solution?
When I looked into the IMU data of euroc and data9_workbench, I found that the directions of gravity are not equal (+9.7 for euroc / -9.7 for data9_workbench). I guess the orientation of the mounted IMU differs however I am not sure which parameter to adapt in order to correct for this.
from xivo.
I haven't had time to really look at this, but I can comment on how Xivo deals with gravity.
If you start from constant velocity (e.g. rest), and if the parameter gravity_init_counter
is greater than 0, then Xivo will use the average of the first gravity_init_counter
IMU measurements to solve for the transformation that aligns the parameter gravity
to the spatial frame. This transformation is stored as the state variable Wg
(gravity vector -> spatial frame, so really Wsg
). During this period, Xivo will not attempt to estimate the state. Wg
will be adjusted/updated during state estimation.
The code that initializes gravity is the function xivo::Estimator::InitializeGravity
which is called from xivo::Estimator::InertialMeasInternal
If you already know the proper value of Wg
, then you can put that value in X.Wg
and then set gravity_init_counter
to 0. If your dataset does not start from constant velocity, you absolutely must do this.
from xivo.
I have a question about your definition of W_{sg}
. According to the xivo paper, the spatial frame is defined such that the gravity goes along the z-axis of the spatial frame:
"The spatial frame s is attached to Earth and oriented so gravity T = [0 0 1]T x k is known."
Shouldn't in this case W_{sg} always be Identity?
What xivo::Estimator::InitializeGravity()
seams to calculate is W_{bs}
. Are my thoughts correct?
from xivo.
Another possible explanation: the spatial frame coincides with the body frame during gravity initialization. Then everything is clear. Could someone please verify? Thanks
from xivo.
The body frame is always aligned with the spatial frame during initialization; the spatial frame is defined to be wherever the body frame is at the very beginning.
The body frame, however, is not necessarily aligned with gravity at initialization. Then, W_{sg]
is nonzero. Does that make sense?
from xivo.
Yes that makes perfectly sense. Thank you very much for this clear explanation. I have one more question and even though it might not be directly connected to the EurocMav dataset it might help me to find a working configuration:
What exactly are the values in P
used for?
I tried to do some digging in the source code but Im still not sure what P is used for.
from xivo.
P
contains the initial value of the state covariance. See
from xivo.
Hi, was a config every uploaded that worked? I don't see one here.
https://github.com/ucla-vision/xivo/tree/devel/cfg
from xivo.
Oh whoops. It's been a while and I thought the problem had been solved.
from xivo.
Related Issues (20)
- Feature Matching Tracker HOT 1
- Gauge Features
- Optional Mapper
- Rodrigues Unit Tests Fail HOT 1
- Reusing map HOT 4
- Filter-only interface
- Optionally use GPU to detect new features
- Unit tests for dynamics jacobians HOT 2
- Make coordinate transformations have two letters HOT 1
- Optional RANSAC to the tracker
- Memory manager infinite looping
- Errors in Python interface HOT 2
- Upgrade dependencies
- Separate gyroscopes and accelerometer streams
- Optionally only estimate depth of features
- Robot state estimation HOT 1
- Gravity HOT 1
- World scale? HOT 1
- Triangulate using more than two frames
- Can't build the repo
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 xivo.