]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
navigation stack tuning
authorErik Andresen <erik@vontaene.de>
Sat, 18 Oct 2014 23:09:52 +0000 (01:09 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 18 Oct 2014 23:09:52 +0000 (01:09 +0200)
arm.launch
config/costmap_common_params.yaml
config/global_costmap_params.yaml
config/local_costmap_params.yaml
move_base.launch

index 03255e2f51e0dd2fbd57b113d5904ed77f143017..d63bd6aa2480a9e1d6e0a693ec1129c6009f029f 100644 (file)
@@ -7,7 +7,4 @@
                <remap from="camera_info" to="/camera/depth/camera_info"/>
                <param name="output_frame_id" value="/scan" />
        </node>
-
-       <param name="robot_description" command="$(find xacro)/xacro.py $(find arm)/urdf/arm.urdf.xacro" />
-       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
 </launch>
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}
index 01a3c8feda3a0fe67e413d27c3ee6db180dc8b1e..483f9fa6141345b9e5c0d55071a0833aa2340c17 100644 (file)
@@ -3,3 +3,7 @@ global_costmap:
   robot_base_frame: base_link
   update_frequency: 5.0
   static_map: true
+  plugins:
+  - {name: static_layer, type: 'costmap_2d::StaticLayer'}
+  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+  - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
index 544e1b32dab449bf2bbaae4578c2060894bda609..3ee2d1e90b266da835853799657d4817e047b73b 100644 (file)
@@ -8,3 +8,6 @@ local_costmap:
   width: 6.0
   height: 6.0
   resolution: 0.05
+  plugins:
+  - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+  - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
index d15b07722ba01a0d18c60f8f1d1f31b2769a6fb6..8d46da1af9245e6c5ae965ddb4c1808f69db840e 100644 (file)
@@ -14,4 +14,7 @@
                <rosparam file="$(find arm)/config/local_costmap_params.yaml" command="load" />
                <rosparam file="$(find arm)/config/base_local_planner_params.yaml" command="load" />
        </node>
+
+       <param name="robot_description" command="$(find xacro)/xacro.py $(find arm)/urdf/arm.urdf.xacro" />
+       <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
 </launch>