(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Basic Move Base Flex plugin setup

Description: In this tutorial you will learn how to use the full coverage global planner plugin for move base flex

Tutorial Level: BEGINNER

Next Tutorial: In the next tutorial the FCPP is used in combination with a trajectory tracker to let a robot fully cover a given map. full_coverage_path_planner/Tutorials/CombineWithTrackingPID

Basic Global Planner Plugin Setup

Please refer to the README.md file of the full_coverage_path_planner/ repository to learn about all parameters and their defaults.

The ros launch file 'test_full_coverage_path_planner_plugin.launch' is provided in the package as an example:

<launch>
    <arg name="map" default="$(find full_coverage_path_planner)/maps/grid.yaml"/>
    <arg name="robot_radius" default="0.3"/>
    <arg name="tool_radius" default="0.3"/>

    <!--Move base flex, using the full_coverage_path_planner-->
    <node pkg="mbf_costmap_nav" type="mbf_costmap_nav" respawn="false" name="move_base_flex" output="screen" required="true">
        <param name="tf_timeout" value="1.5"/>
        <rosparam file="$(find full_coverage_path_planner)/test/full_coverage_path_planner/param/planners.yaml" command="load" />
        <rosparam file="$(find full_coverage_path_planner)/test/full_coverage_path_planner/param/local_costmap_params.yaml" command="load" />

        <param name="SpiralSTC/robot_radius" value="$(arg robot_radius)"/>
        <param name="SpiralSTC/tool_radius" value="$(arg tool_radius)"/>
        <param name="global_costmap/robot_radius" value="$(arg robot_radius)"/>
        <remap from="odom" to="/odom"/>
        <remap from="scan" to="/scan"/>

        <remap from="/move_base_flex/SpiralSTC/plan" to="/move_base/SpiralSTC/plan"/>
        <remap from="/move_base_flex/tracking_pid/interpolator" to="/move_base/TrackingPidLocalPlanner/interpolator"/>
    </node>
    <!-- Move Base backwards compatibility -->
    <node pkg="mbf_costmap_nav" type="move_base_legacy_relay.py" name="move_base"/>

    <!--We need a map to fully cover-->
    <node name="grid_server" pkg="map_server" type="map_server" args="$(arg map)">
        <param name="frame_id" value="/map"/>
    </node>

    <!-- Mobile robot simulator -->
    <node pkg="mobile_robot_simulator" type="mobile_robot_simulator_node" name="mobile_robot_simulator" output="screen">
        <param name="publish_map_transform" value="true"/>
        <param name="publish_rate" value="10.0"/>
        <param name="velocity_topic" value="/move_base/cmd_vel"/>
        <param name="odometry_topic" value="/odom"/>
    </node>

    <!-- rviz -->
    <node name="rviz" pkg="rviz" type="rviz" args="-d $(find full_coverage_path_planner)/test/full_coverage_path_planner/fcpp.rviz" />
</launch>

Move base flex is configured to use the global planner plugin "full_coverage_path_planner/SpiralSTC" via the file "/test/full_coverage_path_planner/param/planners.yaml".

planners:
  - name: 'SpiralSTC'
    type: 'full_coverage_path_planner/SpiralSTC'

You can refer to the documentation of move_base_flex.

You can launch the file as follows:

   roslaunch full_coverage_path_planner test_full_coverage_path_planner_plugin.launch 

To trigger the planner, send any goal to the topic "/move_base/goal". Use for instance the corresponding rviz tool. You will see the generated full coverage path which fills up the space on the given map.

fcpp.png

On each corner there are two poses, indicating hoe the robot should rotate in place. The robot will not move because we have not yet setup a local motion planner.

Adjust tool radius

In practice many robots have a bigger footprint than their tool. Set the turning radius to a smaller value than robot radius:

    <arg name="robot_radius" default="0.3"/>
    <arg name="tool_radius" default="0.2"/>

and relaunch the application. You will notice the grid becomes finer in the free space and the path lies with enough distance away from walls.

fcpp_2.png

Wiki: full_coverage_path_planner/Tutorials/BasicSetup (last edited 2020-07-15 06:45:28 by César López)