From 33048fc72d62001e4a7962bb75954cc24464be71 Mon Sep 17 00:00:00 2001 From: Chris Iverach-Brereton Date: Thu, 19 Sep 2024 17:57:12 -0400 Subject: [PATCH] Revert to using base_link for navigation; the create3 uses that for odom, and using a different link appears to break slam_toolbox. Update the SLAM launch parameters --- .../config/localization.yaml | 2 +- turtlebot4_navigation/config/nav2.yaml | 12 +++++------ turtlebot4_navigation/config/slam.yaml | 21 ++++++++++--------- 3 files changed, 18 insertions(+), 17 deletions(-) diff --git a/turtlebot4_navigation/config/localization.yaml b/turtlebot4_navigation/config/localization.yaml index da3c1f1..9ca39f4 100644 --- a/turtlebot4_navigation/config/localization.yaml +++ b/turtlebot4_navigation/config/localization.yaml @@ -6,7 +6,7 @@ amcl: alpha3: 0.2 alpha4: 0.2 alpha5: 0.2 - base_frame_id: "base_footprint" + base_frame_id: "base_link" beam_skip_distance: 0.5 beam_skip_error_threshold: 0.9 beam_skip_threshold: 0.3 diff --git a/turtlebot4_navigation/config/nav2.yaml b/turtlebot4_navigation/config/nav2.yaml index 4ff52de..8b1c18f 100644 --- a/turtlebot4_navigation/config/nav2.yaml +++ b/turtlebot4_navigation/config/nav2.yaml @@ -3,7 +3,7 @@ bt_navigator: use_sim_time: true enable_stamped_cmd_vel: true global_frame: map - robot_base_frame: base_footprint + robot_base_frame: base_link odom_topic: odom bt_loop_duration: 10 default_server_timeout: 20 @@ -133,7 +133,7 @@ local_costmap: update_frequency: 5.0 publish_frequency: 2.0 global_frame: odom - robot_base_frame: base_footprint + robot_base_frame: base_link use_sim_time: true rolling_window: true width: 3 @@ -178,7 +178,7 @@ global_costmap: update_frequency: 1.0 publish_frequency: 1.0 global_frame: map - robot_base_frame: base_footprint + robot_base_frame: base_link use_sim_time: true robot_radius: 0.175 resolution: 0.06 @@ -253,7 +253,7 @@ behavior_server: plugin: "nav2_behaviors::AssistedTeleop" global_frame: map local_frame: odom - robot_base_frame: base_footprint + robot_base_frame: base_link transform_tolerance: 0.1 simulate_ahead_time: 2.0 max_rotational_vel: 1.0 @@ -297,7 +297,7 @@ collision_monitor: ros__parameters: use_sim_time: true enable_stamped_cmd_vel: true - base_frame_id: "base_footprint" + base_frame_id: "base_link" odom_frame_id: "odom" cmd_vel_in_topic: "cmd_vel_smoothed" cmd_vel_out_topic: "cmd_vel" @@ -337,7 +337,7 @@ docking_server: undock_linear_tolerance: 0.05 undock_angular_tolerance: 0.1 max_retries: 3 - base_frame: "base_footprint" + base_frame: "base_link" fixed_frame: "odom" dock_backwards: false dock_prestaging_tolerance: 0.5 diff --git a/turtlebot4_navigation/config/slam.yaml b/turtlebot4_navigation/config/slam.yaml index b4522ef..eac796b 100644 --- a/turtlebot4_navigation/config/slam.yaml +++ b/turtlebot4_navigation/config/slam.yaml @@ -12,29 +12,30 @@ slam_toolbox: # ROS Parameters odom_frame: odom map_frame: map - base_frame: base_footprint - scan_topic: scan + base_frame: base_link + scan_topic: /scan + use_map_saver: true mode: mapping debug_logging: false throttle_scans: 1 transform_publish_period: 0.02 #if 0 never publishes odometry - map_update_interval: 0.5 + map_update_interval: 1.0 resolution: 0.05 - max_laser_range: 12.0 #for rastering images - minimum_time_interval: 0.25 + max_laser_range: 12.0 + minimum_time_interval: 0.5 transform_timeout: 0.2 tf_buffer_duration: 30. - stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps + stack_size_to_use: 40000000 enable_interactive_mode: true # General Parameters use_scan_matching: true use_scan_barycenter: true - minimum_travel_distance: 0.0 - minimum_travel_heading: 0.0 - scan_buffer_size: 20 - scan_buffer_maximum_scan_distance: 12.0 + minimum_travel_distance: 0.1 + minimum_travel_heading: 0.1 + scan_buffer_size: 10 + scan_buffer_maximum_scan_distance: 10.0 link_match_minimum_response_fine: 0.1 link_scan_maximum_distance: 1.5 loop_search_maximum_distance: 3.0