David Preiss / Mbed OS FINAL_PROJECT

Dependencies:   ExperimentServer QEI_pmw MotorShield

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers main.cpp Source File

main.cpp

00001 #include "mbed.h"
00002 #include "rtos.h"
00003 #include "EthernetInterface.h"
00004 #include "ExperimentServer.h"
00005 #include "QEI.h"
00006 #include "BezierCurve.h"
00007 #include "MotorShield.h" 
00008 #include "HardwareSetup.h"
00009 
00010 #define BEZIER_ORDER_JUMP    7
00011 #define BEZIER_ORDER_FLIGHT  7
00012 #define BEZIER_ORDER_LAND    7
00013 
00014 #define NUM_INPUTS (12 + 2*(BEZIER_ORDER_JUMP+1) + 2*(BEZIER_ORDER_FLIGHT+1) + 2*(BEZIER_ORDER_LAND+1) + 2*(BEZIER_ORDER_FLIGHT+1))
00015 #define NUM_OUTPUTS 19
00016 
00017 #define PULSE_TO_RAD (2.0f*3.14159f / 1200.0f)
00018 
00019 // Initializations
00020 Serial pc(USBTX, USBRX);    // USB Serial Terminal
00021 ExperimentServer server;    // Object that lets us communicate with MATLAB
00022 Timer t;                    // Timer to measure elapsed time of experiment
00023 
00024 QEI encoderA(PE_9,PE_11, NC, 1200, QEI::X4_ENCODING);  // MOTOR A ENCODER (no index, 1200 counts/rev, Quadrature encoding)
00025 QEI encoderB(PA_5, PB_3, NC, 1200, QEI::X4_ENCODING);  // MOTOR B ENCODER (no index, 1200 counts/rev, Quadrature encoding)
00026 QEI encoderC(PC_6, PC_7, NC, 1200, QEI::X4_ENCODING);  // MOTOR C ENCODER (no index, 1200 counts/rev, Quadrature encoding)
00027 QEI encoderD(PD_12, PD_13, NC, 1200, QEI::X4_ENCODING);// MOTOR D ENCODER (no index, 1200 counts/rev, Quadrature encoding)
00028 
00029 MotorShield motorShield(12000); //initialize the motor shield with a period of 12000 ticks or ~20kHZ
00030 Ticker currentLoop;
00031 
00032 // Variables for q1
00033 float current1;
00034 float current_des1 = 0;
00035 float prev_current_des1 = 0;
00036 float current_int1 = 0;
00037 float angle1;
00038 float velocity1;
00039 float duty_cycle1;
00040 float angle1_init;
00041 
00042 // Variables for q2
00043 float current2;
00044 float current_des2 = 0;
00045 float prev_current_des2 = 0;
00046 float current_int2 = 0;
00047 float angle2;
00048 float velocity2;
00049 float duty_cycle2;
00050 float angle2_init;
00051 
00052 // Fixed kinematic parameters
00053 const float l_OA=.03673; 
00054 const float l_OB=.06773; 
00055 const float l_AC=.096; 
00056 const float l_DE=.127-(l_OB-l_OA);
00057 
00058 // Timing parameters
00059 float current_control_period_us = 200.0f;     // 5kHz current control loop
00060 float impedance_control_period_us = 1000.0f;  // 1kHz impedance control loop
00061 float start_period, traj_period, end_period;
00062 float jump_period, flight_period, land_period;
00063 
00064 // Control parameters
00065 float current_Kp = 4.0f;         
00066 float current_Ki = 0.4f;           
00067 float current_int_max = 3.0f;       
00068 float duty_max;      
00069 float K_xx;
00070 float K_yy;
00071 float K_xy;
00072 float D_xx;
00073 float D_xy;
00074 float D_yy;
00075 
00076 // Model parameters
00077 float supply_voltage = 12;     // motor supply voltage
00078 float R = 2.0f;                // motor resistance
00079 float k_t = 0.18f;             // motor torque constant
00080 float nu = 0.0005;             // motor viscous friction
00081 
00082 // Foot Sensor Parameters
00083 bool airborne = 0;
00084 bool landCheck = false;
00085 uint8_t gaitState = 0;
00086 uint8_t hopCount = 0;
00087 uint8_t hopCountLim = 4; // 0 means 1 hop
00088 
00089 // Current control interrupt function
00090 void CurrentLoop()
00091 {
00092     // This loop sets the motor voltage commands using PI current controllers with feedforward terms.
00093     //use the motor shield as follows:
00094     //motorShield.motorAWrite(DUTY CYCLE, DIRECTION), DIRECTION = 0 is forward, DIRECTION =1 is backwards.
00095         
00096     current1 = -(((float(motorShield.readCurrentA())/65536.0f)*30.0f)-15.0f);           // measure current
00097     velocity1 = encoderA.getVelocity() * PULSE_TO_RAD;                                  // measure velocity        
00098     float err_c1 = current_des1 - current1;                                             // current errror
00099     current_int1 += err_c1;                                                             // integrate error
00100     current_int1 = fmaxf( fminf(current_int1, current_int_max), -current_int_max);      // anti-windup
00101     float ff1 = R*current_des1 + k_t*velocity1;                                         // feedforward terms
00102     duty_cycle1 = (ff1 + current_Kp*err_c1 + current_Ki*current_int1)/supply_voltage;   // PI current controller
00103     
00104     float absDuty1 = abs(duty_cycle1);
00105     if (absDuty1 > duty_max) {
00106         duty_cycle1 *= duty_max / absDuty1;
00107         absDuty1 = duty_max;
00108     }    
00109     if (duty_cycle1 < 0) { // backwards
00110         motorShield.motorAWrite(absDuty1, 1);
00111     } else { // forwards
00112         motorShield.motorAWrite(absDuty1, 0);
00113     }             
00114     prev_current_des1 = current_des1; 
00115     
00116     current2     = -(((float(motorShield.readCurrentB())/65536.0f)*30.0f)-15.0f);       // measure current
00117     velocity2 = encoderB.getVelocity() * PULSE_TO_RAD;                                  // measure velocity  
00118     float err_c2 = current_des2 - current2;                                             // current error
00119     current_int2 += err_c2;                                                             // integrate error
00120     current_int2 = fmaxf( fminf(current_int2, current_int_max), -current_int_max);      // anti-windup   
00121     float ff2 = R*current_des2 + k_t*velocity2;                                         // feedforward terms
00122     duty_cycle2 = (ff2 + current_Kp*err_c2 + current_Ki*current_int2)/supply_voltage;   // PI current controller
00123     
00124     float absDuty2 = abs(duty_cycle2);
00125     if (absDuty2 > duty_max) {
00126         duty_cycle2 *= duty_max / absDuty2;
00127         absDuty2 = duty_max;
00128     }    
00129     if (duty_cycle2 < 0) { // backwards
00130         motorShield.motorBWrite(absDuty2, 1);
00131     } else { // forwards
00132         motorShield.motorBWrite(absDuty2, 0);
00133     }             
00134     prev_current_des2 = current_des2; 
00135     
00136 }
00137 
00138 int main (void)
00139 {
00140     // Object for 7th order Cartesian foot trajectory
00141     BezierCurve rDesJump_bez(2,BEZIER_ORDER_JUMP);
00142     BezierCurve rDesFlight_bez(2,BEZIER_ORDER_FLIGHT);
00143     BezierCurve rDesLand_bez(2,BEZIER_ORDER_LAND);
00144     
00145     // Link the terminal with our server and start it up
00146     server.attachTerminal(pc);
00147     server.init();
00148     
00149     // Continually get input from MATLAB and run experiments
00150     float input_params[NUM_INPUTS];
00151     pc.printf("%f",input_params[0]);
00152     
00153     // Setup our foot sensor input
00154     DigitalIn  footContactPin(PC_6);
00155     
00156     // NOW WE STAY IN THIS WHILE STATEMENT FOREVER -------------------------------------------------------------------
00157     while(1) {
00158         // EVERYTHING IS NOW WAITING FOR SERIAL COMMUNICATION TO RUN BELOW, OTHERWISE WE ARE LOOPING THIS IF STATEMENT, this still only runs once per jump
00159         if (server.getParams(input_params,NUM_INPUTS)) {
00160             
00161             // Get inputs from MATLAB, note that these are formatted in Experiment_trajectory        
00162             gaitState = 0;
00163             landCheck = 0;
00164             start_period                = 1.5; // removed it as a parameter but we have a 1 second delay before starting the jump
00165             traj_period                 = 5.0;
00166             end_period                  = 1.0;
00167             jump_period                 = input_params[0];    // First buffer time, before trajectory
00168             flight_period               = input_params[1];    // Trajectory time/length
00169             land_period                 = input_params[2];    // Second buffer time, after trajectory
00170     
00171             angle1_init                 = input_params[3];    // Initial angle for q1 (rad)
00172             angle2_init                 = input_params[4];    // Initial angle for q2 (rad)
00173 
00174             K_xx                        = input_params[5];    // Foot stiffness N/m
00175             K_yy                        = input_params[6];    // Foot stiffness N/m
00176             K_xy                        = input_params[7];    // Foot stiffness N/m
00177             D_xx                        = input_params[8];    // Foot damping N/(m/s)
00178             D_yy                        = input_params[9];    // Foot damping N/(m/s)
00179             D_xy                        = input_params[10];   // Foot damping N/(m/s)
00180             duty_max                    = input_params[11];   // Maximum duty factor
00181           
00182             // Get foot trajectory points - start by initializing an empty array for each curve
00183             float jump_pts[2*(BEZIER_ORDER_JUMP+1)]; // foot_pts is a matrix sized for the bezier order
00184             float flight_pts[2*(BEZIER_ORDER_FLIGHT+1)]; 
00185             float land_pts[2*(BEZIER_ORDER_LAND+1)]; 
00186             
00187             // Now fill each array up with its respective points
00188             for(int i = 0; i<2*(BEZIER_ORDER_JUMP+1);i++) { 
00189                 jump_pts[i] = input_params[12+i];    // assign the proper input parameters to each foot position
00190                 flight_pts[i] = input_params[12+BEZIER_ORDER_JUMP+1 +i];
00191                 land_pts[i] = input_params[12+BEZIER_ORDER_JUMP+1 + BEZIER_ORDER_FLIGHT+1 +i];
00192                 // Adding this line to try and get the proper flight in
00193                 //flight_pts[i] = input_params[12+BEZIER_ORDER_JUMP+1 + BEZIER_ORDER_FLIGHT+1 + BEZIER_ORDER_FLIGHT+1 +i];
00194             }
00195             //pc.printf("%f" " = flight points \n\r",flight_pts[1]);
00196             //float flight_pts[2][8] = {{0.0651000,0.0650000,0.0650000,0.0417000,-0.0169000,-0.0700000,-0.0700000,-0.0700000},
00197             //{-0.215000,-0.215000,-0.215000,-0.159700,-0.147000,-0.175000,-0.175000,-0.175100}};
00198             
00199             flight_pts[0] = .065000;
00200             flight_pts[1] = -.215000;
00201             flight_pts[2] = .065000;
00202             flight_pts[3] = -.215000;
00203             flight_pts[4] = .065000;
00204             flight_pts[5] = -.215000;
00205             flight_pts[6] = .0417;
00206             flight_pts[7] = -.1597;
00207             flight_pts[8] = -.0169;
00208             flight_pts[9] = -.147;
00209             flight_pts[10] = -.0700000;
00210             flight_pts[11] = -.175;
00211             flight_pts[12] = -.0700000;
00212             flight_pts[13] = -.175;
00213             flight_pts[14] = -.0700000;
00214             flight_pts[15] = -.175;
00215             
00216             
00217             //pc.printf("%f" " = flight points \n\r",flight_pts[1]);
00218             
00219             rDesJump_bez.setPoints(jump_pts);
00220             rDesFlight_bez.setPoints(flight_pts);
00221             rDesLand_bez.setPoints(land_pts);
00222             
00223             // Attach current loop interrupt
00224             currentLoop.attach_us(CurrentLoop,current_control_period_us);
00225                         
00226             // Setup experiment
00227             t.reset();
00228             t.start();
00229             encoderA.reset();
00230             encoderB.reset();
00231             encoderC.reset();
00232             encoderD.reset();
00233 
00234             motorShield.motorAWrite(0, 0); //turn motor A off
00235             motorShield.motorBWrite(0, 0); //turn motor B off
00236             
00237             hopCount = 0;
00238                          
00239             // Run experiment HERE's THE REAL MAIN LOOP ---------------------------------------------------------------------------------------------------------------------------
00240             while(gaitState < 5) { 
00241             //while( t.read() < 8.0) { 
00242                 // Check to see if we are airborne or not, where airborne = 1 means we are not touching the ground
00243                 if(footContactPin == true) {
00244                     airborne = true;}
00245                 else {airborne = false;}
00246                 // pc.printf("%d" " = Airborne? \n\r",airborne); // confirmed to be working
00247                 
00248                 // Read encoders to get motor states
00249                 angle1 = encoderA.getPulses() *PULSE_TO_RAD + angle1_init;       
00250                 velocity1 = encoderA.getVelocity() * PULSE_TO_RAD;
00251                 angle2 = encoderB.getPulses() * PULSE_TO_RAD + angle2_init;       
00252                 velocity2 = encoderB.getVelocity() * PULSE_TO_RAD;           
00253                 
00254                 const float th1 = angle1;
00255                 const float th2 = angle2;
00256                 const float dth1= velocity1;
00257                 const float dth2= velocity2;
00258  
00259                 // Calculate the Jacobian
00260                 float Jx_th1 = l_AC*cos(th1 + th2) + l_DE*cos(th1) + l_OB*cos(th1);
00261                 float Jx_th2 = l_AC*cos(th1 + th2);
00262                 float Jy_th1 = l_AC*sin(th1 + th2) + l_DE*sin(th1) + l_OB*sin(th1);
00263                 float Jy_th2 = l_AC*sin(th1 + th2);
00264                                 
00265                 // Calculate the forward kinematics (position and velocity)
00266                 float xFoot = l_AC*sin(th1 + th2) + l_DE*sin(th1) + l_OB*sin(th1);
00267                 float yFoot = - l_AC*cos(th1 + th2) - l_DE*cos(th1) - l_OB*cos(th1);
00268                 float dxFoot = dth1*(l_AC*cos(th1 + th2) + l_DE*cos(th1) + l_OB*cos(th1)) + dth2*l_AC*cos(th1 + th2);
00269                 float dyFoot = dth1*(l_AC*sin(th1 + th2) + l_DE*sin(th1) + l_OB*sin(th1)) + dth2*l_AC*sin(th1 + th2);       
00270 
00271                 // Set gains based on buffer and traj times, then calculate desired x,y from Bezier trajectory at current time if necessary
00272                 float teff  = 0;
00273                 float vMult = 0;
00274                 
00275                 
00276                 // HERE IS WHERE WE CHECK WHERE WE ARE IN THE GAIT ----------------------------------------------------------------------------------------------
00277                 // gaitState 0 is just a buffer time before the jump holding the intial position
00278                 if( t < start_period) {
00279                     if (K_xx > 0 || K_yy > 0) {
00280                         K_xx = input_params[5];  // Foot stiffness N/m
00281                         K_yy = input_params[6];  // Foot stiffness N/m
00282                         K_xy = input_params[7];  // Foot stiffness N/m
00283                         D_xx = input_params[8];  // Foot damping N/(m/s)
00284                         D_yy = input_params[9];  // Foot damping N/(m/s)
00285                         D_xy = input_params[10]; // Foot damping N/(m/s)
00286                         gaitState = 0;
00287                     }
00288                     teff = 0;
00289                     //pc.printf("%f" " Start Phase \n\r",teff);
00290                 }
00291                 // Jump Phase = gait 1
00292                 else if (t < start_period + jump_period) {
00293                     // Lets only update the gains if we need to, this will be the last one for now
00294                     K_xx = input_params[5];  // Foot stiffness N/m
00295                     K_yy = input_params[6];  // Foot stiffness N/m
00296                     K_xy = input_params[7];  // Foot stiffness N/m
00297                     D_xx = input_params[8];  // Foot damping N/(m/s)
00298                     D_yy = input_params[9];  // Foot damping N/(m/s)
00299                     D_xy = input_params[10]; // Foot damping N/(m/s)
00300                     vMult = 1;
00301                     teff = (t - start_period);
00302                     gaitState = 1;
00303 //                    pc.printf("%f" " Jump Phase \n\r",teff);
00304                 }
00305                 // Flight Phase = gait 2, we should not be touching the ground here
00306                 // If t is lower than expected 
00307                 else if (t < start_period + jump_period + land_period + 1.6 && landCheck == false) {
00308                     teff = (t - start_period - jump_period);
00309                     gaitState = 2;
00310 //                    pc.printf("%f" " Flight Phase \n\r",teff);
00311                     
00312                     // If we land, or if we are 1 second past the expected flight phase, continue to the land gait
00313                     if (airborne == 0 || t > start_period + jump_period + flight_period + 1.5) { 
00314 //                        pc.printf("%f" " < FLIGHT PHASE OVER, AIRBORNE FOR THIS LONG \n\r",teff);
00315                         landCheck = true;
00316                         flight_period = (t - start_period - jump_period);
00317                         gaitState = 3;
00318                         teff = (t - start_period - jump_period - flight_period);
00319                     }
00320                 }
00321                 // Land Phase = gait 3
00322                 else if (gaitState == 3) {
00323                     teff = (t - start_period - jump_period - flight_period);
00324                     gaitState = 3;
00325 //                    pc.printf("%f" " Land Phase \n\r",teff);
00326                     if (t > start_period + jump_period + flight_period + land_period) {
00327                         gaitState = 4;
00328                         vMult = 0;
00329                     }
00330                 }
00331                 else {
00332                     if (hopCount <= hopCountLim) {
00333                         hopCount = hopCount + 1;
00334                         t.reset();
00335                         t.start();
00336                     }
00337                     else {
00338                         gaitState = 5;
00339                         vMult = 0;
00340                     }
00341                     hopCount = hopCount + 1;
00342                 }
00343                 
00344                 // Get desired foot positions and velocities                
00345                 float rDesFoot[2] , vDesFoot[2];
00346                 // Evaluate the correct gait (bezier curve) at the % detemined by how far into teff we are. There are 4 gaitStates...
00347                 if (gaitState == 0){
00348                     rDesFoot[0] = jump_pts[0];
00349                     rDesFoot[1] = jump_pts[1];
00350                     vDesFoot[0] = 0.0;
00351                     vDesFoot[1] = 0.0;
00352                 }
00353                 else if (gaitState == 1){
00354 //                    pc.printf("%d" " 1=JUMP \n\r",gaitState);
00355                     rDesJump_bez.evaluate(teff/jump_period, rDesFoot);
00356                     rDesJump_bez.evaluateDerivative(teff/jump_period, vDesFoot);
00357                     vDesFoot[0] /= jump_period;
00358                     vDesFoot[1] /= jump_period;
00359                 }
00360                 else if (gaitState == 2){
00361 //                   pc.printf("%d" " 2=FLIGHT \n\r",gaitState);
00362                     rDesFlight_bez.evaluate(teff/flight_period, rDesFoot);
00363                     rDesFlight_bez.evaluateDerivative(teff/flight_period, vDesFoot);
00364                     vDesFoot[0] /= flight_period;
00365                     vDesFoot[1] /= flight_period;
00366                     if (teff > jump_period) {
00367                         rDesFoot[0] = flight_pts[14];
00368                         rDesFoot[1] = flight_pts[15];
00369                         vDesFoot[0] = 0.0;
00370                         vDesFoot[1] = 0.0;
00371                     }
00372                 }
00373                 else if (gaitState == 3){
00374 //                    pc.printf("%d" " 3=LAND \n\r",gaitState);
00375                     rDesLand_bez.evaluate(teff/land_period, rDesFoot);
00376                     rDesLand_bez.evaluateDerivative(teff/land_period, vDesFoot);
00377                     vDesFoot[0] /= land_period;
00378                     vDesFoot[1] /= land_period;
00379                 }
00380                 // if we are past the trajectory period multiply by 0
00381                 vDesFoot[0]*=vMult; 
00382                 vDesFoot[1]*=vMult;
00383                 
00384                 // Calculate the inverse kinematics (joint positions and velocities) for desired joint angles              
00385                 float xFoot_inv = -rDesFoot[0];
00386                 float yFoot_inv = rDesFoot[1];                
00387                 float l_OE = sqrt( (pow(xFoot_inv,2) + pow(yFoot_inv,2)) );
00388                 float alpha = abs(acos( (pow(l_OE,2) - pow(l_AC,2) - pow((l_OB+l_DE),2))/(-2.0f*l_AC*(l_OB+l_DE)) ));
00389                 float th2_des = -(3.14159f - alpha); 
00390                 float th1_des = -((3.14159f/2.0f) + atan2(yFoot_inv,xFoot_inv) - abs(asin( (l_AC/l_OE)*sin(alpha) )));
00391                 
00392                 float dd = (Jx_th1*Jy_th2 - Jx_th2*Jy_th1);
00393                 float dth1_des = (1.0f/dd) * (  Jy_th2*vDesFoot[0] - Jx_th2*vDesFoot[1] );
00394                 float dth2_des = (1.0f/dd) * ( -Jy_th1*vDesFoot[0] + Jx_th1*vDesFoot[1] );
00395         
00396                 // Calculate error variables
00397                 float e_x = xFoot_inv - xFoot;
00398                 float e_y = yFoot_inv - yFoot;
00399                 float de_x = vDesFoot[0] - dxFoot;
00400                 float de_y = vDesFoot[1] - dyFoot;
00401         
00402                 // Calculate virtual force on foot
00403                 float fx = K_xx*(e_x) + K_xy*(e_y) + D_xx*(de_x) + D_xy*(de_y);
00404                 float fy = K_xy*(e_x) + K_yy*(e_y) + D_xy*(de_x) + D_yy*(de_y);
00405                 
00406                 float tau1 = Jx_th1*fx + Jy_th1*fy;
00407                 float tau2 = Jx_th2*fx + Jy_th2*fy;
00408                 
00409                 current_des1 = tau1/k_t;
00410                 current_des2 = tau2/k_t;
00411                 
00412                 // All of the above was to set these current_des values which will get fed into the CurrentLoop function running on an interrupt
00413                                                 
00414                 // Joint impedance
00415                 // sub Kxx for K1, Dxx for D1, Kyy for K2, Dyy for D2
00416                 // Note: Be careful with signs now that you have non-zero desired angles!
00417                 // Your equations should be of the form i_d = K1*(q1_d - q1) + D1*(dq1_d - dq1)
00418                 //current_des1 = (K_xx*(angle1_init - angle1) + D_xx*(0.0 - velocity1))/k_t;           
00419                 //current_des2 = (K_yy*(angle2_init - angle2) + D_yy*(0.0 - velocity2))/k_t;   
00420                 //current_des1 = 0;
00421                 //current_des2 = 0;
00422                      
00423                 // Cartesian impedance  
00424                 // Note: As with the joint space laws, be careful with signs!              
00425                 //current_des1 = (K_xx*(th1_des - angle1) + D_xx*(th1_des - velocity1))/k_t;           
00426                 //current_des2 = (K_yy*(th2_des - angle2) + D_yy*(th2_des - velocity2))/k_t;    
00427                 
00428                 
00429                 // Form output to send to MATLAB     
00430                 float output_data[NUM_OUTPUTS];
00431                 
00432                 // current time
00433                 output_data[0] = t.read();
00434                 // motor 1 state
00435                 output_data[1] = angle1;
00436                 output_data[2] = velocity1;  
00437                 output_data[3] = current1;
00438                 output_data[4] = current_des1;
00439                 output_data[5] = duty_cycle1;
00440                 // motor 2 state
00441                 output_data[6] = angle2;
00442                 output_data[7] = velocity2;
00443                 output_data[8] = current2;
00444                 output_data[9] = current_des2;
00445                 output_data[10]= duty_cycle2;
00446                 // foot state
00447                 output_data[11] = xFoot;
00448                 output_data[12] = yFoot;
00449                 output_data[13] = dxFoot;
00450                 output_data[14] = dyFoot;
00451                 output_data[15] = rDesFoot[0];
00452                 output_data[16] = rDesFoot[1];
00453                 output_data[17] = vDesFoot[0];
00454                 output_data[18] = vDesFoot[1];
00455                 
00456                 // Send data to MATLAB
00457                 server.sendData(output_data,NUM_OUTPUTS);
00458 
00459                 wait_us(impedance_control_period_us);   
00460             }
00461             
00462             // Cleanup after experiment
00463             server.setExperimentComplete();
00464             currentLoop.detach();
00465             motorShield.motorAWrite(0, 0); //turn motor A off
00466             motorShield.motorBWrite(0, 0); //turn motor B off
00467         
00468         } // end if
00469         
00470     } // end while
00471     
00472 } // end main
00473 
00474 /*
00475 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[0]);
00476 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[1]);
00477 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[2]);
00478 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[3]);
00479 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[4]);
00480 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[5]);
00481 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[6]);
00482 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[7]);
00483 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[8]);
00484 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[9]);
00485 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[10]);
00486 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[11]);
00487 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[12]);
00488 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[13]);
00489 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[14]);
00490 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[15]);
00491 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[16]);
00492 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[17]);
00493 pc.printf("%f" " OUTPUT DATA 0 \n\r",output_data[18]);
00494 */