TrajectoryPlannerROS:
min_vel_x: 0.2
- max_vel_x: 0.3
- min_vel_theta: -0.4
- max_vel_theta: 0.4
+ max_vel_x: 0.5
+ min_vel_theta: -1.0
+ max_vel_theta: 1.0
min_in_place_vel_theta: 0.4
- max_rotational_vel: 0.5 # used by rotate recovery
+ max_rotational_vel: 1.0 # used by rotate recovery
acc_lim_x: 10.07
acc_lim_y: 0.0
max_trans_vel: 0.5
min_trans_vel: 0.2
- max_rot_vel: 0.5
+ max_rot_vel: 1.0
min_rot_vel: 0.4
- xy_goal_tolerance: 0.20
- yaw_goal_tolerance: 0.3
+ xy_goal_tolerance: 0.1
+ yaw_goal_tolerance: 0.2
footprint: [[0.14, 0.16], [-0.14, 0.16], [-0.14, -0.16], [0.14, -0.16]]
-inflation_radius: 0.5
obstacle_layer:
observation_sources: laser_scan_sensor
obstacle_range: 2.5
raytrace_range: 3.0
laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true}
+
+inflation_layer:
+ inflation_radius: 0.5
#must match incoming static map
global_frame: map
-robot_base_frame: base_link
-resolution: 0.05
+robot_base_frame: base_footprint
+update_frequency: 5.0
+resolution: 0.01
-track_unknown_space: true
rolling_window: false
+track_unknown_space: true
plugins:
-- {name: static, type: "costmap_2d::StaticLayer"}
+- {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
-- {name: sensor, type: "costmap_2d::ObstacleLayer"}
-- {name: inflation, type: "costmap_2d::InflationLayer"}
+- {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'}
+- {name: inflation_layer, type: 'costmap_2d::InflationLayer'}
explore_boundary:
- resize_to_boundary: false
+ resize_to_boundary: true
frontier_travel_point: middle
#set to false for gmapping, true if re-exploring a known area
- explore_clear_space: false
+ explore_clear_space: true
<node pkg="frontier_exploration" type="explore_client" name="explore_client" output="screen"/>
<node pkg="frontier_exploration" type="explore_server" name="explore_server" output="screen" >
- <param name="frequency" type="double" value="1.0"/>
+ <param name="frequency" type="double" value="2.0"/>
<!-- Should be less than sensor range -->
<param name="goal_aliasing" type="double" value="2.0"/>
<arg name="slam_gmapping" default="false" />
<arg name="map_file" default="$(find wild_thumper)/data/map.yaml" />
<arg name="nomap" default="false" />
- <arg name="base_local_planner" default="dwa_local_planner/DWAPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
+ <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS -->
<!-- Run AMCL -->
<group unless="$(arg nomap)">
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="$(arg base_local_planner)"/>
+ <param name="controller_frequency" value="10.0" />
<rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find wild_thumper)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find wild_thumper)/config/global_costmap_params.yaml" command="load" unless="$(arg nomap)" />
<link name="base_footprint">
<visual>
<geometry>
- <box size="0.28 0.31 0.0"/>
+ <box size="0.28 0.31 0.000001"/>
</geometry>
<material name="grey">
<color rgba="0.5 0.5 0.5 0.5"/>