Remove sim_granularity for usage on ARM
authorErik Andresen <erik@vontaene.de>
Sun, 4 Mar 2018 10:03:22 +0000 (11:03 +0100)
committerErik Andresen <erik@vontaene.de>
Sun, 4 Mar 2018 10:03:22 +0000 (11:03 +0100)
config/base_local_planner_params.yaml
config/global_costmap_params.yaml

index b163e5e..612ab55 100644 (file)
@@ -29,6 +29,12 @@ TrajectoryPlannerROS:
   # How far the robot must travel in meters before oscillation flags are reset, default: 0.05
   oscillation_reset_dist: 0.1
 
+  # The step size, in meters, to take between points on a given trajectory, default: 0.025
+  sim_granularity: 0.05
+
+  # The step size, in radians, to take between angular samples on a given trajectory, default: sim_granularity
+  angular_sim_granularity: 0.05
+
 DWAPlannerROS:
   acc_lim_x: 10.07
   acc_lim_y: 0.0
index 5bb308d..eb3e89c 100644 (file)
@@ -1,7 +1,6 @@
 global_costmap:
   global_frame: /map
   robot_base_frame: base_footprint
-  update_frequency: 5.0
   static_map: true
   plugins:
   - {name: static_layer, type: 'costmap_2d::StaticLayer'}