|
1 | 1 | <?xml version="1.0"?>
|
2 | 2 |
|
3 | 3 | <launch>
|
4 |
| - <arg name="map" default="$(find full_coverage_path_planner)/maps/basement.yaml"/> |
| 4 | + <arg name="map" default="$(find full_coverage_path_planner)/maps/grid.yaml"/> |
5 | 5 | <arg name="target_x_vel" default="0.5"/>
|
6 | 6 | <arg name="target_yaw_vel" default="0.4"/>
|
7 |
| - <arg name="robot_radius" default="0.5"/> |
8 |
| - <arg name="tool_radius" default="0.5"/> |
| 7 | + <arg name="robot_radius" default="0.3"/> |
| 8 | + <arg name="tool_radius" default="0.3"/> |
9 | 9 |
|
10 | 10 | <!--Move base flex, using the full_coverage_path_planner-->
|
11 | 11 | <node pkg="mbf_costmap_nav" type="mbf_costmap_nav" respawn="false" name="move_base_flex" output="screen" required="true">
|
12 | 12 | <param name="tf_timeout" value="1.5"/>
|
13 |
| - <param name="planner_max_retries" value="3"/> |
14 | 13 | <rosparam file="$(find full_coverage_path_planner)/test/full_coverage_path_planner/param/planners.yaml" command="load" />
|
15 | 14 | <rosparam file="$(find full_coverage_path_planner)/test/full_coverage_path_planner/param/local_costmap_params.yaml" command="load" />
|
16 |
| - |
17 | 15 | <param name="SpiralSTC/robot_radius" value="$(arg robot_radius)"/>
|
18 | 16 | <param name="SpiralSTC/tool_radius" value="$(arg tool_radius)"/>
|
19 | 17 | <param name="global_costmap/robot_radius" value="$(arg robot_radius)"/>
|
|
26 | 24 | <!-- Move Base backwards compatibility -->
|
27 | 25 | <node pkg="mbf_costmap_nav" type="move_base_legacy_relay.py" name="move_base"/>
|
28 | 26 |
|
29 |
| - <!--Rather than running Gazebo to simulate a robot, just use cmd_vel to calculate odom and TF--> |
| 27 | + <!-- Mobile robot simulator --> |
30 | 28 | <node pkg="mobile_robot_simulator" type="mobile_robot_simulator_node" name="mobile_robot_simulator" output="screen">
|
31 | 29 | <param name="publish_map_transform" value="true"/>
|
32 | 30 | <param name="publish_rate" value="10.0"/>
|
|
63 | 61 | </node>
|
64 | 62 |
|
65 | 63 | <!-- Launch coverage progress tracking -->
|
66 |
| - <node pkg="tf" type="static_transform_publisher" name="map_to_coveragemap" args="3 -0.25 0 1.57 0 0 map coverage_map 100" /> |
| 64 | + <node pkg="tf" type="static_transform_publisher" name="map_to_coveragemap" args="-2.5 -2.5 0 0.0 0 0 map coverage_map 100" /> |
67 | 65 | <node pkg="full_coverage_path_planner" type="coverage_progress" name="coverage_progress">
|
68 |
| - <param name="~target_area/x" value="3.0" /> <!--20--> |
69 |
| - <param name="~target_area/y" value="5" /> <!--30--> |
| 66 | + <param name="~target_area/x" value="10" /> |
| 67 | + <param name="~target_area/y" value="10" /> |
70 | 68 | <param name="~coverage_radius" value="$(arg tool_radius)" />
|
71 | 69 | <remap from="reset" to="coverage_progress/reset" />
|
72 | 70 | <param name="~map_frame" value="/coverage_map"/>
|
73 | 71 | </node>
|
74 | 72 |
|
75 |
| - <!--Tracking_pid can be paused and it must be actively unpaused--> |
76 |
| - <node name="publish_enable" pkg="rostopic" type="rostopic" args="pub --latch /enable_control std_msgs/Bool 'data: true'"/> |
77 |
| - |
| 73 | + <!-- Trigger planner by publishing a move_base goal --> |
78 | 74 | <node name="publish_simple_goal" pkg="rostopic" type="rostopic" launch-prefix="bash -c 'sleep 1.0; $0 $@' "
|
79 | 75 | args="pub --latch /move_base/goal move_base_msgs/MoveBaseActionGoal --file=$(find full_coverage_path_planner)/test/simple_goal.yaml"/>
|
80 | 76 |
|
| 77 | + <!-- rviz --> |
81 | 78 | <node name="rviz" pkg="rviz" type="rviz" args="-d $(find full_coverage_path_planner)/test/full_coverage_path_planner/fcpp.rviz" />
|
82 | 79 | </launch>
|
0 commit comments