|
1 | 1 | <?xml version="1.0"?>
|
2 | 2 |
|
3 | 3 | <launch>
|
4 |
| - <arg name="map" default="$(find full_coverage_path_planner)/maps/basement.yaml"/> |
5 |
| - <arg name="target_x_vel" default="0.5"/> |
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"/> |
9 |
| - <arg name="launch_rviz" default="false"/> |
10 |
| - |
11 |
| - <!--Move base flex, using the full_coverage_path_planner--> |
12 |
| - <node pkg="mbf_costmap_nav" type="mbf_costmap_nav" respawn="false" name="move_base_flex" output="screen" required="true"> |
13 |
| - <param name="tf_timeout" value="1.5"/> |
14 |
| - <param name="planner_max_retries" value="3"/> |
15 |
| - <rosparam file="$(find full_coverage_path_planner)/test/full_coverage_path_planner/param/planners.yaml" command="load" /> |
16 |
| - <rosparam file="$(find full_coverage_path_planner)/test/full_coverage_path_planner/param/local_costmap_params.yaml" command="load" /> |
17 |
| - |
18 |
| - <param name="SpiralSTC/robot_radius" value="$(arg robot_radius)"/> |
19 |
| - <param name="SpiralSTC/tool_radius" value="$(arg tool_radius)"/> |
20 |
| - <param name="global_costmap/robot_radius" value="$(arg robot_radius)"/> |
21 |
| - <remap from="odom" to="/odom"/> |
22 |
| - <remap from="scan" to="/scan"/> |
23 |
| - |
24 |
| - <remap from="/move_base_flex/SpiralSTC/plan" to="/move_base/SpiralSTC/plan"/> |
25 |
| - <remap from="/move_base_flex/tracking_pid/interpolator" to="/move_base/TrackingPidLocalPlanner/interpolator"/> |
26 |
| - </node> |
27 |
| - <!-- Move Base backwards compatibility --> |
28 |
| - <node pkg="mbf_costmap_nav" type="move_base_legacy_relay.py" name="move_base"/> |
29 |
| - |
30 |
| - <!--Rather than running Gazebo to simulate a robot, just use cmd_vel to calculate odom and TF--> |
31 |
| - <node pkg="mobile_robot_simulator" type="mobile_robot_simulator_node" name="mobile_robot_simulator" output="screen"> |
32 |
| - <param name="publish_map_transform" value="true"/> |
33 |
| - <param name="publish_rate" value="10.0"/> |
34 |
| - <param name="velocity_topic" value="/move_base/cmd_vel"/> |
35 |
| - <param name="odometry_topic" value="/odom"/> |
36 |
| - </node> |
37 |
| - |
38 |
| - <!--We need a map to fully cover--> |
39 |
| - <node name="grid_server" pkg="map_server" type="map_server" args="$(arg map)"> |
40 |
| - <param name="frame_id" value="/map"/> |
41 |
| - </node> |
42 |
| - |
43 |
| - <!--Tracking_pid cannot just accept a nav_msgs/Path, it can only go to a PoseStamped, |
44 |
| - so the path_interpolator drags a PoseStamped over a Path at a given speed--> |
45 |
| - <node name="interpolator" pkg="tracking_pid" type="path_interpolator"> |
46 |
| - <param name="target_x_vel" value="$(arg target_x_vel)"/> |
47 |
| - <param name="target_yaw_vel" value="$(arg target_yaw_vel)"/> |
48 |
| - <remap from="path" to="/move_base/SpiralSTC/plan"/> |
49 |
| - </node> |
50 |
| - |
51 |
| - <!--Tracking_pid tries to get the robot as close to it's goal point as possible--> |
52 |
| - <node name="controller" pkg="tracking_pid" type="controller" output="screen"> |
53 |
| - <remap from="move_base/cmd_vel" to="/move_base/cmd_vel"/> |
54 |
| - <remap from="local_trajectory" to="trajectory"/> |
55 |
| - <param name="controller_debug_enabled" value="True"/> |
56 |
| - <param name="track_base_link" value="true"/> |
57 |
| - <param name="l" value="0.5"/> |
58 |
| - <param name="Ki_long" value="0.0"/> |
59 |
| - <param name="Kp_long" value="2.0"/> |
60 |
| - <param name="Kd_long" value="0.5"/> |
61 |
| - <param name="Ki_lat" value="0.0"/> |
62 |
| - <param name="Kp_lat" value="4.0"/> |
63 |
| - <param name="Kd_lat" value="0.3"/> |
64 |
| - </node> |
65 |
| - |
66 |
| - <!-- Launch coverage progress tracking --> |
67 |
| - <node pkg="tf" type="static_transform_publisher" name="map_to_coveragemap" args="3 -0.25 0 1.57 0 0 map coverage_map 100" /> |
68 |
| - <node pkg="full_coverage_path_planner" type="coverage_progress" name="coverage_progress"> |
69 |
| - <param name="~target_area/x" value="3.0" /> <!--20--> |
70 |
| - <param name="~target_area/y" value="5" /> <!--30--> |
71 |
| - <param name="~coverage_radius" value="$(arg tool_radius)" /> |
72 |
| - <remap from="reset" to="coverage_progress/reset" /> |
73 |
| - <param name="~map_frame" value="/coverage_map"/> |
74 |
| - </node> |
75 |
| - |
76 |
| - <!--Tracking_pid can be paused and it must be actively unpaused--> |
77 |
| - <node name="publish_enable" pkg="rostopic" type="rostopic" args="pub --latch /enable_control std_msgs/Bool 'data: true'"/> |
78 |
| - |
79 |
| - <node name="publish_simple_goal" pkg="rostopic" type="rostopic" launch-prefix="bash -c 'sleep 1.0; $0 $@' " |
80 |
| - args="pub --latch /move_base/goal move_base_msgs/MoveBaseActionGoal --file=$(find full_coverage_path_planner)/test/simple_goal.yaml"/> |
| 4 | + <arg name="rviz" default="false"/> |
| 5 | + |
| 6 | + <include file="$(find full_coverage_path_planner)/test/full_coverage_path_planner/test_full_coverage_path_planner.launch" > |
| 7 | + <arg name="map" value="$(find full_coverage_path_planner)/maps/basement.yaml"/> |
| 8 | + <arg name="coverage_area_offset" value="3 -0.25 0 1.57 0 0"/> |
| 9 | + <arg name="coverage_area_size_x" value="3.0"/> |
| 10 | + <arg name="coverage_area_size_y" value="5.0"/> |
| 11 | + <arg name="target_x_vel" value="0.5"/> |
| 12 | + <arg name="target_yaw_vel" value="0.4"/> |
| 13 | + <arg name="robot_radius" value="0.5"/> |
| 14 | + <arg name="tool_radius" value="0.5"/> |
| 15 | + <arg name="rviz" value="$(eval rviz)"/> |
| 16 | + </include> |
81 | 17 |
|
82 | 18 | <test test-name="rostest_full_coverage_path_planner_node" pkg="full_coverage_path_planner" type="test_full_coverage_path_planner_system.py" time-limit="300.0" />
|
83 | 19 |
|
84 |
| - <node if="$(eval launch_rviz)" name="rviz" pkg="rviz" type="rviz" args="-d $(find full_coverage_path_planner)/test/full_coverage_path_planner/fcpp.rviz" /> |
85 | 20 | </launch>
|
0 commit comments