wh200720041 / iscloam

Intensity Scan Context based full SLAM implementation for autonomous driving. ICRA 2020
Other
578 stars 134 forks source link

loop closure index #8

Closed narutojxl closed 4 years ago

narutojxl commented 4 years ago

Hi doctor wang, When geometryConsistencyVerification() in line 68 of iscOptimizationClass.cpp, return true, there is a true loop between history matched frame id and curr id. Why the code is this ? Thanks for your help !

graph.push_back( gtsam::BetweenFactor(gtsam::Symbol('x', matched_frame_id[i]+1), //TODO:why not is matched_frame_id[i] gtsam::Symbol('x', pointcloud_edge_arr.size()), //TODO: why not is pointcloud_edge_arr.size()-1 loop_temp, loopModel));

wh200720041 commented 4 years ago

Hi @narutojxl

I think according to the gtsam tutorial, the first pose_id is 1 instead of 0,

You can find the example from here. https://github.com/dongjing3309/gtsam-examples/blob/master/cpp/examples/Pose2SLAMExample.cpp

However, the array in cpp starts with 0, so here we need to add 1 to match the gtsam symbol.

Han

narutojxl commented 4 years ago

Hi doctor wang, Thanks for your help, i didn't notice the fisrt node is marked as graph.push_back(gtsam::PriorFactor<gtsam::Pose3>(gtsam::Symbol('x', 1), pose_optimized_arr.front(), priorModel)); line 41 in code, thanks for your advice! BTW, if we mark the origin node is gtsam::Symbol('x', 0), then we no need plus 1, right?

wh200720041 commented 4 years ago

Hi @narutojxl

Yes I think so, but if you want to change this, you may have to change the corresponding ids in other function as well. However, it is not necessary to change this because changing ids does not affect the performance

narutojxl commented 4 years ago

Yes, i agree with you! Thanks doctor, my problem is solved.