Skip to content

Commit

Permalink
Tuned nav_stack params
Browse files Browse the repository at this point in the history
  • Loading branch information
l0g1c-80m8 committed Jun 19, 2022
1 parent fe7814a commit 960f21d
Show file tree
Hide file tree
Showing 4 changed files with 27 additions and 20 deletions.
18 changes: 9 additions & 9 deletions my_robot/config/base_local_planner_params.yaml
Original file line number Diff line number Diff line change
@@ -1,29 +1,29 @@
controller_frequency: 10

TrajectoryPlannerROS:
max_vel_x: 1.0 #0.5
max_vel_x: 1.5 #0.5
min_vel_x: -0.1 #0.01
max_vel_theta: 1.57 #1.5
max_vel_theta: 0.785398 #1.5

min_in_place_vel_theta: 0.314

acc_lim_theta: 3.14
acc_lim_x: 2.0
acc_lim_y: 2.0
acc_lim_theta: 1.5708
acc_lim_x: 1.5708
acc_lim_y: 1.5708

sim_time: 1.0
sim_time: 4.0

vx_samples: 4.0
vtheta_samples: 50.0

pdist_scale: 20.0 #0.6
gdist_scale: 0.1 #0.8
pdist_scale: 0.6 #0.6
gdist_scale: 0.8 #0.8
occdist_scale: 0.2

heading_scoring: false
# heading_lookahead: 1.0
meter_scoring: true
holonomic_robot: true
holonomic_robot: false

shutdown_costmaps: false

Expand Down
7 changes: 5 additions & 2 deletions my_robot/config/costmap_common_params.yaml
Original file line number Diff line number Diff line change
@@ -1,14 +1,17 @@
map_type: costmap

obstacle_range: 1.0 # 2.0
obstacle_range: 1.2 # 2.0
raytrace_range: 2.0 # 3.0

transform_tolerance: 0.2 # 0.0

robot_radius: 0.3 # 0.0
inflation_radius: 0.5 # 0.0
cost_scaling_factor: 5.0
cost_scaling_factor: 3.0

observation_sources: laser_scan_sensor

laser_scan_sensor: {sensor_frame: hokuyo, data_type: LaserScan, topic: /scan, marking: true, clearing: true}

visualize_potential: true
cost_factor: 0.8
8 changes: 4 additions & 4 deletions my_robot/config/global_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
global_costmap:
global_frame: map
robot_base_frame: robot_footprint
update_frequency: 1.0
publish_frequency: 1.0
width: 20.0
height: 20.0
update_frequency: 2.0
publish_frequency: 2.0
width: 12.0
height: 12.0
resolution: 0.05
static_map: true
rolling_window: false
14 changes: 9 additions & 5 deletions my_robot/config/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
local_costmap:
global_frame: odom
robot_base_frame: robot_footprint
update_frequency: 2.0
publish_frequency: 2.0
width: 10.0
height: 10.0
resolution: 0.05
update_frequency: 3.0
publish_frequency: 3.0
width: 3.0
height: 3.0
resolution: 0.025
static_map: false
rolling_window: true
path_distance_bias: 32.0
goal_distance_bias: 20.0
occdist_scale: 0.02
latch_xy_goal_tolerance: false

0 comments on commit 960f21d

Please sign in to comment.