]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Move config/global_costmap_params_odom.yaml go config/global_costmap_params_utm.yaml
authorErik Andresen <erik@vontaene.de>
Sat, 8 Jul 2017 15:51:44 +0000 (17:51 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 8 Jul 2017 15:51:44 +0000 (17:51 +0200)
config/base_local_planner_params.yaml
config/global_costmap_params.yaml
config/global_costmap_params_odom.yaml [deleted file]
config/global_costmap_params_utm.yaml [new file with mode: 0644]
launch/move_base.launch

index ce83faa07793005fc700ea3ac52652be9d4765ce..b163e5e1e649c8e14cc591ce1c8852566d7df1f0 100644 (file)
@@ -26,6 +26,9 @@ TrajectoryPlannerROS:
   # How far to look ahead in time in seconds along the simulated trajectory when using heading scoring, default: 0.1
   heading_scoring_timestep: 0.3
 
+  # How far the robot must travel in meters before oscillation flags are reset, default: 0.05
+  oscillation_reset_dist: 0.1
+
 DWAPlannerROS:
   acc_lim_x: 10.07
   acc_lim_y: 0.0
index 3dfcf594d94e7c24227cc543864b3003c71cd359..5bb308db66f22f0b6c874f6d335bbc9f9d66f509 100644 (file)
@@ -7,7 +7,7 @@ global_costmap:
   - {name: static_layer, type: 'costmap_2d::StaticLayer'}
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
-inflation_layer:
-  # low slope decay curve
-  inflation_radius: 1.75
-  cost_scaling_factor: 2.58
+  inflation_layer:
+    # low slope decay curve
+    inflation_radius: 1.75
+    cost_scaling_factor: 2.58
diff --git a/config/global_costmap_params_odom.yaml b/config/global_costmap_params_odom.yaml
deleted file mode 100644 (file)
index 0cb31e5..0000000
+++ /dev/null
@@ -1,11 +0,0 @@
-# only differences to config/global_costmap_params.yaml
-global_costmap:
-  global_frame: odom
-  rolling_window: true
-  width: 100.0
-  height: 100.0
-  resolution: 1.0
-  resolution: 0.05
-  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
new file mode 100644 (file)
index 0000000..8ecf0b5
--- /dev/null
@@ -0,0 +1,10 @@
+# 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 c1320cb074dc75a9660c32d8d46420e08003fd2a..9508c32cff4a8ae83693d511bcf85f0068ab2c3a 100644 (file)
@@ -2,6 +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="nomap" default="false" />
        <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
 
@@ -19,9 +20,9 @@
                        <!-- Specifies the expected noise in odometry's rotation estimate from translational component of the robot's motion. -->
                        <param name="odom_alpha2" value="0.00001" />
                        <!-- Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion. -->
-                       <param name="odom_alpha3" value="0.01" />
+                       <param name="odom_alpha3" value="0.03" />
                        <!-- Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion. -->
-                       <param name="odom_alpha4" value="0.03" />
+                       <param name="odom_alpha4" value="0.001" />
                        <!-- How many evenly-spaced beams in each scan to be used when updating the filter. -->
                        <param name="laser_max_beams" value="50" />
                        <!-- Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. -->
@@ -41,7 +42,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 nomap)" />
+               <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_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" />
                <remap from="/cmd_vel" to="move_base/cmd_vel"/>