]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Removed global_costmap_params_gps and increased
authorErik Andresen <erik@vontaene.de>
Tue, 5 Sep 2017 14:31:27 +0000 (16:31 +0200)
committerErik Andresen <erik@vontaene.de>
Tue, 5 Sep 2017 14:31:27 +0000 (16:31 +0200)
global_costmap_params_odom size

config/global_costmap_params_gps.yaml [deleted file]
config/global_costmap_params_odom.yaml
launch/move_base.launch

diff --git a/config/global_costmap_params_gps.yaml b/config/global_costmap_params_gps.yaml
deleted file mode 100644 (file)
index fa54a35..0000000
+++ /dev/null
@@ -1,10 +0,0 @@
-# only differences to config/global_costmap_params.yaml
-global_costmap:
-  global_frame: gps
-  rolling_window: true
-  width: 200.0
-  height: 200.0
-  resolution: 0.10
-  plugins:
-  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
-  - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
index 60d391a2b0b41a47ec6d1c1e5c48d74c2cfdba10..417e0512d2ea1b7bbe9c72cd4192e8356e7c3840 100644 (file)
@@ -2,9 +2,9 @@
 global_costmap:
   global_frame: odom
   rolling_window: true
-  width: 100.0
-  height: 100.0
-  resolution: 0.05
+  width: 200.0
+  height: 200.0
+  resolution: 0.10
   plugins:
   - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
index e64852e14b1ff795b45f6d8f17e9f7b780a0f4a8..eb425c3c10e2ca54786551d11630a495284c007a 100644 (file)
@@ -2,7 +2,6 @@
 <launch>
        <arg name="slam_gmapping" default="false" />
        <arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
-       <arg name="global_gps" 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 -->
@@ -44,7 +43,6 @@
                <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_odom.yaml" command="load" if="$(arg global_odom)" />
-               <rosparam file="$(find wild_thumper)/config/global_costmap_params_gps.yaml" command="load" if="$(arg global_gps)" />
                <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" />
                <remap from="/cmd_vel" to="move_base/cmd_vel"/>