-
Notifications
You must be signed in to change notification settings - Fork 869
Description
In windows, I want to use orbslam3 as odometry of rtab without ros in Stereo-Inertial mode. I built rtabmap and orbslam3 from source. But I get an error: [FATAL] OdometryORBSLAM3.cpp:465:: rtabmap::OdometryORBSLAM3::computeTransform() Condition (TcwMat.cols == 4 && TcwMat.rows == 4) not met! I print TcwMat: TcwMat.size: [0 x 0] [] .
I load and process my offline imu and img data as follows. The imu and img timestamp is set like 1758629768630017090/1e9:
... ...
static Odometry* odom_;
Rtabmap rtabmap_;
std::map<double, rtabmap::IMU> imus_buffer_;
int32_t LoadIMU(std::string imutxt){
//# Transformation from camera 0 to body-frame (imu)
Transform cam2body(-0.00705823, 0.25437846, 0.96707899, 0.43901792,
-0.9996779, 0.02178153, -0.01302552, -0.00571947,
-0.02437788, -0.96685943, 0.25414279, 0.01104183);
std::ifstream infile(imutxt);
if (!infile.is_open()){
std::cerr<<"Can't open Imu txt: "<<imutxt<<std::endl;
return -1;
}
int num=0;
cv::Mat gyroCov = cv::Mat::eye(3,3,CV_64FC1) * (1.2644368869086185e-03 * 1.2644368869086185e-03);
cv::Mat accelCov = cv::Mat::eye(3,3,CV_64FC1) * (7.1818670767832245e-03 * 7.1818670767832245e-03);
std::string line;
while (std::getline(infile, line)) {
if (line.empty() || line[0] == '#') {
continue;
}
std::istringstream iss(line);
std::string token;
std::vector<double> values;
while(std::getline(iss,token,',')){
values.push_back(std::stod(token));
}
if (values.size()==7){
double imustamp=values[0]/1e9;
//double imustamp=values[0];
cv::Vec3d gyro(values[1], values[2], values[3]); // w_RS_S [rad/s]
cv::Vec3d acc(values[4], values[5], values[6]); // a_RS_S [m/s²]
rtabmap::IMU imu(gyro, gyroCov, acc, accelCov,cam2body);
imus_buffer_.insert({imustamp, imu});
num++;
}else{
std::cerr << "IMU txt : error number of elements : "<<values.size()<<std::endl;
}
}
infile.close();
std::cout<<"Load IMU data from txt success ... "<< num <<" imu data !"<<std::endl;
return 0;
}
int32_t processIMU(double imgstamp){
std::vector<std::pair<double, rtabmap::IMU> > imus_to_process;
{
auto iterEnd =imus_buffer_.lower_bound(imgstamp);
if (iterEnd != imus_buffer_.end()){
iterEnd++;
}
for(std::map<double, rtabmap::IMU>::iterator iter=imus_buffer_.begin(); iter!=iterEnd;)
{
imus_to_process.push_back(*iter);
imus_buffer_.erase(iter++);
}
}
std::cout<<"imus_to_process.size(): "<<imus_to_process.size()<<std::endl;
for(size_t i=0; i<imus_to_process.size(); ++i)
{
SensorData dataIMU(imus_to_process[i].second, 0, imus_to_process[i].first);
odom_->process(dataIMU);
//imuProcessed_ = true;
}
return 0;
}
int32_t main(SensorData data)
{
if (!init){
odomStrategy="5"; //orb_slam2/3
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/VocPath", "D:/rxy/project/myMapper/configFile/ORBvoc.txt"));
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/Fps", "30"));
if (useImu_) {
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/Inertial", "true"));
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/ThDepth", "35"));
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/GyroNoise", "1.2644368869086185e-03"));
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/AccNoise", "7.1818670767832245e-03"));
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/GyroWalk", "1.2205310336593159e-05"));
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/AccWalk", "3.0893755104534506e-04"));
uInsert(odomParams, rtabmap::ParametersPair("OdomORBSLAM/SamplingRate", "200"));
LoadIMU(./imu.txt);
}
uInsert(odomParams, rtabmap::ParametersPair("Odom/Strategy", odomStrategy));
odom_=Odometry::create(odomParams);
rtabmap_.init();
init=true;
}
double imgstamp=data.stamp();
if (useImu_){
processIMU(imgstamp);
}
if (frameCounter_ % odomUpdate_ == 0)
{
pose = odom_->process(data, &info);
if (frameCounter_ % mapUpdate_ == 0)
{
if(rtabmap_.process(data, pose))
{
if (rtabmap_.getLoopClosureId() > 0)
{
getLoopClosure_=true;
printf("Loop closure detected! \n");
}
}
}
}
}
The log is :
D:\rxy\project\myMapper\cmake-build-release\bin\testodomOffline.exe
StereoModel of camera init success
Load IMU data from txt success ... 20934 imu data !
[DEBUG] (2025-10-10 09:58:34) Odometry.cpp:69::rtabmap::Odometry::create() type=5
[DEBUG] (2025-10-10 09:58:34) Rtabmap.cpp:319::rtabmap::Rtabmap::init() path=
[ WARN] (2025-10-10 09:58:34) Rtabmap.cpp:328::rtabmap::Rtabmap::init() Using empty database. Mapping session will not b
e saved unless it is closed with an output database path.
[DEBUG] (2025-10-10 09:58:34) VWDictionary.cpp:470::rtabmap::VWDictionary::update() incremental=1
[DEBUG] (2025-10-10 09:58:34) FlannIndex.cpp:52::rtabmap::FlannIndex::release()
[DEBUG] (2025-10-10 09:58:34) FlannIndex.cpp:80::rtabmap::FlannIndex::release()
[DEBUG] (2025-10-10 09:58:34) VWDictionary.cpp:681::rtabmap::VWDictionary::update() Dictionary updated! (size=0 added=0
removed=0)
[DEBUG] (2025-10-10 09:58:34) VWDictionary.cpp:689::rtabmap::VWDictionary::update()
[DEBUG] (2025-10-10 09:58:34) Registration.cpp:49::rtabmap::Registration::create() type=0
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:557::rtabmap::Memory::parseParameters()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:166::rtabmap::Memory::init()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:557::rtabmap::Memory::parseParameters()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:1736::rtabmap::Memory::clear()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:6115::rtabmap::Memory::cleanUnusedWords() Removing 0 words (dictionary size=0).
..
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:1792::rtabmap::Memory::clear()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:1816::rtabmap::Memory::clear()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:1822::rtabmap::Memory::clear()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:6115::rtabmap::Memory::cleanUnusedWords() Removing 0 words (dictionary size=0).
..
[DEBUG] (2025-10-10 09:58:34) VWDictionary.cpp:694::rtabmap::VWDictionary::clear()
[DEBUG] (2025-10-10 09:58:34) FlannIndex.cpp:52::rtabmap::FlannIndex::release()
[DEBUG] (2025-10-10 09:58:34) FlannIndex.cpp:80::rtabmap::FlannIndex::release()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:1853::rtabmap::Memory::clear()
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:62::rtabmap::DBDriverSqlite3::DBDriverSqlite3() treadSafe=1
[DEBUG] (2025-10-10 09:58:34) DBDriver.cpp:88::rtabmap::DBDriver::openConnection()
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:449::rtabmap::DBDriverSqlite3::disconnectDatabaseQuery()
[ INFO] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:353::rtabmap::DBDriverSqlite3::connectDatabaseQuery() Using empty data
base in the memory.
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:522::rtabmap::DBDriverSqlite3::executeNoResultQuery() Time=0.000571s
[ INFO] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:426::rtabmap::DBDriverSqlite3::connectDatabaseQuery() Database version
= 0.21.4
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:522::rtabmap::DBDriverSqlite3::executeNoResultQuery() Time=0.000006s
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:522::rtabmap::DBDriverSqlite3::executeNoResultQuery() Time=0.000004s
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:522::rtabmap::DBDriverSqlite3::executeNoResultQuery() Time=0.000003s
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:522::rtabmap::DBDriverSqlite3::executeNoResultQuery() Time=0.000006s
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:3536::rtabmap::DBDriverSqlite3::loadLastNodesQuery()
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:3579::rtabmap::DBDriverSqlite3::loadLastNodesQuery() Loading 0 signatu
res...
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2897::rtabmap::DBDriverSqlite3::loadSignaturesQuery() count=0
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:3581::rtabmap::DBDriverSqlite3::loadLastNodesQuery() loaded=0, Time=0.
000368s
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:314::rtabmap::Memory::loadDataFromDb() Get labels
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2856::rtabmap::DBDriverSqlite3::getAllLabelsQuery() Time=0.000012
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:317::rtabmap::Memory::loadDataFromDb() Check if all nodes are in Working Memory
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:329::rtabmap::Memory::loadDataFromDb() allNodesInWM()=true
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:331::rtabmap::Memory::loadDataFromDb() update odomMaxInf vector
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:353::rtabmap::Memory::loadDataFromDb() update odomMaxInf vector, done!
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2626::rtabmap::DBDriverSqlite3::getLastIdQuery() get last id from tabl
e "Node"
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2657::rtabmap::DBDriverSqlite3::getLastIdQuery() Time=0.000015s
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2626::rtabmap::DBDriverSqlite3::getLastIdQuery() get last id from tabl
e "Statistics"
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2657::rtabmap::DBDriverSqlite3::getLastIdQuery() Time=0.000025s
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2626::rtabmap::DBDriverSqlite3::getLastIdQuery() get last map_id from
table "Node"
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2657::rtabmap::DBDriverSqlite3::getLastIdQuery() Time=0.000021s
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:375::rtabmap::Memory::loadDataFromDb() Loading dictionary...
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:419::rtabmap::Memory::loadDataFromDb() load words
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:3587::rtabmap::DBDriverSqlite3::loadQuery()
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2626::rtabmap::DBDriverSqlite3::getLastIdQuery() get last id from tabl
e "Word"
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:2657::rtabmap::DBDriverSqlite3::getLastIdQuery() Time=0.000015s
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:3668::rtabmap::DBDriverSqlite3::loadQuery() Time=0.000426s
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:423::rtabmap::Memory::loadDataFromDb() 0 words loaded!
[DEBUG] (2025-10-10 09:58:34) VWDictionary.cpp:470::rtabmap::VWDictionary::update() incremental=1
[DEBUG] (2025-10-10 09:58:34) FlannIndex.cpp:52::rtabmap::FlannIndex::release()
[DEBUG] (2025-10-10 09:58:34) FlannIndex.cpp:80::rtabmap::FlannIndex::release()
[DEBUG] (2025-10-10 09:58:34) VWDictionary.cpp:681::rtabmap::VWDictionary::update() Dictionary updated! (size=0 added=0
removed=0)
[DEBUG] (2025-10-10 09:58:34) VWDictionary.cpp:689::rtabmap::VWDictionary::update()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:455::rtabmap::Memory::loadDataFromDb() Total word references added = 0
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:463::rtabmap::Memory::loadDataFromDb()
[DEBUG] (2025-10-10 09:58:34) DBDriver.cpp:1127::rtabmap::DBDriver::addInfoAfterRun()
[DEBUG] (2025-10-10 09:58:34) Parameters.cpp:105::rtabmap::Parameters::serialize() output=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.015
1 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/VirtualPlacePri
orThr:0.9;Db/TargetVersion:;DbSqlite3/CacheSize:10000;DbSqlite3/InMemory:false;DbSqlite3/JournalMode:3;DbSqlite3/Synchro
nous:0;DbSqlite3/TempStore:2;FAST/CV:0;FAST/Gpu:false;FAST/GpuKeypointsRatio:0.05;FAST/GridCols:0;FAST/GridRows:0;FAST/M
axThreshold:200;FAST/MinThreshold:7;FAST/NonmaxSuppression:true;FAST/Threshold:20;FREAK/NOctaves:4;FREAK/OrientationNorm
alized:true;FREAK/PatternScale:22;FREAK/ScaleNormalized:true;GFTT/BlockSize:3;GFTT/K:0.04;GFTT/MinDistance:7;GFTT/Qualit
yLevel:0.001;GFTT/UseHarrisDetector:false;GMS/ThresholdFactor:6.0;GMS/WithRotation:false;GMS/WithScale:false;GTSAM/Optim
izer: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/GroundIsO
bstacle:false;Grid/MapFrameProjection:false;Grid/MaxGroundAngle:45;Grid/MaxGroundHeight:0.0;Grid/MaxObstacleHeight:0.0;G
rid/MinClusterSize:10;Grid/MinGroundHeight:0.0;Grid/NoiseFilteringMinNeighbors:5;Grid/NoiseFilteringRadius:0.0;Grid/Norm
alK:20;Grid/NormalsSegmentation:true;Grid/PreVoxelFiltering:true;Grid/RangeMax:5.0;Grid/RangeMin:0.0;Grid/RayTracing:fal
se;Grid/Scan2dUnknownSpaceFilled:false;Grid/ScanDecimation:1;Grid/Sensor:1;GridGlobal/AltitudeDelta:0;GridGlobal/Eroded:
false;GridGlobal/FloodFillDepth:0;GridGlobal/FootprintRadius:0.0;GridGlobal/MaxNodes:0;GridGlobal/MinSize:0.0;GridGlobal
/OccupancyThr:0.5;GridGlobal/ProbClampingMax:0.971;GridGlobal/ProbClampingMin:0.1192;GridGlobal/ProbHit:0.7;GridGlobal/P
robMiss:0.4;GridGlobal/UpdateError:0.01;Icp/CCFilterOutFarthestPoints:false;Icp/CCMaxFinalRMS:0.2;Icp/CCSamplingLimit:50
000;Icp/CorrespondenceRatio:0.1;Icp/DebugExportFormat:;Icp/DownsamplingStep:1;Icp/Epsilon:0;Icp/Force4DoF:false;Icp/Iter
ations:30;Icp/MaxCorrespondenceDistance:0.05;Icp/MaxRotation:0.78;Icp/MaxTranslation:0.2;Icp/OutlierRatio:0.85;Icp/PMCon
fig:;Icp/PMMatcherEpsilon:0.0;Icp/PMMatcherIntensity:false;Icp/PMMatcherKnn:1;Icp/PointToPlane:false;Icp/PointToPlaneGro
undNormalsUp:0.0;Icp/PointToPlaneK:5;Icp/PointToPlaneLowComplexityStrategy:1;Icp/PointToPlaneMinComplexity:0.02;Icp/Poin
tToPlaneRadius:0.0;Icp/RangeMax:0;Icp/RangeMin:0;Icp/ReciprocalCorrespondences:true;Icp/Strategy:0;Icp/VoxelSize:0.05;Im
uFilter/ComplementaryBiasAlpha:0.01;ImuFilter/ComplementaryDoAdpativeGain:true;ImuFilter/ComplementaryDoBiasEstimation:t
rue;ImuFilter/ComplementaryGainAcc:0.01;ImuFilter/MadgwickGain:0.1;ImuFilter/MadgwickZeta:0.0;KAZE/Diffusivity:1;KAZE/Ex
tended:false;KAZE/NOctaveLayers:4;KAZE/NOctaves:4;KAZE/Threshold:0.001;KAZE/Upright:false;Kp/BadSignRatio:0.5;Kp/ByteToF
loat:false;Kp/DetectorStrategy:6;Kp/DictionaryPath:;Kp/FlannRebalancingFactor:2.0;Kp/GridCols:1;Kp/GridRows:1;Kp/Increme
ntalDictionary:true;Kp/IncrementalFlann:true;Kp/MaxDepth:0;Kp/MaxFeatures:500;Kp/MinDepth:0;Kp/NNStrategy:1;Kp/NewWordsC
omparedTogether:true;Kp/NndrRatio:0.8;Kp/Parallelized:true;Kp/RoiRatios:0.0 0.0 0.0 0.0;Kp/SubPixEps:0.02;Kp/SubPixItera
tions: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/Priors:;Marker/PriorsVarianceAngular:0.001;M
arker/PriorsVarianceLinear:0.001;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:tr
ue;Mem/ImageCompressionFormat:.jpg;Mem/ImageKept:false;Mem/ImagePostDecimation:1;Mem/ImagePreDecimation:1;Mem/Incrementa
lMemory:true;Mem/InitWMWithAllNodes:false;Mem/IntermediateNodeDataKept:false;Mem/LaserScanDownsampleStepSize:1;Mem/Laser
ScanNormalK:0;Mem/LaserScanNormalRadius:0.0;Mem/LaserScanVoxelSize:0.0;Mem/LocalizationDataSaved:false;Mem/MapLabelsAdde
d:true;Mem/NotLinkedNodesKept:true;Mem/RawDescriptorsKept:true;Mem/RecentWmRatio:0.2;Mem/ReduceGraph:false;Mem/Rehearsal
IdUpdatedToNewOne:false;Mem/RehearsalSimilarity:0.6;Mem/RehearsalWeightIgnoredWhileMoving:false;Mem/RotateImagesUpsideUp
:false;Mem/STMSize:10;Mem/SaveDepth16Format:false;Mem/StereoFromMotion:false;Mem/TransferSortingByWeightId:false;Mem/Use
OdomFeatures:true;Mem/UseOdomGravity:false;ORB/EdgeThreshold:19;ORB/FirstLevel:0;ORB/Gpu:false;ORB/NLevels:3;ORB/PatchSi
ze:31;ORB/ScaleFactor:2;ORB/ScoreType:0;ORB/WTA_K:2;Odom/AlignWithGround:false;Odom/FillInfoData:true;Odom/FilteringStra
tegy: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/Part
icleLambdaT:100;Odom/ParticleNoiseR:0.002;Odom/ParticleNoiseT:0.002;Odom/ParticleSize:400;Odom/ResetCountdown:0;Odom/Sca
nKeyFrameThr:0.9;Odom/Strategy:0;Odom/VisKeyFrameThr:150;OdomF2M/BundleAdjustment:0;OdomF2M/BundleAdjustmentMaxFrames:10
;OdomF2M/MaxNewFeatures:0;OdomF2M/MaxSize:2000;OdomF2M/ScanMaxSize:2000;OdomF2M/ScanRange:0;OdomF2M/ScanSubtractAngle:45
;OdomF2M/ScanSubtractRadius:0.05;OdomF2M/ValidDepthRatio:0.75;OdomFovis/BucketHeight:80;OdomFovis/BucketWidth:80;OdomFov
is/CliqueInlierThreshold:0.1;OdomFovis/FastThreshold:20;OdomFovis/FastThresholdAdaptiveGain:0.005;OdomFovis/FeatureSearc
hWindow:25;OdomFovis/FeatureWindowSize:9;OdomFovis/InlierMaxReprojectionError:1.5;OdomFovis/MaxKeypointsPerBucket:25;Odo
mFovis/MaxMeanReprojectionError:10.0;OdomFovis/MaxPyramidLevel:3;OdomFovis/MinFeaturesForEstimate:20;OdomFovis/MinPyrami
dLevel:0;OdomFovis/StereoMaxDisparity:128;OdomFovis/StereoMaxDistEpipolarLine:1.5;OdomFovis/StereoMaxRefinementDisplacem
ent:1.0;OdomFovis/StereoRequireMutualMatch:true;OdomFovis/TargetPixelsPerFeature:250;OdomFovis/UpdateTargetFeaturesWithR
efined:false;OdomFovis/UseAdaptiveThreshold:true;OdomFovis/UseBucketing:true;OdomFovis/UseHomographyInitialization:true;
OdomFovis/UseImageNormalization:false;OdomFovis/UseSubpixelRefinement:true;OdomLOAM/AngVar:0.01;OdomLOAM/LinVar:0.01;Odo
mLOAM/LocalMapping:true;OdomLOAM/Resolution:0.2;OdomLOAM/ScanPeriod:0.1;OdomLOAM/Sensor:2;OdomMSCKF/FastThreshold:10;Odo
mMSCKF/GridCol:5;OdomMSCKF/GridMaxFeatureNum:4;OdomMSCKF/GridMinFeatureNum:3;OdomMSCKF/GridRow:4;OdomMSCKF/InitCovAccBia
s:0.01;OdomMSCKF/InitCovExRot:0.00030462;OdomMSCKF/InitCovExTrans:0.000025;OdomMSCKF/InitCovGyroBias:0.01;OdomMSCKF/Init
CovVel:0.25;OdomMSCKF/MaxCamStateSize:20;OdomMSCKF/MaxIteration:30;OdomMSCKF/NoiseAcc:0.05;OdomMSCKF/NoiseAccBias:0.01;O
domMSCKF/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;OdomMSCK
F/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;O
domMono/MinTranslation:0.02;OdomOKVIS/ConfigPath:;OdomORBSLAM/AccNoise:0.1;OdomORBSLAM/AccWalk:0.0001;OdomORBSLAM/Bf:0.0
76;OdomORBSLAM/Fps:0.0;OdomORBSLAM/GyroNoise:0.01;OdomORBSLAM/GyroWalk:0.000001;OdomORBSLAM/Inertial:false;OdomORBSLAM/M
apSize:3000;OdomORBSLAM/MaxFeatures:1000;OdomORBSLAM/SamplingRate:0;OdomORBSLAM/ThDepth:40.0;OdomORBSLAM/VocPath:;OdomOp
en3D/MaxDepth:3.0;OdomOpen3D/Method:0;OdomOpenVINS/AccelerometerNoiseDensity:0.01;OdomOpenVINS/AccelerometerRandomWalk:0
.001;OdomOpenVINS/CalibCamExtrinsics:false;OdomOpenVINS/CalibCamIntrinsics:false;OdomOpenVINS/CalibCamTimeoffset:false;O
domOpenVINS/CalibIMUGSensitivity:false;OdomOpenVINS/CalibIMUIntrinsics:false;OdomOpenVINS/DtSLAMDelay:0.0;OdomOpenVINS/F
eatRepMSCKF:0;OdomOpenVINS/FeatRepSLAM:4;OdomOpenVINS/FiMaxBaseline:40;OdomOpenVINS/FiMaxCondNumber:10000;OdomOpenVINS/F
iMaxRuns:5;OdomOpenVINS/FiRefineFeatures:true;OdomOpenVINS/FiTriangulate1d:false;OdomOpenVINS/GravityMag:9.81;OdomOpenVI
NS/GyroscopeNoiseDensity:0.001;OdomOpenVINS/GyroscopeRandomWalk:0.0001;OdomOpenVINS/InitDynInflationBa:100.0;OdomOpenVIN
S/InitDynInflationBg:10.0;OdomOpenVINS/InitDynInflationOri:10.0;OdomOpenVINS/InitDynInflationVel:100.0;OdomOpenVINS/Init
DynMLEMaxIter:50;OdomOpenVINS/InitDynMLEMaxThreads:6;OdomOpenVINS/InitDynMLEMaxTime:0.05;OdomOpenVINS/InitDynMLEOptCalib
:false;OdomOpenVINS/InitDynMinDeg:10.0;OdomOpenVINS/InitDynMinRecCond:1e-15;OdomOpenVINS/InitDynNumPose:6;OdomOpenVINS/I
nitDynUse:false;OdomOpenVINS/InitIMUThresh:1.0;OdomOpenVINS/InitMaxDisparity:10.0;OdomOpenVINS/InitMaxFeatures:50;OdomOp
enVINS/InitWindowTime:2.0;OdomOpenVINS/Integration:1;OdomOpenVINS/LeftMaskPath:;OdomOpenVINS/MaxClones:11;OdomOpenVINS/M
axMSCKFInUpdate:50;OdomOpenVINS/MaxSLAM:50;OdomOpenVINS/MaxSLAMInUpdate:25;OdomOpenVINS/MinPxDist:15;OdomOpenVINS/NumPts
:200;OdomOpenVINS/RightMaskPath:;OdomOpenVINS/TryZUPT:true;OdomOpenVINS/UpMSCKFChi2Multiplier:1.0;OdomOpenVINS/UpMSCKFSi
gmaPx:1.0;OdomOpenVINS/UpSLAMChi2Multiplier:1.0;OdomOpenVINS/UpSLAMSigmaPx:1.0;OdomOpenVINS/UseFEJ:true;OdomOpenVINS/Use
KLT:true;OdomOpenVINS/UseStereo:true;OdomOpenVINS/ZUPTChi2Multiplier:0.0;OdomOpenVINS/ZUPTMaxDisparity:0.5;OdomOpenVINS/
ZUPTMaxVelodicy:0.1;OdomOpenVINS/ZUPTNoiseMultiplier:10.0;OdomOpenVINS/ZUPTOnlyAtBeginning:false;OdomROBOT/RobotPosePath
:;OdomVINS/ConfigPath:;OdomViso2/BucketHeight:50;OdomViso2/BucketMaxFeatures:2;OdomViso2/BucketWidth:50;OdomViso2/Inlier
Threshold:2.0;OdomViso2/MatchBinsize:50;OdomViso2/MatchDispTolerance:2;OdomViso2/MatchHalfResolution:true;OdomViso2/Matc
hMultiStage:true;OdomViso2/MatchNmsN:3;OdomViso2/MatchNmsTau:50;OdomViso2/MatchOutlierDispTolerance:5;OdomViso2/MatchOut
lierFlowTolerance:5;OdomViso2/MatchRadius:200;OdomViso2/MatchRefinement:1;OdomViso2/RansacIters:200;OdomViso2/Reweightin
g:true;Optimizer/Epsilon:0.00001;Optimizer/GravitySigma:0.0;Optimizer/Iterations:100;Optimizer/LandmarksIgnored:false;Op
timizer/PriorsIgnored:true;Optimizer/Robust:false;Optimizer/Strategy:0;Optimizer/VarianceIgnored:false;PyDetector/Cuda:t
rue;PyDetector/Path:;PyMatcher/Cuda:true;PyMatcher/Iterations:20;PyMatcher/Model:indoor;PyMatcher/Path:;PyMatcher/Thresh
old:0.2;RGBD/AngularSpeedUpdate:0.0;RGBD/AngularUpdate:0.1;RGBD/CreateOccupancyGrid:false;RGBD/Enabled:true;RGBD/GoalRea
chedRadius:0.5;RGBD/GoalsSavedInUserData:false;RGBD/InvertedReg:false;RGBD/LinearSpeedUpdate:0.0;RGBD/LinearUpdate:0.1;R
GBD/LocalBundleOnLoopClosure:false;RGBD/LocalImmunizationRatio:0.25;RGBD/LocalRadius:10;RGBD/LocalizationPriorError:0.00
1;RGBD/LocalizationSmoothing:true;RGBD/LoopClosureIdentityGuess:false;RGBD/LoopClosureReextractFeatures:false;RGBD/LoopC
ovLimited:false;RGBD/MarkerDetection:false;RGBD/MaxLocalRetrieved:2;RGBD/MaxLoopClosureDistance:0.0;RGBD/MaxOdomCacheSiz
e:10;RGBD/NeighborLinkRefining:false;RGBD/NewMapOdomChangeDistance:0;RGBD/OptimizeFromGraphEnd:false;RGBD/OptimizeMaxErr
or:3.0;RGBD/PlanAngularVelocity:0;RGBD/PlanLinearVelocity:0;RGBD/PlanStuckIterations:0;RGBD/ProximityAngle:45;RGBD/Proxi
mityBySpace:true;RGBD/ProximityByTime:false;RGBD/ProximityGlobalScanMap:false;RGBD/ProximityMaxGraphDepth:50;RGBD/Proxim
ityMaxPaths:3;RGBD/ProximityMergedScanCovFactor:100.0;RGBD/ProximityOdomGuess:false;RGBD/ProximityPathFilteringRadius:1;
RGBD/ProximityPathMaxNeighbors:0;RGBD/ProximityPathRawPosesUsed:true;RGBD/ScanMatchingIdsSavedInLinks:true;RGBD/StartAtO
rigin:false;Reg/Force3DoF:false;Reg/RepeatOnce:true;Reg/Strategy:0;Rtabmap/ComputeRMSE:true;Rtabmap/CreateIntermediateNo
des:false;Rtabmap/DetectionRate:1;Rtabmap/ImageBufferSize:1;Rtabmap/ImagesAlreadyRectified:true;Rtabmap/LoopGPS:true;Rta
bmap/LoopRatio:0;Rtabmap/LoopThr:0.11;Rtabmap/MaxRepublished:2;Rtabmap/MaxRetrieved:2;Rtabmap/MemoryThr:0;Rtabmap/Publis
hLastSignature:true;Rtabmap/PublishLikelihood:true;Rtabmap/PublishPdf:true;Rtabmap/PublishRAMUsage:false;Rtabmap/Publish
Stats:true;Rtabmap/RectifyOnlyFeatures:false;Rtabmap/SaveWMState:false;Rtabmap/StartNewMapOnGoodSignature:false;Rtabmap/
StartNewMapOnLoopClosure:false;Rtabmap/StatisticLogged:false;Rtabmap/StatisticLoggedHeaders:true;Rtabmap/StatisticLogsBu
fferedInRAM: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/Hessian
Threshold:500;SURF/OctaveLayers:2;SURF/Octaves:4;SURF/Upright:false;Stereo/DenseStrategy:0;Stereo/Eps:0.01;Stereo/Iterat
ions:30;Stereo/MaxDisparity:128.0;Stereo/MaxLevel:5;Stereo/MinDisparity:0.5;Stereo/OpticalFlow:true;Stereo/SSD:true;Ster
eo/WinHeight:3;Stereo/WinWidth:15;StereoBM/BlockSize:15;StereoBM/Disp12MaxDiff:-1;StereoBM/MinDisparity:0;StereoBM/NumDi
sparities:128;StereoBM/PreFilterCap:31;StereoBM/PreFilterSize:9;StereoBM/SpeckleRange:4;StereoBM/SpeckleWindowSize:30;St
ereoBM/TextureThreshold:5;StereoBM/UniquenessRatio:15;StereoOur/ConfigPath:D:/rxy/project/robot/realsense_config/848x480
/realsense_calib.xml;StereoSGBM/BlockSize:15;StereoSGBM/Disp12MaxDiff:1;StereoSGBM/MinDisparity:0;StereoSGBM/Mode:2;Ster
eoSGBM/NumDisparities:128;StereoSGBM/P1:2;StereoSGBM/P2:5;StereoSGBM/PreFilterCap:31;StereoSGBM/SpeckleRange:4;StereoSGB
M/SpeckleWindowSize:100;StereoSGBM/UniquenessRatio:20;SuperPoint/Cuda:true;SuperPoint/ModelPath:;SuperPoint/NMS:true;Sup
erPoint/NMSRadius:4;SuperPoint/Threshold:0.010;VhEp/Enabled:false;VhEp/MatchCountMin:8;VhEp/RansacParam1:3;VhEp/RansacPa
ram2:0.99;Vis/BundleAdjustment:0;Vis/CorFlowEps:0.01;Vis/CorFlowIterations:30;Vis/CorFlowMaxLevel:3;Vis/CorFlowWinSize:1
6;Vis/CorGuessMatchToProjection:false;Vis/CorGuessWinSize:40;Vis/CorNNDR:0.8;Vis/CorNNType:1;Vis/CorType:0;Vis/DepthAsMa
sk:true;Vis/EpipolarGeometryVar:0.1;Vis/EstimationType:1;Vis/FeatureType:6;Vis/ForwardEstOnly:true;Vis/GridCols:1;Vis/Gr
idRows:1;Vis/InlierDistance:0.1;Vis/Iterations:300;Vis/MaxDepth:0;Vis/MaxFeatures:1000;Vis/MeanInliersDistance:0.0;Vis/M
inDepth:0;Vis/MinInliers:20;Vis/MinInliersDistribution:0.0;Vis/PnPFlags:0;Vis/PnPMaxVariance:0.0;Vis/PnPRefineIterations
:0;Vis/PnPReprojError:2;Vis/PnPSamplingPolicy:1;Vis/PnPSplitLinearCovComponents:false;Vis/PnPVarianceMedianRatio:4;Vis/R
efineIterations:5;Vis/RoiRatios:0.0 0.0 0.0 0.0;Vis/SubPixEps:0.02;Vis/SubPixIterations:0;Vis/SubPixWinSize:3;g2o/Baseli
ne:0.075;g2o/Optimizer:0;g2o/PixelVariance:1.0;g2o/RobustKernelDelta:8;g2o/Solver:3
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:522::rtabmap::DBDriverSqlite3::executeNoResultQuery() Time=0.000079s
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:475::rtabmap::Memory::loadDataFromDb() ids start with 1
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:476::rtabmap::Memory::loadDataFromDb() map ids start with 0
[DEBUG] (2025-10-10 09:58:34) Rtabmap.cpp:551::rtabmap::Rtabmap::parseParameters()
[DEBUG] (2025-10-10 09:58:34) Memory.cpp:557::rtabmap::Memory::parseParameters()
[DEBUG] (2025-10-10 09:58:34) BayesFilter.cpp:114::rtabmap::BayesFilter::setPredictionLC() predictionEpsilon = 0.000000
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:4970::rtabmap::DBDriverSqlite3::loadOptimizedPosesQuery()
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:5035::rtabmap::DBDriverSqlite3::loadOptimizedPosesQuery() lastlocaliza
tionPose=xyz=[null] rpy=[null]
[DEBUG] (2025-10-10 09:58:34) DBDriverSqlite3.cpp:5045::rtabmap::DBDriverSqlite3::loadOptimizedPosesQuery() Time=0.00022
0s
[DEBUG] (2025-10-10 09:58:34) Rtabmap.cpp:291::rtabmap::Rtabmap::setupLogFiles() Log disabled!
Incremental Reconstruction, Press 'Esc' to quit...
process image 0: 1758629768630017090.png
imus_to_process.size(): 4
after processIMU------
[DEBUG] (2025-10-10 09:58:34) Odometry.cpp:349::rtabmap::Odometry::process() Processing image data 848x480: rgbd models=
0, stereo models=1
[DEBUG] (2025-10-10 09:58:34) Rtabmap.cpp:1170::rtabmap::Rtabmap::process()
[ INFO] (2025-10-10 09:58:34) Rtabmap.cpp:1230::rtabmap::Rtabmap::process() getting data...
[DEBUG] (2025-10-10 09:58:34) Rtabmap.cpp:1288::rtabmap::Rtabmap::process() incremental=1 odomPose=xyz=[null] rpy=[null]
optimizedPoses=0 mapCorrection=xyz=0.000000,0.000000,0.000000 rpy=0.000000,-0.000000,0.000000 lastLocalizationPose=xyz=
[null] rpy=[null] lastLocalizationNodeId=0
[ERROR] (2025-10-10 09:58:34) Rtabmap.cpp:1349::rtabmap::Rtabmap::process() RGB-D SLAM mode is enabled, memory is increm
ental but no odometry is provided. Image 0 is ignored!
process image 1: 1758629768663373291.png
imus_to_process.size(): 7
after processIMU------
[DEBUG] (2025-10-10 09:58:34) Odometry.cpp:349::rtabmap::Odometry::process() Processing image data 848x480: rgbd models=
0, stereo models=1
[ WARN] (2025-10-10 09:58:34) OdometryORBSLAM3.cpp:119::rtabmap::OdometryORBSLAM3::init() Loading ORB Vocabulary: "D:/rx
y/project/myMapper/configFile/ORBvoc.txt". This could take a while...
ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. G贸mez, Jos茅 M.M. Montiel and Juan D. Tard贸s,
University of Zaragoza.
ORB-SLAM2 Copyright (C) 2014-2016 Ra煤l Mur-Artal, Jos茅 M.M. Montiel and Juan D. Tard贸s, University of Zaragoza.
This program comes with ABSOLUTELY NO WARRANTY;
This is free software, and you are welcome to redistribute it
under certain conditions. See LICENSE.txt.
Input sensor was set to: Stereo-Inertial
Loading ORB Vocabulary. This could take a while...
Vocabulary loaded!
Creation of new map with id: 0
Creation of new map with last KF id: 0
Seq. Name:
Camera Parameters:
- Camera: Pinhole
- fx: 426.025
- fy: 426.025
- cx: 420.888
- cy: 235.796
- k1: 0
- k2: 0
- p1: 0
- p2: 0
- k3: 0
- fps: 30
- color order: RGB (ignored if grayscale)
Depth Threshold (Close/Far Points): 1.75234
ORB Extractor Parameters:
- Number of Features: 1000
- Scale Levels: 3
- Scale Factor: 2
- Initial Fast Threshold: 20
- Minimum Fast Threshold: 7
Left camera to Imu Transform (Tbc):
[-0.0070582628, 0.25437856, 0.96707904, 0.43901792;
-0.99967802, 0.021781445, -0.013025463, -0.0057194699;
-0.024377912, -0.96685952, 0.25414276, 0.01104183;
0, 0, 0, 1]
IMU frequency: 200 Hz
IMU gyro noise: 0.00126444 rad/s/sqrt(Hz)
IMU gyro walk: 1.22053e-05 rad/s^2/sqrt(Hz)
IMU accelerometer noise: 0.00718187 m/s^2/sqrt(Hz)
IMU accelerometer walk: 0.000308938 m/s^3/sqrt(Hz)
not IMU meas
TcwMat.size: [0 x 0] []
[FATAL] (2025-10-10 09:58:48) OdometryORBSLAM3.cpp:465::rtabmap::OdometryORBSLAM3::computeTransform() Condition (TcwMat.
cols == 4 && TcwMat.rows == 4) not met!
The process has ended and the exit code is -1073740791 (0xC0000409)
When I run orb_slam3 alone, eyerything works fine. It seems that outputting "not IMU meas" and Tcw is empty at the start is normal. I attempted to delete the first one hundred frames of img and reset TcwMat=cv::Mat::eye(4,4,CV_32FC1) when it is empty but is don't works. How can I solve the problem?
ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. G贸mez, Jos茅 M.M. Montiel and Juan D. Tard贸s,
University of Zaragoza.
ORB-SLAM2 Copyright (C) 2014-2016 Ra煤l Mur-Artal, Jos茅 M.M. Montiel and Juan D. Tard贸s, University of Zaragoza.
This program comes with ABSOLUTELY NO WARRANTY;
This is free software, and you are welcome to redistribute it
under certain conditions. See LICENSE.txt.
Input sensor was set to: Stereo-Inertial
Loading ORB Vocabulary. This could take a while...
Vocabulary loaded!
Creation of new map with id: 0
Creation of new map with last KF id: 0
Seq. Name:
Camera Parameters:
- Camera: Pinhole
- fx: 426.02505493164062
- fy: 426.02505493164062
- cx: 420.88778686523438
- cy: 235.79617309570312
- k1: 0
- k2: 0
- p1: 0
- p2: 0
- fps: 30
- color order: RGB (ignored if grayscale)
Depth Threshold (Close/Far Points): 1.7523394823074341
ORB Extractor Parameters:
- Number of Features: 1200
- Scale Levels: 8
- Scale Factor: 1.2000000476837158
- Initial Fast Threshold: 20
- Minimum Fast Threshold: 7
Left camera to Imu Transform (Tbc):
[-0.0070582302, 0.25437847, 0.96707898, 0.43901792;
-0.9996779, 0.02178153, -0.01302552, -0.0057194699;
-0.024377881, -0.9668594, 0.25414279, 0.01104183;
0, 0, 0, 1]
IMU frequency: 200 Hz
IMU gyro noise: 0.0012644368689507246 rad/s/sqrt(Hz)
IMU gyro walk: 1.2205310667923186e-05 rad/s^2/sqrt(Hz)
IMU accelerometer noise: 0.0071818670257925987 m/s^2/sqrt(Hz)
IMU accelerometer walk: 0.0003089375386480242 m/s^3/sqrt(Hz)
not IMU meas
Tcw.size(): [0 x 0] []
not IMU meas
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
not enough acceleration
Tcw.size(): [0 x 0] []
First KF:0; Map init KF:0
New Map created with 712 points
Tcw.size(): [4 x 4] [1, 7.4505806e-09, -4.1909516e-09, -9.3132257e-10;
7.4505806e-09, 0.99999994, 1.4901161e-08, 0;
-4.1909516e-09, 1.4901161e-08, 0.99999994, 2.9802322e-08;
0, 0, 0, 1]
Tcw.size(): [4 x 4] [0.99999994, -5.4582711e-06, 0.00025355592, -0.00027912096;
5.6415006e-06, 0.99999976, -0.0007226434, -0.0021543158;
-0.0002535519, 0.00072264485, 0.9999997, -0.0060908222;
0, 0, 0, 1]
Tcw.size(): [4 x 4] [0.99999988, 0.00011783258, 0.00046347966, -0.001203413;
-0.000117444, 0.99999964, -0.0008383441, -0.0037155116;
-0.00046357827, 0.00083828956, 0.99999952, -0.0118046;
0, 0, 0, 1]
Tcw.size(): [4 x 4] [0.99999982, -0.00026379351, 0.00048195757, -0.00042454546;
0.00026422372, 0.99999958, -0.0008927983, -0.0044264961;
-0.00048172186, 0.00089292548, 0.99999946, -0.017697811;
0, 0, 0, 1]
Tcw.size(): [4 x 4] [0.9999997, -0.00020859772, 0.0007231551, -0.00026846616;
0.0002091085, 0.9999997, -0.00070632988, -0.0057396353;
-0.0007230076, 0.00070648087, 0.99999946, -0.02106561;
0, 0, 0, 1]
Tcw.size(): [4 x 4] [0.9999997, -9.4697833e-05, 0.00074778375, -0.0007891758;
9.4930605e-05, 0.99999994, -0.00031124902, -0.0057172119;
-0.00074775424, 0.00031131992, 0.99999964, -0.023363676;
0, 0, 0, 1]
Tcw.size(): [4 x 4] [0.99999976, 8.1131453e-05, 0.00067158282, 0.00013523936;
-8.1441518e-05, 0.99999988, 0.00046167945, -0.0063481871;
-0.00067154528, -0.00046173402, 0.99999964, -0.026490711;
0, 0, 0, 1]