## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0=[[http://www.ros.org/wiki/differential_drive/tutorials/Install|Install]] ## descriptive title for the tutorial ## title = Setting up the differential_drive package PID controller ## multi-line description to be displayed in search ## description = This tutorial goes through setting up the differential_drive package and tuning the PID parameters ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link=[[http://www.ros.org/wiki/differential_drive/tutorials/setup_urdf|URDF differential_drive setup]] ## next.1.link= ## what level user is this tutorial for ## level= IntermediateCategory ## keywords = #################################### <> <> = 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 [[https://code.google.com/p/knex-ros/|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: {{{#!xml 70 200 200 0 -255 255 30 4 5 200 200 0 -255 255 30 4 5 0.245 }}} 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 [[http://en.wikipedia.org/wiki/PID_controller|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: [[http://www.ros.org/wiki/differential_drive/tutorials/setup_urdf|URDF setup for differential_drive]] ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE