Skip to content

Commit 597f00d

Browse files
Merge pull request #7 from logivations/add_footprint_parameter
make params have default value && change agv footprint
2 parents c7dcd8f + e7ede02 commit 597f00d

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

nav2_bringup/bringup/params/forklift_params.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -160,9 +160,9 @@ planner_server:
160160
angle_quantization_bins: 72 # For SE2 node: Number of angle bins for search, must be 1 for 2D node (no angle search)
161161
minimum_turning_radius: 0.20 # For SE2 node & smoother: minimum turning radius in m of path / vehicle
162162
reverse_penalty: 2.1 # For Reeds-Shepp model: penalty to apply if motion is reversing, must be => 1
163-
change_penalty: 0.20 # For SE2 node: penalty to apply if motion is changing directions, must be >= 0
163+
change_penalty: 0.5 # For SE2 node: penalty to apply if motion is changing directions, must be >= 0
164164
non_straight_penalty: 1.05 # For SE2 node: penalty to apply if motion is non-straight, must be => 1
165-
cost_penalty: 1.8 # For SE2 node: penalty to apply to higher cost zones
165+
cost_penalty: 1.2 # For SE2 node: penalty to apply to higher cost zones
166166

167167
smoother:
168168
smoother:
@@ -199,7 +199,7 @@ global_costmap:
199199
global_frame: map
200200
robot_base_frame: base_link
201201
use_sim_time: True
202-
robot_radius: 0.22
202+
footprint: "[[1.8, 0.4], [1.8, -0.4], [-0.2, -0.4], [-0.2, 0.4]]"
203203
map_topic: /costmap_node/map
204204
track_unknown_space: false
205205
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]

0 commit comments

Comments
 (0)