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
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
- {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:
# 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
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
<!-- 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" />