Kimera-VIO
Kimera-VIO copied to clipboard
Segmentation fault when running testKimeraVIO
Description:
Attempting to run testKimeraVIO will result in a segmentation fault. This can be reproduced using the provided branch and Dockerfile
git clone https://github.com/ruffsl/Kimera-VIO.git -b focal
cd Kimera-VIO
export DOCKER_BUILDKIT=1
docker build \
--tag spark/kimera_vio:focal \
--progress=plain \
--file focal.Dockerfile .
Note the .repos
files use for the workspace underlays:
https://github.com/ruffsl/Kimera-VIO/tree/focal/install
Command:
docker run -it --rm spark/kimera_vio:focal bash
ln -s ../src/MIT-SPARK/Kimera-VIO/tests/ build/tests
cd build/kimera_vio/
./testKimeraVIO --gtest_output="xml:testresults.xml"
Console output:
[==========] Running 187 tests from 40 test suites.
[----------] Global test environment set-up.
[----------] 16 tests from VioPipelineFixture
[ RUN ] VioPipelineFixture.OnlineSequentialStart
Segmentation fault (core dumped)
Additional files:
Same effect, but build with debug instead:
[==========] Running 187 tests from 40 test suites.
[----------] Global test environment set-up.
[----------] 16 tests from VioPipelineFixture
[ RUN ] VioPipelineFixture.OnlineSequentialStart
I0513 14:57:43.480235 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.480299 47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.495240 47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.496774 47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.496795 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.496800 47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.496816 47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.496822 47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.496830 47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.496897 47 MesherModule.cpp:65] Shutting down queues for: Mesher
W0513 14:57:43.496984 47 Pipeline.cpp:884] No backend thread, not joining.
W0513 14:57:43.497002 47 Pipeline.cpp:884] No frontend thread, not joining.
W0513 14:57:43.497009 47 Pipeline.cpp:884] No mesher thread, not joining.
W0513 14:57:43.497014 47 Pipeline.cpp:884] No lcd thread, not joining.
W0513 14:57:43.497020 47 Pipeline.cpp:884] No visualizer thread, not joining.
I0513 14:57:43.497026 47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.497315 47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.497490 47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.498016 47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.498059 47 DataProviderInterface.cpp:31] Data provider destructor called.
I0513 14:57:43.498080 47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.499624 47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.499727 47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.499740 47 Pipeline.h:184] Spinning Kimera-VIO.
I0513 14:57:43.499799 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.499809 47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.499814 47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.499821 47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.499828 47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.499840 47 MesherModule.cpp:65] Shutting down queues for: Mesher
I0513 14:57:43.499846 47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.499886 47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.499923 47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.500255 47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.500270 47 DataProviderInterface.cpp:31] Data provider destructor called.
[ OK ] VioPipelineFixture.OnlineSequentialStart (25 ms)
[ RUN ] VioPipelineFixture.OnlineSequentialShutdown
I0513 14:57:43.501441 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.501454 47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.502830 47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.502936 47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.502952 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.502957 47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.502961 47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.502964 47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.502970 47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.502982 47 MesherModule.cpp:65] Shutting down queues for: Mesher
W0513 14:57:43.502991 47 Pipeline.cpp:884] No backend thread, not joining.
W0513 14:57:43.503001 47 Pipeline.cpp:884] No frontend thread, not joining.
W0513 14:57:43.503010 47 Pipeline.cpp:884] No mesher thread, not joining.
W0513 14:57:43.503016 47 Pipeline.cpp:884] No lcd thread, not joining.
W0513 14:57:43.503026 47 Pipeline.cpp:884] No visualizer thread, not joining.
I0513 14:57:43.503032 47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.503094 47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.503129 47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.503425 47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.503439 47 DataProviderInterface.cpp:31] Data provider destructor called.
I0513 14:57:43.503446 47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.504812 47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.504917 47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.505040 47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.505049 47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.505054 47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.505067 47 MesherModule.cpp:65] Shutting down queues for: Mesher
I0513 14:57:43.505074 47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.505080 47 Pipeline.h:184] Spinning Kimera-VIO.
I0513 14:57:43.505089 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.505095 47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.505100 47 Pipeline.cpp:283] Manual shutdown was requested.
I0513 14:57:43.505131 47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.505167 47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.505477 47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.505491 47 DataProviderInterface.cpp:31] Data provider destructor called.
[ OK ] VioPipelineFixture.OnlineSequentialShutdown (5 ms)
[ RUN ] VioPipelineFixture.OnlineSequentialSpinOnce
I0513 14:57:43.506578 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.506589 47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.507920 47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.508038 47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.508054 47 testPipeline.cpp:121] Destroying pipeline.
I0513 14:57:43.508059 47 Pipeline.cpp:278] Pipeline destructor called.
I0513 14:57:43.508064 47 Pipeline.cpp:493] Shutting down VIO pipeline.
I0513 14:57:43.508069 47 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0513 14:57:43.508074 47 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0513 14:57:43.508085 47 MesherModule.cpp:65] Shutting down queues for: Mesher
W0513 14:57:43.508093 47 Pipeline.cpp:884] No backend thread, not joining.
W0513 14:57:43.508105 47 Pipeline.cpp:884] No frontend thread, not joining.
W0513 14:57:43.508112 47 Pipeline.cpp:884] No mesher thread, not joining.
W0513 14:57:43.508121 47 Pipeline.cpp:884] No lcd thread, not joining.
W0513 14:57:43.508131 47 Pipeline.cpp:884] No visualizer thread, not joining.
I0513 14:57:43.508141 47 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0513 14:57:43.508183 47 VioBackEnd.h:87] Backend destructor called.
I0513 14:57:43.508221 47 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0513 14:57:43.508517 47 EurocDataProvider.cpp:88] ETHDatasetParser destructor called.
I0513 14:57:43.508532 47 DataProviderInterface.cpp:31] Data provider destructor called.
I0513 14:57:43.508538 47 testPipeline.cpp:40] Building pipeline.
I0513 14:57:43.509769 47 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 14:57:43.509874 47 testPipeline.cpp:67] Connecting pipeline.
I0513 14:57:43.509889 47 EurocDataProvider.cpp:97] Parsing Euroc dataset...
Segmentation fault (core dumped)
Please give also the following information:
- SparkVio version used: ?
- GTSAM version used: https://github.com/borglab/gtsam/tree/develop
- OpenGV version used: https://github.com/ruffsl/opengv/tree/patch-1
- Same as upstream
master
branch; fork only fixes thepackage.xml
- Same as upstream
- OpenCV version used: 4.2.0
- Operating system: Ubuntu 20.04
- Source code changes:
- https://github.com/MIT-SPARK/Kimera-VIO/pull/32
- https://github.com/MIT-SPARK/Kimera-VIO/pull/74
- https://github.com/MIT-SPARK/Kimera-VIO/pull/61
Stack trace via gdb:
I0513 16:42:32.140525 1740 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0513 16:42:32.140625 1740 testPipeline.cpp:67] Connecting pipeline.
I0513 16:42:32.140637 1740 EurocDataProvider.cpp:97] Parsing Euroc dataset...
Thread 1 "testKimeraVIO" received signal SIGSEGV, Segmentation fault.
0x00007fdb34ae272d in cv::FileNode::ptr() () from /lib/x86_64-linux-gnu/libopencv_core.so.4.2
(gdb) where
#0 0x00007fdb34ae272d in cv::FileNode::ptr() () at /lib/x86_64-linux-gnu/libopencv_core.so.4.2
#1 0x00007fdb34ae281d in cv::FileNode::type() const () at /lib/x86_64-linux-gnu/libopencv_core.so.4.2
#2 0x00007fdb34ae288d in cv::FileNode::isMap() const () at /lib/x86_64-linux-gnu/libopencv_core.so.4.2
#3 0x00007fdb34aebd15 in cv::FileNode::operator[](std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) const () at /lib/x86_64-linux-gnu/libopencv_core.so.4.2
#4 0x00007fdb34aebf39 in cv::FileStorage::operator[](std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) const () at /lib/x86_64-linux-gnu/libopencv_core.so.4.2
#5 0x00007fdb34aebfe7 in cv::FileStorage::operator[](char const*) const () at /lib/x86_64-linux-gnu/libopencv_core.so.4.2
#6 0x00007fdb35ff5e2c in VIO::EurocDataProvider::parseGtData(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (this=0x56106f08abf0, input_dataset_path="../tests/data/MicroEurocDataset", gtSensorName="state_groundtruth_estimate0")
at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/dataprovider/EurocDataProvider.cpp:293
#7 0x00007fdb35ff78a9 in VIO::EurocDataProvider::parseDataset() (this=0x56106f08abf0) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/dataprovider/EurocDataProvider.cpp:429
#8 0x00007fdb35ff4f24 in VIO::EurocDataProvider::parse() (this=0x56106f08abf0) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/dataprovider/EurocDataProvider.cpp:180
#9 0x00007fdb35ff40cc in VIO::EurocDataProvider::spin() (this=0x56106f08abf0) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/dataprovider/EurocDataProvider.cpp:98
#10 0x000056106dcac401 in VIO::VioPipelineFixture_OnlineSequentialSpinOnce_Test::TestBody() (this=0x56106f07f6b0) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/tests/testPipeline.cpp:157
#11 0x000056106df11501 in testing::internal::HandleSehExceptionsInMethodIfSupported<testing::Test, void>(testing::Test*, void (testing::Test::*)(), char const*)
(object=0x56106f07f6b0, method=&virtual testing::Test::TestBody(), location=0x56106dfe7773 "the test body") at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2433
#12 0x000056106df0aa37 in testing::internal::HandleExceptionsInMethodIfSupported<testing::Test, void>(testing::Test*, void (testing::Test::*)(), char const*)
(object=0x56106f07f6b0, method=&virtual testing::Test::TestBody(), location=0x56106dfe7773 "the test body") at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2469
#13 0x000056106dee6734 in testing::Test::Run() (this=0x56106f07f6b0) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2508
#14 0x000056106dee711f in testing::TestInfo::Run() (this=0x56106f064070) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2684
#15 0x000056106dee785a in testing::TestSuite::Run() (this=0x56106f00ee50) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2816
#16 0x000056106def3916 in testing::internal::UnitTestImpl::RunAllTests() (this=0x56106f059340) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:5338
#17 0x000056106df1288c in testing::internal::HandleSehExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool>(testing::internal::UnitTestImpl*, bool (testing::internal::UnitTestImpl::*)(), char const*)
(object=0x56106f059340, method=(bool (testing::internal::UnitTestImpl::*)(testing::internal::UnitTestImpl * const)) 0x56106def350e <testing::internal::UnitTestImpl::RunAllTests()>, location=0x56106dfe81b0 "auxiliary test code (environments or event listeners)") at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2433
#18 0x000056106df0bb0d in testing::internal::HandleExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool>(testing::internal::UnitTestImpl*, bool (testing::internal::UnitTestImpl::*)(), char const*) (object=0x56106f059340, method=(bool (testing::internal::UnitTestImpl::*)(testing::internal::UnitTestImpl * const)) 0x56106def350e <testing::internal::UnitTestImpl::RunAllTests()>, location=0x56106dfe81b0 "auxiliary test code (environments or event listeners)") at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2469
#19 0x000056106def2156 in testing::UnitTest::Run() (this=0x56106e108fa0 <testing::UnitTest::GetInstance()::instance>) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:4925
#20 0x000056106dcab9bb in RUN_ALL_TESTS() () at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/include/gtest/gtest.h:2473
#21 0x000056106dcab70f in main(int, char**) (argc=1, argv=0x7ffec80aaf38) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/tests/testKimeraVIO.cpp:16
(gdb) list
1 #include <gflags/gflags.h>
2 #include <glog/logging.h>
3 #include <gtest/gtest.h>
4
5 DEFINE_string(test_data_path, "../tests/data", "Path to data for unit tests.");
6
7 int main(int argc, char **argv) {
8 // Initialize Google's testing library.
9 ::testing::InitGoogleTest(&argc, argv);
10 // Initialize Google's flags library.
(gdb) frame 6
#6 0x00007f28be42ae2c in VIO::EurocDataProvider::parseGtData (this=0x5617c32a1af0, input_dataset_path="../tests/data/MicroEurocDataset", gtSensorName="state_groundtruth_estimate0")
at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/dataprovider/EurocDataProvider.cpp:293
293 CHECK_EQ(static_cast<int>(fs["T_BS"]["rows"]), 4u);
(gdb) list
288 return false;
289 }
290
291 // Rows and cols are redundant info, since the pose 4x4, but we parse just
292 // to check we are all on the same page.
293 CHECK_EQ(static_cast<int>(fs["T_BS"]["rows"]), 4u);
294 CHECK_EQ(static_cast<int>(fs["T_BS"]["cols"]), 4u);
295 std::vector<double> vector_pose;
296 fs["T_BS"]["data"] >> vector_pose;
297 gt_data_.body_Pose_cam_ = UtilsOpenCV::poseVectorToGtsamPose3(vector_pose);
Ok, seems something may have changed with cv::FileStorage
deserializing to vectors, so I fixed EurocDataProvider::parseGtData
to use YamlParser
like elseware in ImuParams::parseYAML
.
https://github.com/ruffsl/Kimera-VIO/commit/f20d50aed04d7f611d305fea09993c828c60cb3c
Looks like we get a bit further, but still fails when checking we do not have repeated lmk ids:
...
[ OK ] VioPipelineFixture.OnlineSequentialSpinOnce (623 ms)
[ RUN ] VioPipelineFixture.OnlineSequentialSpin
I0514 01:36:46.101933 41 testPipeline.cpp:121] Destroying pipeline.
I0514 01:36:46.101943 41 testPipeline.cpp:40] Building pipeline.
I0514 01:36:46.103184 41 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0514 01:36:46.103291 41 testPipeline.cpp:67] Connecting pipeline.
I0514 01:36:46.103302 41 testPipeline.cpp:121] Destroying pipeline.
I0514 01:36:46.103312 41 Pipeline.cpp:278] Pipeline destructor called.
I0514 01:36:46.103317 41 Pipeline.cpp:493] Shutting down VIO pipeline.
I0514 01:36:46.103320 41 Pipeline.cpp:499] Calling registered shutdown callbacks...
I0514 01:36:46.103324 41 DataProviderInterface.cpp:72] Shutting down DataProviderInterface.
I0514 01:36:46.103332 41 MesherModule.cpp:65] Shutting down queues for: Mesher
W0514 01:36:46.103340 41 Pipeline.cpp:884] No backend thread, not joining.
W0514 01:36:46.103348 41 Pipeline.cpp:884] No frontend thread, not joining.
W0514 01:36:46.103354 41 Pipeline.cpp:884] No mesher thread, not joining.
W0514 01:36:46.103359 41 Pipeline.cpp:884] No lcd thread, not joining.
W0514 01:36:46.103365 41 Pipeline.cpp:884] No visualizer thread, not joining.
I0514 01:36:46.103370 41 Pipeline.cpp:513] VIO Pipeline's threads shutdown successfully.
VIO Pipeline successful shutdown.
I0514 01:36:46.103399 41 VioBackEnd.h:87] Backend destructor called.
I0514 01:36:46.103426 41 StereoVisionFrontEnd.h:63] StereoVisionFrontEnd destructor called.
I0514 01:36:46.103451 41 EurocDataProvider.cpp:95] ETHDatasetParser destructor called.
I0514 01:36:46.103458 41 DataProviderInterface.cpp:31] Data provider destructor called.
I0514 01:36:46.103463 41 testPipeline.cpp:40] Building pipeline.
I0514 01:36:46.104708 41 RegularVioBackEnd.cpp:114] Using Regular VIO backend.
I0514 01:36:46.104789 41 testPipeline.cpp:67] Connecting pipeline.
I0514 01:36:46.104799 41 EurocDataProvider.cpp:104] Parsing Euroc dataset...
I0514 01:36:46.703676 41 Pipeline.h:184] Spinning Kimera-VIO.
I0514 01:36:46.708084 41 Pipeline.h:184] Spinning Kimera-VIO.
I0514 01:36:46.713817 41 Pipeline.cpp:788] Frontend running in sequential mode (parallel_run set to 0).
I0514 01:36:46.713850 41 Pipeline.cpp:580] ------------------- Initialize Pipeline with frame k = 11--------------------
I0514 01:36:46.802433 41 Pipeline.h:184] Spinning Kimera-VIO.
W0514 01:36:46.817224 41 PipelineModule.h:398] Module: VioBackEnd - Input queue: backend_input_queue didn't return an output.
I0514 01:36:46.821652 41 Pipeline.h:184] Spinning Kimera-VIO.
W0514 01:36:46.835650 41 PipelineModule.h:398] Module: VioBackEnd - Input queue: backend_input_queue didn't return an output.
I0514 01:36:46.840306 41 Pipeline.h:184] Spinning Kimera-VIO.
W0514 01:36:46.850548 41 PipelineModule.h:398] Module: VioBackEnd - Input queue: backend_input_queue didn't return an output.
I0514 01:36:46.855231 41 Pipeline.h:184] Spinning Kimera-VIO.
F0514 01:36:46.967811 41 VioBackEnd.cpp:692] Check failed: std::find(landmarks_kf->begin(), landmarks_kf->end(), lmk_id_in_kf_i) == landmarks_kf->end()
*** Check failure stack trace: ***
@ 0x7f2b34f921c3 google::LogMessage::Fail()
@ 0x7f2b34f9725b google::LogMessage::SendToLog()
@ 0x7f2b34f91ebf google::LogMessage::Flush()
@ 0x7f2b34f926ef google::LogMessageFatal::~LogMessageFatal()
@ 0x7f2b367d414d VIO::VioBackEnd::addStereoMeasurementsToFeatureTracks()
@ 0x7f2b36936ed2 VIO::RegularVioBackEnd::addVisualInertialStateAndOptimize()
@ 0x7f2b367d109b VIO::VioBackEnd::addVisualInertialStateAndOptimize()
@ 0x7f2b367cf933 VIO::VioBackEnd::spinOnce()
@ 0x7f2b367ca0af VIO::VioBackEndModule::spinOnce()
@ 0x7f2b367cbe12 VIO::PipelineModule<>::spin()
@ 0x7f2b36a2a104 VIO::Pipeline::spinSequential()
@ 0x7f2b36a29dc8 VIO::Pipeline::spinOnce()
@ 0x7f2b36a4eb95 std::__invoke_impl<>()
@ 0x7f2b36a4bd8a std::__invoke<>()
@ 0x7f2b36a48b44 _ZNSt5_BindIFMN3VIO8PipelineEFvSt10unique_ptrINS0_19StereoImuSyncPacketESt14default_deleteIS3_EEEPS1_St12_PlaceholderILi1EEEE6__callIvJOS6_EJLm0ELm1EEEET_OSt5tupleIJDpT0_EESt12_Index_tupleIJXspT1_EEE
@ 0x7f2b36a444d6 std::_Bind<>::operator()<>()
@ 0x7f2b36a3f776 std::_Function_handler<>::_M_invoke()
@ 0x7f2b366fe2d9 std::function<>::operator()()
@ 0x7f2b366fa05f VIO::DataProviderModule::getInputPacket()
@ 0x7f2b3670717f VIO::PipelineModule<>::spin()
@ 0x55ba9ad7bcaa VIO::Pipeline::spin()
@ 0x55ba9ad72841 VIO::VioPipelineFixture_OnlineSequentialSpin_Test::TestBody()
@ 0x55ba9afd7501 testing::internal::HandleSehExceptionsInMethodIfSupported<>()
@ 0x55ba9afd0a37 testing::internal::HandleExceptionsInMethodIfSupported<>()
@ 0x55ba9afac734 testing::Test::Run()
@ 0x55ba9afad11f testing::TestInfo::Run()
@ 0x55ba9afad85a testing::TestSuite::Run()
@ 0x55ba9afb9916 testing::internal::UnitTestImpl::RunAllTests()
@ 0x55ba9afd888c testing::internal::HandleSehExceptionsInMethodIfSupported<>()
@ 0x55ba9afd1b0d testing::internal::HandleExceptionsInMethodIfSupported<>()
@ 0x55ba9afb8156 testing::UnitTest::Run()
@ 0x55ba9ad719bb RUN_ALL_TESTS()
Thread 1 "testKimeraVIO" received signal SIGABRT, Aborted.
__GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
50 ../sysdeps/unix/sysv/linux/raise.c: No such file or directory.
(gdb) where
#0 __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
#1 0x00007f2b3446c859 in __GI_abort () at abort.c:79
#2 0x00007f2b34f8f90e in ?? () from /lib/x86_64-linux-gnu/libglog.so.0
#3 0x00007f2b34f921c3 in google::LogMessage::Fail() () from /lib/x86_64-linux-gnu/libglog.so.0
#4 0x00007f2b34f9725b in google::LogMessage::SendToLog() () from /lib/x86_64-linux-gnu/libglog.so.0
#5 0x00007f2b34f91ebf in google::LogMessage::Flush() () from /lib/x86_64-linux-gnu/libglog.so.0
#6 0x00007f2b34f926ef in google::LogMessageFatal::~LogMessageFatal() () from /lib/x86_64-linux-gnu/libglog.so.0
#7 0x00007f2b367d414d in VIO::VioBackEnd::addStereoMeasurementsToFeatureTracks (this=0x55ba9ca2af80, frame_num=@0x55ba9ca2b4c4: 1, stereo_meas_kf=std::vector of length 525, capacity 525 = {...},
landmarks_kf=0x7ffedeca8e40) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/backend/VioBackEnd.cpp:692
#8 0x00007f2b36936ed2 in VIO::RegularVioBackEnd::addVisualInertialStateAndOptimize (this=0x55ba9ca2af80, timestamp_kf_nsec=@0x55ba9c024648: 1403715274012143104, status_smart_stereo_measurements_kf={...},
pim=..., stereo_ransac_body_pose=...) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/backend/RegularVioBackEnd.cpp:197
#9 0x00007f2b367d109b in VIO::VioBackEnd::addVisualInertialStateAndOptimize (this=0x55ba9ca2af80, input=...) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/backend/VioBackEnd.cpp:353
#10 0x00007f2b367cf933 in VIO::VioBackEnd::spinOnce (this=0x55ba9ca2af80, input=...) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/backend/VioBackEnd.cpp:141
#11 0x00007f2b367ca0af in VIO::VioBackEndModule::spinOnce (this=0x55ba9ca339e0, input=std::unique_ptr<struct VIO::BackendInput> = {...})
at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/backend/VioBackEndModule.cpp:32
#12 0x00007f2b367cbe12 in VIO::PipelineModule<VIO::BackendInput, VIO::BackendOutput>::spin (this=0x55ba9ca339e0) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/include/kimera-vio/pipeline/PipelineModule.h:204
#13 0x00007f2b36a2a104 in VIO::Pipeline::spinSequential (this=0x55ba9c02dd00) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/pipeline/Pipeline.cpp:357
#14 0x00007f2b36a29dc8 in VIO::Pipeline::spinOnce (this=0x55ba9c02dd00, stereo_imu_sync_packet=std::unique_ptr<class VIO::StereoImuSyncPacket> = {...})
at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/pipeline/Pipeline.cpp:329
#15 0x00007f2b36a4eb95 in std::__invoke_impl<void, void (VIO::Pipeline::*&)(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >), VIO::Pipeline*&, std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> > > (__f=
@0x55ba9c024fc0: (void (VIO::Pipeline::*)(class VIO::Pipeline * const, class std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)) 0x7f2b36a298fa <VIO::Pipeline::spinOnce(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)>, __t=@0x55ba9c024fd0: 0x55ba9c02dd00) at /usr/include/c++/9/bits/invoke.h:73
#16 0x00007f2b36a4bd8a in std::__invoke<void (VIO::Pipeline::*&)(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >), VIO::Pipeline*&, std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> > > (__fn=
@0x55ba9c024fc0: (void (VIO::Pipeline::*)(class VIO::Pipeline * const, class std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)) 0x7f2b36a298fa <VIO::Pipeline::spinOnce(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)>) at /usr/include/c++/9/bits/invoke.h:95
#17 0x00007f2b36a48b44 in std::_Bind<void (VIO::Pipeline::*(VIO::Pipeline*, std::_Placeholder<1>))(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)>::__call<void, std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >&&, 0ul, 1ul>(std::tuple<std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >&&>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55ba9c024fc0, __args=...) at /usr/include/c++/9/functional:400
#18 0x00007f2b36a444d6 in std::_Bind<void (VIO::Pipeline::*(VIO::Pipeline*, std::_Placeholder<1>))(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)>::operator()<std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >, void>(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >&&) (this=0x55ba9c024fc0)
at /usr/include/c++/9/functional:484
#19 0x00007f2b36a3f776 in std::_Function_handler<void (std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >), std::_Bind<void (VIO::Pipeline::*(VIO::Pipeline*, std::_Placeholder<1>))(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)> >::_M_invoke(std::_Any_data const&, std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >&&) (__functor=..., __args#0=...) at /usr/include/c++/9/bits/std_function.h:300
#20 0x00007f2b366fe2d9 in std::function<void (std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >)>::operator()(std::unique_ptr<VIO::StereoImuSyncPacket, std::default_delete<VIO::StereoImuSyncPacket> >) const (this=0x55ba9c026c70, __args#0=std::unique_ptr<class VIO::StereoImuSyncPacket> = {...}) at /usr/include/c++/9/bits/std_function.h:688
#21 0x00007f2b366fa05f in VIO::DataProviderModule::getInputPacket (this=0x55ba9c0268e0) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/dataprovider/DataProviderModule.cpp:155
#22 0x00007f2b3670717f in VIO::PipelineModule<VIO::StereoImuSyncPacket, VIO::StereoImuSyncPacket>::spin (this=0x55ba9c0268e0)
at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/include/kimera-vio/pipeline/PipelineModule.h:198
#23 0x000055ba9ad7bcaa in VIO::Pipeline::spin (this=0x55ba9c02dd00) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/include/kimera-vio/pipeline/Pipeline.h:185
#24 0x000055ba9ad72841 in VIO::VioPipelineFixture_OnlineSequentialSpin_Test::TestBody (this=0x55ba9c01e630) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/tests/testPipeline.cpp:169
#25 0x000055ba9afd7501 in testing::internal::HandleSehExceptionsInMethodIfSupported<testing::Test, void> (object=0x55ba9c01e630, method=&virtual testing::Test::TestBody(),
location=0x55ba9b0ad773 "the test body") at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2433
#26 0x000055ba9afd0a37 in testing::internal::HandleExceptionsInMethodIfSupported<testing::Test, void> (object=0x55ba9c01e630, method=&virtual testing::Test::TestBody(), location=0x55ba9b0ad773 "the test body")
at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2469
#27 0x000055ba9afac734 in testing::Test::Run (this=0x55ba9c01e630) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2508
#28 0x000055ba9afad11f in testing::TestInfo::Run (this=0x55ba9c0031b0) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2684
#29 0x000055ba9afad85a in testing::TestSuite::Run (this=0x55ba9bfade40) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2816
#30 0x000055ba9afb9916 in testing::internal::UnitTestImpl::RunAllTests (this=0x55ba9bff8330) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:5338
#31 0x000055ba9afd888c in testing::internal::HandleSehExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool> (object=0x55ba9bff8330,
method=(bool (testing::internal::UnitTestImpl::*)(class testing::internal::UnitTestImpl * const)) 0x55ba9afb950e <testing::internal::UnitTestImpl::RunAllTests()>,
location=0x55ba9b0ae1b0 "auxiliary test code (environments or event listeners)") at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2433
#32 0x000055ba9afd1b0d in testing::internal::HandleExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool> (object=0x55ba9bff8330,
method=(bool (testing::internal::UnitTestImpl::*)(class testing::internal::UnitTestImpl * const)) 0x55ba9afb950e <testing::internal::UnitTestImpl::RunAllTests()>,
location=0x55ba9b0ae1b0 "auxiliary test code (environments or event listeners)") at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:2469
#33 0x000055ba9afb8156 in testing::UnitTest::Run (this=0x55ba9b1cefa0 <testing::UnitTest::GetInstance()::instance>) at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/src/gtest.cc:4925
#34 0x000055ba9ad719bb in RUN_ALL_TESTS () at /opt/kimera_ws/build/kimera_vio/external/googletest-src/googletest/include/gtest/gtest.h:2473
#35 0x000055ba9ad7170f in main (argc=1, argv=0x7ffedecaa9b8) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/tests/testKimeraVIO.cpp:16
(gdb) frame 7
#7 0x00007f2b367d414d in VIO::VioBackEnd::addStereoMeasurementsToFeatureTracks (this=0x55ba9ca2af80, frame_num=@0x55ba9ca2b4c4: 1, stereo_meas_kf=std::vector of length 525, capacity 525 = {...},
landmarks_kf=0x7ffedeca8e40) at /opt/kimera_ws/src/MIT-SPARK/Kimera-VIO/src/backend/VioBackEnd.cpp:692
692 DCHECK(std::find(landmarks_kf->begin(),
(gdb) list
687
688 // Thinner structure that only keeps landmarkIds.
689 // These landmark ids are only the ones visible in current keyframe,
690 // with a valid track...
691 // CHECK that we do not have repeated lmk ids!
692 DCHECK(std::find(landmarks_kf->begin(),
693 landmarks_kf->end(),
694 lmk_id_in_kf_i) == landmarks_kf->end());
695 (*landmarks_kf)[i] = lmk_id_in_kf_i;
https://github.com/MIT-SPARK/Kimera-VIO/blob/5f30001208002724f35676ddffc52a3d28efa534/src/backend/VioBackEnd.cpp#L688-L695