HKUST-Aerial-Robotics / VINS-Mono

A Robust and Versatile Monocular Visual-Inertial State Estimator
GNU General Public License v3.0
4.96k stars 2.09k forks source link

question about“ optimize_posegraph_buf” #52

Closed dymymao closed 7 years ago

dymymao commented 7 years ago

in function void process() estimator_node.cpp image use estimator.Headers[0] to choose the keyframe and push it into the optimize_posegraph_buf for 4dof pose graph, and the Headers[0] is after the function “void Estimator::slideWindow()” ,so Headers[0] is no longer the margin frame but the Headers[1] before slidewindow but in paper《Technical Report:VINS-Mono.....》V.LOOP CLOSURE->D.Adding Keyframe into Pose Graph:"When a keyframe is marginalized out from sliding window,it will be added into pose graph." so how can I understand it, and the same question in“void Estimator::slideWindow()” where use Headers[0] to delete the margin frame in “all_image_frame” after swap the Headers[0] and Headers[1]. image

Thanks a lot for help.

dymymao commented 7 years ago

sorry for another question also in function void process() estimator_node.cpp image after getting the pointer of cur_kf ,why not do "cur_kf->updateOriginPose()”for the newest optimiztion value before adding into 4dof pose graph. I think it will result in the confusion in the calculation of 4dof pose residuals(void KeyFrameDatabase::optimize4DoFLoopPoseGraph): sequential edge use Origin pose which is initial in the keyframe's construction, and loop edge use value “getLoopRelativeT()” which is calculate when the keyframe is margin out

image Do I have an exact understanding? Thanks for help!

qintonguav commented 7 years ago

Thanks for your questions. You understand the code at a deep level.

  1. In the code, the keyframe is added to the pose graph a little earlier before it is marginalized. That's because of the easy programming purpose. We first add it to keyframe database, then marginalize it out the sliding window. Basically, little difference.
  2. Admitly, what you say is all right. However, if we do relocalization (add the loop constraints in the sliding window), the loop information will influence the pose. The pose is not purely comes from VIO, we can't update the origin pose anymore.
dymymao commented 7 years ago

@qintony
Thank you very much for your answer,it helps me l lot. I still have a little confusion about the question 2. We use Origin pose initialized in Keyframe construction for the calculation of 4dof pose graph residuals to avoid the loop information's influence to pose[to get the pure vio pose]: Vector3d vio_T_w_i = estimator.Ps[WINDOW_SIZE - 2]; however, on my mind, the estimator.Ps[WINDOW_SIZE - 2] have gone throuth the nonlinear optimization twice, if there are loop constraints in the slidewindow , haven't the optimization which include loop information influenced the pose of the keyframe added into the database?

dymymao commented 7 years ago

@qintony for latter half of question 1 in“void Estimator::slideWindow()” where use Headers[0] to delete the margin frame in “all_image_frame” after swap the Headers. So how can we AddResidualBlock of imu model and visual reprojection model in the next optimization loop for the keyframe(Ps[0]) which is still in slidewindow but looks like marginalized out. image Thanks!

qintonguav commented 7 years ago

Question 2. what you said is right. I am trying to design a new structure to avoid this.

Question 1. I don't fully understand your question. "all_image_frame" is just used in the initialization part, which contains a lot of non-keyframes. After initialization, you can ignore it.

dymymao commented 7 years ago

@qintony sorry,it's my mistake in the undestanding of question 1 . The deleted it_0->second.pre_integration will not be used in the next nonlinear optimiztion loop. Thanks for your great work.