]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Readd global_costmap_params_odom.yaml
authorErik Andresen <erik@vontaene.de>
Sat, 8 Jul 2017 16:24:04 +0000 (18:24 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 8 Jul 2017 16:24:04 +0000 (18:24 +0200)
config/global_costmap_params_odom.yaml [new file with mode: 0644]
launch/move_base.launch

diff --git a/config/global_costmap_params_odom.yaml b/config/global_costmap_params_odom.yaml
new file mode 100644 (file)
index 0000000..60d391a
--- /dev/null
@@ -0,0 +1,10 @@
+# only differences to config/global_costmap_params.yaml
+global_costmap:
+  global_frame: odom
+  rolling_window: true
+  width: 100.0
+  height: 100.0
+  resolution: 0.05
+  plugins:
+  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+  - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
index 9508c32cff4a8ae83693d511bcf85f0068ab2c3a..69073a4b44a239d2d6de174903c3b53c14f1c991 100644 (file)
@@ -3,6 +3,7 @@
        <arg name="slam_gmapping" default="false" />
        <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
        <arg name="global_utm" default="false" />
+       <arg name="global_odom" default="false" />
        <arg name="nomap" default="false" />
        <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
 
@@ -42,7 +43,7 @@
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
                <rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
                <rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" />
-               <rosparam file="$(find wild_thumper)/config/global_costmap_params_nomap.yaml" command="load" if="$(arg nomap)" />
+               <rosparam file="$(find wild_thumper)/config/global_costmap_params_odom.yaml" command="load" if="$(arg global_odm)" />
                <rosparam file="$(find wild_thumper)/config/global_costmap_params_utm.yaml" command="load" if="$(arg global_utm)" />
                <rosparam file="$(find wild_thumper)/config/local_costmap_params.yaml" command="load" />
                <rosparam file="$(find wild_thumper)/config/base_local_planner_params.yaml" command="load" />