Comments (7)
Thanks for trying the noimu mode first.
Have you also passed the camchain file and is it read correctly?
Could you please post the command you use for running and the beginning of the commandline output where all the settings are printed, until the error first occurs?
from dm-vio.
Thank you for your reply!
I made camchain file using the default camera-inertial calibration values of realsense d435i.
My run command is below:
python3 run_dmvio.py --output=console --dataset=sr --dmvio_settings=sr.yaml --withgui --iter=1 --only_seq=1 --dmvio_args="init_pgba_skipFirstKFs=1 init_requestFullResetNormalizedErrorThreshold=0.8"
Here, sr is my dataset name.
Since "#-stats: 0" repeats a lot, I deleted "#-stats:" log for readability.
----------- create_dmvio_commands -----------
files=./data calib=./camera.txt imuCalib=/home/jychoi/git_ws/src/dm-vio/configs/sr_calib/camchain.yaml mode=1 preset=0 nogui=0 useimu=1 quiet=0 settingsFile=/home/jychoi/git_ws/src/dm-vio/configs/sr.yaml init_pgba_skipFirstKFs=1 init_requestFullResetNormalizedErrorThreshold=0.8
WARNING: No end times for dataset.
----------- Save Project Status -----------
{'name': 'dmvioresult', 'dataset': 'sr', 'build_type': 'RelWithDebInfo', 'num_iter': 1, 'only_seq': 1, 'results_name': 'dmvioresult-sr-2022-05-17--09-57-11', 'config_name': 'workpc', 'date_run': datetime.datetime(2022, 5, 17, 9, 57, 11, 382691), 'realtime': False, 'temporary': False, 'noimu': False, 'quiet': False, 'output_type': 'console', 'withgui': True, 'custom_dmvio_args': 'init_pgba_skipFirstKFs=1 init_requestFullResetNormalizedErrorThreshold=0.8', 'dmvio_settings': 'sr.yaml', 'gdb': False, 'git_hash': '5bf2a67c10973a91c061483b10a0257e2e0c5b11', 'commit_message': 'Added note on the GTSAM version to the README.', 'commit_time': datetime.datetime(2022, 5, 4, 15, 26, 58), 'diff_empty': False, 'eval_tool_command': 'run_dmvio.py --output=console --dataset=sr --dmvio_settings=sr.yaml --withgui --iter=1 --only_seq=1 --dmvio_args=init_pgba_skipFirstKFs=1 init_requestFullResetNormalizedErrorThreshold=0.8', 'eval_tools_git_hash': 'f1e581e26022706b97aceee8022489e8a97e5c82', 'eval_tools_commit_message': 'Initial commit.', 'eval_tools_diff_empty': False, 'command_0': '/home/jychoi/git_ws/src/dm-vio/cmake-build-relwithdebinfo/bin/dmvio_dataset files=./data calib=./camera.txt imuCalib=/home/jychoi/git_ws/src/dm-vio/configs/sr_calib/camchain.yaml mode=1 preset=0 nogui=0 useimu=1 quiet=0 settingsFile=/home/jychoi/git_ws/src/dm-vio/configs/sr.yaml init_pgba_skipFirstKFs=1 init_requestFullResetNormalizedErrorThreshold=0.8 resultsPrefix=/home/jychoi/git_ws/src/dm-vio-result/dmvioresult-sr-2022-05-17--09-57-11/sr_220426_162017_cam_40_light_on_ir_color_2_0/ start=1', 'cwd0': '/home/jychoi/dataset/SR_VIO_EuRoC/220426_162017_cam_40_light_on_ir_color_2/cam0'}
WARNING: apt does not have a stable CLI interface. Use with caution in scripts.
----------- STARTING EXECUTION! -----------
Working Dir: /home/jychoi/dataset/SR_VIO_EuRoC/220426_162017_cam_40_light_on_ir_color_2/cam0
Command: /home/jychoi/git_ws/src/dm-vio/cmake-build-relwithdebinfo/bin/dmvio_dataset files=./data calib=./camera.txt imuCalib=/home/jychoi/git_ws/src/dm-vio/configs/sr_calib/camchain.yaml mode=1 preset=0 nogui=0 useimu=1 quiet=0 settingsFile=/home/jychoi/git_ws/src/dm-vio/configs/sr.yaml init_pgba_skipFirstKFs=1 init_requestFullResetNormalizedErrorThreshold=0.8 resultsPrefix=/home/jychoi/git_ws/src/dm-vio-result/dmvioresult-sr-2022-05-17--09-57-11/sr_220426_162017_cam_40_light_on_ir_color_2_0/ start=1
loading data from ./data!
loading calibration from ./camera.txt!
Loading imu parameters from /home/jychoi/git_ws/src/dm-vio/configs/sr_calib/camchain.yaml!
Loading IMU parameter file at: /home/jychoi/git_ws/src/dm-vio/configs/sr_calib/camchain.yaml
Used T_cam_imu:
1 0 0 0.006
0 1 0 -0.0051
0 0 1 -0.012
0 0 0 1
Used noise values: 0.00447213 0.0014142 0.316227 0.1
PHOTOMETRIC MODE WITHOUT CALIBRATION!
=============== PRESET Settings: ===============
DEFAULT settings:
- no real-time enforcing
- 2000 active points
- 5-7 active frames
- 1-6 LM iteration each KF
- original image resolution
==============================================
Enabling IMU integration!
Loading settings from yaml file: /home/jychoi/git_ws/src/dm-vio/configs/sr_calib/camchain.yaml!
START AT 1!
Settings:
accelerometer_noise_density: 0.2
accelerometer_random_walk: 0.04
addVisualToCoarseGraphIfTrackingBad: 0
alwaysCanBreakIMU: 0
baToCoarseAccBiasVariance: 1000
baToCoarseGyrBiasVariance: 0.05
baToCoarsePoseVariance: 0.1
baToCoarseRotVariance: 1
baToCoarseVelVariance: 0.1
dynamicWeightRMSEThresh: 8
fixKeyframeDuringCoarseTracking: 1
generalScaleIntervalSize: 60
gravityDirectionFixZ: 1
gyroscope_noise_density: 0.02
gyroscope_random_walk: 0.004
init_coarseScaleUncertaintyThresh: 1
init_conversionType: 0
init_disableVIOUntilFirstInit: 1
init_fixPoses: 1
init_initDSOParams: 1
init_lambdaLowerBound: 1e-16
init_maxNumPoses: 100
init_multipleBiases: 0
init_multithreadedInitDespiteNonRT: 0
init_onlyKFs: 1
init_pgba_conversionType: 0
init_pgba_delay: 100
init_pgba_prepareGraphAddDelValues: 0
init_pgba_prepareGraphAddFactors: 0
init_pgba_priorExtrinsicsRot: 0.01
init_pgba_priorExtrinsicsTrans: 0.1
init_pgba_priorGravityDirection: 0.4
init_pgba_priorGravityDirectionZ: 0.0001
init_pgba_reinitScaleUncertaintyThresh: 0.5
init_pgba_scaleUncertaintyThresh: 1
init_pgba_skipFirstKFs: 1
init_priorExtrinsicsRot: 0.01
init_priorExtrinsicsTrans: 0.1
init_priorGravityDirection: 0.4
init_priorGravityDirectionZ: 0.0001
init_priorRotSigma: 1e-05
init_priorTransSigma: 1e-05
init_requestFullResetErrorThreshold: -1
init_requestFullResetNormalizedErrorThreshold: 0.8
init_scalePriorAfterInit: 0
init_secondthreshGravdir: 1000
init_secondthreshScale: 1e+07
init_threshGravdir: 1000
init_threshScale: 1.02
init_transitionModel: 2
init_updatePoses: 1
integration_sigma: 0.316227
maxFrameEnergyThreshold: 5000
maxPreloadImages: 0
maxTimeBetweenInitFrames: 100000
numMeasurementsGravityInit: 40
preload: 0
priorExtrinsicsRot: 0.01
priorExtrinsicsTrans: 0.1
priorGravityDirection: 0.4
priorGravityDirectionZ: 0.0001
resultsPrefix: /home/jychoi/git_ws/src/dm-vio-result/dmvioresult-sr-2022-05-17--09-57-11/sr_220426_162017_cam_40_light_on_ir_color_2_0/
setting_forceNoKFTranslationThresh: 0
setting_maxOptIterations: 6
setting_minFramesBetweenKeyframes: -0.5
setting_minIdepth: 0.02
setting_minOptIterations: 1
setting_optGravity: 1
setting_optIMUExtrinsics: 0
setting_optScaleBA: 1
setting_prior_bias: 0
setting_prior_velocity: 0
setting_scaleFixTH: 0
setting_solverMode: 2048
setting_transferCovToCoarse: 1
setting_visualOnlyAfterScaleFixing: 0
setting_weightDSOCoarse: 0.001
setting_weightDSOToGTSAM: 1.66667e-05
setting_weightZeroPriorDSOInitX: 0
setting_weightZeroPriorDSOInitY: 0
skipFirstKeyframe: 0
transferCovToCoarseMultiplier: 1
updateDynamicWeightDuringOptimization: 1
use16Bit: 0
useScaleDiagonalHack: 0
Reading Calibration from file ./camera.txt ... found!
found RadTan (OpenCV) camera model, building rectifier.
Creating RadTan undistorter
Input resolution: 640 480
In: 385.755000 385.755000 323.121000 236.743000 0.000000 0.000000 0.000000 0.000000
Out: No Rectification
Output resolution: 640 480
Rectified Kamera Matrix:
385.755 0 323.121
0 385.755 236.743
0 0 1
NO PHOTOMETRIC Calibration!
Reading Photometric Calibration from file
PhotometricUndistorter: Could not open file!
image num: 3013time num: 3013
set EXPOSURES to zero!
got 3013 images and 3013 timestamps and 0 exposures.!
ImageFolderReader: got 3013 files in ./data!
IMU Id: 1650957618591295744
IMU-data too old -> skipping frame
IMU-data too old -> skipping frame
====This sentence "IMU-data too old -> skipping frame" came up a lot. ====
IMU-data too old -> skipping frame
Found no start frame for IMU-data!
using pyramid levels 0 to 3. coarsest resolution: 80 x 60!
START PANGOLIN!
Using setting_minFramesBetweenKeyframes=0.5 because of non-realtime mode.
Switching to initializer state: CoarseIMUInit
PixelSelector: Using block sizes: 16, 16
Loading gt data
GTData distance (seconds): 0.0078123
PixelSelector: Using block sizes: 16, 16
GTData distance (seconds): 0.0067623
InitTimeBetweenFrames: 0.0333583
==== GTdata distance and InitTimeBetweenFrames are repeated.====
Scaling with rescaleFactor: 1.28913
Initialization: keep 10.9% (need 1000, have 9202)!
INITIALIZE FROM INITIALIZER (974 pts)!
Frame history size: 192
Preparing keyframe: 191
Frames between KFs: 190
SPARSITY: MinActDist 1.900000 (need 1000 points, have 974 points)!
OPTIMIZE 974 pts, 974 active res, 0 lin res!
activeResiduals.size(): 974
Initial Error A(0.000000)=(AV -nan). Num: A(0) + M(0); ab 0.000000 0.000000!
Dynamic weight: 1
STEPS: A nan; B nan; R nan; T nan. REJECT 0 (L -5.00, dir nan, ss 1.0): A(0.000000)=(AV -nan). Num: A(0) + M(0); ab nan nan!
Dynamic weight: 1
from dm-vio.
The problem is that the IMU data cannot be associated with the image data.
The line IMU-data too old -> skipping frame
should only printed a couple of times maximum. If it is printed out a lot and with the line Found no start frame for IMU-data!
there is no frame with associated IMU data.
Have you interpolated the IMU file, so that each frame has an IMU measurement with exactly its timestamp (e.g. with this script?
If that's not the issue, the association code makes some strong assumptions:
- The first column in
times.txt
must be the timestamp of the corresponding image in nanoseconds. There should be a measurement in the IMU file with exactly the same timestamp. - Images are associated with the line in
times.txt
simply by order. It's best practice to name each image after the first column in times.txt (the timestamp in nanoseconds), but this is not checked at runtime.
I hope this helps in finding the issue, (otherwise you could also post your times.txt
and imu.txt
file.)
from dm-vio.
When realsense d435i is turned on, imu and camera are not completely synchronized, but I thought that they bring data of a somewhat similar time.
If you look at the time.txt and imu.txt files below, you can see that they have data at the same time although there is a slight difference.
======= times.txt ==========
1650957618546289920 1650957618.546289920
1650957618579647744 1650957618.579647744
1650957618613006080 1650957618.613006080
1650957618646362624 1650957618.646362624
1650957618679720192 1650957618.679720192
1650957618713077760 1650957618.713077760
1650957618746436352 1650957618.746436352
1650957618779792640 1650957618.779792640
1650957618813150208 1650957618.813150208
1650957618846507776 1650957618.846507776
1650957618879865344 1650957618.879865344
1650957618913222912 1650957618.913222912
1650957618946580224 1650957618.946580224
1650957618979937792 1650957618.979937792
1650957619013294848 1650957619.013294848
1650957619046651904 1650957619.046651904
1650957619080008960 1650957619.080008960
1650957619113366272 1650957619.113366272
1650957619146723328 1650957619.146723328
1650957619180080384 1650957619.180080384
...
...
======= imu.txt ==========
1650957618591295744 -0.001701 -0.003494 -0.001733 0.015765 -7.701474 6.218314
1650957618596292352 0.000044 -0.008730 0.001758 0.055764 -7.662160 6.268433
1650957618601289984 -0.001701 -0.000003 0.000013 0.055764 -7.662160 6.268433
1650957618606286592 0.000044 -0.000003 -0.003478 0.055764 -7.662160 6.268433
1650957618611283200 -0.003447 -0.000003 0.000013 0.035688 -7.661873 6.288426
1650957618616279808 -0.001701 -0.000003 0.000013 0.035688 -7.661873 6.288426
1650957618621277696 0.000044 0.003487 0.000013 0.035688 -7.661873 6.288426
1650957618626274048 -0.001701 -0.000003 -0.003478 0.035688 -7.661873 6.288426
1650957618631270656 -0.001701 -0.003494 0.003503 0.055689 -7.662184 6.288163
1650957618636267264 0.000044 -0.000003 0.000013 0.055689 -7.662184 6.288163
1650957618641264896 -0.001701 -0.001749 0.000013 0.055689 -7.662184 6.288163
1650957618646261760 -0.003447 -0.003494 0.000013 0.055781 -7.642186 6.288824
1650957618651258368 -0.001701 -0.000003 -0.003478 0.055781 -7.642186 6.288824
1650957618656254976 -0.005192 0.015705 0.001758 0.055781 -7.642186 6.288824
1650957618661252352 0.000044 0.003487 -0.001733 0.035596 -7.681871 6.287766
1650957618666248960 0.000044 0.001742 0.000013 0.035596 -7.681871 6.287766
1650957618671245824 0.000044 -0.000003 0.000013 0.035596 -7.681871 6.287766
1650957618676242432 -0.003447 -0.000003 0.000013 0.055689 -7.662184 6.288163
1650957618681240064 0.000044 -0.000003 0.001758 0.055689 -7.662184 6.288163
1650957618686236672 0.000044 -0.005239 -0.003478 0.055689 -7.662184 6.288163
...
...
from dm-vio.
There are two "levels" of IMU-camera synchronization:
- The first one is that IMU and camera timestamps are recorded with the same device or otherwise made consistent. This is a prerequisite for running DM-VIO, and I think for the D435i this is the case.
- The second level is that the IMU is triggered manually and always records an IMU sample exactly during the timestamp (middle of exposure) of each image. E.g. the VI-Sensor used in the EuRoC dataset does this, but most other visual-inertial sensors don't. For these sensors you can still run DM-VIO, but first you need to add a "fake IMU measurement" for each camera timestamp, by interpolating the neighboring IMU samples. As mentioned, this script does this for you.
So long story short: You need to run
python3 interpolate_imu_file --input imu.txt --times times.txt --output pass_this_imu_file_to_dmvio.txt
and then it should work.
Please let me know if this solves the issue for you.
from dm-vio.
There are two "levels" of IMU-camera synchronization:
- The first one is that IMU and camera timestamps are recorded with the same device or otherwise made consistent. This is a prerequisite for running DM-VIO, and I think for the D435i this is the case.
- The second level is that the IMU is triggered manually and always records an IMU sample exactly during the timestamp (middle of exposure) of each image. E.g. the VI-Sensor used in the EuRoC dataset does this, but most other visual-inertial sensors don't. For these sensors you can still run DM-VIO, but first you need to add a "fake IMU measurement" for each camera timestamp, by interpolating the neighboring IMU samples. As mentioned, this script does this for you.
So long story short: You need to run
python3 interpolate_imu_file --input imu.txt --times times.txt --output pass_this_imu_file_to_dmvio.txt
and then it should work.Please let me know if this solves the issue for you.
It works!!!!!!!!!
Thank you so much for being patient with me.
I think it will be of great help to others if it is included in the readme.
It was confirmed that it works well even in environments where pure DSO did not work properly.
from dm-vio.
I'm glad that it helped. Yes, I will include it in the README with a later update.
from dm-vio.
Related Issues (20)
- Nothing happened on the GUI HOT 3
- The compilation succeeds, but the visualization window crashes when the dataset is run HOT 5
- The visualization window crashes after receiving the dataset HOT 1
- Porting to Windows, crash on init HOT 8
- Large CoarseIMUInitializer error! HOT 3
- How do I compare the data in the ground truth and the data in the result? HOT 2
- Initial velocity for initialization HOT 1
- What does integration_sigma mean? HOT 1
- gtsam symbol error HOT 2
- Can I load a map and localize the camera and pose within the map HOT 1
- The TUM-VI Euroc is not available
- why would this happened? I set the right PATH, but it still didn't work. HOT 1
- Will dm-vio work with low sub 10Hz IMU sample rate? HOT 2
- save result when running live with D435i camera
- Trouble with subfolder for dm-vio-ros HOT 1
- Resetting camera HOT 19
- Vignette error HOT 1
- PreintegratedImuMeasurements::integrateMeasurement: dt <=0
- JacobianFactor::updateHessian: cannot update information with constrained noise model
- Camera model support 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 dm-vio.