]> defiant.homedns.org Git - arm_ros_conn.git/blobdiff - config/costmap_common_params.yaml
navigation stack tuning
[arm_ros_conn.git] / config / costmap_common_params.yaml
index ffff33a49af181b867f2c23217304b3408707747..8decd3b1d2af7e6daa2d7aefdad1cfe880291724 100644 (file)
@@ -1,9 +1,11 @@
 obstacle_range: 2.5
 raytrace_range: 3.0
-#footprint: [[x0, y0], [x1, y1], ... [xn, yn]]
-robot_radius: 0.15
+footprint: [ [0.22, 0.11], [-0.08, 0.11], [-0.08, -0.11], [0.22, -0.11] ]
+#robot_radius: 0.15
 inflation_radius: 0.55
+transform_tolerance: 0.5
 
-observation_sources: laser_scan_sensor
+obstacle_layer:
+  observation_sources: laser_scan_sensor
 
 laser_scan_sensor: {sensor_frame: scan, data_type: LaserScan, topic: scan, marking: true, clearing: true}