Closed dymymao closed 7 years ago
sorry for another question also in function void process() estimator_node.cpp 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
Do I have an exact understanding? Thanks for help!
Thanks for your questions. You understand the code at a deep level.
@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?
@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. Thanks!
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.
@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.
in function void process() estimator_node.cpp 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].
Thanks a lot for help.