Note: This tutorial assumes that you have completed the previous tutorials: Install.
(!) 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.

Setting up the differential_drive package PID controller

Description: This tutorial goes through setting up the differential_drive package and tuning the PID parameters

Tutorial Level: INTERMEDIATE

Next Tutorial: URDF differential_drive setup

Introduction

This tutorial will guide you through the steps to set up a robot to use the differential_drive package. I intended to make this package generic, but I've written the tutorial from the perspective of my hacked K'nex robot

Setup

Setting up a package and launch file

First, create a package for your robot, where [my_robot] is the name of your robot:

$ roscd
$ roscreate-pkg [my_robot] differential_drive
$ rosws set ~/fuerte_workspace/[my_robot]/
$ source /opt/ros/fuerte/setup.bash
$ roscd [my_robot]

Create a new launch file:

$ mkdir launch
$ touch launch/my_robot_drive.launch

Edit this file in your favorite editor to make it look like this:

   1 <launch>
   2   <!-- change this next line to include the launch file for your robot's hardware drivers: -->
   3   <include file="$(find knex_ros)/launch/knex_arduino_ser.launch" />
   4 
   5   <rosparam param="ticks_meter">70</rosparam>
   6 
   7   <node pkg="differential_drive" type="pid_velocity.py" name="lpid_velocity">
   8       <remap from="wheel" to="lwheel"/>
   9       <remap from="motor_cmd" to="lmotor_cmd"/>
  10       <remap from="wheel_vtarget" to="lwheel_vtarget"/>
  11       <remap from="wheel_vel" to="lwheel_vel"/>
  12       <rosparam param="Kp">200</rosparam>
  13       <rosparam param="Ki">200</rosparam>
  14       <rosparam param="Kd">0</rosparam>
  15       <rosparam param="out_min">-255</rosparam>
  16       <rosparam param="out_max">255</rosparam>
  17       <rosparam param="rate">30</rosparam>
  18       <rosparam param="timeout_ticks">4</rosparam>
  19       <rosparam param="rolling_pts">5</rosparam>
  20   </node>
  21   <node pkg="differential_drive" type="pid_velocity.py" name="rpid_velocity">
  22       <remap from="wheel" to="rwheel"/>
  23       <remap from="motor_cmd" to="rmotor_cmd"/>
  24       <remap from="wheel_vtarget" to="rwheel_vtarget"/>
  25       <remap from="wheel_vel" to="rwheel_vel"/>
  26       <rosparam param="Kp">200</rosparam>
  27       <rosparam param="Ki">200</rosparam>
  28       <rosparam param="Kd">0</rosparam>
  29       <rosparam param="out_min">-255</rosparam>
  30       <rosparam param="out_max">255</rosparam>
  31       <rosparam param="rate">30</rosparam>
  32       <rosparam param="timeout_ticks">4</rosparam>
  33       <rosparam param="rolling_pts">5</rosparam>
  34   </node>
  35 
  36   <node pkg="differential_drive" type="virtual_joystick.py" name="virtual_joystick" output="screen"/>
  37   <node pkg="differential_drive" type="twist_to_motors.py" name="twist_to_motors" output="screen">
  38     <rosparam param="base_width">0.245</rosparam>
  39   </node>
  40 
  41 </launch>

This launch file assumes your robot:

  • Takes commands for the wheel power on /lmotor_cmd and /rmotor_cmd

  • Publishes the wheel encoder on /lwheel and /rwheel

  • The base_width parameter should be set to the wheel spacing of your robot.

If this is not the case, you can change the mapping in the launch file.

As long as you meet these conditions, and the PID values are sane for your robot, you should be able to drive the robot around with the virtual joystick.

Calibrating the ticks per meter

In order for the odometry and PID controller to work correctly, they have to know how many wheel encoder ticks there are per meter of travel. You could calculate this value from the circumference of the wheel and the number of ticks per revolution but it's probably easier to:

  • Put two marks on the floor, 1 meter apart.
  • Launch the software to control the robot.
  • In another window type rostopic echo /lwheel to view the output of the encoder. Take note of the starting value.

  • Run rxplot with rxplot /lwheel/data -p 100 to get a graphical view of what's going on.

  • Drive the robot from the first mark to the second.
  • Record the end value of the encoder.
  • Take note of the number of times the encoder "wraps around" in rxgraph.
  • The ticks per meter will be equal to the total number of ticks received when the robot traveled one meter.
  • If your encoder wraps around, the equation will be: end - start + wrap_arounds * range

Optimizing the PID parameters

The Wikipedia PID controller page is a very good resource for PID controllers. The section on manual tuning gives some good advice.

Set the Ki and Kd parameters (in the .launch file) to 0.

Increase the Kp value until the wheel speed starts to oscillate.

  1. Just concentrate on one wheel at a time.
  2. Put the robot up with the wheels off the ground.
  3. It helps to comment out the virtual joystick node so you don't have to close it each time.
  4. Start with a low value of Kp (like 1).
  5. Launch the [my_robot].launch file.
  6. Use rxplot /lwheel_vtarget/data /lwheel_vel/data /lmotor_cmd/data -p 100 to plot the parameters.

  7. Use rostopic pub /lwheel_vtarget std_msgs/Float32 .5 -r 10 to drive the wheel to 0.5 meters/sec

  8. Use several different velocities, and see if there is any oscillation.
  9. Increase the Kp value and go back to step e.
  10. I increased Kp in steps of 10x to find the order of magnitude for Kp first, then went back and tried to narrow it down a little more.
  11. Set Kp to 1/2 of the value of the onset of oscillation.

Increase Ki until the wheel reaches full speed in a reasonable time

  1. Use the same method as when adjusting Kp.
  2. Here the rxplot really comes in handy.
  3. Setting Ki too high will result in oscillations.

Set Kd

  1. The Kd parameter is notoriously difficult to tune correctly, and I have left it at 0 for my robot, but it could be used to improve the time it takes for the wheel to reach its velocity after a disturbance.
  2. One method I tried for adjusting Kd was using my thumb to create some drag on the wheel while it's spinning, then releasing it, and watching the velocity overshoot. This wasn't very successful though, Kd didn't seem to make much of a difference.

Next: URDF setup for differential_drive

Wiki: differential_drive/tutorials/setup (last edited 2012-12-18 11:54:30 by JonStephan)