diff --git a/src/papa_navigation/launch/includes/move_base.launch.xml b/src/papa_navigation/launch/includes/move_base.launch.xml
index 8e1fe81..52eb669 100644
--- a/src/papa_navigation/launch/includes/move_base.launch.xml
+++ b/src/papa_navigation/launch/includes/move_base.launch.xml
@@ -31,7 +31,8 @@
-
+
+
diff --git a/src/papa_navigation/param/costmap_common_params.yaml b/src/papa_navigation/param/costmap_common_params.yaml
index 1868655..2f55890 100644
--- a/src/papa_navigation/param/costmap_common_params.yaml
+++ b/src/papa_navigation/param/costmap_common_params.yaml
@@ -22,7 +22,7 @@ obstacle_layer:
z_resolution: 0.2
z_voxels: 2
publish_voxel_map: false
- observation_sources: scan bump
+ observation_sources: scan
scan:
data_type: LaserScan
topic: scan
@@ -30,13 +30,6 @@ obstacle_layer:
clearing: true
min_obstacle_height: 0.25
max_obstacle_height: 0.35
- bump:
- data_type: PointCloud2
- topic: mobile_base/sensors/bumper_pointcloud
- marking: true
- clearing: false
- min_obstacle_height: 0.0
- max_obstacle_height: 0.15
# for debugging only, let's you see the entire voxel grid
#cost_scaling_factor and inflation_radius were now moved to the inflation_layer ns
diff --git a/src/papa_navigation/param/global_costmap_params.yaml b/src/papa_navigation/param/global_costmap_params.yaml
index 56b23c7..96a1e7a 100644
--- a/src/papa_navigation/param/global_costmap_params.yaml
+++ b/src/papa_navigation/param/global_costmap_params.yaml
@@ -1,8 +1,10 @@
global_costmap:
+ height: 50
+ width: 50
global_frame: /map
robot_base_frame: /base_footprint
- update_frequency: 1.0
- publish_frequency: 0.5
+ update_frequency: 2.0
+ publish_frequency: 2.0
static_map: true
transform_tolerance: 0.5
plugins:
diff --git a/src/papa_navigation/param/local_costmap_params.yaml b/src/papa_navigation/param/local_costmap_params.yaml
index b422ee1..95e6258 100644
--- a/src/papa_navigation/param/local_costmap_params.yaml
+++ b/src/papa_navigation/param/local_costmap_params.yaml
@@ -3,12 +3,12 @@ local_costmap:
robot_base_frame: /base_footprint
update_frequency: 5.0
publish_frequency: 2.0
- static_map: false
- rolling_window: true
+ static_map: true
+ rolling_window: false
width: 4.0
height: 4.0
resolution: 0.05
transform_tolerance: 0.5
plugins:
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
- - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
\ No newline at end of file
+ - {name: inflation_layer, type: "costmap_2d::InflationLayer"}