Closed j1and1 closed 4 months ago
I see that those are sub-maps that are shown in the screenshot, but it still doesn't localize to the correct point. If I give it a start position then it can compensate for the small amount of rotation difference between the actual position and the hint.
So my problem is that it needs a hint with somewhat precise rotation... I would like to avoid passing precise rotation when I'm running in localization mode
Hello @j1and1 , I'm not sure my solution whether is the best method. But I could use the old map and do re-localization. I will not use pure_localization_trimmer this parameter. Below is lua about parameters of pure localization:
TRAJECTORY_BUILDER.pure_localization = true
--TRAJECTORY_BUILDER.pure_localization_trimmer = {max_submaps_to_keep = 3,}
-- TEST
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1
--TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.05
--TRAJECTORY_BUILDER_2D.submaps.num_range_data = 45
MAP_BUILDER.num_background_threads = 4
-- TEST
POSE_GRAPH.constraint_builder.min_score = 0.65
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.6
POSE_GRAPH.global_sampling_ratio = 0.9
POSE_GRAPH.constraint_builder.sampling_ratio = 0.5
POSE_GRAPH.optimize_every_n_nodes = 5
Be free to discuss.
I forgot that I opened this issue. I resolved the issue by setting the POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher.angular_search_window
to math.rad(180.)
since we didn't pass the angle with the initial position from UI and this worked. The cartographer could compensate rotation based on the map that was created before.
I have created a 2D map with rosbags and ros2/cartographer_ros and saved the map as
*.pbstream
.I am now trying to test the localization part of the cartographer by offsetting the playback start of the bag playback. I have modified config according to backpack_2d_localization.lua sample provided in the ros2 cartographer repo. However, it still is updating the map and not trying to localize to the correct spot in the map.
The questions that rose in my mind are:
TRAJECTORY_BUILDER.pure_localization
is deprecated?I run the cartographer node with following args:
The config I have currently looks like so:
The issue looks like this: