diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch
index ee300253880..7f5e8f7a253 100644
--- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch
+++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch
@@ -183,8 +183,9 @@
inflater:
- inflation_radius: 0.30 # 0.7
- cost_scaling_factor: 10.0 # 10.0
+ inflation_radius: 3.0 # 0.7
+ cost_scaling_factor: 3.0 # 10.0
+ footprint_padding: 0.05
inflater:
@@ -192,6 +193,7 @@
cost_scaling_factor: 3.0 # 25.0 default 10, increasing factor decrease the cost value
# default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
update_frequency: 10.0
+ footprint_padding: 0.05
base_local_planner: base_local_planner/TrajectoryPlannerROS
diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml
index 38569b60fb1..5ec5b938cbf 100644
--- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml
+++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml
@@ -76,12 +76,15 @@
-
- local_costmap:
- # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
- update_frequency: 10.0
-
+
+ inflater:
+ inflation_radius: 3.0 # 0.7
+ cost_scaling_factor: 3.0 # 25.0 default 10, increasing factor decrease the cost value
+ # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide)
+ update_frequency: 10.0
+ footprint_padding: 0.05
+