hdl_graph_slam icon indicating copy to clipboard operation
hdl_graph_slam copied to clipboard

g2o optimize all the time even there is no other constrained edge

Open FishInWave opened this issue 3 years ago • 5 comments

hi, @koide3 I disable the floor detection, and use a rosbag without any loop closure to run hdl_graph_slam. The purpose of my experiment is to figure out what will g2o do while there is no other constrained edge except odom from the scan_matching_nodelet. The results show like follows:

nodes: 144   edges: 143
iterations: 512 / 512
chi2: (before)24.9365 -> (after)3.64978e-29
time: 0.436[sec]
[ INFO] [1607912580.610194682, 1605164128.959502665]: num??? 80 iterations: 33748 time: 12.2224
nodes: 146   edges: 145
iterations: 512 / 512
chi2: (before)47.0893 -> (after)3.51605e-29
time: 0.414[sec]
[ INFO] [1607912582.055616888, 1605164130.396942136]: num??? 81 iterations: 34260 time: 12.6369
nodes: 148   edges: 147
iterations: 512 / 512
chi2: (before)3.51605e-29 -> (after)5.64421e-29
time: 0.485[sec]
[ INFO] [1607912583.642410340, 1605164131.988057454]: num??? 82 iterations: 34772 time: 13.1221
nodes: 150   edges: 149
iterations: 35 / 512
chi2: (before)7.54993e-07 -> (after)5.54168e-29
time: 0.024[sec]
[ INFO] [1607912584.693144666, 1605164133.040456984]: num??? 83 iterations: 34807 time: 13.1465
nodes: 151   edges: 150
iterations: 512 / 512
chi2: (before)27.6246 -> (after)7.58819e-29
time: 0.481[sec]
[ INFO] [1607912586.619230363, 1605164134.965360703]: num??? 84 iterations: 35319 time: 13.6275

where NODELET_INFO is my extra code to accumlate the time that g2o have spent. I also dump the inside data:

stamp 1605164120 846135000
estimate
  0.161431   0.986767 -0.0151997   -21.7165
 -0.986837   0.161254 -0.0122047    15.7058
-0.0095922  0.0169699    0.99981 -0.0959998
         0          0          0          1
odom
  0.161431   0.986767 -0.0151997   -21.7164
 -0.986837   0.161254 -0.0122047    15.7058
-0.0095922  0.0169699    0.99981 -0.0959997
         0          0          0          1
accum_distance 141.422
id 135

In theory, if there are only inter frame constraint (obtained from odom), it's no need for g2o to optimize anymore as the origin pose is the best solution.However, in practice, g2o runs out of iterations(512/512) to get an estimation value which is equal to the origin pose. Did I get something wrong? Any suggestions or discussions are appreciated! Ps: g2o not always runs 512 iterations —— my sum of iterations is 39138 while the number of run time is 98, which means the average number of iterations is 399.

FishInWave avatar Dec 14 '20 02:12 FishInWave

I guess you set g2o_solver_type to gn_var_cholmod, right? GN-based solvers in g2o doesn't check the convergence of the optimization while LM-based ones terminate when some convergence criteria is satisfied. Probably, by changing the optimizer to LM-based one, the optimization stops in a few steps.

koide3 avatar Dec 14 '20 04:12 koide3

hdl_indoor_2_local_new.TXT I check my launch file and upload a copy here.Its solver type is lm_var_cholmod:

    <!-- typical solvers: gn_var, gn_fix6_3, gn_var_cholmod, lm_var, lm_fix6_3, lm_var_cholmod, ... -->
    <param name="g2o_solver_type" value="lm_var_cholmod" />
    <param name="g2o_solver_num_iterations" value="512" />

Maybe not this reason.

FishInWave avatar Dec 14 '20 05:12 FishInWave

Hmm, it's strange. I reproduced the problem on my PC. I tried to save the pose graph and optimize it on g2o_viewer, and it also didn't converge until ran out of iterations. I'm not sure, but I guess g2o changed something relating to the convergence criteria. I'll take a look at recent changes on g2o to find the cause of the problem.

koide3 avatar Dec 15 '20 11:12 koide3

Hmm, it's strange. I reproduced the problem on my PC. I tried to save the pose graph and optimize it on g2o_viewer, and it also didn't converge until ran out of iterations. I'm not sure, but I guess g2o changed something relating to the convergence criteria. I'll take a look at recent changes on g2o to find the cause of the problem.

I am having the same issue as well, have you figured out why?

zhimouliang avatar Jan 12 '21 07:01 zhimouliang

I found that this is caused by the graph structure. It seems lm_var optimizer causes some oscillation when a graph that has a structure like v1(fixed) -> v0 -> v2 -> v3 .... The oscillation disappeared when I swapped the vertex IDs such that it becomes v0(fixed) -> v1 -> v2 .... I'm not really sure why this happens, anyways I'll fix it later.

koide3 avatar Jan 20 '21 11:01 koide3