Comments (5)
linsanity@linsanity-Legion-Y7000P-IAH7:~/dm-vio-ros/src/dm-vio-ros$ rosrun dmvio_ros node calib=/home/linsanity/dm-vio-ros/src/dm-vio-ros/camConfigs/euroc.txt settingsFile=/home/linsanity/DM-VIO/src/dm-vio/configs/euroc.yaml mode=1 nogui=0 preset=0 useimu=1 quiet=1 start=2 init_requestFullResetNormalizedErrorThreshold=0.8 init_pgba_skipFirstKFs=1
Loading settings from yaml file: /home/linsanity/DM-VIO/src/dm-vio/configs/euroc.yaml!
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!
QUIET MODE, I'll shut up!
Settings:
accelerometer_noise_density: 0.2
accelerometer_random_walk: 0.003
addVisualToCoarseGraphIfTrackingBad: 0
alwaysCanBreakIMU: 0
baToCoarseAccBiasVariance: 1000
baToCoarseGyrBiasVariance: 0.05
baToCoarsePoseVariance: 0.1
baToCoarseRotVariance: 1
baToCoarseVelVariance: 0.1
calib: /home/linsanity/dm-vio-ros/src/dm-vio-ros/camConfigs/euroc.txt
dynamicWeightRMSEThresh: 8
fixKeyframeDuringCoarseTracking: 1
gamma:
generalScaleIntervalSize: 60
gravityDirectionFixZ: 1
gyroscope_noise_density: 0.016968
gyroscope_random_walk: 1.9393e-05
imuCalib:
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
maxSkipFramesFullReset: -1
maxSkipFramesVisualInertial: 2
maxSkipFramesVisualInit: 0
maxSkipFramesVisualOnlyMode: 1
maxTimeBetweenInitFrames: 100000
minQueueSizeForSkipping: 2
normalizeCamSize: 0
numMeasurementsGravityInit: 40
preload: 0
priorExtrinsicsRot: 0.01
priorExtrinsicsTrans: 0.1
priorGravityDirection: 0.4
priorGravityDirectionZ: 0.0001
resultsPrefix:
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
skipFramesVisualOnlyDelay: 30
speed: 0
start: 2
transferCovToCoarseMultiplier: 1
updateDynamicWeightDuringOptimization: 1
useScaleDiagonalHack: 0
vignette:
Reading Calibration from file /home/linsanity/dm-vio-ros/src/dm-vio-ros/camConfigs/euroc.txt ... found!
found RadTan (OpenCV) camera model, building rectifier.
Creating RadTan undistorter
Input resolution: 752 480
In: 458.654000 457.296000 367.215000 248.375000 -0.283408 0.073959 0.000194 0.000018
Out: Rectify Crop
Output resolution: 640 480
finding CROP optimal new model!
initial range: x: -1.0297 - 1.1007; y: -0.6043 - 0.5523!
iteration 00001: range: x: -1.0245 - 1.0952; y: -0.6043 - 0.5523!
iteration 00002: range: x: -1.0194 - 1.0897; y: -0.6043 - 0.5523!
iteration 00003: range: x: -1.0194 - 1.0897; y: -0.6013 - 0.5495!
iteration 00004: range: x: -1.0194 - 1.0897; y: -0.5983 - 0.5468!
iteration 00005: range: x: -1.0194 - 1.0897; y: -0.5983 - 0.5468!
Rectified Kamera Matrix:
302.967 0 308.852
0 418.335 250.271
0 0 1
NO PHOTOMETRIC Calibration!
Reading Photometric Calibration from file
PhotometricUndistorter: Could not open file!
using pyramid levels 0 to 3. coarsest resolution: 80 x 60!
START PANGOLIN!
Switching to initializer state: RealtimeCoarseIMUInitState
PixelSelector: Using block sizes: 16, 16
OpenGL Error: GL_INVALID_OPERATION: The specified operation is not allowed in the current state. (1282)
In: /usr/local/include/pangolin/gl/gl.hpp, line 201
PixelSelector: Using block sizes: 16, 16
InitTimeBetweenFrames: 0.05
InitTimeBetweenFrames: 0.1
InitTimeBetweenFrames: 0.15
InitTimeBetweenFrames: 0.2
InitTimeBetweenFrames: 0.25
InitTimeBetweenFrames: 0.3
Scaling with rescaleFactor: 1.19942
INITIALIZE FROM INITIALIZER (972 pts)!
段错误 (核心已转储)
from dm-vio.
This might be a duplicate of lukasvst/dm-vio-ros#6
Do you have multiple boost versions installed on your machine?
Other possibilities:
Does the system work with useimu=0
?
Does running DM-VIO on a dataset (without the ROS driver) work?
Otherwise you can run the code with gdb and print the backtrace to find the cause of the issue.
from dm-vio.
Thank you very much for taking the time to reply to me, I have successfully reproduced your project with dm-vio-ros, and have conducted experiments on the EuRoC dataset and evaluated the results. Now I want to run your project on the Field Environment Dataset (ROOAD), which provides monocular data streams and IMU data streams, but I can't successfully estimate pose after setting up the camera.txt and corresponding yaml files. I'm guessing it might be somewhere where the configuration is imperfect.
from dm-vio.
I've evaluated the ROOAD dataset on VINSFusion and I think your project is definitely better than VINSFusion, but I've had some issues and would like your guidance.
from dm-vio.
From your screenshots it looks like it doesn't get past the "visual-init" stage. This would suggest that the camera calibration is not good enough (or maybe the motion is too fast for it to initialize?). Can you confirm that it can successfully track easy (slow) sequences with this camera calibration?
Another trick might be to use the following settings if you are on a vehicle which only moves forward:
setting_weightZeroPriorDSOInitY: 5e09
setting_weightZeroPriorDSOInitX: 5e09
(Maybe you need also to want to increase maxTimeBetweenInitFrames: 1.0
, e.g to 2.0)
from dm-vio.
Related Issues (20)
- How does dm-vio pick points to track? HOT 1
- make error HOT 1
- How to saveout the result as pointcloud? HOT 1
- undefined reference to `boost::system::generic_category()' HOT 1
- run dm-vio with own data HOT 3
- Any plan for Stereo camera Support? plz
- Cmake Error HOT 3
- integration sigma HOT 1
- Nothing happened on the GUI HOT 3
- 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
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.