Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[QUESTION] Configuration of DSG Loop Closure Detection with the new release of Hydra #52

Open
claragb7 opened this issue Jun 27, 2024 · 3 comments
Assignees
Labels
question Further information is requested

Comments

@claragb7
Copy link

claragb7 commented Jun 27, 2024

Hi! First of all, thank you for sharing this great framework. We started using hydra a while ago and we are now moving our changes to the new release of hydra. We are interested in running hydra only with Teaser++ loop closure registration, we believe that this can be achieved by setting the flag "enable_agent_registration" to false. However, when setting it to false in the new release of hydra for the rosbag "uhumans2_office_s1_00h.bag" (office environment of uHumans2), Teaser++ does not seem to find any valid loop closure (loop_closures.csv file is empty). Is there some other configuration that we need to change to make it work with Teaser++?

Additional information that can help understand the problem:

  1. We are running hydra with kimera using these two commands:

roslaunch kimera_vio_ros kimera_vio_ros_uhumans2.launch online:=true viz_type:=1 use_lcd:=true lcd_no_detection:=true

roslaunch hydra_ros uhumans2.launch use_gt_frame:=false enable_dsg_lcd:=true start_visualizer:=false

  1. When running the new release of hydra with "enable_agent_registration = true", the output file loop_closures.csv contains approximately 90-100 entries. All of them finishing with type=1 and level=0 (which, if we understood correctly refer to the agent registration)

  2. Debugging the execution of Teaser++ registration, it can reach registerDsgLayerSemantic function in registration.h approximately 2030 times: of those, approximately 1800 times it fails due to a low number of inliers (the most common output is: "Not enough inliers for registration at layer 2: 2 / 5"); and 200 times it fails because the result is not valid (being the result the output from the solve function: teaser::RegistrationSolution result = solver.solve(src_points, dest_points); if (!result.valid) {}).

We appreciate any help! Let us know if some more insights or results are needed:)

UPDATE: We have observed this behavior (empty loop_closures.csv file) with the default configuration for inlier_selection_mode (PMC_EXACT) and with PMC_HEU and KCORE_HEU. Setting that parameter to NONE provides loop closures.

@claragb7 claragb7 added the question Further information is requested label Jun 27, 2024
@claragb7 claragb7 changed the title [QUESTION] Configuration of DSG Loop Closure Detection with the updated Hydra [QUESTION] Configuration of DSG Loop Closure Detection with the new release of Hydra Jun 27, 2024
@nathanhhughes
Copy link
Collaborator

Hi, thanks for your interest in our work! The basic behavior you're outlining all checks out (i.e., that you're seeing about ~100 detected agent loop closures for the office scene, that enable_agent_registration:=false turns off agent loop closures, and turning off teaser outlier rejection gives you scene graph loop closures). I admittedly haven't run with the scene graph-based loop closures recently, so I'm not entirely sure why there aren't any valid loop closures being detected (from what I remember from running experiments, there should be around 200 or so valid object-based loop closures for the office).

I will look into this on my side, but here are a couple follow up items:

  • Have you changed any of Hydra's loop closure detection parameters beyond the teaser inlier selection mode?
  • Can you turn up the logging verbosity (verbosity:=5 in combination with glog_to_file:=true and glog_dir:=some/output/path would make a convenient set of logs to upload to the issue)?
  • Are you seeing any other warnings or errors when running? The LCD code is admittedly a little brittle, and so there's a chance that something else I'm forgetting is configured incorrectly and discarding potentially valid loop closures prematurely

@claragb7
Copy link
Author

Hi Nathan, thank you very much for your answer! Regarding the follow up items:

  1. We have tested changing the parameters to match the ones of the previous release of hydra but the result was the same. Then, dsg_lcd_config.yaml looked like this:

lcd_visualizer_ns: /dsg/lcd_visualizer
lcd_agent_horizon_s: 3.5
descriptor_creation_horizon_m: 15.0
lcd:
enable_agent_registration: true #false
place_histogram_config: {min: 0.5, max: 2.5, bins: 30}
num_semantic_classes: 20
object_extraction: {fixed_radius: true, max_radius_m: 13.0}
places_extraction: {fixed_radius: true, max_radius_m: 13.0}
registration_configs:
objects:
min_correspondences: 5
min_inliers: 5
log_registration_problem: false
registration_output_path: ''
recreate_subgraph: false
search_configs:
agent:
min_time_separation_s: 100.0 #CG: original 25.0
min_score: 0.01 #CG: original 0.040
min_registration_score: 0.01 # this gets overriden
max_registration_matches: 1 #CG: orignal 2
min_score_ratio: 1.0 #CG: original 0.95
min_match_separation_m: 0.0
type: L1
objects:
min_time_separation_s: 100.0 #CG: original 25.0
min_score: 0.3
min_registration_score: 0.80 #CG: original 0.90
max_registration_matches: 5 #CG: original 2
min_score_ratio: 0.7 #CG: original 0.9
min_match_separation_m: 5.0
type: L1
places:
min_time_separation_s: 100.0 #CG: original 25.0
min_score: 0.5 #CG: original 0.2
min_registration_score: 1.5
max_registration_matches: 5
min_score_ratio: 0.7
min_match_separation_m: 5.0
type: L1
teaser:
estimate_scaling: false
noise_bound: 0.100
cbar2: 1.0
rotation_gnc_factor: 1.4
rotation_max_iterations: 100
rotation_cost_threshold: 1.0e-6
kcore_heuristic_threshold: 0.5
inlier_selection_mode: PMC_EXACT #CG: original PMC_EXACT; other options: PMC_HEU, KCORE_HEU and NONE
max_clique_time_limit: 3600

  1. Regarding the logs, you can find them attached.
    hydra_ros_node_ERROR.txt
    hydra_ros_node_INFO.txt
    hydra_ros_node_log_ERROR.txt
    hydra_ros_node_log_INFO.txt
    hydra_ros_node_log_WARNING.txt
    hydra_ros_node_WARNING.txt

  2. We did get some (it depends between runs but can be around 100-150 times) tf warnings during the execution referring to extrapolation into the future (i.e., Failed to get tf from base_link_kimera to world @ 224054900000 [ns]. Reason: Lookup would require extrapolation 0.100000000s into the future. Requested time 224.054900000 but the latest data is at time 223.954900000, when looking up transform from frame [base_link_kimera] to frame [world]. canTransform returned after 2.1407e-05 timeout was 0). The time of the extrapolation varies between 0.25s and 0.05s. We forgot to mention that when running the rosbag we are using the --clock flag: rosbag play bags/uHumans2_office_s1_00h.bag --clock

@claragb7 claragb7 reopened this Jul 16, 2024
@claragb7
Copy link
Author

(Sorry, I closed the issue by accident as posting the comment)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Further information is requested
Projects
None yet
Development

No branches or pull requests

2 participants