]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Use gps instead utm as gps frame
authorErik Andresen <erik@vontaene.de>
Sun, 16 Jul 2017 09:22:42 +0000 (11:22 +0200)
committerErik Andresen <erik@vontaene.de>
Sun, 16 Jul 2017 09:22:42 +0000 (11:22 +0200)
config/global_costmap_params_gps.yaml [new file with mode: 0644]
config/global_costmap_params_utm.yaml [deleted file]
launch/move_base.launch

diff --git a/config/global_costmap_params_gps.yaml b/config/global_costmap_params_gps.yaml
new file mode 100644 (file)
index 0000000..fa54a35
--- /dev/null
@@ -0,0 +1,10 @@
+# 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'}
diff --git a/config/global_costmap_params_utm.yaml b/config/global_costmap_params_utm.yaml
deleted file mode 100644 (file)
index 8ecf0b5..0000000
+++ /dev/null
@@ -1,10 +0,0 @@
-# only differences to config/global_costmap_params.yaml
-global_costmap:
-  global_frame: utm
-  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 69073a4b44a239d2d6de174903c3b53c14f1c991..e64852e14b1ff795b45f6d8f17e9f7b780a0f4a8 100644 (file)
@@ -2,7 +2,7 @@
 <launch>
        <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_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 -->
@@ -43,8 +43,8 @@
                <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_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/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"/>