added rotaion_shim, denoise_layer, tweak inflation

This commit is contained in:
Björn Ellensohn 2023-08-21 08:39:22 +02:00
parent cb84a50fa5
commit 073eba0dc2

View File

@ -138,7 +138,18 @@ controller_server:
yaw_goal_tolerance: 0.25 yaw_goal_tolerance: 0.25
# DWB parameters # DWB parameters
FollowPath: FollowPath:
plugin: "dwb_core::DWBLocalPlanner" # plugin: "dwb_core::DWBLocalPlanner"
# trying roation_shim_controller
plugin: "nav2_rotation_shim_controller::RotationShimController"
primary_controller: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
angular_dist_threshold: 0.785
forward_sampling_distance: 0.5
rotate_to_heading_angular_vel: 1.8
max_angular_accel: 3.2
simulate_ahead_time: 1.0
# primary controller params (dwb)
debug_trajectory_details: True debug_trajectory_details: True
min_vel_x: 0.0 min_vel_x: 0.0
min_vel_y: 0.0 min_vel_y: 0.0
@ -193,11 +204,14 @@ local_costmap:
resolution: 0.05 resolution: 0.05
#robot_radius: 0.50 #robot_radius: 0.50
footprint: "[ [0.21, 0.255], [0.21, -0.255], [-0.52, -0.255], [-0.52, 0.255] ]" footprint: "[ [0.21, 0.255], [0.21, -0.255], [-0.52, -0.255], [-0.52, 0.255] ]"
plugins: ["voxel_layer", "inflation_layer"] plugins: ["voxel_layer", "inflation_layer"], "denoise_layer"
denoise_layer:
plugin: "nav2_costmap_2d::DenoiseLayer"
enabled: True
inflation_layer: inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer" plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0 cost_scaling_factor: 10.0 # was 3.0
inflation_radius: 0.11 inflation_radius: 0.55
voxel_layer: voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer" plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True enabled: True
@ -234,7 +248,10 @@ global_costmap:
robot_radius: 0.50 robot_radius: 0.50
resolution: 0.05 resolution: 0.05
track_unknown_space: true track_unknown_space: true
plugins: ["static_layer", "obstacle_layer", "inflation_layer"] plugins: ["static_layer", "obstacle_layer", "inflation_layer", "denoise_layer"]
denoise_layer:
plugin: "nav2_costmap_2d::DenoiseLayer"
enabled: True
obstacle_layer: obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer" plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True enabled: True
@ -254,8 +271,8 @@ global_costmap:
map_subscribe_transient_local: True map_subscribe_transient_local: True
inflation_layer: inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer" plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0 cost_scaling_factor: 10.0 # was 3.0
inflation_radius: 0.11 inflation_radius: 0.55
always_send_full_costmap: True always_send_full_costmap: True
map_server: map_server:
@ -339,8 +356,8 @@ velocity_smoother:
use_sim_time: True use_sim_time: True
smoothing_frequency: 20.0 smoothing_frequency: 20.0
scale_velocities: False scale_velocities: False
#feedback: "OPEN_LOOP" feedback: "OPEN_LOOP"
feedback: "CLOSED_LOOP" #feedback: "CLOSED_LOOP"
max_velocity: [0.26, 0.0, 1.0] max_velocity: [0.26, 0.0, 1.0]
min_velocity: [-0.26, 0.0, -1.0] min_velocity: [-0.26, 0.0, -1.0]
max_accel: [2.5, 0.0, 3.2] max_accel: [2.5, 0.0, 3.2]