diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 6d1ba83146..269e49b940 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -1,10 +1,16 @@ amcl: ros__parameters: use_sim_time: True - alpha1: 0.2 + set_initial_pose: True + initial_pose: + x: 6.3 + y: 28.6 + z: 0.0 + yaw: -1.57 + alpha1: 0.1 alpha2: 0.2 - alpha3: 0.2 - alpha4: 0.2 + alpha3: 0.3 + alpha4: 0.1 alpha5: 0.2 base_frame_id: "base_footprint" beam_skip_distance: 0.5 @@ -14,15 +20,15 @@ amcl: global_frame_id: "map" lambda_short: 0.1 laser_likelihood_max_dist: 2.0 - laser_max_range: 100.0 - laser_min_range: -1.0 + laser_max_range: 21.0 + laser_min_range: 0.30 laser_model_type: "likelihood_field" max_beams: 60 - max_particles: 2000 - min_particles: 500 + max_particles: 200 + min_particles: 400 odom_frame_id: "odom" - pf_err: 0.05 - pf_z: 0.99 + pf_err: 0.01 + pf_z: 0.90 recovery_alpha_fast: 0.0 recovery_alpha_slow: 0.0 resample_interval: 1 @@ -31,11 +37,11 @@ amcl: sigma_hit: 0.2 tf_broadcast: true transform_tolerance: 1.0 - update_min_a: 0.2 - update_min_d: 0.25 - z_hit: 0.5 + update_min_a: 0.08725 + update_min_d: 0.10 + z_hit: 0.9 z_max: 0.05 - z_rand: 0.5 + z_rand: 0.2 z_short: 0.05 scan_topic: scan @@ -139,11 +145,11 @@ controller_server: debug_trajectory_details: True min_vel_x: 0.0 min_vel_y: 0.0 - max_vel_x: 0.26 + max_vel_x: 1.2 max_vel_y: 0.0 max_vel_theta: 1.0 min_speed_xy: 0.0 - max_speed_xy: 0.26 + max_speed_xy: 1.2 min_speed_theta: 0.0 # Add high threshold velocity for turtlebot 3 issue. # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 @@ -185,15 +191,15 @@ local_costmap: robot_base_frame: base_link use_sim_time: True rolling_window: true - width: 3 - height: 3 - resolution: 0.05 - robot_radius: 0.22 + width: 4 + height: 4 + resolution: 0.1 + robot_radius: 0.34 plugins: ["voxel_layer", "inflation_layer"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 - inflation_radius: 0.55 + cost_scaling_factor: 6.5 + inflation_radius: 1.75 voxel_layer: plugin: "nav2_costmap_2d::VoxelLayer" enabled: True @@ -206,13 +212,13 @@ local_costmap: observation_sources: scan scan: topic: /scan - max_obstacle_height: 2.0 + max_obstacle_height: 5.0 clearing: True marking: True data_type: "LaserScan" - raytrace_max_range: 3.0 + raytrace_max_range: 15.0 raytrace_min_range: 0.0 - obstacle_max_range: 2.5 + obstacle_max_range: 5.0 obstacle_min_range: 0.0 static_layer: plugin: "nav2_costmap_2d::StaticLayer" @@ -225,10 +231,10 @@ global_costmap: update_frequency: 1.0 publish_frequency: 1.0 global_frame: map - robot_base_frame: base_link + robot_base_frame: base_footprint use_sim_time: True - robot_radius: 0.22 - resolution: 0.05 + robot_radius: 0.34 + resolution: 0.1 track_unknown_space: true plugins: ["static_layer", "obstacle_layer", "inflation_layer"] obstacle_layer: @@ -237,13 +243,13 @@ global_costmap: observation_sources: scan scan: topic: /scan - max_obstacle_height: 2.0 + max_obstacle_height: 5.0 clearing: True marking: True data_type: "LaserScan" - raytrace_max_range: 3.0 + raytrace_max_range: 15.0 raytrace_min_range: 0.0 - obstacle_max_range: 2.5 + obstacle_max_range: 5.0 obstacle_min_range: 0.0 static_layer: plugin: "nav2_costmap_2d::StaticLayer" @@ -334,8 +340,8 @@ velocity_smoother: smoothing_frequency: 20.0 scale_velocities: False feedback: "OPEN_LOOP" - max_velocity: [0.26, 0.0, 1.0] - min_velocity: [-0.26, 0.0, -1.0] + max_velocity: [1.2, 0.0, 1.0] + min_velocity: [-1.2, 0.0, -1.0] max_accel: [2.5, 0.0, 3.2] max_decel: [-2.5, 0.0, -3.2] odom_topic: "odom"