This post was updated on .
Hi Mathieu,
I have some questions about your results that I've read at this paper. I want to replicate what you've done at the sequence 00 using only lidar. I've found out that at this post, as you say, you're passing the arguments that were used for the tests that were made in the paper. So, I launched rtabmap passing these arguments. roslaunch rtabmap_ros rtabmap.launch \ use_sim_time:=true \ depth:=false \ subscribe_scan_cloud:=true \ frame_id:=base_link \ scan_cloud_topic:=/kitti/velo/pointcloud \ scan_cloud_max_points:=131072 \ icp_odometry:=true \ approx_sync:=false \ args:="-d \ --RGBD/CreateOccupancyGrid false \ --Rtabmap/DetectionRate 2 \ --Odom/ScanKeyFrameThr 0.8 \ --OdomF2M/ScanMaxSize 10000 \ --OdomF2M/ScanSubtractRadius 0.5 \ --Icp/PM true \ --Icp/VoxelSize 0.5 \ --Icp/MaxTranslation 2 \ --Icp/MaxCorrespondenceDistance 1.5 \ --Icp/PMOutlierRatio 0.7 \ --Icp/Iterations 10 \ --Icp/PointToPlane false \ --Icp/PMMatcherKnn 3 \ --Icp/PMMatcherEpsilon 1 \ --Icp/Epsilon 0.0001 \ --Icp/PointToPlaneK 0 \ --Icp/PointToPlaneRadius 0 \ --Icp/CorrespondenceRatio 0.01" Also, as I've read from the odometry developement kit the sequence 00 can be downloaded from here according to the following table. Nr. Sequence name Start End 00: 2011_10_03_drive_0027 000000 004540 01: 2011_10_03_drive_0042 000000 001100 02: 2011_10_03_drive_0034 000000 004660 03: 2011_09_26_drive_0067 000000 000800 04: 2011_09_30_drive_0016 000000 000270 05: 2011_09_30_drive_0018 000000 002760 06: 2011_09_30_drive_0020 000000 001100 07: 2011_09_30_drive_0027 000000 001100 08: 2011_09_30_drive_0028 001100 005170 09: 2011_09_30_drive_0033 000000 001590 10: 2011_09_30_drive_0034 000000 001200 Assuming that I am right at all the previously said, my graph looks like this which is completely different from the results that are shown in the paper, but I don't know what am I doing wrong... Also, when I use the imu_topic it says that it can not perform the registration with a null guess. So, I do not know what to do to improve my solution. And when I am rerunning the rtabmap I get different results. So Mathieu, do you have any idea for what I've been missing ? Sincerely, Anthony. |
Administrator
|
Hi Anthony,
For the paper, the dataset from this page has been used. The tool used to evaluate that dataset is called rtabmap-kitti_dataset, used in that script. I just tried the command you used with that bag: This is without loop closure detection. The results in the paper are with loop closure detection. What is your rtabmap config? $ rtabmap --version cheers, Mathieu |
Hey Mathieu,
antonis@antonis-VirtualBox:~$ rtabmap --version RTAB-Map: 0.20.9 PCL: 1.8.1 With VTK: 6.3.0 OpenCV: 3.2.0 With OpenCV xfeatures2d: false With OpenCV nonfree: false With ORB OcTree: true With SuperPoint Torch: false With Python3: false With FastCV: false With Madgwick: true With TORO: true With g2o: true With GTSAM: true With Vertigo: true With CVSBA: false With Ceres: false With OpenNI2: true With Freenect: true With Freenect2: false With K4W2: false With K4A: false With DC1394: true With FlyCapture2: false With ZED: false With RealSense: false With RealSense SLAM: false With RealSense2: false With MYNT EYE S: false With libpointmatcher: true With octomap: true With cpu-tsdf: false With open chisel: false With Alice Vision: false With LOAM: false With FOVIS: false With Viso2: false With DVO: false With ORB_SLAM2: false With OKVIS: false With MSCKF_VIO: false With VINS-Fusion: false This is my configuration. |
Administrator
|
It looks okay, and the created database:
rtabmap-info ~/.ros/rtabmap.db |
This post was updated on .
This is my output:
$ rtabmap-info ~/.ros/rtabmap.db Parameters (Yellow=modified, Red=old parameter not used anymore): BRIEF/Bytes= 32 BRISK/Octaves= 3 BRISK/PatternScale= 1 BRISK/Thresh= 30 Bayes/FullPredictionUpdate= false Bayes/PredictionLC= 0.1 0.36 0.30 0.16 0.062 0.0151 0.00255 0.000324 2.5e-05 1.3e-06 4.8e-08 1.2e-09 1.9e-11 2.2e-13 1.7e-15 8.5e-18 2.9e-20 6.9e-23 Bayes/VirtualPlacePriorThr= 0.9 DbSqlite3/CacheSize= 10000 DbSqlite3/InMemory= false DbSqlite3/JournalMode= 3 DbSqlite3/Synchronous= 0 DbSqlite3/TempStore= 2 FAST/CV= 0 FAST/Gpu= false FAST/GpuKeypointsRatio= 0.05 FAST/GridCols= 0 FAST/GridRows= 0 FAST/MaxThreshold= 200 FAST/MinThreshold= 7 FAST/NonmaxSuppression= true FAST/Threshold= 20 FREAK/NOctaves= 4 FREAK/OrientationNormalized= true FREAK/PatternScale= 22 FREAK/ScaleNormalized= true GFTT/BlockSize= 3 GFTT/K= 0.04 GFTT/MinDistance= 7 GFTT/QualityLevel= 0.001 GFTT/UseHarrisDetector= false GMS/ThresholdFactor= 6.0 GMS/WithRotation= false GMS/WithScale= false GTSAM/Optimizer= 1 Grid/3D= true Grid/CellSize= 0.05 Grid/ClusterRadius= 0.1 Grid/DepthDecimation= 4 Grid/DepthRoiRatios= 0.0 0.0 0.0 0.0 Grid/FlatObstacleDetected= true Grid/FootprintHeight= 0.0 Grid/FootprintLength= 0.0 Grid/FootprintWidth= 0.0 Grid/FromDepth= false (default=true) Grid/GroundIsObstacle= false Grid/MapFrameProjection= false Grid/MaxGroundAngle= 45 Grid/MaxGroundHeight= 0.0 Grid/MaxObstacleHeight= 0.0 Grid/MinClusterSize= 10 Grid/MinGroundHeight= 0.0 Grid/NoiseFilteringMinNeighbors= 5 Grid/NoiseFilteringRadius= 0.0 Grid/NormalK= 20 Grid/NormalsSegmentation= true Grid/PreVoxelFiltering= true Grid/RangeMax= 0 (default=5.0) Grid/RangeMin= 0.0 Grid/RayTracing= false Grid/Scan2dUnknownSpaceFilled= false Grid/ScanDecimation= 1 GridGlobal/AltitudeDelta= 0 GridGlobal/Eroded= false GridGlobal/FootprintRadius= 0.0 GridGlobal/FullUpdate= true GridGlobal/MaxNodes= 0 GridGlobal/MinSize= 0.0 GridGlobal/OccupancyThr= 0.5 GridGlobal/ProbClampingMax= 0.971 GridGlobal/ProbClampingMin= 0.1192 GridGlobal/ProbHit= 0.7 GridGlobal/ProbMiss= 0.4 GridGlobal/UpdateError= 0.01 Icp/CorrespondenceRatio= 0.01 (default=0.1) Icp/DownsamplingStep= 1 Icp/Epsilon= 0.0001 (default=0) Icp/Iterations= 10 (default=30) Icp/MaxCorrespondenceDistance= 1.5 (default=0.1) Icp/MaxRotation= 0.78 Icp/MaxTranslation= 2 (default=0.2) Icp/PM= true Icp/PMForce4DoF= false Icp/PMMatcherEpsilon= 1 (default=0.0) Icp/PMMatcherIntensity= false Icp/PMMatcherKnn= 3 (default=1) Icp/PMOutlierRatio= 0.7 (default=0.85) Icp/PointToPlane= false (default=true) Icp/PointToPlaneGroundNormalsUp= 0.0 Icp/PointToPlaneK= 0 (default=5) Icp/PointToPlaneLowComplexityStrategy=1 Icp/PointToPlaneMinComplexity= 0.02 Icp/PointToPlaneRadius= 0 (default=1.0) Icp/RangeMax= 0 Icp/RangeMin= 0 Icp/VoxelSize= 0.5 (default=0.05) ImuFilter/ComplementaryBiasAlpha= 0.01 ImuFilter/ComplementaryDoAdpativeGain=true ImuFilter/ComplementaryDoBiasEstimation=true ImuFilter/ComplementaryGainAcc= 0.01 ImuFilter/MadgwickGain= 0.1 ImuFilter/MadgwickZeta= 0.0 KAZE/Diffusivity= 1 KAZE/Extended= false KAZE/NOctaveLayers= 4 KAZE/NOctaves= 4 KAZE/Threshold= 0.001 KAZE/Upright= false Kp/BadSignRatio= 0.5 Kp/ByteToFloat= false Kp/DetectorStrategy= 8 Kp/FlannRebalancingFactor= 2.0 Kp/GridCols= 1 Kp/GridRows= 1 Kp/IncrementalDictionary= true Kp/IncrementalFlann= true Kp/MaxDepth= 0 Kp/MaxFeatures= 500 Kp/MinDepth= 0 Kp/NNStrategy= 1 Kp/NewWordsComparedTogether= true Kp/NndrRatio= 0.8 Kp/Parallelized= true Kp/RoiRatios= 0.0 0.0 0.0 0.0 Kp/SubPixEps= 0.02 Kp/SubPixIterations= 0 Kp/SubPixWinSize= 3 Kp/TfIdfLikelihoodUsed= true Marker/CornerRefinementMethod= 0 Marker/Dictionary= 0 Marker/Length= 0 Marker/MaxDepthError= 0.01 Marker/MaxRange= 0.0 Marker/MinRange= 0.0 Marker/VarianceAngular= 0.01 Marker/VarianceLinear= 0.001 Mem/BadSignaturesIgnored= false Mem/BinDataKept= true Mem/CompressionParallelized= true Mem/CovOffDiagIgnored= true Mem/DepthAsMask= true Mem/GenerateIds= true Mem/ImageCompressionFormat= .jpg Mem/ImageKept= false Mem/ImagePostDecimation= 1 Mem/ImagePreDecimation= 1 Mem/IncrementalMemory= true Mem/InitWMWithAllNodes= false Mem/IntermediateNodeDataKept= false Mem/LaserScanDownsampleStepSize= 1 Mem/LaserScanNormalK= 0 Mem/LaserScanNormalRadius= 0.0 Mem/LaserScanVoxelSize= 0.0 Mem/LocalizationDataSaved= false Mem/MapLabelsAdded= true Mem/NotLinkedNodesKept= true Mem/RawDescriptorsKept= true Mem/RecentWmRatio= 0.2 Mem/ReduceGraph= false Mem/RehearsalIdUpdatedToNewOne= false Mem/RehearsalSimilarity= 0.6 Mem/RehearsalWeightIgnoredWhileMoving=false Mem/STMSize= 10 Mem/SaveDepth16Format= false Mem/StereoFromMotion= false Mem/TransferSortingByWeightId= false Mem/UseOdomFeatures= true Mem/UseOdomGravity= false ORB/EdgeThreshold= 19 ORB/FirstLevel= 0 ORB/Gpu= false ORB/NLevels= 3 ORB/PatchSize= 31 ORB/ScaleFactor= 2 ORB/ScoreType= 0 ORB/WTA_K= 2 Odom/AlignWithGround= false Odom/FillInfoData= true Odom/FilteringStrategy= 0 Odom/GuessMotion= true Odom/GuessSmoothingDelay= 0 Odom/Holonomic= true Odom/ImageBufferSize= 1 Odom/ImageDecimation= 1 Odom/KalmanMeasurementNoise= 0.01 Odom/KalmanProcessNoise= 0.001 Odom/KeyFrameThr= 0.3 Odom/ParticleLambdaR= 100 Odom/ParticleLambdaT= 100 Odom/ParticleNoiseR= 0.002 Odom/ParticleNoiseT= 0.002 Odom/ParticleSize= 400 Odom/ResetCountdown= 0 Odom/ScanKeyFrameThr= 0.8 (default=0.9) Odom/Strategy= 0 Odom/VisKeyFrameThr= 150 OdomF2M/BundleAdjustment= 1 OdomF2M/BundleAdjustmentMaxFrames= 10 OdomF2M/MaxNewFeatures= 0 OdomF2M/MaxSize= 2000 OdomF2M/ScanMaxSize= 10000 (default=2000) OdomF2M/ScanRange= 0 OdomF2M/ScanSubtractAngle= 45 OdomF2M/ScanSubtractRadius= 0.5 (default=0.05) OdomF2M/ValidDepthRatio= 0.75 OdomFovis/BucketHeight= 80 OdomFovis/BucketWidth= 80 OdomFovis/CliqueInlierThreshold= 0.1 OdomFovis/FastThreshold= 20 OdomFovis/FastThresholdAdaptiveGain=0.005 OdomFovis/FeatureSearchWindow= 25 OdomFovis/FeatureWindowSize= 9 OdomFovis/InlierMaxReprojectionError=1.5 OdomFovis/MaxKeypointsPerBucket= 25 OdomFovis/MaxMeanReprojectionError=10.0 OdomFovis/MaxPyramidLevel= 3 OdomFovis/MinFeaturesForEstimate= 20 OdomFovis/MinPyramidLevel= 0 OdomFovis/StereoMaxDisparity= 128 OdomFovis/StereoMaxDistEpipolarLine=1.5 OdomFovis/StereoMaxRefinementDisplacement=1.0 OdomFovis/StereoRequireMutualMatch=true OdomFovis/TargetPixelsPerFeature= 250 OdomFovis/UpdateTargetFeaturesWithRefined=false OdomFovis/UseAdaptiveThreshold= true OdomFovis/UseBucketing= true OdomFovis/UseHomographyInitialization=true OdomFovis/UseImageNormalization= false OdomFovis/UseSubpixelRefinement= true OdomLOAM/AngVar= 0.01 OdomLOAM/LinVar= 0.01 OdomLOAM/LocalMapping= true OdomLOAM/ScanPeriod= 0.1 OdomLOAM/Sensor= 2 OdomMSCKF/FastThreshold= 10 OdomMSCKF/GridCol= 5 OdomMSCKF/GridMaxFeatureNum= 4 OdomMSCKF/GridMinFeatureNum= 3 OdomMSCKF/GridRow= 4 OdomMSCKF/InitCovAccBias= 0.01 OdomMSCKF/InitCovExRot= 0.00030462 OdomMSCKF/InitCovExTrans= 0.000025 OdomMSCKF/InitCovGyroBias= 0.01 OdomMSCKF/InitCovVel= 0.25 OdomMSCKF/MaxCamStateSize= 20 OdomMSCKF/MaxIteration= 30 OdomMSCKF/NoiseAcc= 0.05 OdomMSCKF/NoiseAccBias= 0.01 OdomMSCKF/NoiseFeature= 0.035 OdomMSCKF/NoiseGyro= 0.005 OdomMSCKF/NoiseGyroBias= 0.001 OdomMSCKF/OptTranslationThreshold= 0 OdomMSCKF/PatchSize= 15 OdomMSCKF/PositionStdThreshold= 8.0 OdomMSCKF/PyramidLevels= 3 OdomMSCKF/RansacThreshold= 3 OdomMSCKF/RotationThreshold= 0.2618 OdomMSCKF/StereoThreshold= 5 OdomMSCKF/TrackPrecision= 0.01 OdomMSCKF/TrackingRateThreshold= 0.5 OdomMSCKF/TranslationThreshold= 0.4 OdomMono/InitMinFlow= 100 OdomMono/InitMinTranslation= 0.1 OdomMono/MaxVariance= 0.01 OdomMono/MinTranslation= 0.02 OdomORBSLAM2/Bf= 0.076 OdomORBSLAM2/Fps= 0.0 OdomORBSLAM2/MapSize= 3000 OdomORBSLAM2/MaxFeatures= 1000 OdomORBSLAM2/ThDepth= 40.0 OdomViso2/BucketHeight= 50 OdomViso2/BucketMaxFeatures= 2 OdomViso2/BucketWidth= 50 OdomViso2/InlierThreshold= 2.0 OdomViso2/MatchBinsize= 50 OdomViso2/MatchDispTolerance= 2 OdomViso2/MatchHalfResolution= true OdomViso2/MatchMultiStage= true OdomViso2/MatchNmsN= 3 OdomViso2/MatchNmsTau= 50 OdomViso2/MatchOutlierDispTolerance=5 OdomViso2/MatchOutlierFlowTolerance=5 OdomViso2/MatchRadius= 200 OdomViso2/MatchRefinement= 1 OdomViso2/RansacIters= 200 OdomViso2/Reweighting= true Optimizer/Epsilon= 0.00001 Optimizer/GravitySigma= 0.3 Optimizer/Iterations= 20 Optimizer/LandmarksIgnored= false Optimizer/PriorsIgnored= true Optimizer/Robust= false Optimizer/Strategy= 2 Optimizer/VarianceIgnored= false PyDetector/Cuda= true PyMatcher/Cuda= true PyMatcher/Iterations= 20 PyMatcher/Model= indoor PyMatcher/Threshold= 0.2 RGBD/AngularSpeedUpdate= 0.0 RGBD/AngularUpdate= 0.1 RGBD/CreateOccupancyGrid= false RGBD/Enabled= true RGBD/GoalReachedRadius= 0.5 RGBD/GoalsSavedInUserData= false RGBD/LinearSpeedUpdate= 0.0 RGBD/LinearUpdate= 0.1 RGBD/LocalBundleOnLoopClosure= false RGBD/LocalImmunizationRatio= 0.25 RGBD/LocalRadius= 10 RGBD/LoopClosureReextractFeatures= false RGBD/LoopCovLimited= false RGBD/MarkerDetection= false RGBD/MaxLocalRetrieved= 2 RGBD/MaxLoopClosureDistance= 0.0 RGBD/MaxOdomCacheSize= 0 RGBD/NeighborLinkRefining= false RGBD/NewMapOdomChangeDistance= 0 RGBD/OptimizeFromGraphEnd= false RGBD/OptimizeMaxError= 3.0 RGBD/PlanAngularVelocity= 0 RGBD/PlanLinearVelocity= 0 RGBD/PlanStuckIterations= 0 RGBD/ProximityAngle= 45 RGBD/ProximityBySpace= true RGBD/ProximityByTime= false RGBD/ProximityMaxGraphDepth= 50 RGBD/ProximityMaxPaths= 3 RGBD/ProximityOdomGuess= false RGBD/ProximityPathFilteringRadius= 1 RGBD/ProximityPathMaxNeighbors= 0 RGBD/ProximityPathRawPosesUsed= true RGBD/SavedLocalizationIgnored= false RGBD/ScanMatchingIdsSavedInLinks= true Reg/Force3DoF= false Reg/RepeatOnce= true Reg/Strategy= 0 Rtabmap/ComputeRMSE= true Rtabmap/CreateIntermediateNodes= false Rtabmap/DetectionRate= 2 (default=1) Rtabmap/ImageBufferSize= 1 Rtabmap/ImagesAlreadyRectified= true Rtabmap/LoopGPS= true Rtabmap/LoopRatio= 0 Rtabmap/LoopThr= 0.11 Rtabmap/MaxRetrieved= 2 Rtabmap/MemoryThr= 0 Rtabmap/PublishLastSignature= true Rtabmap/PublishLikelihood= true Rtabmap/PublishPdf= true Rtabmap/PublishRAMUsage= false Rtabmap/PublishStats= true Rtabmap/RectifyOnlyFeatures= false Rtabmap/SaveWMState= false Rtabmap/StartNewMapOnGoodSignature=false Rtabmap/StartNewMapOnLoopClosure= false Rtabmap/StatisticLogged= false Rtabmap/StatisticLoggedHeaders= true Rtabmap/StatisticLogsBufferedInRAM=true Rtabmap/TimeThr= 0 SIFT/ContrastThreshold= 0.04 SIFT/EdgeThreshold= 10 SIFT/NFeatures= 0 SIFT/NOctaveLayers= 3 SIFT/RootSIFT= false SIFT/Sigma= 1.6 SURF/Extended= false SURF/GpuKeypointsRatio= 0.01 SURF/GpuVersion= false SURF/HessianThreshold= 500 SURF/OctaveLayers= 2 SURF/Octaves= 4 SURF/Upright= false Stereo/DenseStrategy= 0 Stereo/Eps= 0.01 Stereo/Iterations= 30 Stereo/MaxDisparity= 128.0 Stereo/MaxLevel= 5 Stereo/MinDisparity= 0.5 Stereo/OpticalFlow= true Stereo/SSD= true Stereo/WinHeight= 3 Stereo/WinWidth= 15 StereoBM/BlockSize= 15 StereoBM/Disp12MaxDiff= -1 StereoBM/MinDisparity= 0 StereoBM/NumDisparities= 128 StereoBM/PreFilterCap= 31 StereoBM/PreFilterSize= 9 StereoBM/SpeckleRange= 4 StereoBM/SpeckleWindowSize= 100 StereoBM/TextureThreshold= 10 StereoBM/UniquenessRatio= 15 StereoSGBM/BlockSize= 15 StereoSGBM/Disp12MaxDiff= 1 StereoSGBM/MinDisparity= 0 StereoSGBM/Mode= 2 StereoSGBM/NumDisparities= 128 StereoSGBM/P1= 2 StereoSGBM/P2= 5 StereoSGBM/PreFilterCap= 31 StereoSGBM/SpeckleRange= 4 StereoSGBM/SpeckleWindowSize= 100 StereoSGBM/UniquenessRatio= 20 SuperPoint/Cuda= true SuperPoint/NMS= true SuperPoint/NMSRadius= 4 SuperPoint/Threshold= 0.010 VhEp/Enabled= false VhEp/MatchCountMin= 8 VhEp/RansacParam1= 3 VhEp/RansacParam2= 0.99 Vis/BundleAdjustment= 1 Vis/CorFlowEps= 0.01 Vis/CorFlowIterations= 30 Vis/CorFlowMaxLevel= 3 Vis/CorFlowWinSize= 16 Vis/CorGuessMatchToProjection= false Vis/CorGuessWinSize= 40 Vis/CorNNDR= 0.8 Vis/CorNNType= 1 Vis/CorType= 0 Vis/DepthAsMask= true Vis/EpipolarGeometryVar= 0.1 Vis/EstimationType= 1 Vis/FeatureType= 8 Vis/ForwardEstOnly= true Vis/GridCols= 1 Vis/GridRows= 1 Vis/InlierDistance= 0.1 Vis/Iterations= 300 Vis/MaxDepth= 0 Vis/MaxFeatures= 1000 Vis/MeanInliersDistance= 0.0 Vis/MinDepth= 0 Vis/MinInliers= 20 Vis/MinInliersDistribution= 0.0 Vis/PnPFlags= 0 Vis/PnPRefineIterations= 0 Vis/PnPReprojError= 2 Vis/RefineIterations= 5 Vis/RoiRatios= 0.0 0.0 0.0 0.0 Vis/SubPixEps= 0.02 Vis/SubPixIterations= 0 Vis/SubPixWinSize= 3 g2o/Baseline= 0.075 g2o/Optimizer= 0 g2o/PixelVariance= 1.0 g2o/RobustKernelDelta= 8 g2o/Solver= 0 Info: Path: /home/antonis/.ros/rtabmap.db Version: 0.20.9 Sessions: 1 Total odometry length:2894.902588 m Total time: 470.685171s LTM: 582 nodes and 0 words (dim=0 type=8U) WM: 582 nodes and 0 words Global graph: 582 poses and 605 links Optimized graph: 0 poses Maps in graph: 0/1 [] Ground truth: 0 poses GPS: 0 poses Links: Neighbor: 580 GlobalClosure: 0 LocalSpaceClosure:25 LocalTimeClosure: 0 UserClosure: 0 VirtualClosure: 0 NeighborMerged: 0 PosePrior: 0 Landmark: 0 Gravity: 0 Database size: 551 MB Nodes size: 92 KB (0.02%) Links size: 208 KB (0.04%) RGB Images size: 0 Bytes (0.00%) Depth Images size: 0 Bytes (0.00%) Calibrations size: 0 Bytes (0.00%) Grids size: 6 KB (0.00%) Scans size: 549 MB (99.53%) User data size: 0 Bytes (0.00%) Dictionary size: 0 Bytes (0.00%) Features size: 0 Bytes (0.00%) Statistics size: 835 KB (0.15%) Other (indexing, unused):1 MB (0.26%) It really makes me wonder what is going wrong, I've downloaded again the data and used the kitti2bag to turn them in bagfiles. Using the kitti2bag -t <date> -r <sequence number> raw_syncedcommand thinking that my data are problematic because rtab works great with the ouster drive under the rain bag and the other that I shared at this post but still, the odometry goes wild. |
Administrator
|
Hi Mikor,
Here my stats: Info: Path: /home/mathieu/.ros/rtabmap.db Version: 0.20.9 Sessions: 1 Total odometry length:3710.642822 m Total time: 470.581516s LTM: 909 nodes and 0 words (dim=0 type=8U) WM: 907 nodes and 0 words Global graph: 909 poses and 1818 links Optimized graph: 907 poses Maps in graph: 1/1 [0(907)] Ground truth: 0 poses GPS: 0 poses Links: Neighbor: 1812 GlobalClosure: 0 LocalSpaceClosure:6 LocalTimeClosure: 0 UserClosure: 0 VirtualClosure: 0 NeighborMerged: 0 PosePrior: 0 Landmark: 0 Gravity: 0 Database size: 863 MB Nodes size: 145 KB (0.02%) Links size: 623 KB (0.07%) RGB Images size: 0 Bytes (0.00%) Depth Images size: 0 Bytes (0.00%) Calibrations size: 0 Bytes (0.00%) Grids size: 10 KB (0.00%) Scans size: 858 MB (99.49%) User data size: 0 Bytes (0.00%) Dictionary size: 0 Bytes (0.00%) Features size: 0 Bytes (0.00%) Statistics size: 1 MB (0.15%) Other (indexing, unused):2 MB (0.27%) I would expect 900-940 nodes in your map (for 2 Hz during 470 sec). Can you show processing time for odometry? rtabmap-report Odometry/TimeEstimation/ms ~/.ros/rtabmap.db On my laptop it is able to process all velodyne point clouds (< 100 ms processing time). |
This post was updated on .
Good morning Mathieu,
I guess it's morning there, here are my results. It averages at 338ms EDIT: Also I noticed this when I launched rtabmap [ INFO] [1615558080.547552628]: Odometry: Ignored parameter "Rtabmap/DetectionRate"="2" from argumentsI do not know if this is expected behavior. And at the end I got these warnings [ WARN] (2021-03-12 16:19:14.925) MainWindow.cpp:1775::processStats() Processing time (1,380790s) is over detection rate (0,500000s), real-time problem! |
Administrator
|
Hi Mikor,
It is indeed morning here. What are the specifications of your computer? To get similar results than in the paper, it is assumed that the computer can process all the velodyne point clouds (at 10Hz) in real-time. A workaround would be play slower the bag: rosbag play -r 0.5 --clock ... If you are using rtabmapviz to visualize, remove the 3D map rendering to save computation time (Preferences->3D Rendering-> under Map column scroll down to disable scan). On my computer I disable it so that rendering doesn't take much processing power, keeping only odom scan visualization. EDIT: the warning "Odometry: Ignored parameter "Rtabmap/DetectionRate"="2" from arguments" is fine, that parameter is not used in odometry. cheers, Mathieu |
This post was updated on .
Hey Mathieu,
I tried it with 0.5 rate as you said and it didn't work well enough, now I've set it at 0.1, it takes ages but it looks good so far. I'm running it on a lenovo legion y530 with an i5-8300H and 8gb of ram, but it's also running on VM using half of the cpu and ram. I will keep you updated once it's done, thanks once again. Here it is..! |
Administrator
|
This post was updated on .
|
This post was updated on .
Hello Mathieu,
I have a KITTI related question so I will post it here, if that's not appropriate I can create a new post. My question is specifically about the evaluation of 07 sequence but I guess it happens to the rest sequences too. Could you help me figure out how to use the evaluation script you posted before, I am not familiar with bash files and I wonder how can the 220 poses, that I get as output, be compared to the 1100 grountruth poses. Also, is it possible the imu topic to rotate the graph? The left is with the imu topic. Thank you in advance Mathieu, Regards, Anthony. |
Administrator
|
This post was updated on .
Hi Anthony,
Do you want to compare trajectory created with the rosbag against the ground truth of the odometry (files not rosbag) leaderboard? For the ground truth, the number of poses shold be exactly the same than the trajectory size. I would also doubt that the poses from the rosbag would be exactly the ground truth poses at exact timestamp. For benchmarking with the kitti's groundtruth, use the folder of files, not the rosbag. Well, you would lose IMU data when not using the rosbag. You may check if someone has integrated the ground truth in the rosbag. Without the ground truth, you could compare with the GPS at least for qualitative results. For the bash file, it is using the rtabmap-kitti_dataset tool, here is the description and an example at the bottom (note the Rtabmap/CreateIntermediateNodes that is required to get the same number of poses than the images in the kitti folders, and thus the same number of poses than the ground truth): $ rtabmap-kitti_dataset Usage: rtabmap-kitti_dataset [options] path path Folder of the sequence (e.g., "~/KITTI/dataset/sequences/07") containing least calib.txt, times.txt, image_0 and image_1 folders. Optional image_2, image_3 and velodyne folders. --output Output directory. By default, results are saved in "path". --output_name Output database name (default "rtabmap"). --gt "path" Ground truth path (e.g., ~/KITTI/devkit/cpp/data/odometry/poses/07.txt) --quiet Don't show log messages and iteration updates. --color Use color images for stereo (image_2 and image_3 folders). --height Add car's height to camera local transform (1.67m). --disp Generate full disparity. --exposure_comp Do exposure compensation between left and right images. --scan Include velodyne scan in node's data (use --scan_only to ignore image data). --scan_step # Scan downsample step (default=1). --scan_voxel #.# Scan voxel size (default 0.5 m). --scan_k Scan normal K (default 0). --scan_radius Scan normal radius (default 0). RTAB-Map options: --help Show usage. --version Show version of rtabmap and its dependencies. --params Show all parameters with their default value and description. If a database path is set as last argument, the parameters in the database will be shown in INI format. --"parameter name" "value" Overwrite a specific RTAB-Map's parameter : --SURF/HessianThreshold 150 For parameters in table format, add ',' between values : --Kp/RoiRatios 0,0,0.1,0 Logger options: --nolog Disable logger --logconsole Set logger console type --logfile "path" Set logger file type --logfilea "path" Set logger file type with appending mode if the file already exists --udebug Set logger level to debug --uinfo Set logger level to info --uwarn Set logger level to warn --uerror Set logger level to error --logtime "bool" Print time when logging --logwhere "bool" Print where when logging --logthread "bool" Print thread id when logging Example: $ rtabmap-kitti_dataset \ --Rtabmap/PublishRAMUsage true\ --Rtabmap/DetectionRate 2\ --Rtabmap/CreateIntermediateNodes true\ --RGBD/LinearUpdate 0\ --GFTT/QualityLevel 0.01\ --GFTT/MinDistance 7\ --OdomF2M/MaxSize 3000\ --Mem/STMSize 30\ --Kp/MaxFeatures 750\ --Vis/MaxFeatures 1500\ --gt "~/KITTI/devkit/cpp/data/odometry/poses/07.txt"\ ~/KITTI/dataset/sequences/07 For the graph rotating with imu, do you use Optimizer/Strategy=2 (GTSAM)? and which rtabmap version are you using? as I added some new constraints to gtsam recently to avoid this kind of rotation. I'll download the rosbag to see if I have the same rotation. EDIT: I tested the bag, the orientation is coming from the IMU's initial yaw: [ WARN] (2021-03-16 19:09:13.297) Odometry.cpp:307::process() Updated initial pose from xyz=0.000000,0.000000,0.000000 rpy=0.000000,-0.000000,0.000000 to xyz=0.000000,0.000000,0.000000 rpy=0.022268,0.011411,-0.551108 with IMU orientation cheers, Mathieu |
This post was updated on .
Hi Mathieu,
I try to use the rtabmap-kitti_dataset tool with scan only option enabled. rtabmap-kitti_dataset \ --scan_only \ --Reg/Strategy 1 \ --RGBD/Enabled false\ --RGBD/CreateOccupancyGrid false \ --Rtabmap/DetectionRate 2 \ --Odom/ScanKeyFrameThr 0.8 \ --OdomF2M/ScanMaxSize 10000 \ --OdomF2M/ScanSubtractRadius 0.5 \ --Icp/PM true \ --Icp/VoxelSize 0.5 \ --Icp/MaxTranslation 2 \ --Icp/MaxCorrespondenceDistance 1.5 \ --Icp/PMOutlierRatio 0.7 \ --Icp/Iterations 10 \ --Icp/PointToPlane false \ --Icp/PMMatcherKnn 3 \ --Icp/PMMatcherEpsilon 1 \ --Icp/Epsilon 0.0001 \ --Icp/PointToPlaneK 0 \ --Icp/PointToPlaneRadius 0 \ --icp_odometry:=true \ --Icp/CorrespondenceRatio 0.01 \ --gt "/home/antonis/07/07.txt" \ /home/antonis/07 This is the parameters I set but I get this output Paths: Sequence number: 07 Sequence path: /home/antonis/07 Output: /home/antonis/07 Output name: rtabmap left images: /home/antonis/07/image_0 right images: /home/antonis/07/image_1 calib.txt: /home/antonis/07/calib.txt times.txt: /home/antonis/07/times.txt Ground Truth: /home/antonis/07/07.txt Exposure Compensation: false Disparity: false Scan: /home/antonis/07/velodyne Scan only: true Scan step: 1 Scan voxel: 0.500000m Scan normal k: 0 Scan normal radius: 0.000000 Saved calibration "rtabmap_calib" to "/home/antonis/07" Parameters: Icp/CorrespondenceRatio=0.01 Icp/Epsilon=0.0001 Icp/Iterations=10 Icp/MaxCorrespondenceDistance=1.5 Icp/MaxTranslation=2 Icp/PM=true Icp/PMMatcherEpsilon=1 Icp/PMMatcherKnn=3 Icp/PMOutlierRatio=0.7 Icp/PointToPlane=false Icp/PointToPlaneK=0 Icp/PointToPlaneRadius=0 Icp/VoxelSize=0.5 Odom/ScanKeyFrameThr=0.8 OdomF2M/ScanMaxSize=10000 OdomF2M/ScanSubtractRadius=0.5 RGBD/CreateOccupancyGrid=false RGBD/Enabled=false Reg/Strategy=1 Rtabmap/DetectionRate=2 Rtabmap/PublishRAMUsage=true Rtabmap/WorkingDirectory=/home/antonis/07 RTAB-Map version: 0.20.9 Processing 1101 images... [ WARN] (2021-03-17 14:26:03.964) OdometryF2M.cpp:164::OdometryF2M() OdomF2M/BundleAdjustment=1 cannot be used with registration not done only with images (Reg/Strategy=1), disabling bundle adjustment. Iteration 1/1101: speed=0km/h camera=31ms, odom(quality=0.000000, kfs=1)=0ms, slam=25ms, rmse=0.000000m Iteration 2/1101: speed=3km/h camera=34ms, odom(quality=0.943217, kfs=1)=154ms, slam=0ms, rmse=0.000000m Iteration 3/1101: speed=2km/h camera=17ms, odom(quality=0.914549, kfs=1)=122ms, slam=0ms, rmse=0.000000m Iteration 4/1101: speed=2km/h camera=28ms, odom(quality=0.918854, kfs=1)=132ms, slam=0ms, rmse=0.000000m Iteration 5/1101: speed=6km/h camera=34ms, odom(quality=0.917901, kfs=1)=129ms, slam=0ms, rmse=0.000000m Iteration 6/1101: speed=3km/h camera=27ms, odom(quality=0.892217, kfs=1)=125ms, slam=7ms, rmse=0.000000m Iteration 7/1101: speed=3km/h camera=16ms, odom(quality=0.907208, kfs=1)=115ms, slam=0ms, rmse=0.000000m Iteration 8/1101: speed=5km/h camera=27ms, odom(quality=0.910995, kfs=1)=100ms, slam=0ms, rmse=0.000000m Iteration 9/1101: speed=5km/h camera=21ms, odom(quality=0.896019, kfs=1)=100ms, slam=0ms, rmse=0.000000m Iteration 10/1101: speed=5km/h camera=26ms, odom(quality=0.882009, kfs=1)=97ms, slam=0ms, rmse=0.000000m Iteration 11/1101: speed=5km/h camera=23ms, odom(quality=0.873261, kfs=1)=128ms, slam=14ms, rmse=0.000000m Iteration 12/1101: speed=5km/h camera=34ms, odom(quality=0.844877, kfs=1)=133ms, slam=0ms, rmse=0.000000m Iteration 13/1101: speed=6km/h camera=27ms, odom(quality=0.841638, kfs=1)=137ms, slam=0ms, rmse=0.000000m And it goes on until it prints this: Iteration 1100/1101: speed=0km/h camera=18ms, odom(quality=0.881621, kfs=63)=197ms, slam=0ms, rmse=0.000000m Iteration 1101/1101: speed=0km/h camera=18ms, odom(quality=0.879493, kfs=63)=193ms, slam=8ms, rmse=0.000000m Total time=214.098361s Saving trajectory ... Saving /home/antonis/07/rtabmap_poses.txt... failed! Ground truth comparison: KITTI t_err = -nan % KITTI r_err = -nan deg/m translational_rmse= 0.000000 m rotational_rmse= 0.000000 deg Saving rtabmap database (with all statistics) to "/home/antonis/07/rtabmap.db" Do: $ rtabmap-databaseViewer /home/antonis/07/rtabmap.db Any ideas about what I do wrong ? |
Administrator
|
Hi Mikor,
Remove "--RGBD/Enabled false\". I didn't realize there was no description for this parameter, which I assumed it should be always true for everyone. I added a description in this commit. cheers, Mathieu |
Okay now it works great, thank you again!
I can see that in the database I get around 200 poses but the groundtruth data has around 1100. How does this difference occur ? Also, what do the poses of the txt file mean? I can see that there are 12 elements in every pose, are they referring to a translation and rotation matrix meaning that the first 3 elements describe the translations and the other 9 are the elements of the rotation matrix ? Regards, Anthony. |
Administrator
|
Hi Anthony,
The detection rate is 2 Hz, and data is 10 Hz, so there is one pose added to map each 5 scans. To have all poses, you can add "--Rtabmap/CreateIntermediateNodes true". For the kitti 12 values format, it is the 3x4 transformation matrix if I remember correctly: r00,r01,r02,t0,r10,r10,r11,r12,t1,r20,r21,r22,t2 cheers, Mathieu |
This post was updated on .
Hey Mathieu,
thanks again for your response, but it seems that I am not getting an exact match of poses. I work on this example in the 07 sequence (because it is smaller and it saves time), when I use the /Rtabmap/CreateIntermediateNodes I get a few less poses than the groundtruth txt contains 1101. I thought that when I change the My second thought based on this post was that it doesn't create a crucial key frame in order to fill the intermediate nodes and I set the threshold to lower values but this does not seem to work and the errors increase so even it worked it wouldn't be ideal. With detection rate set at 2 and the use of intermediate nodes I get 1020 poses. Same detection rate and without the intermediate nodes I get 208 poses. When I set the detection rate at 10 and with or without intermediate nodes I get 1018 poses. If I open the database it says that 1101 ids loaded but if I export map's graph it results in 1020 poses and if export odometry then the poses match the 1101, should I do the latter and do the rest comparisons to test my parameters?? Also you are correct about the format of kitti values. I double checked the text file in devkit that KITTI provides and it says the same thing. With gratitude, Anthony |
Administrator
|
Ah yeah, you have to add also "--RGBD/LinearUpdate 0". Without RGBD/LinearUpdate disabled, when the car is not moving, no nodes are added to graph. It is counter-intuitive to add nodes while not moving, but to comply to dataset, we have to add them. I get 1020 nodes when enabled, 1101 when disabled. cheers, Mathieu |
This post was updated on .
Unscrupulously hijacking this thread: I'm facing the issue of smaller amount of poses obtained than the ground truth for KITTI, when using "rtabmap-kitti_dataset" with images and Velodyne.
In sequence 0, there are 4541 pictures, and I can see all 4541 nodes in the database-viewer when the detection rate is 2Hz and "createIntermediaryNodes=true". However, the 3D map shows very sparse point clouds, probably because the intermediate nodes were not assigned their point clouds because of the 2Hz rate. I really need all nodes to have their point clouds, so I set the rate to 10Hz, but to my surprise, now I had only 384 nodes, even with the intermediary nodes option being set. The same amount of nodes is obtained when the rate is set to 20Hz. What could be going on? All the other options for "rtabmap-kitti_dataset" are the standard ones shown in the help text, with "--scan". EDIT: "rtabmap-report" says that odometry processing time stays below 100ms, so probably it's not a CPU processing issue. (However, my RTAB-Map version is 0.17.6, the statistics is called "Odometry/TotalTime/ms", but hopefully it means the same thing.) EDIT 2: I solved it partially by realizing that sequence 00 had several straight line segments, and "RGBD/AngularUpdate = 0.1" (its default value) prevented new nodes from being generated. After setting it to zero, I finally obtained all nodes matching with the ground truth, even without creating intermediary ones. However, several nodes do not have depth data ("SensorData.depthRaw().empty()" is true for them). Why is that? |
Solved. I was treating Velodyne data as point cloud, since it's in 3D, but it's a regular scan data in RTAB-Map. So I had to use stereo option ("-- disp" argument in "rtabmap-kitti_dataset") to build the point cloud. All good now!
|
Free forum by Nabble | Edit this page |