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