]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - launch/move_base.launch
Added full_coverage_path_planner launch file
[ros_wild_thumper.git] / launch / move_base.launch
index 33c5636f3cf9ffdb09eeb780b7ccc04440c5fe16..70974dc1d11bceec5d02268de3af7becf65002c1 100644 (file)
@@ -5,10 +5,11 @@
        <arg name="global_odom" default="false" />
        <arg name="close_to_obstacles" default="false" />
        <arg name="nomap" default="false" />
-       <arg name="base_global_planner" default="navfn/NavfnROS"/> <!-- navfn/NavfnROS || carrot_planner/CarrotPlanner -->
+       <arg name="base_global_planner" default="navfn/NavfnROS"/> <!-- navfn/NavfnROS || carrot_planner/CarrotPlanner || full_coverage_path_planner/SpiralSTC -->
        <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> <!-- base_local_planner/TrajectoryPlannerROS || dwa_local_planner/DWAPlannerROS || pose_follower/PoseFollower -->
        <!-- default: [{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]" -->
        <arg name="recovery_behaviors" default="[{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]"/>
+       <arg name="tool_radius" default="0.175"/>
 
        <!-- Run AMCL -->
        <group unless="$(arg nomap)">
@@ -50,6 +51,8 @@
                <param name="conservative_reset/affected_maps" value="local" />
                <param name="make_plan_clear_costmap" value="false" />
                <param name="make_plan_add_unreachable_goal" value="false" />
+               <param name="SpiralSTC/robot_radius" value="0.23" />
+               <param name="SpiralSTC/tool_radius" value="$(arg tool_radius)" />
                <rosparam param="recovery_behaviors" subst_value="True">$(arg recovery_behaviors)</rosparam>
                <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" />