(!) 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.

Track trajectory with base_link

Description: In this tutorial you will enable the track_base_link option and closely follow a trajectory defined by waypoints while stopping at them with desired acceleration and deceleration limits

Tutorial Level: INTERMEDIATE

Modify the launch file of the previous tutorial to track a trajectory with the base_link.

    <!-- Interpolator -->
    <node name="interpolator" pkg="tracking_pid" type="path_interpolator">
        <param name="target_x_vel" value="0.7"/>
        <param name="target_x_acc" value="0.5"/>
    </node>

    <!-- PID controller -->
    <node name="controller" pkg="tracking_pid" type="controller" output="screen">
      <remap from="move_base/cmd_vel" to="/move_base/cmd_vel"/>
      <remap from="local_trajectory" to="trajectory"/>
      <param name="controller_debug_enabled" value="True"/>
      <param name="l" value="0.5"/>
      <param name="track_base_link" value="True"/>
    </node>

Next, the trajectory to follow should then have properly defined the orientations of the poses to follow. An example is provided in the file coverage_with_orientation.yaml:

    <!-- Test path -->
    <node name="publish_path" pkg="rostopic" type="rostopic" args="pub --latch /path nav_msgs/Path --file=$(find tracking_pid)/trajectories/coverage_with_orientation.yaml"/>

If you launch the test again, you will see that now the robot stops on each corner and then turns in place before moving to the next corner. In this case each corner has two waypoints with same position and different orientation.

pid_tbl.png

Tune controller

In the previous simulation, on the straight lines it still seems that the robot is following the carrot at a distance. However this is not the case, as in the corners the robot reaches it correctly. To improve the tracking behavior, you can increase the proportional gain of the PID controller:

    <!-- PID controller -->
    <node name="controller" pkg="tracking_pid" type="controller" output="screen">
      <remap from="move_base/cmd_vel" to="/move_base/cmd_vel"/>
      <remap from="local_trajectory" to="trajectory"/>
      <param name="controller_debug_enabled" value="True"/>
      <param name="l" value="0.5"/>
      <param name="track_base_link" value="True"/>
      <param name="Kp_long" value="5.0"/>
    </node>

Relaunch the application and you will notice the robot frame follows more closely the moving pose. For a real experiment take into account that increasing Kp_long too much can cause the robot to have overshoot or oscillatory behavior.

Tune turning behavior interpolator

If desired, change the rotational acceleration and velocity values.

    <!-- Interpolator -->
    <node name="interpolator" pkg="tracking_pid" type="path_interpolator">
        <param name="target_x_vel" value="0.7"/>
        <param name="target_x_acc" value="0.5"/>
        <param name="target_yaw_vel" value="0.2"/>
        <param name="target_yaw_acc" value="0.1"/>
    </node>

This time the robot turns slower, which is also easier to follow by the controller.

Example with a Full Coverage Path Global Planner

You can also check the full_coverage_path_planner repository, which provides a global planner plugin to do full coverage path planning of a given map. In this tutorial you can see how to setup that application.

Wiki: tracking_pid/Tutorials/UseTrackBaseLink (last edited 2020-07-15 08:18:56 by César López)