00001 /* 00002 ArbotiX Firmware for ROS driver 00003 Copyright (c) 2009-2011 Vanadium Labs LLC. All right reserved. 00004 00005 Redistribution and use in source and binary forms, with or without 00006 modification, are permitted provided that the following conditions are met: 00007 * Redistributions of source code must retain the above copyright 00008 notice, this list of conditions and the following disclaimer. 00009 * Redistributions in binary form must reproduce the above copyright 00010 notice, this list of conditions and the following disclaimer in the 00011 documentation and/or other materials provided with the distribution. 00012 * Neither the name of Vanadium Labs LLC nor the names of its 00013 contributors may be used to endorse or promote products derived 00014 from this software without specific prior written permission. 00015 00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00019 DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT, 00020 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 00021 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, 00022 OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF 00023 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE 00024 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 00025 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 */ 00027 00028 #include <WProgram.h> 00029 #include <math.h> 00030 00031 /* Register Storage */ 00032 int left_pwm; 00033 int right_pwm; 00034 int left_speed; 00035 int right_speed; 00036 00037 /* PID Parameters */ 00038 int Kp; 00039 int Kd; 00040 int Ki; 00041 int Ko; // output scale 00042 int maxAccel; // maximum acceleration per frame (ticks) 00043 00044 /* PID modes */ 00045 unsigned int PIDmode; 00046 #define PID_NONE 0 00047 #define PID_SPEED 1 00048 00049 #define FRAME_RATE 33 // frame rate in millis (30Hz) 00050 #define FRAMES 30 00051 unsigned long f_time; // last frame 00052 00053 unsigned char moving = 0; // base in motion 00054 unsigned char paused = 0; // base was in motion, can resume 00055 #define MAXOUTPUT 255 // motor PWM 00056 00057 /* Setpoint Info For a Motor */ 00058 typedef struct{ 00059 int Velocity; // desired actual speed (count/frame) 00060 long Encoder; // actual reading 00061 long PrevEnc; // last reading 00062 int PrevErr; 00063 int Ierror; 00064 int output; // last motor setting 00065 } SetPointInfo; 00066 00067 SetPointInfo left, right; 00068 00069 /* Initialize PID parameters to something known */ 00070 void setupPID(){ 00071 // Default values for the PR-MINI 00072 Kp = 25; 00073 Kd = 30; 00074 Ki = 0; 00075 Ko = 100; 00076 maxAccel = 50; 00077 f_time = 0; 00078 } 00079 00080 /* PID control of motor speed */ 00081 void DoPid(SetPointInfo * p){ 00082 long Perror; 00083 long output; 00084 00085 Perror = p->Velocity - (p->Encoder-p->PrevEnc); 00086 00087 // Derivative error is the delta Perror 00088 output = (Kp*Perror + Kd*(Perror - p->PrevErr) + Ki*p->Ierror)/Ko; 00089 p->PrevErr = Perror; 00090 p->PrevEnc = p->Encoder; 00091 00092 output += p->output; 00093 // Accumulate Integral error *or* Limit output. 00094 // Stop accumulating when output saturates 00095 if (output >= MAXOUTPUT) 00096 output = MAXOUTPUT; 00097 else if (output <= -MAXOUTPUT) 00098 output = -MAXOUTPUT; 00099 else 00100 p->Ierror += Perror; 00101 00102 p->output = output; 00103 } 00104 00105 /* Clear accumulators */ 00106 void ClearPID(){ 00107 PIDmode = 0; moving = 0; 00108 left.PrevErr = 0; 00109 left.Ierror = 0; 00110 left.output = 0; 00111 right.PrevErr = 0; 00112 right.Ierror = 0; 00113 right.output = 0; 00114 } 00115 00116 /* This is called by the main loop, does a X HZ PID loop. */ 00117 void updatePID(){ 00118 if((moving > 0) && (PIDmode > 0)){ // otherwise, just return 00119 unsigned long j = millis(); 00120 if(j > f_time){ 00121 // update encoders 00122 left.Encoder = Encoders.left; 00123 right.Encoder = Encoders.right; 00124 // do PID update on PWM 00125 DoPid(&left); 00126 DoPid(&right); 00127 // set updated motor outputs 00128 if(PIDmode > 0){ 00129 drive.set(left.output, right.output); 00130 } 00131 // update timing 00132 f_time = j + FRAME_RATE; 00133 } 00134 } 00135 } 00136 00137 void clearAll(){ 00138 PIDmode = 0; 00139 left.Encoder = 0; 00140 right.Encoder = 0; 00141 left.PrevEnc = 0; 00142 right.PrevEnc = 0; 00143 left.output = 0; 00144 right.output = 0; 00145 Encoders.Reset(); 00146 } 00147