Skip to content

Commit 3ddd397

Browse files
committed
update costmap parameters
1 parent 8aadb69 commit 3ddd397

File tree

2 files changed

+12
-7
lines changed

2 files changed

+12
-7
lines changed

jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -183,15 +183,17 @@
183183

184184
<rosparam ns="move_base/global_costmap">
185185
inflater:
186-
inflation_radius: 0.30 # 0.7
187-
cost_scaling_factor: 10.0 # 10.0
186+
inflation_radius: 3.0 # 0.7
187+
cost_scaling_factor: 3.0 # 10.0
188+
footprint_padding: 0.05
188189
</rosparam>
189190
<rosparam ns="move_base/local_costmap">
190191
inflater:
191192
inflation_radius: 3.0 # 0.7
192193
cost_scaling_factor: 3.0 # 25.0 default 10, increasing factor decrease the cost value
193194
# default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
194195
update_frequency: 10.0
196+
footprint_padding: 0.05
195197
</rosparam>
196198
<rosparam ns="move_base">
197199
base_local_planner: base_local_planner/TrajectoryPlannerROS

jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -76,12 +76,15 @@
7676
<rosparam file="$(find fetch_navigation)/config/fetch/costmap_common.yaml" command="load" ns="local_costmap" />
7777
<rosparam file="$(find fetch_navigation)/config/costmap_local.yaml" command="load" ns="local_costmap" />
7878
<rosparam file="$(find fetch_navigation)/config/fetch/costmap_local.yaml" command="load" ns="local_costmap" />
79-
<rosparam>
80-
local_costmap:
81-
# default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
82-
update_frequency: 10.0
83-
</rosparam>
8479
</node>
80+
<rosparam ns="safe_teleop_base/local_costmap">
81+
inflater:
82+
inflation_radius: 3.0 # 0.7
83+
cost_scaling_factor: 3.0 # 25.0 default 10, increasing factor decrease the cost value
84+
# default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
85+
update_frequency: 10.0
86+
footprint_padding: 0.05
87+
</rosparam>
8588

8689
<node name="safe_tilt_head" pkg="jsk_fetch_startup" type="safe_tilt_head.py" />
8790

0 commit comments

Comments
 (0)