]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Adapt navigation config to more trustworthy IMU
authorErik Andresen <erik@vontaene.de>
Mon, 5 Jun 2017 09:10:07 +0000 (11:10 +0200)
committerErik Andresen <erik@vontaene.de>
Mon, 5 Jun 2017 09:10:07 +0000 (11:10 +0200)
config/base_local_planner_params.yaml
config/global_costmap_params.yaml
launch/move_base.launch

index 18234088eae5148d365085886e2f23e2e6ea5819..ce83faa07793005fc700ea3ac52652be9d4765ce 100644 (file)
@@ -14,14 +14,14 @@ TrajectoryPlannerROS:
   # gdist_scale and pdist_scale parameters should assume meters
   meter_scoring: true
 
-  xy_goal_tolerance: 0.20
-  yaw_goal_tolerance: 0.3
+  xy_goal_tolerance: 0.15
+  yaw_goal_tolerance: 0.1
 
   # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01
   occdist_scale: 0.02
 
   # Whether to score based on the robot's heading to the path or its distance from the path, default: false
-  heading_scoring: true
+  heading_scoring: false
 
   # 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
index dde44ae674fb6d8fa098ae218e330edd6b385d06..3dfcf594d94e7c24227cc543864b3003c71cd359 100644 (file)
@@ -8,4 +8,6 @@ global_costmap:
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
 inflation_layer:
-  inflation_radius: 0.25
+  # low slope decay curve
+  inflation_radius: 1.75
+  cost_scaling_factor: 2.58
index f2fd7330fcbd6d14dc28ab36f0f5cc832fbf315e..9c6755d01a66ed35711e20b0aefe6af19e26d08c 100644 (file)
@@ -25,9 +25,9 @@
                        <!-- 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. -->
-                       <param name="recovery_alpha_slow" value="0.01" />
+                       <param name="recovery_alpha_slow" value="0.001" />
                        <!-- Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. -->
-                       <param name="recovery_alpha_fast" value="0.2" />
+                       <param name="recovery_alpha_fast" value="0.1" />
                        <!-- Minimum allowed number of particles. -->
                        <param name="min_particles" value="100" />
                </group>