Hydra
Hydra copied to clipboard
[QUESTION] About registration solvers
Hi. Thank you for releasing a great work :) I'm now enjoying your work. Actually, I have some questions about the loop closure detection and registration solvers.
-
I found that there are two different solvers for the registration:
DsgAgentSolver
andDsgTeaserSolver
. I guess that both solvers are used to get theregistration_result
when the functionregisterAndVerfiy()
is running. Based on the released code, I could find howDsgTeaserSolver::solve()
function works. (As stated in the paper, it usesteaser::RobustRegistrationSolver
to get the valid result and correspondences inregisterDsgLayer()
function.) However, I wonder howDsgAgentSolver::solve()
function works because I couldn't find the corresponding service client function. Does the service response the registration of visual features based on the standard RANSAC-based geometric verification, as you stated in the paper? -
Also, I think that the registration service is related to kimera_vio_ros since the service
frame_registration
is remapped to/kimera_vio_ros/kimera_vio_ros_node/register_lcd_frames
indsg_builder.launch
file. ( I guess this is the unreleased code of kimera-vio what you stated in here ). If you know whether the corresponding codes will be released in kimera_vio_ros or not, please let me know.
- Enable scene graph loop closures: This will require no development on your part, but is the least tested of the options (we haven't had much of a reason to run the scene graph loop closure pipeline without BoW descriptors). As long as you have the pose_graph_publisher_node operating (which use_gt_frame:=true will enable), then all you have to do is set enable_dsg_lcd:=true and internal loop closure detection and registration will be enabled. You may also want to set min_glog_level:=0 and verbosity:=2 to see the current status for the internal loop closures.
- Finally, I have understood scene graph loop closures can be enabled without additional development based on your mention in here as above. However, if
lcd_queue_
is empty, I guess that loop closure detection would not be performed because it stops at the line 158 in here. ( I thinklcd_queue_
will be always empty if bow vectors are not received. ) I wonder is it possible to enable scene graph loop closure without bow vectors.
Thank you for releasing your great work once more!
Thank you for your interest!
Does the service response the registration of visual features based on the standard RANSAC-based geometric verification, as you stated in the paper?
Yes. The service definition passes match_id
and query_id
to this section of the Kimera-VIO code (approximately, though we separate out the geometric verification code into another function and call it in a thread-safe manner in response to the service request)
If you know whether the corresponding codes will be released in kimera_vio_ros or not, please let me know.
Yes, it will get released, but I still don't have a definitive timeline. There is steady progress being made to the next Kimera-VIO release (where the changes needed to work with Hydra will be included), and hopefully we will have a more solid timeline for the next Kimera-VIO release soon.
However, if
lcd_queue_
is empty, I guess that loop closure detection would not be performed because it stops at the line 158 in here. ( I thinklcd_queue_
will be always empty if bow vectors are not received. )
Good question, this is a little tricky in the code. lcd_queue_
is actually a queue of added agent nodes (i.e. poses representing keyframes). As long as some external process is publishing a pose graph that Hydra subscribes to, this queue will be populated. The LCD module pops agent nodes from the queue periodically and performs loop closure detection with them regardless of whether or not they have an associated DBoW2 descriptor populated in their attributes here. We assign the DBoW2 descriptors here to their associated agent nodes, but we only loosely couple assigning them and performing loop closure detection. We have a time delay before popping the next "query" node (roughly three seconds or so) where we hope that a) the DBoW2 descriptor for that node is received and assigned and b) the scene graph around the query node has a chance to get fully populated (we observed qualitatively that this helped the matching performance of the scene graph descriptors).
I wonder is it possible to enable scene graph loop closure without bow vectors.
As mentioned earlier, it is technically possible. I've tried it before myself, but not recently. If you end up trying it and it doesn't end up working, please let me know! As we haven't really been regularly testing that aspect of the pipeline, i.e. running with just scene-graph loop closures, there might be minor code issues (but I hope not :smile:)
Thank you for your very kind reply. Your descriptions help me a lot in understanding your great work. I will try what you have mentioned. Thank you once more :+1:
I'm going to close this issue. Feel free to re-open if you have further questions!