]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
-reenable range layer
authorErik Andresen <erik@vontaene.de>
Sun, 20 Nov 2016 10:58:13 +0000 (11:58 +0100)
committerErik Andresen <erik@vontaene.de>
Sun, 20 Nov 2016 10:58:13 +0000 (11:58 +0100)
-navigation/exploration tuning

config/costmap_common_params.yaml
config/costmap_exploration.yaml
config/local_costmap_params.yaml
launch/move_base.launch

index 02ff12dc426672e9bc013215d8f4a245dcf5babf..674c1cc85d29ce5678b54b597dabab4edaeffc2a 100644 (file)
@@ -7,4 +7,9 @@ obstacle_layer:
   laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true}
 
 inflation_layer:
-  inflation_radius: 0.5
+  inflation_radius: 0.25
+
+range_layer:
+  topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"]
+  no_readings_timeout: 1.0
+  clear_on_max_reading: true
index 6414e9b6812d9f9c5d96caf2478cbdb1b212656e..63685630a384cd62a8d03a2bfd64f966d3b0d831 100644 (file)
@@ -3,7 +3,7 @@ global_frame: map
 robot_base_frame: base_footprint
 update_frequency: 5.0
 publish_frequency: 5.0
-resolution: 0.01
+resolution: 0.05
 
 rolling_window: false
 track_unknown_space: true
@@ -13,6 +13,7 @@ plugins:
 - {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"}
 # Can disable sensor layer if gmapping is fast enough to update scans
 - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+- {name: range_layer,   type: "range_sensor_layer::RangeSensorLayer"}
 - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
 
 static_layer:
@@ -21,6 +22,11 @@ static_layer:
   # map_topic: move_base/global_costmap/costmap
   subscribe_to_updates: true
 
+range_layer:
+  topics: ["/range_forward", "/range_backward"]
+  no_readings_timeout: 1.0
+  clear_on_max_reading: true
+
 explore_boundary:
   resize_to_boundary: false
   frontier_travel_point: middle
index 62b586d16818b9e558c9e7dfb60aff2179495784..29fc1bc3a1110422437cfafd1ce69f80657841ef 100644 (file)
@@ -10,10 +10,5 @@ local_costmap:
   resolution: 0.05
   plugins:
   - {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
-  #- {name: range_layer,   type: "range_sensor_layer::RangeSensorLayer"}
+  - {name: range_layer,   type: "range_sensor_layer::RangeSensorLayer"}
   - {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
-
-  range_layer:
-    topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"]
-    no_readings_timeout: 1.0
-    clear_on_max_reading: true
index 30f7ff1118caaa7e93aa8b51df49f12c7630f3f9..102f98dadb2639e63b42d40eadbc31c4e7a0f826 100644 (file)
@@ -8,13 +8,13 @@
        <!-- Run AMCL -->
        <group unless="$(arg nomap)">
                <!-- Run the map server -->
-               <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" unless="$(arg slam_gmapping)" />
+               <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen" unless="$(arg slam_gmapping)" />
 
                <include file="$(find amcl)/examples/amcl_diff.launch" unless="$(arg slam_gmapping)" />
                <param name="amcl/base_frame_id" value="base_footprint" />
        </group>
 
-       <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" output="screen" if="$(arg slam_gmapping)">
+       <node pkg="gmapping" type="slam_gmapping" name="slap_gmapping" if="$(arg slam_gmapping)">
                <param name="scan" value="scan" />
                <param name="delta" value="0.01" />
                <param name="map_update_interval" value="30" />