-#must match incoming static map
+# must match incoming static map
global_frame: map
robot_base_frame: base_footprint
update_frequency: 5.0
+publish_frequency: 5.0
resolution: 0.01
rolling_window: false
plugins:
- {name: static_layer, type: 'costmap_2d::StaticLayer'}
- {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"}
-#Can disable sensor layer if gmapping is fast enough to update scans
+# Can disable sensor layer if gmapping is fast enough to update scans
- {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
- {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
+static_layer:
+ # Can pull data from gmapping, map_server or a non-rolling costmap
+ map_topic: /map
+ # map_topic: move_base/global_costmap/costmap
+ subscribe_to_updates: true
+
explore_boundary:
- resize_to_boundary: true
+ resize_to_boundary: false
frontier_travel_point: middle
- #set to false for gmapping, true if re-exploring a known area
+ # set to false for gmapping, true if re-exploring a known area
explore_clear_space: true
<launch>
<node pkg="frontier_exploration" type="explore_client" name="explore_client" output="screen"/>
- <node pkg="frontier_exploration" type="explore_server" name="explore_server" output="screen" >
+ <node pkg="frontier_exploration" type="explore_server" name="explore_server" output="screen">
<param name="frequency" type="double" value="2.0"/>
<!-- Should be less than sensor range -->
- <param name="goal_aliasing" type="double" value="2.0"/>
+ <param name="goal_aliasing" type="double" value="1.0"/>
<rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="explore_costmap" />
<rosparam file="$(find wild_thumper)/config/costmap_exploration.yaml" command="load" ns="explore_costmap" />
<param name="map_update_interval" value="30" />
<param name="linearUpdate" value="0.5" />
<param name="angularUpdate" value="0.25" />
- <param name="xmin" value="-1.0"/>
- <param name="ymin" value="-1.0"/>
- <param name="xmax" value="1.0"/>
- <param name="ymax" value="1.0"/>
+ <param name="xmin" value="-5.0"/>
+ <param name="ymin" value="-5.0"/>
+ <param name="xmax" value="5.0"/>
+ <param name="ymax" value="5.0"/>
<param name="odom_frame" value="odom"/>
</node>
#!/bin/sh
#
# Client:
-# socat PTY,link=/dev/ttyS4,mode=777 TCP:wildthumper:10001
+# socat PTY,link=/dev/ttyS4,raw,echo=0,mode=777 TCP:wildthumper:10001
socat /dev/ttyUSB0,b57600 TCP4-LISTEN:10001,reuseaddr