ORB_SLAM3 icon indicating copy to clipboard operation
ORB_SLAM3 copied to clipboard

i had a problem when loading atlas maps:terminate called after throwing an instance of 'boost::archive::archive_exception' what(): input stream error Aborted (core dumped)

Open aboluo opened this issue 1 year ago • 10 comments

for example, when i load the map in osa format file that was saved before, it reports:terminate called after throwing an instance of 'boost::archive::archive_exception' what(): input stream error Aborted (core dumped) has anyone encountered a similar problem and how did you solve it, many thanks

aboluo avatar Apr 18 '24 02:04 aboluo

@aboluo I have exactly the same issue when trying to load a previously saved map. Have you found a fix for this?

RaduCorcodel avatar Jul 30 '24 14:07 RaduCorcodel

@RaduCorcodel what is the size of .osa file?

arjunskumar avatar Jul 30 '24 15:07 arjunskumar

@arjunskumar size on disk is 92MB

RaduCorcodel avatar Jul 30 '24 15:07 RaduCorcodel

@RaduCorcodel can I have your config file of loading the map ?

arjunskumar avatar Jul 30 '24 16:07 arjunskumar

@arjunskumar Of course. I'm using this:

%YAML:1.0

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
File.version: "1.0"

Camera.type: "PinHole"

# Right Camera calibration and distortion parameters (OpenCV)
Camera1.fx: 617.201
Camera1.fy: 617.362
Camera1.cx: 324.637
Camera1.cy: 242.462


# distortion parameters
Camera1.k1: 0.0
Camera1.k2: 0.0
Camera1.p1: 0.0
Camera1.p2: 0.0

# Camera resolution
Camera.width: 640
Camera.height: 480

# Camera frames per second 
Camera.fps: 30

# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1

# Close/Far threshold. Baseline times.
Stereo.ThDepth: 40.0
Stereo.b: 0.0745

# Depth map values factor
RGBD.DepthMapFactor: 1000.0

#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1250

# ORB Extractor: Scale factor between levels in the scale pyramid 	
ORBextractor.scaleFactor: 1.2

# ORB Extractor: Number of levels in the scale pyramid	
ORBextractor.nLevels: 8

# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast			
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7

#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1.0
Viewer.GraphLineWidth: 0.9
Viewer.PointSize: 2.0
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3.0
Viewer.ViewpointX: 0.0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -3.5
Viewer.ViewpointF: 500.0

####
# SLAM SYSTEM SETTINGS #
####
System.SaveAtlasToFile: map1
System.LoadAtlasFromFile: map1

RaduCorcodel avatar Jul 30 '24 17:07 RaduCorcodel

@RaduCorcodel is your map1.osa located in .ros folder?

arjunskumar avatar Jul 30 '24 17:07 arjunskumar

Alas, no. I'm not using ROS. Should it be in the .ros folder? I did a little poking around and it looks like it exits in the middle of writing the .osa file. I start to believe the archive is corrupted

RaduCorcodel avatar Aug 01 '24 15:08 RaduCorcodel

@RaduCorcodel can you share the .osa file ?

arjunskumar avatar Aug 02 '24 05:08 arjunskumar

Hi, were you able to resolve this?

tianyilim avatar Sep 26 '25 15:09 tianyilim

Aside from the solutions in this comment in #443, I found a potential other source of the bug.

In src/System.cc:

        string pathSaveFileName = "./";
        pathSaveFileName = pathSaveFileName.append(mStrSaveAtlasToFile);
        pathSaveFileName = pathSaveFileName.append(".osa");

If you specified an absolute path in your config file (System.SaveAtlasToFile), this code will nonetheless attempt to create the atlas file as a relative path. This then leads to the later line creating a Boost Archive to fail, because (possibly multiple folders) have to be created before the Atlas .osa file is saved.

If you change the code block above to:

        string pathSaveFileName = "";
        // if user specifies an absolute path, don't do anything silly
        if (mStrSaveAtlasToFile[0] != '/') {
            pathSaveFileName = "./";
        }
        pathSaveFileName = pathSaveFileName.append(mStrSaveAtlasToFile);
        pathSaveFileName = pathSaveFileName.append(".osa");

it will behave as you expect.

Don't forget to create all parents of the save file you specify beforehand!

(C++17 offers the filesystem library, which would make doing mkdir operations easier natively in the code, but unfortunately ORB-SLAM3 is on C++11)

tianyilim avatar Sep 27 '25 13:09 tianyilim