Comments (8)
Hi @fboris ,
- If you have never used the framework before I would suggest you start with an estimator-setup that uses only the ptam pose first and later add pressure measurements. E.g. you should start off using pose-sensor.
- Reconsider the usefulness of pressure measurements in an indoor scenario (AC and closing/opening of doors create pressure changes). I would suggest you characterize your measurements to see if they are useful.
- If you want to use an estimator with pose and pressure the
pose_pressure_sensor.launch
would be good. - The
core/core_noise_acc
etc. parameters are the noise densities of IMU measurements and IMU biases respectively. - If you want to set the initial state of the filter you can do so programmatically in the
Init
method https://github.com/ethz-asl/ethzasl_msf/blob/master/msf_updates/src/pose_msf/pose_sensormanager.h#L159 - I will look into making the framework be independent of asctec_mav_framework, however the dependency is only there for message definitions, there is no need to run it on asctec platforms, in fact we often run it on desktop-PCs, Smartphones etc.
- I tested the framework for IMU rates up to 18KHz with 700Hz Visual updates without dropping messages. (above that single IMU messages will get dropped from time to time). Like in any indirect EKF formulation your IMU measurement rate should be higher than your update rate. My colleague @markusachtelik ran the filter with update rates as low as 1Hz, so anything in between should work (with differences in the performance obviously)
Great, let me know if there are more issues.
Simon
from ethzasl_msf.
Simon,
Your advice is very helpful. I understand this framework more clearly. I think the question I ask about the dependency issue is minor issue. Because I found actually It could launch without any asctec_mav_framework yesterday. Anyway, I will start with single sensor fusion(ptam). If I have more issues I will reply in this thread. Thanks a lot!
FBoris
from ethzasl_msf.
Hi @simonlynen,
Another question. What is the unit of noise densities and biases in this pose_sensor_fix.yaml?
core/core_noise_acc: 0.03
core/core_noise_accbias: 0.0083
core/core_noise_gyr: 0.01
core/core_noise_gyrbias: 0.0013
I found some information about noise configuration in Weiss's thesis(page 68
). But the unit of variance are strange.
So I took the screen shot of this equation above.Why the variance of gyro noise is not rad^2/sec^2 in equation 3.7? In my opinion, the unit of the variance should be the square of it. Do I misunderstand something?
from ethzasl_msf.
I haven't double checked Stephan's math, but it should be the result of
going from the continuous time noise density to the discrete time one.
Check this tr ~eq 150:
http://www-users.cs.umn.edu/~trawny/Publications/Quaternions_3D.pdf
On Mon, Mar 31, 2014 at 1:09 AM, fboris [email protected] wrote:
Hi @simonlynen https://github.com/simonlynen,
Another question. What is the unit of noise densities and biases in this
pose_sensor_fix.yaml?core/core_noise_acc: 0.03
core/core_noise_accbias: 0.0083
core/core_noise_gyr: 0.01
core/core_noise_gyrbias: 0.0013I found some information about noise configuration in Weiss's thesis(page
68
). But the unit of variance are strange.
[image: noise2]https://cloud.githubusercontent.com/assets/4323584/2564907/c42e82ec-b8aa-11e3-8a41-daec0c8d395c.png
So I took the screen shot of this equation above.Why the variance of gyro
noise is not rad^2/sec^2 in equation 3.7? In my opinion, the unit of the
variance should be the square of it. or Do I misunderstand something?—
Reply to this email directly or view it on GitHubhttps://github.com//issues/54#issuecomment-39063072
.
from ethzasl_msf.
@heschian ,
I check the math again. The noise configuration in Weiss's thesis is correct. I also took a look at the code.
In template PredictProcessCovariance
, I found the following code below
// Noises.
const Vector3 nav = Vector3::Constant(usercalc_.GetParamNoiseAcc());
const Vector3 nbav = Vector3::Constant(usercalc_.GetParamNoiseAccbias());
const Vector3 nwv = Vector3::Constant(usercalc_.GetParamNoiseGyr());
const Vector3 nbwv = Vector3::Constant(usercalc_.GetParamNoiseGyrbias());
and
CalcQCore<StateSequence_T, StateDefinition_T>(
dt, state_new->template Get<StateDefinition_T::q>(), ew, ea, nav, nbav,
nwv, nbwv, Qd);
It means the noise densities configuration affect the Qk(covariance of the process noise
) directly. So I should put the discrete noise densities in yam. l did not understand the eigen and this framework very well. I just use the EKF theory to explain that.
from ethzasl_msf.
Hi @fboris,
you should use the continuous time densities as described in the ros.org tutorial http://wiki.ros.org/ethzasl_sensor_fusion/Tutorials/custom_sensor_design#Finding_the_correct_noise_values here since the discretization is performed here: https://github.com/ethz-asl/ethzasl_msf/blob/master/msf_core/include/msf_core/implementation/calcQCore.h
Simon
from ethzasl_msf.
@simonlynen ,
It is my fault, I did not read this part of tutorial. Thanks again!
from ethzasl_msf.
For future ref, we have a proper documentation of this here: #90
from ethzasl_msf.
Related Issues (20)
- Set up with LSD SLAM and front-looking camera on quadcopter in Gazebo
- msf State Initialization HOT 1
- What's exactly the definition of q?
- ERROR: cannot launch node of type [msf_updates/pose_sensor]: can't locate node [pose_sensor] in package [msf_updates]
- Issues about sensor_fusion
- Template mismatch under vs 2017 HOT 1
- Drift in pose estimation HOT 1
- Simple Guide for windows VS 2017 build
- IMU is working wrong? Parameters?
- tf broadcaster
- GPS + SLAM, P quickly diverges.
- Raw imu input witjout orientation
- Graph not appearing HOT 1
- No such file or directory
- Is it possible to Fuse IMU and Pressure (barometer) data? HOT 1
- Fusion IMU+LIDAR+CAMERA
- Tutorial graph not appearing
- Can the filtered trajectory be saved?
- 10-year anniversary of SSF/MSF HOT 2
- Not able to reset password HOT 1
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 ethzasl_msf.