diff --git a/turtlebot4_navigation/config/localization.yaml b/turtlebot4_navigation/config/localization.yaml index 9ca39f4..c4e6155 100644 --- a/turtlebot4_navigation/config/localization.yaml +++ b/turtlebot4_navigation/config/localization.yaml @@ -1,6 +1,5 @@ amcl: ros__parameters: - use_sim_time: true alpha1: 0.2 alpha2: 0.2 alpha3: 0.2 @@ -39,16 +38,8 @@ amcl: z_short: 0.05 scan_topic: scan -map_server: - ros__parameters: - use_sim_time: true - # Overridden in launch by the "map" launch configuration or provided default value. - # To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below. - yaml_filename: "" - map_saver: ros__parameters: - use_sim_time: true save_map_timeout: 5.0 free_thresh_default: 0.25 occupied_thresh_default: 0.65 diff --git a/turtlebot4_navigation/config/nav2.yaml b/turtlebot4_navigation/config/nav2.yaml index 8b1c18f..67b1bcb 100644 --- a/turtlebot4_navigation/config/nav2.yaml +++ b/turtlebot4_navigation/config/nav2.yaml @@ -1,6 +1,5 @@ bt_navigator: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true global_frame: map robot_base_frame: base_link @@ -20,7 +19,6 @@ bt_navigator: controller_server: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true controller_frequency: 20.0 min_x_velocity_threshold: 0.001 @@ -128,13 +126,11 @@ controller_server: local_costmap: local_costmap: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true update_frequency: 5.0 publish_frequency: 2.0 global_frame: odom robot_base_frame: base_link - use_sim_time: true rolling_window: true width: 3 height: 3 @@ -173,13 +169,11 @@ local_costmap: global_costmap: global_costmap: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true update_frequency: 1.0 publish_frequency: 1.0 global_frame: map robot_base_frame: base_link - use_sim_time: true robot_radius: 0.175 resolution: 0.06 track_unknown_space: true @@ -209,10 +203,8 @@ global_costmap: planner_server: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true #expected_planner_frequency: 20.0 - use_sim_time: true planner_plugins: ["GridBased"] GridBased: plugin: "nav2_navfn_planner::NavfnPlanner" @@ -222,7 +214,6 @@ planner_server: smoother_server: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true smoother_plugins: ["simple_smoother"] simple_smoother: @@ -233,7 +224,6 @@ smoother_server: behavior_server: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true local_costmap_topic: local_costmap/costmap_raw global_costmap_topic: global_costmap/costmap_raw @@ -260,13 +250,8 @@ behavior_server: min_rotational_vel: 0.4 rotational_acc_lim: 3.2 -robot_state_publisher: - ros__parameters: - use_sim_time: true - waypoint_follower: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true loop_rate: 20 stop_on_failure: false @@ -279,7 +264,6 @@ waypoint_follower: velocity_smoother: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true smoothing_frequency: 20.0 scale_velocities: False @@ -295,7 +279,6 @@ velocity_smoother: collision_monitor: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true base_frame_id: "base_link" odom_frame_id: "odom" @@ -328,7 +311,6 @@ collision_monitor: docking_server: ros__parameters: - use_sim_time: true enable_stamped_cmd_vel: true controller_frequency: 50.0 initial_perception_timeout: 5.0