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

Description: In this tutorial you will setup the tracking pid to follow a trajectory at a desired constant velocity

Tutorial Level: BEGINNER

Next Tutorial: In the next 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 tracking_pid/Tutorials/UseTrackBaseLink

Basic usage

Please refer to the README.md file of the tracking_pid repository to learn about all parameters and their defaults. Important parameters are those of the interpolator node, since they determine how fast the reference global point (GP) moves along the trajectory.

The ros test file 'test_tracking_pid.test' is provided in the package as an example:

<launch>
    <arg name="rviz" default="false"/>

    <!-- Interpolator -->
    <node name="interpolator" pkg="tracking_pid" type="path_interpolator">
        <param name="target_x_vel" value="0.7"/>
        <param name="target_x_acc" value="100.0"/>
    </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"/>
    </node>

    <!-- Test path -->
    <node name="publish_path" pkg="rostopic" type="rostopic" args="pub --latch /path nav_msgs/Path --file=$(find tracking_pid)/trajectories/zigzag_short.yaml"/>
    <node pkg="tf" type="static_transform_publisher" args=" 0 0 0 0 0 0 map path_frame 100" name="path_frame_tfpub"/>

    <!-- Rviz -->
    <node if="$(arg rviz)" name="$(anon rviz)" pkg="rviz" type="rviz" args="-d $(find tracking_pid)/test/tracking_pid/controller.rviz" />

    <!-- Simulator -->
    <node pkg="mobile_robot_simulator" type="mobile_robot_simulator_node" name="fake_odometry" 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>

    <!-- test script -->
    <test test-name="rostest_tracking_pid_node" pkg="tracking_pid" type="test_tracking_pid_system.py" />

</launch>

You can launch the file as follows:

   roslaunch tracking_pid test_tracking_pid.test rviz:=true 

You will see a carrot moving across a zig-zag trajectory made out of three waypoints. The robot frame will follow the carrot at a distance determined by the parameter "l". Note that in this example we have set a high acceleration value for the interpolator. As a result, the carrot passes the waypoints seemingly not stopping.

pid_zigzag.png

Tune interpolator

Now, change the acceleration value,

    <!-- 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>

and relaunch the application. You will notice that the carrot decelerates until coming to a stop on each waypoint, then accelerates again until reaching the desired velocity.

Dynamic reconfigure

Most of parameters of the interpolator and the controller can be tuned dynamically using rqt_reconfigure. Run the following command

   rosrun rqt_reconfigure rqt_reconfigure

Two separate tabs are available for the interpolator and controller respectively.

Wiki: tracking_pid/Tutorials/BasicSetup (last edited 2020-07-15 07:27:23 by César López)