Help with running rtabmap headless
I am working with D457 and the core Rtabmap. I built it with the flags
-DWITH_QT=ON
-DWITH_FREENECT2=OFF
-DWITH_REALSENSE=OFF
-DWITH_REALSENSE2=ON
-DWITH_G2O=OFF
-DWITH_GTSAM=ON
-DWITH_OCTOMAP=ON
-DWITH_CUDASIFT=ON
-DWITH_TORCH=ON
-DWITH_ORB_SLAM=ON
After connecting my camera I built a wrapper to use the libraries and do the functions of the GUI directly. Here is my code.
#include <librealsense2/rs.hpp>
#include <rtabmap/core/Rtabmap.h>
#include <rtabmap/core/Parameters.h>
#include <rtabmap/core/SensorData.h>
#include <rtabmap/core/CameraModel.h>
#include <rtabmap/core/Transform.h>
#include <rtabmap/utilite/UTimer.h>
#include <opencv2/opencv.hpp>
#include <iostream>
#include <fstream>
#include <csignal>
volatile bool running = true;
void signalHandler(int signum)
{
std::cout << "\nInterrupt signal (" << signum << ") received. Exiting gracefully...\n";
running = false;
}
int main(int argc, char** argv)
{
// Register signal handler
signal(SIGINT, signalHandler);
// Initialize RealSense pipeline
rs2::pipeline pipe;
rs2::config cfg;
cfg.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 15);
cfg.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 15);
try
{
pipe.start(cfg);
std::cout << "Pipeline started." << std::endl;
}
catch (const rs2::error & e)
{
std::cerr << "RealSense error starting pipeline: " << e.what() << std::endl;
return -1;
}
// Initialize RTAB-Map
rtabmap::Rtabmap rtabmap;
rtabmap::ParametersMap parameters;
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRtabmapWorkingDirectory(), "./rtabmap_db"));
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRGBDEnabled(), "true"));
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemBinDataKept(), "false")); // optimize for Jetson
// Jetson-optimized parameters
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kVisMaxFeatures(), "500"));
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kKpMaxFeatures(), "500"));
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRGBDOptimizeMaxError(), "0.01"));
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRegStrategy(), "0")); // visual-only for now (IMPORTANT!)
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRtabmapDetectionRate(), "5.0")); // Hz
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kOptimizerStrategy(), "1")); // TORO optimizer
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRGBDLinearUpdate(), "0.05")); // 5cm
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRGBDAngularUpdate(), "0.05")); // ~3 deg
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRGBDNewMapOdomChangeDistance(), "0.3")); // 30cm
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemRehearsalSimilarity(), "0.3"));
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemImagePreDecimation(), "2")); // Reduce image res
parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kKpMaxDepth(), "4.0")); // Filter depth >4m
rtabmap.init(parameters);
std::cout << "RTAB-Map initialized. Starting SLAM..." << std::endl;
std::ofstream poseFile("poses.txt");
if (!poseFile.is_open())
{
std::cerr << "Failed to open poses.txt for writing!" << std::endl;
return -1;
}
int frame_id = 0;
UTimer globalTimer;
double lastPrintTime = 0.0;
while (running)
{
UTimer frameTimer;
try
{
rs2::frameset frames = pipe.wait_for_frames(1000); // timeout 1 sec
// Print loop heartbeat once per second
double t = globalTimer.ticks();
if (t - lastPrintTime > 1.0)
{
std::cout << "Loop heartbeat. Frame ID = " << frame_id << std::endl;
lastPrintTime = t;
}
rs2::video_frame color_frame = frames.get_color_frame();
rs2::depth_frame depth_frame = frames.get_depth_frame();
std::cout << "Captured frame " << frame_id << std::endl;
// Convert RealSense frames to OpenCV
cv::Mat color(cv::Size(640, 480), CV_8UC3, (void*)color_frame.get_data(), cv::Mat::AUTO_STEP);
cv::Mat depth(cv::Size(640, 480), CV_16UC1, (void*)depth_frame.get_data(), cv::Mat::AUTO_STEP);
// Print image sizes (IMPORTANT!)
std::cout << "Color image size: " << color.cols << "x" << color.rows
<< ", Depth image size: " << depth.cols << "x" << depth.rows << std::endl;
// Timestamp
double timestamp = UTimer::now();
// Focal length and principal point → RealSense intrinsics
rs2_intrinsics intrinsics = color_frame.get_profile().as<rs2::video_stream_profile>().get_intrinsics();
rtabmap::CameraModel cameraModel(
intrinsics.fx, intrinsics.fy,
intrinsics.ppx, intrinsics.ppy,
rtabmap::Transform::getIdentity(),
0.0,
cv::Size(640, 480)
);
// Wrap data into SensorData → CameraModel in vector
rtabmap::SensorData data(
color.clone(),
depth.clone(),
std::vector<rtabmap::CameraModel>{cameraModel},
frame_id,
timestamp
);
std::cout << "Calling RTAB-Map process()..." << std::endl;
UTimer procTimer;
bool success = rtabmap.process(data, rtabmap::Transform());
double procTime = procTimer.ticks();
std::cout << "RTAB-Map process() done. Time: " << procTime << " s" << std::endl;
// Get current pose
rtabmap::Transform pose = rtabmap.getPose(rtabmap.getLastLocationId());
if (!pose.isNull())
{
std::cout << "Frame " << frame_id << " Pose: " << pose.prettyPrint() << std::endl;
// Save pose to file
poseFile << frame_id << " "
<< pose.r11() << " " << pose.r12() << " " << pose.r13() << " " << pose.x() << " "
<< pose.r21() << " " << pose.r22() << " " << pose.r23() << " " << pose.y() << " "
<< pose.r31() << " " << pose.r32() << " " << pose.r33() << " " << pose.z() << std::endl;
}
else
{
std::cout << "Frame " << frame_id << " Pose: Not available" << std::endl;
}
double elapsed = frameTimer.ticks();
std::cout << "Frame " << frame_id << " total processing time: " << elapsed << " s" << std::endl;
frame_id++;
}
catch (const rs2::error & e)
{
std::cerr << "RealSense error: " << e.what() << std::endl;
}
}
// Finalize
rtabmap.close(); // flush DB
poseFile.close();
pipe.stop();
std::cout << "Finished. Poses saved to poses.txt, database in ./rtabmap_db." << std::endl;
return 0;
}
When I launch on Jetson it freezes at Captured frame 0 and refused to exit. Is there something wrong with how I am accessing the rtabmap library
I suggest to add these two lines at the beginning of your main function to get all debug logs:
#include <rtabmap/utilite/ULogger.h>
int main(int argc, char ** argv) {
ULogger::setType(ULogger::kTypeConsole);
ULogger::setLevel(ULogger::kDebug);
...
Thank you for replying matlabbbe. I added that as you suggested and I get this
➜ build ./bin/rtabmap_d457_wrapper
Pipeline started.
[DEBUG] (2025-06-09 07:19:10.056) Rtabmap.cpp:323::init() path=
[ WARN] (2025-06-09 07:19:10.056) Rtabmap.cpp:332::init() Using empty database. Mapping session will not be saved unless it is closed with an output database path.
[ERROR] (2025-06-09 07:19:10.056) Rtabmap.cpp:4830::setWorkingDirectory() Directory "./rtabmap_db" doesn't exist!
[DEBUG] (2025-06-09 07:19:10.056) VWDictionary.cpp:470::update() incremental=1
[DEBUG] (2025-06-09 07:19:10.056) FlannIndex.cpp:52::release()
[DEBUG] (2025-06-09 07:19:10.056) FlannIndex.cpp:80::release()
[DEBUG] (2025-06-09 07:19:10.056) VWDictionary.cpp:680::update() Dictionary updated! (size=0 added=0 removed=0)
[DEBUG] (2025-06-09 07:19:10.056) VWDictionary.cpp:689::update()
[DEBUG] (2025-06-09 07:19:10.056) Registration.cpp:49::create() type=0
[DEBUG] (2025-06-09 07:19:10.057) GlobalDescriptorExtractor.cpp:51::create() Creating global descriptor of type 0
[DEBUG] (2025-06-09 07:19:10.057) RegistrationIcp.cpp:162::parseParameters() libpointmatcher enabled! config=""
[DEBUG] (2025-06-09 07:19:10.057) Memory.cpp:563::parseParameters()
[DEBUG] (2025-06-09 07:19:10.058) RegistrationIcp.cpp:162::parseParameters() libpointmatcher enabled! config=""
[DEBUG] (2025-06-09 07:19:10.058) Memory.cpp:172::init()
[DEBUG] (2025-06-09 07:19:10.058) Memory.cpp:563::parseParameters()
[DEBUG] (2025-06-09 07:19:10.059) RegistrationIcp.cpp:162::parseParameters() libpointmatcher enabled! config=""
[DEBUG] (2025-06-09 07:19:10.059) Memory.cpp:1780::clear()
[DEBUG] (2025-06-09 07:19:10.059) Memory.cpp:6356::cleanUnusedWords() Removing 0 words (dictionary size=0)...
[DEBUG] (2025-06-09 07:19:10.059) Memory.cpp:1836::clear()
[DEBUG] (2025-06-09 07:19:10.059) Memory.cpp:1860::clear()
[DEBUG] (2025-06-09 07:19:10.059) Memory.cpp:1866::clear()
[DEBUG] (2025-06-09 07:19:10.059) Memory.cpp:6356::cleanUnusedWords() Removing 0 words (dictionary size=0)...
[DEBUG] (2025-06-09 07:19:10.059) VWDictionary.cpp:694::clear()
[DEBUG] (2025-06-09 07:19:10.059) FlannIndex.cpp:52::release()
[DEBUG] (2025-06-09 07:19:10.059) FlannIndex.cpp:80::release()
[DEBUG] (2025-06-09 07:19:10.059) Memory.cpp:1897::clear()
[DEBUG] (2025-06-09 07:19:10.059) DBDriverSqlite3.cpp:63::DBDriverSqlite3() treadSafe=1
[DEBUG] (2025-06-09 07:19:10.059) DBDriver.cpp:88::openConnection()
[DEBUG] (2025-06-09 07:19:10.059) DBDriverSqlite3.cpp:451::disconnectDatabaseQuery()
[ INFO] (2025-06-09 07:19:10.059) DBDriverSqlite3.cpp:354::connectDatabaseQuery() Using empty database in the memory.
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:524::executeNoResultQuery() Time=0.000499s
[ INFO] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:428::connectDatabaseQuery() Database version = 0.22.0
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:524::executeNoResultQuery() Time=0.000002s
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:524::executeNoResultQuery() Time=0.000002s
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:524::executeNoResultQuery() Time=0.000001s
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:524::executeNoResultQuery() Time=0.000001s
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:3631::loadLastNodesQuery()
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:3674::loadLastNodesQuery() Loading 0 signatures...
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2992::loadSignaturesQuery() count=0
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:3676::loadLastNodesQuery() loaded=0, Time=0.000017s
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:320::loadDataFromDb() Get labels
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2951::getAllLabelsQuery() Time=0.000007
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:323::loadDataFromDb() Check if all nodes are in Working Memory
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:335::loadDataFromDb() allNodesInWM()=true
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:337::loadDataFromDb() update odomMaxInf vector
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:359::loadDataFromDb() update odomMaxInf vector, done!
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2721::getLastIdQuery() get last id from table "Node"
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2752::getLastIdQuery() Time=0.000008s
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2721::getLastIdQuery() get last id from table "Statistics"
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2752::getLastIdQuery() Time=0.000004s
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2721::getLastIdQuery() get last map_id from table "Node"
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2752::getLastIdQuery() Time=0.000004s
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:381::loadDataFromDb() Loading dictionary...
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:425::loadDataFromDb() load words
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:3682::loadQuery()
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2721::getLastIdQuery() get last id from table "Word"
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:2752::getLastIdQuery() Time=0.000003s
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:3763::loadQuery() Time=0.000018s
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:429::loadDataFromDb() 0 words loaded!
[DEBUG] (2025-06-09 07:19:10.060) VWDictionary.cpp:470::update() incremental=1
[DEBUG] (2025-06-09 07:19:10.060) FlannIndex.cpp:52::release()
[DEBUG] (2025-06-09 07:19:10.060) FlannIndex.cpp:80::release()
[DEBUG] (2025-06-09 07:19:10.060) VWDictionary.cpp:680::update() Dictionary updated! (size=0 added=0 removed=0)
[DEBUG] (2025-06-09 07:19:10.060) VWDictionary.cpp:689::update()
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:461::loadDataFromDb() Total word references added = 0
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:469::loadDataFromDb()
[DEBUG] (2025-06-09 07:19:10.060) DBDriver.cpp:1167::addInfoAfterRun()
[DEBUG] (2025-06-09 07:19:10.060) Parameters.cpp:105::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.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;Db/TargetVersion:;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/Gpu:false;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/IncRelinearizeSkip:1;GTSAM/IncRelinearizeThreshold:0.01;GTSAM/Incremental: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/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:5.0;Grid/RangeMin:0.0;Grid/RayTracing:false;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/ProbMiss:0.4;GridGlobal/UpdateError:0.01;Icp/CCFilterOutFarthestPoints:false;Icp/CCMaxFinalRMS:0.2;Icp/CCSamplingLimit:50000;Icp/CorrespondenceRatio:0.1;Icp/DebugExportFormat:;Icp/DownsamplingStep:1;Icp/Epsilon:0;Icp/FiltersEnabled:3;Icp/Force4DoF:false;Icp/Iterations:30;Icp/MaxCorrespondenceDistance:0.1;Icp/MaxRotation:0.78;Icp/MaxTranslation:0.2;Icp/OutlierRatio:0.85;Icp/PMConfig:;Icp/PMMatcherEpsilon:0.0;Icp/PMMatcherIntensity:false;Icp/PMMatcherKnn:1;Icp/PointToPlane:true;Icp/PointToPlaneGroundNormalsUp:0.0;Icp/PointToPlaneK:5;Icp/PointToPlaneLowComplexityStrategy:1;Icp/PointToPlaneMinComplexity:0.02;Icp/PointToPlaneRadius:0.0;Icp/RangeMax:0;Icp/RangeMin:0;Icp/ReciprocalCorrespondences:true;Icp/Strategy:1;Icp/VoxelSize: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/DictionaryPath:;Kp/FlannRebalancingFactor:2.0;Kp/GridCols:1;Kp/GridRows:1;Kp/IncrementalDictionary:true;Kp/IncrementalFlann:true;Kp/MaxDepth:4.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/SSC:false;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/Priors:;Marker/PriorsVarianceAngular:0.001;Marker/PriorsVarianceLinear:0.001;Marker/VarianceAngular:0.01;Marker/VarianceLinear:0.001;Marker/VarianceOrientationIgnored:false;Mem/BadSignaturesIgnored:false;Mem/BinDataKept:false;Mem/CompressionParallelized:true;Mem/CovOffDiagIgnored:true;Mem/DepthAsMask:true;Mem/DepthCompressionFormat:.rvl;Mem/DepthMaskFloorThr:0.0;Mem/GenerateIds:true;Mem/GlobalDescriptorStrategy:0;Mem/ImageCompressionFormat:.jpg;Mem/ImageKept:false;Mem/ImagePostDecimation:1;Mem/ImagePreDecimation:2;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.3;Mem/RehearsalWeightIgnoredWhileMoving:false;Mem/RotateImagesUpsideUp: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/Deskewing:true;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.9;Odom/Strategy:0;Odom/VisKeyFrameThr:150;OdomF2M/BundleAdjustment:0;OdomF2M/BundleAdjustmentMaxFrames:10;OdomF2M/BundleAdjustmentMaxKeyFramesPerFeature:0;OdomF2M/BundleAdjustmentMinMotion:0.0;OdomF2M/BundleUpdateFeatureMapOnAllFrames:false;OdomF2M/FloorThreshold:0.0;OdomF2M/InitDepthFactor:0.05;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;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/Resolution:0.2;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;OdomOKVIS/ConfigPath:;OdomORBSLAM/AccNoise:0.1;OdomORBSLAM/AccWalk:0.0001;OdomORBSLAM/Bf:0.076;OdomORBSLAM/Fps:0.0;OdomORBSLAM/GyroNoise:0.01;OdomORBSLAM/GyroWalk:0.000001;OdomORBSLAM/Inertial:false;OdomORBSLAM/MapSize:3000;OdomORBSLAM/MaxFeatures:1000;OdomORBSLAM/SamplingRate:0;OdomORBSLAM/ThDepth:40.0;OdomORBSLAM/VocPath:;OdomOpen3D/MaxDepth:3.0;OdomOpen3D/Method:0;OdomOpenVINS/AccelerometerNoiseDensity:0.01;OdomOpenVINS/AccelerometerRandomWalk:0.001;OdomOpenVINS/CalibCamExtrinsics:false;OdomOpenVINS/CalibCamIntrinsics:false;OdomOpenVINS/CalibCamTimeoffset:false;OdomOpenVINS/CalibIMUGSensitivity:false;OdomOpenVINS/CalibIMUIntrinsics:false;OdomOpenVINS/DtSLAMDelay:0.0;OdomOpenVINS/FeatRepMSCKF:0;OdomOpenVINS/FeatRepSLAM:4;OdomOpenVINS/FiMaxBaseline:40;OdomOpenVINS/FiMaxCondNumber:10000;OdomOpenVINS/FiMaxRuns:5;OdomOpenVINS/FiRefineFeatures:true;OdomOpenVINS/FiTriangulate1d:false;OdomOpenVINS/GravityMag:9.81;OdomOpenVINS/GyroscopeNoiseDensity:0.001;OdomOpenVINS/GyroscopeRandomWalk:0.0001;OdomOpenVINS/InitDynInflationBa:100.0;OdomOpenVINS/InitDynInflationBg:10.0;OdomOpenVINS/InitDynInflationOri:10.0;OdomOpenVINS/InitDynInflationVel:100.0;OdomOpenVINS/InitDynMLEMaxIter:50;OdomOpenVINS/InitDynMLEMaxThreads:6;OdomOpenVINS/InitDynMLEMaxTime:0.05;OdomOpenVINS/InitDynMLEOptCalib:false;OdomOpenVINS/InitDynMinDeg:10.0;OdomOpenVINS/InitDynMinRecCond:1e-15;OdomOpenVINS/InitDynNumPose:6;OdomOpenVINS/InitDynUse:false;OdomOpenVINS/InitIMUThresh:1.0;OdomOpenVINS/InitMaxDisparity:10.0;OdomOpenVINS/InitMaxFeatures:50;OdomOpenVINS/InitWindowTime:2.0;OdomOpenVINS/Integration:1;OdomOpenVINS/LeftMaskPath:;OdomOpenVINS/MaxClones:11;OdomOpenVINS/MaxMSCKFInUpdate:50;OdomOpenVINS/MaxSLAM:50;OdomOpenVINS/MaxSLAMInUpdate:25;OdomOpenVINS/MinPxDist:15;OdomOpenVINS/NumPts:200;OdomOpenVINS/RightMaskPath:;OdomOpenVINS/TryZUPT:true;OdomOpenVINS/UpMSCKFChi2Multiplier:1.0;OdomOpenVINS/UpMSCKFSigmaPx:1.0;OdomOpenVINS/UpSLAMChi2Multiplier:1.0;OdomOpenVINS/UpSLAMSigmaPx:1.0;OdomOpenVINS/UseFEJ:true;OdomOpenVINS/UseKLT:true;OdomOpenVINS/UseStereo:true;OdomOpenVINS/ZUPTChi2Multiplier:0.0;OdomOpenVINS/ZUPTMaxDisparity:0.5;OdomOpenVINS/ZUPTMaxVelodicy:0.1;OdomOpenVINS/ZUPTNoiseMultiplier:10.0;OdomOpenVINS/ZUPTOnlyAtBeginning:false;OdomVINS/ConfigPath:;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:1;Optimizer/VarianceIgnored:false;PyDescriptor/Dim:4096;PyDescriptor/Path:;PyDetector/Cuda:true;PyDetector/Path:;PyMatcher/Cuda:true;PyMatcher/Iterations:20;PyMatcher/Model:indoor;PyMatcher/Path:;PyMatcher/Threshold:0.2;RGBD/AggressiveLoopThr:0.05;RGBD/AngularSpeedUpdate:0.0;RGBD/AngularUpdate:0.05;RGBD/CreateOccupancyGrid:false;RGBD/Enabled:true;RGBD/ForceOdom3DoF:true;RGBD/GoalReachedRadius:0.5;RGBD/GoalsSavedInUserData:false;RGBD/InvertedReg:false;RGBD/LinearSpeedUpdate:0.0;RGBD/LinearUpdate:0.05;RGBD/LocalBundleOnLoopClosure:false;RGBD/LocalImmunizationRatio:0.25;RGBD/LocalRadius:10;RGBD/LocalizationPriorError:0.001;RGBD/LocalizationSecondTryWithoutProximityLinks:true;RGBD/LocalizationSmoothing:true;RGBD/LoopClosureIdentityGuess:false;RGBD/LoopClosureReextractFeatures:false;RGBD/LoopCovLimited:false;RGBD/MarkerDetection:false;RGBD/MaxLocalRetrieved:2;RGBD/MaxLoopClosureDistance:0.0;RGBD/MaxOdomCacheSize:10;RGBD/NeighborLinkRefining:false;RGBD/NewMapOdomChangeDistance:0.3;RGBD/OptimizeFromGraphEnd:false;RGBD/OptimizeMaxError:0.01;RGBD/PlanAngularVelocity:0;RGBD/PlanLinearVelocity:0;RGBD/PlanStuckIterations:0;RGBD/ProximityAngle:45;RGBD/ProximityBySpace:true;RGBD/ProximityByTime:false;RGBD/ProximityGlobalScanMap:false;RGBD/ProximityMaxGraphDepth:50;RGBD/ProximityMaxPaths:3;RGBD/ProximityMergedScanCovFactor:100.0;RGBD/ProximityOdomGuess:false;RGBD/ProximityPathFilteringRadius:1;RGBD/ProximityPathMaxNeighbors:0;RGBD/ProximityPathRawPosesUsed:true;RGBD/ScanMatchingIdsSavedInLinks:true;RGBD/StartAtOrigin:false;Reg/Force3DoF:false;Reg/RepeatOnce:true;Reg/Strategy:0;Rtabmap/ComputeRMSE:true;Rtabmap/CreateIntermediateNodes:false;Rtabmap/DetectionRate:5.0;Rtabmap/ImageBufferSize:1;Rtabmap/ImagesAlreadyRectified:true;Rtabmap/LoopGPS:true;Rtabmap/LoopRatio:0;Rtabmap/LoopThr:0.11;Rtabmap/MaxRepublished:2;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;Rtabmap/VirtualPlaceLikelihoodRatio:0;SIFT/ContrastThreshold:0.04;SIFT/EdgeThreshold:10;SIFT/GaussianThreshold:2.0;SIFT/Gpu:false;SIFT/NOctaveLayers:3;SIFT/PreciseUpscale:false;SIFT/RootSIFT:false;SIFT/Sigma:1.6;SIFT/Upscale:false;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/Gpu:false;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/ModelPath:;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:0;Vis/CorFlowEps:0.01;Vis/CorFlowGpu:false;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/DepthMaskFloorThr:0.0;Vis/EpipolarGeometryVar:0.1;Vis/EstimationType:1;Vis/FeatureType:8;Vis/GridCols:1;Vis/GridRows:1;Vis/InlierDistance:0.1;Vis/Iterations:300;Vis/MaxDepth:0;Vis/MaxFeatures:500;Vis/MeanInliersDistance:0.0;Vis/MinDepth:0;Vis/MinInliers:20;Vis/MinInliersDistribution:0.0;Vis/PnPFlags:0;Vis/PnPMaxVariance:0.0;Vis/PnPRefineIterations:1;Vis/PnPReprojError:2;Vis/PnPSamplingPolicy:1;Vis/PnPSplitLinearCovComponents:false;Vis/PnPVarianceMedianRatio:4;Vis/RefineIterations:5;Vis/RoiRatios:0.0 0.0 0.0 0.0;Vis/SSC:false;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
[DEBUG] (2025-06-09 07:19:10.060) DBDriverSqlite3.cpp:524::executeNoResultQuery() Time=0.000048s
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:481::loadDataFromDb() ids start with 1
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:482::loadDataFromDb() map ids start with 0
[DEBUG] (2025-06-09 07:19:10.060) Rtabmap.cpp:555::parseParameters()
[ERROR] (2025-06-09 07:19:10.060) Rtabmap.cpp:4830::setWorkingDirectory() Directory "./rtabmap_db" doesn't exist!
[DEBUG] (2025-06-09 07:19:10.060) Rtabmap.cpp:694::parseParameters() new detector strategy 1
[ WARN] (2025-06-09 07:19:10.060) Optimizer.cpp:106::create() g2o optimizer not available. GTSAM will be used instead.
[DEBUG] (2025-06-09 07:19:10.060) OptimizerGTSAM.cpp:105::parseParameters() GTSAM GTSAM/Optimizer=1
[DEBUG] (2025-06-09 07:19:10.060) OptimizerGTSAM.cpp:106::parseParameters() GTSAM GTSAM/Incremental=0
[DEBUG] (2025-06-09 07:19:10.060) OptimizerGTSAM.cpp:107::parseParameters() GTSAM GTSAM/IncRelinearizeThreshold=0.010000
[DEBUG] (2025-06-09 07:19:10.060) OptimizerGTSAM.cpp:108::parseParameters() GTSAM GTSAM/IncRelinearizeSkip=1
[DEBUG] (2025-06-09 07:19:10.060) Memory.cpp:563::parseParameters()
[DEBUG] (2025-06-09 07:19:10.061) RegistrationIcp.cpp:162::parseParameters() libpointmatcher enabled! config=""
[DEBUG] (2025-06-09 07:19:10.061) BayesFilter.cpp:114::setPredictionLC() predictionEpsilon = 0.000000
[DEBUG] (2025-06-09 07:19:10.061) DBDriverSqlite3.cpp:5068::loadOptimizedPosesQuery()
[DEBUG] (2025-06-09 07:19:10.061) DBDriverSqlite3.cpp:5133::loadOptimizedPosesQuery() lastlocalizationPose=xyz=[null] rpy=[null]
[DEBUG] (2025-06-09 07:19:10.061) DBDriverSqlite3.cpp:5143::loadOptimizedPosesQuery() Time=0.000016s
[DEBUG] (2025-06-09 07:19:10.061) Rtabmap.cpp:295::setupLogFiles() Log disabled!
RTAB-Map initialized. Starting SLAM...
Captured frame 0
Color image size: 640x480, Depth image size: 640x480
I think it is related to this bug (infinite recursive call): https://github.com/introlab/rtabmap/commit/332dde6d74859e6d74834bab890c347ce21a42ba
Either update to latest master, or change:
rtabmap::SensorData data(
color.clone(),
depth.clone(),
- std::vector<rtabmap::CameraModel>{cameraModel},
+ cameraModel,
frame_id,
timestamp
);