diff --git a/config/carto_config/rosbot.lua b/config/carto_config/rosbot.lua deleted file mode 100644 index 7bc3f31..0000000 --- a/config/carto_config/rosbot.lua +++ /dev/null @@ -1,42 +0,0 @@ -include "map_builder.lua" -include "trajectory_builder.lua" - -options = { - map_builder = MAP_BUILDER, - trajectory_builder = TRAJECTORY_BUILDER, - map_frame = "map", - tracking_frame = "base_link", - published_frame = "base_link", - odom_frame = "odom", - provide_odom_frame = true, - publish_frame_projected_to_2d = true, - use_odometry = true, - 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 = 0.2, - 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 = 1., - fixed_frame_pose_sampling_ratio = 1., - imu_sampling_ratio = 1., - landmarks_sampling_ratio = 1., -} - -MAP_BUILDER.use_trajectory_builder_2d = true -TRAJECTORY_BUILDER_2D.min_range = 0.4 -TRAJECTORY_BUILDER_2D.max_range = 6.0 -TRAJECTORY_BUILDER_2D.use_imu_data = false -TRAJECTORY_BUILDER_2D.use_online_correlative_scale_matching = on -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 = 0.1 -TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 5e-1 - -POSE_GRAPH.optimization_problem.huber_scale = 1e2 - -return options diff --git a/config/carto_config/rosbot_localization.lua b/config/carto_config/rosbot_localization.lua deleted file mode 100644 index e6ae826..0000000 --- a/config/carto_config/rosbot_localization.lua +++ /dev/null @@ -1,45 +0,0 @@ -include "map_builder.lua" -include "trajectory_builder.lua" - -options = { - map_builder = MAP_BUILDER, - trajectory_builder = TRAJECTORY_BUILDER, - map_frame = "map", - tracking_frame = "base_link", - published_frame = "base_link", - odom_frame = "odom", - provide_odom_frame = true, - publish_frame_projected_to_2d = true, - use_odometry = true, - 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 = 0.2, - 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 = 1., - fixed_frame_pose_sampling_ratio = 1., - imu_sampling_ratio = 1., - landmarks_sampling_ratio = 1., -} - -MAP_BUILDER.use_trajectory_builder_2d = true -TRAJECTORY_BUILDER_2D.min_range = 0.4 -TRAJECTORY_BUILDER_2D.max_range = 6.0 -TRAJECTORY_BUILDER_2D.use_imu_data = false -TRAJECTORY_BUILDER_2D.use_online_correlative_scale_matching = on -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 = 0.1 -TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1 - -POSE_GRAPH.optimization_problem.huber_scale = 1e2 - --- Localization -- -TRAJECTORY_BUILDER.pure_localization = true -POSE_GRAPH.optimize_every_n_nodes = 20 -return options diff --git a/config/mwpfl_config/start_mwpfl.yaml b/config/mwpfl_config/start_mwpfl.yaml new file mode 100644 index 0000000..25dec43 --- /dev/null +++ b/config/mwpfl_config/start_mwpfl.yaml @@ -0,0 +1,9 @@ +odom_frame_id: odom +base_frame_id: base_link +global_frame_id: map +update_min_distance: 0.01 +update_min_angle: 0.02 +odom_noise_rot_rot: 0.05 +odom_noise_rot_trans: 0.05 +odom_noise_trans_trans: 0.05 +odom_noise_trans_rot: 0.05 diff --git a/config/slam_toolbox_config/slam_toolbox_localization.yaml b/config/slam_toolbox_config/slam_toolbox_localization.yaml index 39486c9..092e671 100644 --- a/config/slam_toolbox_config/slam_toolbox_localization.yaml +++ b/config/slam_toolbox_config/slam_toolbox_localization.yaml @@ -9,20 +9,14 @@ ceres_loss_function: None # ROS Parameters odom_frame: odom map_frame: map -base_frame: base_link -scan_topic: /scan mode: localization #localization -# if you'd like to start localizing on bringup in a map and pose -map_file_name: rosbot -map_start_pose: [0, 0, 0.0] - debug_logging: false throttle_scans: 1 transform_publish_period: 0.02 #if 0 never publishes odometry map_update_interval: 5.0 resolution: 0.05 -max_laser_range: 3.5 #for rastering images +max_laser_range: 20 #for rastering images minimum_time_interval: 0.5 transform_timeout: 0.2 tf_buffer_duration: 10. diff --git a/config/slam_toolbox_config/slam_toolbox_mapping.yaml b/config/slam_toolbox_config/slam_toolbox_mapping.yaml index 0ec46b2..dacb3f3 100644 --- a/config/slam_toolbox_config/slam_toolbox_mapping.yaml +++ b/config/slam_toolbox_config/slam_toolbox_mapping.yaml @@ -9,8 +9,6 @@ ceres_loss_function: None # ROS Parameters odom_frame: odom map_frame: map -base_frame: base_link -scan_topic: /scan mode: mapping #localization debug_logging: false @@ -18,10 +16,10 @@ throttle_scans: 1 transform_publish_period: 0.02 #if 0 never publishes odometry map_update_interval: 5.0 resolution: 0.05 -max_laser_range: 3.5 #for rastering images +max_laser_range: 20 #for rastering images minimum_time_interval: 0.5 transform_timeout: 0.2 -tf_buffer_duration: 10. +tf_buffer_duration: 30. stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps # General Parameters diff --git a/launch/run_mw_mapping.launch b/launch/run_mw_mapping.launch index 893bac7..34c9cda 100644 --- a/launch/run_mw_mapping.launch +++ b/launch/run_mw_mapping.launch @@ -5,7 +5,8 @@ - + + @@ -14,7 +15,7 @@ - + @@ -24,17 +25,12 @@ - - - - - - + + + + + + diff --git a/launch/run_mw_mapping_slam_toolbox.launch b/launch/run_mw_mapping_slam_toolbox.launch deleted file mode 100644 index 4af362e..0000000 --- a/launch/run_mw_mapping_slam_toolbox.launch +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - - diff --git a/launch/run_mw_navigation.launch b/launch/run_mw_navigation.launch index 1f12ca1..f8f0a2f 100644 --- a/launch/run_mw_navigation.launch +++ b/launch/run_mw_navigation.launch @@ -2,15 +2,19 @@ - - + + + + + + - + @@ -20,16 +24,14 @@ - - - - + + + + + + + + diff --git a/launch/run_mw_navigation_slam_toolbox.launch b/launch/run_mw_navigation_slam_toolbox.launch deleted file mode 100644 index d499e30..0000000 --- a/launch/run_mw_navigation_slam_toolbox.launch +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/run_mw_navigation_with_no_map.launch b/launch/run_mw_navigation_with_no_map.launch index c316dc4..bfbce73 100644 --- a/launch/run_mw_navigation_with_no_map.launch +++ b/launch/run_mw_navigation_with_no_map.launch @@ -5,7 +5,8 @@ - + + @@ -16,7 +17,7 @@ - + @@ -26,15 +27,12 @@ - - - - + + + + + + diff --git a/launch/run_mw_navigation_with_no_map_slam_toolbox.launch b/launch/run_mw_navigation_with_no_map_slam_toolbox.launch deleted file mode 100644 index e3193c5..0000000 --- a/launch/run_mw_navigation_with_no_map_slam_toolbox.launch +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/launch/secondary_launch/start_mwpfl.launch b/launch/secondary_launch/start_mwpfl.launch index 57b22d1..24af0bc 100644 --- a/launch/secondary_launch/start_mwpfl.launch +++ b/launch/secondary_launch/start_mwpfl.launch @@ -21,30 +21,10 @@ - - - - - - - - - - - - - - - - - - - - - + diff --git a/launch/secondary_launch/start_slam_toolbox.launch b/launch/secondary_launch/start_slam_toolbox.launch new file mode 100644 index 0000000..80e118e --- /dev/null +++ b/launch/secondary_launch/start_slam_toolbox.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + $(arg map_start_pose) + + + + diff --git a/launch/simulation/sim_follow_me.launch b/launch/simulation/sim_follow_me.launch index c7791ca..0c54785 100644 --- a/launch/simulation/sim_follow_me.launch +++ b/launch/simulation/sim_follow_me.launch @@ -19,9 +19,12 @@ - - - + + + + + + @@ -38,7 +41,7 @@ - + @@ -49,16 +52,14 @@ - - - - + + + + + + + + diff --git a/launch/simulation/sim_mw_mapping.launch b/launch/simulation/sim_mw_mapping.launch index ab0cdf5..c9e5792 100644 --- a/launch/simulation/sim_mw_mapping.launch +++ b/launch/simulation/sim_mw_mapping.launch @@ -5,7 +5,8 @@ - + + @@ -24,7 +25,7 @@ - + @@ -34,15 +35,14 @@ - - - - + + + + + + + + diff --git a/launch/simulation/sim_mw_navigation.launch b/launch/simulation/sim_mw_navigation.launch index b524de1..c7bf97f 100644 --- a/launch/simulation/sim_mw_navigation.launch +++ b/launch/simulation/sim_mw_navigation.launch @@ -3,9 +3,13 @@ - - - + + + + + + + @@ -27,7 +31,7 @@ - + @@ -37,16 +41,14 @@ - - - - + + + + + + + + diff --git a/launch/simulation/sim_mw_navigation_with_no_map.launch b/launch/simulation/sim_mw_navigation_with_no_map.launch index c5abf75..3caa5f1 100644 --- a/launch/simulation/sim_mw_navigation_with_no_map.launch +++ b/launch/simulation/sim_mw_navigation_with_no_map.launch @@ -5,15 +5,13 @@ - + + - - - - + @@ -29,7 +27,7 @@ - + @@ -39,15 +37,12 @@ - - - - + + + + + + diff --git a/samples/maps/slam_map.data b/samples/maps/slam_map.data new file mode 100644 index 0000000..850ecee Binary files /dev/null and b/samples/maps/slam_map.data differ diff --git a/samples/maps/slam_map.posegraph b/samples/maps/slam_map.posegraph new file mode 100644 index 0000000..232cf36 Binary files /dev/null and b/samples/maps/slam_map.posegraph differ