ccm_slam
ccm_slam copied to clipboard
'roslaunch ccmslam Server.launch' error
when i run 'roslaunch ccmslam Server.launch' , the error is:
[ccmslam/ccmslamServerNode-6] process has died [pid 24549, exit code -11, cmd /home/swj/ccmslam_ws/devel/lib/ccmslam/ccmslamServerNode /home/swj/ccmslam_ws/src/ccm_slam/cslam/conf/ORBvoc.txt __name:=ccmslamServerNode __log:=/home/swj/.ros/log/ca1aa532-2f4d-11ed-be68-38f3ab349edb/ccmslam-ccmslamServerNode-6.log]. log file: /home/swj/.ros/log/ca1aa532-2f4d-11ed-be68-38f3ab349edb/ccmslam-ccmslamServerNode-6*.log
Could you identify and additional information in the log file what might happen? Maybe a wrong path?
i have the same problem.
Could you identify and additional information in the log file what might happen? Maybe a wrong path?
the log file is empty.i don't know why.
Could be that the ROS environment is not correctly sourced. Is there any additional terminal output? Do you see the same error when launching the Client launch files? What happens when you try to launch the Server directly via rosrun
, not using the launch file?
Exit code -11 means a SIGSEGV, so there seems to be a segmentaton fault. Would be good to run the Server node with GBD to find out whats happening.
Generally, it's hard to provide to root-cause the error from just this error message, would be very helpful to have some additional information to provide more feedback.
I've met the same problem.And the same error happended when I try to launch the ClinetLaunch files.I spent a long time to figure out the bug.I insert some cout function to help me debug.
When I debug in the Vscode, the debug console output:
0x00007ffff77bc897 in cslam::ClientHandler::InitializeCC() () from /home/bariko/ccm_ws/devel/lib/libccmslam_lib.so
My ClientHandler::InitializeCC() function:
`
void ClientHandler::InitializeCC()
#endif
{
std::stringstream* ss;
cout<<"initialized cc "<<endl;
cout<<mClientId<<endl<<mSysState<<endl<<mpUID<<endl<<shared_from_this()<<endl;
mpCC.reset(new CentralControl(mNh,mNhPrivate,mClientId,mSysState,shared_from_this(),mpUID));
cout<<"initialized cc "<<endl;
if(mSysState == eSystemState::CLIENT)
{
ss = new stringstream;
*ss << "FrameId";
mNhPrivate.param(ss->str(),mpCC->mNativeOdomFrame,std::string("nospec"));
}
else if(mSysState == eSystemState::SERVER)
{
ss = new stringstream;
*ss << "FrameId" << mClientId;
mNhPrivate.param(ss->str(),mpCC->mNativeOdomFrame,std::string("nospec"));
}
else
{
cout << "\033[1;31m!!!!! ERROR !!!!!\033[0m ClientHandler::InitializeThreads(): invalid systems state: " << mpCC->mSysState << endl;
throw infrastructure_ex();
}
if(mpCC->mNativeOdomFrame=="nospec")
{
ROS_ERROR_STREAM("In \" ServerCommunicator::ServerCommunicator(...)\": bad parameters");
throw estd::infrastructure_ex();
}
{
if(mSysState==CLIENT)
{
cv::FileStorage fSettings(mstrCamFile, cv::FileStorage::READ);
float c0t00 = fSettings["Cam0.T00"];
float c0t01 = fSettings["Cam0.T01"];
float c0t02 = fSettings["Cam0.T02"];
float c0t03 = fSettings["Cam0.T03"];
float c0t10 = fSettings["Cam0.T10"];
float c0t11 = fSettings["Cam0.T11"];
float c0t12 = fSettings["Cam0.T12"];
float c0t13 = fSettings["Cam0.T13"];
float c0t20 = fSettings["Cam0.T20"];
float c0t21 = fSettings["Cam0.T21"];
float c0t22 = fSettings["Cam0.T22"];
float c0t23 = fSettings["Cam0.T23"];
float c0t30 = fSettings["Cam0.T30"];
float c0t31 = fSettings["Cam0.T31"];
float c0t32 = fSettings["Cam0.T32"];
float c0t33 = fSettings["Cam0.T33"];
mpCC->mT_SC << c0t00,c0t01,c0t02,c0t03,c0t10,c0t11,c0t12,c0t13,c0t20,c0t21,c0t22,c0t23,c0t30,c0t31,c0t32,c0t33;
}
else
{
//no mstrCamFile on Server...
}
}
mpMap->mOdomFrame = mpCC->mNativeOdomFrame;
mpMap->AddCCPtr(mpCC);
#ifdef LOGGING
mpCC->mpLogger = pLogger;
#endif
delete ss;
}
Then run the server.launch ,the out put:
++++++++++ System ++++++++++
miLockSleep: 1
++++++++++ Stats ++++++++++ mbWriteKFsToFile: 1 msOutputDir: /home/bariko/ccm_ws/src/ccm_slam/cslam/output/ miTrajectoryFormat: 1
++++++++++ Timings ++++++++++ miLockSleep: 1000 ----- Client ----- miRosRate: 1000 miViewerRate: 1000 miMappingRate: 5000 miCommRate: 10000 ----- Server ----- miRosRate: 1000 miViewerRate: 1000 miMappingRate: 5000 miCommRate: 10000 miPlaceRecRateRate: 5000
++++++++++ Tracking ++++++++++ miInitKFs: 5 miMinFrames: 0 miMaxFrames: 20 miMatchesInliersThres: 15 mfThRefRatio: 0.9 miTrackWithRefKfInlierThresSearch: 15 miTrackWithRefKfInlierThresOpt: 10 miTrackWithMotionModelInlierThresSearch: 20 miTrackWithMotionModelInlierThresOpt: 10 miTrackLocalMapInlierThres: 30
++++++++++ Mapping ++++++++++ mfRedundancyThres: 0.98 miKfLimitClient: 50 miKfBufferClient: 20 miNumRecentKFs: 20
++++++++++ Comm ++++++++++ ----- Client ----- mfPubFreq: 5 mfPubPeriodicTime: 0.2 miPubMapBufferSize: 100 miSubMapBufferSize: 100 miKfItBound: 30 miMpItBound: 3000 miKfPubMax: 40 miMpPubMax: 2500 ----- Server ----- mfPubFreq: 1 mfPubPeriodicTime: 1 miKfLimitToClient: 0 miPubMapBufferSize: 1000 miSubMapBufferSize: 1000 miKfItBound: 400 miMpItBound: 12000
++++++++++ PlaceRec ++++++++++ miNewLoopThres: 20 miStartMapMatchingAfterKf: 30 miCovisibilityConsistencyTh: 3
++++++++++ Vis ++++++++++ mbVisMode: 1 mbShowCovGraph: 1 mbShowMPs: 1 mbShowTraj: 1 mbShowKFs: 0 miCovGraphMinFeats: 100 mfScaleFactor: 20 mfTrajMarkerSize: 0.25 mfCovGraphMarkerSize: 0.02 mfLoopMarkerSize: 0.2 mfMarkerSphereDiameter: 0.05 mfCamSize: 0.02 mfCamLineSize: 0.01
++++++++++ Opt ++++++++++ mSolverIterations: 5 mMatchesThres: 20 mInliersThres: 20 mTotalMatchesThres: 40 mProbability: 0.99 mMinInliers: 6 mMaxIterations: 300 mGBAIterations: 20 miEssGraphMinFeats: 100
++++++++++ Extractor ++++++++++ miNumFeatures: 1000 mfScaleFactor: 1.2 miNumLevels: 8 miIniThFAST: 20 miNumThFAST: 7
++++++++++ Colors ++++++++++ R0: 1 G0: 1 B0: 1 R1: 0 G1: 0.8 B1: 0 R2: 0 G2: 0 B2: 1 R3: 0.6 G3: 0 B3: 0.6 Rcov: 0.6 Gcov: 0.6 Bcov: 0.6
Loading ORB Vocabulary. This could take a while... Vocabulary loaded!
+++++ KeyFrame Database Initialized +++++
Map 0 rand seed: 1699255240
+++++ Map 0 Initialized +++++
Map 1 rand seed: 1699255240
+++++ Map 1 Initialized +++++
Map 2 rand seed: 1699255240
+++++ Map 2 Initialized +++++
Map 3 rand seed: 1699255240
+++++ Map 3 Initialized +++++
Create CC!
Cleaning file /home/bariko/ccm_ws/src/ccm_slam/cslam/output/KF_GBA_0.csv
Cleaning file /home/bariko/ccm_ws/src/ccm_slam/cslam/output/KF_GBA_1.csv
Cleaning file /home/bariko/ccm_ws/src/ccm_slam/cslam/output/KF_GBA_2.csv
Cleaning file /home/bariko/ccm_ws/src/ccm_slam/cslam/output/KF_GBA_3.csv
here 1 !
initialized cc
0
1
0x555555add1b0
0x5555636bc1c0
First,I guess the member variable may cause the segmentation fault and tried to out put them to check out.But it works well.I also add the cout in the constructor of CentralControl:
CentralControl(ros::NodeHandle Nh, ros::NodeHandle NhPrivate,
size_t ClientId,
eSystemState SysState,
chptr pCH = nullptr,
uidptr pUID = nullptr,
g2o::Sim3 g2oS_wc_wm = g2o::Sim3()
)
: mNh(Nh), mNhPrivate(NhPrivate),
mClientId(ClientId),
mpCH(pCH),
mpUID(pUID),
mbOptActive(false),
mSysState(SysState),
mbCommLock(false),mbMappingLock(false),mbPlaceRecLock(false),mbTrackingLock(false),
mg2oS_wcurmap_wclientmap(g2oS_wc_wm),
mbGotMerged(false),mbOptimized(false)
{
//...
cout<<"Create CC!"<<endl;
}
Now the problem is :why the
mpCC.reset(new CentralControl(mNh,mNhPrivate,mClientId,mSysState,shared_from_this(),mpUID));` failed and meet a segmentation fault,I still don't konw.Hope for your help! Thanks!
Judging from above feedback, this could be a race condition. I'll leave this open to see whether other user see this. In general, this could be a race condition, and I'd suggest to add a usleep(10000);
before mpCC.reset(...)
to see whether this resolves the problem.