Skip to content

Commit

Permalink
added map
Browse files Browse the repository at this point in the history
  • Loading branch information
fayyazpocker committed Jul 9, 2019
1 parent 0e6a234 commit c047762
Show file tree
Hide file tree
Showing 9 changed files with 395 additions and 5 deletions.
145 changes: 145 additions & 0 deletions configuration_files/cartographer.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,145 @@
include "map_builder.lua"
include "trajectory_builder.lua"

POSE_GRAPH = {
optimize_every_n_nodes = 90,
constraint_builder = {
sampling_ratio = 0.3,
max_constraint_distance = 15.,
min_score = 0.55,
global_localization_min_score = 0.6,
loop_closure_translation_weight = 1.1e4,
loop_closure_rotation_weight = 1e5,
log_matches = true,
fast_correlative_scan_matcher = {
linear_search_window = 7.,
angular_search_window = math.rad(30.),
branch_and_bound_depth = 7,
},
ceres_scan_matcher = {
occupied_space_weight = 20.,
translation_weight = 10.,
rotation_weight = 1.,
ceres_solver_options = {
use_nonmonotonic_steps = true,
max_num_iterations = 10,
num_threads = 1,
},
},
fast_correlative_scan_matcher_3d = {
branch_and_bound_depth = 8,
full_resolution_depth = 3,
min_rotational_score = 0.77,
min_low_resolution_score = 0.55,
linear_xy_search_window = 5.,
linear_z_search_window = 1.,
angular_search_window = math.rad(15.),
},
ceres_scan_matcher_3d = {
occupied_space_weight_0 = 5.,
occupied_space_weight_1 = 30.,
translation_weight = 10.,
rotation_weight = 1.,
only_optimize_yaw = false,
ceres_solver_options = {
use_nonmonotonic_steps = false,
max_num_iterations = 10,
num_threads = 1,
},
},
},
matcher_translation_weight = 5e2,
matcher_rotation_weight = 1.6e3,
optimization_problem = {
huber_scale = 1e1,
acceleration_weight = 1e3,
rotation_weight = 3e5,
local_slam_pose_translation_weight = 1e5,
local_slam_pose_rotation_weight = 1e5,
odometry_translation_weight = 1e5,
odometry_rotation_weight = 1e5,
fixed_frame_pose_translation_weight = 1e1,
fixed_frame_pose_rotation_weight = 1e2,
log_solver_summary = false,
ceres_solver_options = {
use_nonmonotonic_steps = false,
max_num_iterations = 50,
num_threads = 7,
},
},
max_num_final_iterations = 200,
global_sampling_ratio = 0.003,
log_residual_histograms = true,
global_constraint_search_after_n_seconds = 10.,
}

options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_link",
published_frame = "odom",
odom_frame = "odom",
provide_odom_frame = false,
-- publish_frame_projected_to_2d = false,
use_odometry = true,
use_laser_scan = true,
use_multi_echo_laser_scan = false,
-- use_nav_sat = false,
-- use_landmarks = false,
-- num_laser_scans = 1,
-- num_multi_echo_laser_scans = 0,
-- num_subdivisions_per_laser_scan = 1,
num_point_clouds = 0,
lookup_transform_timeout_sec = 1.,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
-- rangefinder_sampling_ratio = 1.,
-- odometry_sampling_ratio = 0.5,
-- fixed_frame_pose_sampling_ratio = 0.5,
-- imu_sampling_ratio = 1.,
-- landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
--TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
--TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
--TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 2e2
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 4e2

POSE_GRAPH.optimization_problem.huber_scale = 1e2
-- SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e2

-----------------TUNE THESE PARAMETERS FOR LOW LATENCY-------------------------------

------------Global SLAM------------
POSE_GRAPH.optimize_every_n_nodes = 1 -- Decrease
MAP_BUILDER.num_background_threads = 4 -- Increase up to number of cores
POSE_GRAPH.global_sampling_ratio = 0.00001 -- Decrease
POSE_GRAPH.constraint_builder.sampling_ratio = 0.0001 -- Decrease
POSE_GRAPH.constraint_builder.min_score = 0.75 -- Increase
POSE_GRAPH.global_constraint_search_after_n_seconds = 30 -- Increase
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.ceres_solver_options.max_num_iterations = 5 -- Decrease

---------Global/Local SLAM---------
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.min_num_points = 100 -- Decrease
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_range = 10. -- Decrease
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_length = 1.0 -- Increase
-- TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.min_num_points = 50 -- Decrease
-- TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.max_range = 10. -- Decrease
-- TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.max_length = 1.8 -- Increase
TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.05 -- Increase
TRAJECTORY_BUILDER_2D.submaps.resolution=0.05 -- Increase
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 100 -- Decrease
TRAJECTORY_BUILDER_2D.max_range = 10. -- Decrease

-------------------------------------------------------------------------------------

return options
10 changes: 6 additions & 4 deletions launch/cartographer_mapping.launch
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
<!-- Debugging parameters -->
<arg name="rviz_flag" default="true" />
<arg name="joint_state_publisher_flag" default="true" />
<arg name="cartographer_enable" default="true"/>



<param name="base_link" value="base_link"/>
Expand All @@ -35,13 +37,13 @@

<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find pocker_bot_vrep_description)/configuration_files
-configuration_basename new_pocker_cartographer.lua"
output="screen">
-configuration_directory $(find cartographer_gmapping_hectorslam)/configuration_files
-configuration_basename cartographer.lua"
output="screen" if="$(arg cartographer_enable)">
</node>


<!-- Show in Rviz -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find pocker_bot_vrep_description)/rviz/urdf_check.rviz" if="$(arg rviz_flag)"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find cartographer_gmapping_hectorslam)/rviz/visualize.rviz" if="$(arg rviz_flag)"/>

</launch>
2 changes: 1 addition & 1 deletion launch/gmapping_mapping.launch
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,6 @@


<!-- Show in Rviz -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find pocker_bot_vrep_description)/rviz/urdf_check.rviz" if="$(arg rviz_flag)"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find cartographer_gmapping_hectorslam)/rviz/visualize.rviz" if="$(arg rviz_flag)"/>

</launch>
Binary file added map/mapping_scene_map.pgm
Binary file not shown.
7 changes: 7 additions & 0 deletions map/mapping_scene_map.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
image: mapping_scene_map.pgm
resolution: 0.050000
origin: [-2.849245, -2.339799, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196

Binary file added map/result.pgm
Binary file not shown.
7 changes: 7 additions & 0 deletions map/result.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
image: result.pgm
resolution: 0.050000
origin: [-2.882053, -2.334484, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196

Loading

0 comments on commit c047762

Please sign in to comment.