NOT FINISHED YET!!! My first try to get a self built fully working Quadrocopter based on an mbed, a self built frame and some other more or less cheap parts.

Dependencies:   mbed MODI2C

Files at this revision

API Documentation at this revision

Comitter:
maetugr
Date:
Sat Nov 17 11:49:21 2012 +0000
Parent:
20:e116e596e540
Child:
22:d301b455a1ad
Commit message:
Erster Flugtest, noch nicht stabil!

Changed in this revision

RC/RC_Channel.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/Acc/ADXL345.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/Comp/HMC5883.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/Gyro/L3G4200D.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/Gyro/L3G4200D.h Show annotated file Show diff for this revision Revisions of this file
Sensors/I2C_Sensor.cpp Show annotated file Show diff for this revision Revisions of this file
Sensors/I2C_Sensor.h Show annotated file Show diff for this revision Revisions of this file
Servo_PWM/Servo_PWM.cpp Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/RC/RC_Channel.cpp	Mon Nov 05 09:19:01 2012 +0000
+++ b/RC/RC_Channel.cpp	Sat Nov 17 11:49:21 2012 +0000
@@ -3,7 +3,7 @@
 
 RC_Channel::RC_Channel(PinName mypin) : myinterrupt(mypin)
 {
-    time = -1; // start value to see if there was any value yet
+    time = -100; // start value to see if there was any value yet
     myinterrupt.rise(this, &RC_Channel::rise);
     myinterrupt.fall(this, &RC_Channel::fall);
     timeoutchecker.attach(this, &RC_Channel::timeoutcheck, 1);
@@ -25,7 +25,7 @@
     timer.stop();
     int tester = timer.read_us();
     if(tester >= 1000 && tester <=2000)
-        time = (tester-70);  // TODO: skalierung mit calibrierung (speichern....)
+        time = (tester-70)-1000;  // TODO: skalierung mit calibrierung (speichern....)
     timer.reset();
     timer.start();
 }
@@ -33,5 +33,5 @@
 void RC_Channel::timeoutcheck()
 {
     if (timer.read() > 0.3)
-        time = 0;
+        time = -100;
 }
\ No newline at end of file
--- a/Sensors/Acc/ADXL345.cpp	Mon Nov 05 09:19:01 2012 +0000
+++ b/Sensors/Acc/ADXL345.cpp	Sat Nov 17 11:49:21 2012 +0000
@@ -1,8 +1,6 @@
 #include "ADXL345.h"
-#include "mbed.h"
 
 ADXL345::ADXL345(PinName sda, PinName scl) : i2c(sda, scl) {
-
     //400kHz, allowing us to use the fastest data rates.
     //there are other chips on board, sorry
     i2c.frequency(400000);   
@@ -11,7 +9,6 @@
     tx[0] = ADXL345_BW_RATE_REG;
     tx[1] = ADXL345_1600HZ; //value greater than or equal to 0x0A is written into the rate bits (Bit D3 through Bit D0) in the BW_RATE register 
     i2c.write( ADXL345_WRITE , tx, 2);  
-
     //Data format (for +-16g) - This is done by setting Bit D3 of the DATA_FORMAT register (Address 0x31) and writing a value of 0x03 to the range bits (Bit D1 and Bit D0) of the DATA_FORMAT register (Address 0x31).
    
  char rx[2];
--- a/Sensors/Comp/HMC5883.cpp	Mon Nov 05 09:19:01 2012 +0000
+++ b/Sensors/Comp/HMC5883.cpp	Sat Nov 17 11:49:21 2012 +0000
@@ -32,8 +32,8 @@
     {
         readraw();
         for(int i = 0; i < 3; i++) {
-            Min[i]= Min[i] < raw[i] ? Min[i] : raw[i];      // after each measurement check if there's a new minimum or maximum
-            Max[i]= Max[i] > raw[i] ? Max[i] : raw[i];
+            Min[i] = Min[i] < raw[i] ? Min[i] : raw[i];      // after each measurement check if there's a new minimum or maximum
+            Max[i] = Max[i] > raw[i] ? Max[i] : raw[i];
         }
     }
     
--- a/Sensors/Gyro/L3G4200D.cpp	Mon Nov 05 09:19:01 2012 +0000
+++ b/Sensors/Gyro/L3G4200D.cpp	Sat Nov 17 11:49:21 2012 +0000
@@ -27,22 +27,7 @@
     
     writeRegister(L3G4200D_CTRL_REG1, 0x0F);            // starts Gyro measurement
     
-    // calibrate gyro with an average of count samples (result of calibration stored in offset[])
-    for (int j = 0; j < 3; j++)
-            offset[j] = 0;
-            
-    float Gyro_calib[3] = {0,0,0};                      // temporary var for the sum of calibration measurement
-    
-    const int count = 50;
-    for (int i = 0; i < count; i++) {                   // read 50 times the data in a very short time
-        readraw();
-        for (int j = 0; j < 3; j++)
-            Gyro_calib[j] += raw[j];
-        wait(0.001);          // TODO: maybe less or no wait !!
-    }
-    
-    for (int j = 0; j < 3; j++)
-        offset[j] = Gyro_calib[j]/count;                // take the average of the calibration measurements
+    calibrate();
 }
 
 void L3G4200D::read()
@@ -67,4 +52,21 @@
     raw[0] = (short) (buffer[1] << 8 | buffer[0]);     // join 8-Bit pieces to 16-bit short integers
     raw[1] = (short) (buffer[3] << 8 | buffer[2]);
     raw[2] = (short) (buffer[5] << 8 | buffer[4]);
+}
+
+void L3G4200D::calibrate()
+{
+    // calibrate gyro with an average of count samples (result of calibration stored in offset[])
+    float Gyro_calib[3] = {0,0,0};                      // temporary var for the sum of calibration measurement
+    
+    const int count = 50;
+    for (int i = 0; i < count; i++) {                   // read 50 times the data in a very short time
+        readraw();
+        for (int j = 0; j < 3; j++)
+            Gyro_calib[j] += raw[j];
+        wait(0.001);          // TODO: maybe less or no wait !!
+    }
+    
+    for (int i = 0; i < 3; i++)
+        offset[i] = Gyro_calib[i]/count;                // take the average of the calibration measurements
 }
\ No newline at end of file
--- a/Sensors/Gyro/L3G4200D.h	Mon Nov 05 09:19:01 2012 +0000
+++ b/Sensors/Gyro/L3G4200D.h	Sat Nov 17 11:49:21 2012 +0000
@@ -45,6 +45,7 @@
     public:            
         L3G4200D(PinName sda, PinName scl); // constructor, uses I2C_Sensor class
         virtual void read();                // read all axis from register to array data
+        void calibrate();                   // calibrate the gyro (get an offset while not moving)
         int readTemp();                     // read temperature from sensor
         
     private:
--- a/Sensors/I2C_Sensor.cpp	Mon Nov 05 09:19:01 2012 +0000
+++ b/Sensors/I2C_Sensor.cpp	Sat Nov 17 11:49:21 2012 +0000
@@ -4,7 +4,7 @@
 #define GET_I2C_WRITE_ADDRESS(ADR)  (ADR << 1&0xFE) // ADR & 1111 1110
 #define GET_I2C_READ_ADDRESS(ADR)   (ADR << 1|0x01) // ADR | 0000 0001
 
-I2C_Sensor::I2C_Sensor(PinName sda, PinName scl, int8_t i2c_address) :  i2c(sda, scl), local("local")
+I2C_Sensor::I2C_Sensor(PinName sda, PinName scl, char i2c_address) :  i2c(sda, scl), local("local")
 {
     I2C_Sensor::i2c_address = i2c_address;
     i2c.frequency(400000); // standard speed
--- a/Sensors/I2C_Sensor.h	Mon Nov 05 09:19:01 2012 +0000
+++ b/Sensors/I2C_Sensor.h	Sat Nov 17 11:49:21 2012 +0000
@@ -8,7 +8,7 @@
 class I2C_Sensor
 {           
     public:
-        I2C_Sensor(PinName sda, PinName scl, int8_t address);
+        I2C_Sensor(PinName sda, PinName scl, char address);
         
         float data[3];                  // where the measured data is saved
         virtual void read() = 0;        // read all axis from register to array data
@@ -30,7 +30,7 @@
         
     private:
         I2C i2c;            // I2C-Bus
-        int8_t i2c_address; // address
+        char i2c_address;   // address
         
         LocalFileSystem local; // file access to save calibration values
 };
--- a/Servo_PWM/Servo_PWM.cpp	Mon Nov 05 09:19:01 2012 +0000
+++ b/Servo_PWM/Servo_PWM.cpp	Sat Nov 17 11:49:21 2012 +0000
@@ -4,18 +4,16 @@
 Servo_PWM::Servo_PWM(PinName Pin) : ServoPin(Pin) {
     ServoPin.period(0.020);
     ServoPin = 0;
-    initialize(); // TODO: Works?
+    initialize();
 }
 
 void Servo_PWM::initialize() {
     // initialize ESC
-    SetPosition(1000); // full throttle
-    wait(0.01);         // for 0.01 secs
-    SetPosition(1000);  // low throttle
+    SetPosition(0);  // zero throttle
 }
 
 void Servo_PWM::SetPosition(int position) {
-    ServoPin.pulsewidth(position/1000000.0);
+    ServoPin.pulsewidth((position+1000)/1000000.0);
 }
 
 void Servo_PWM::operator=(int position) {
--- a/main.cpp	Mon Nov 05 09:19:01 2012 +0000
+++ b/main.cpp	Sat Nov 17 11:49:21 2012 +0000
@@ -9,33 +9,33 @@
 #include "Servo_PWM.h"  // Motor PPM using PwmOut
 #include "PID.h"        // PID Library by Aaron Berk
 
-#define PI              3.1415926535897932384626433832795   // ratio of a circle's circumference to its diameter
-#define RAD2DEG         57.295779513082320876798154814105   // ratio between radians and degree (360/2Pi)
+//#define RAD2DEG         57.295779513082320876798154814105   // ratio between radians and degree (360/2Pi) //TODO not needed??
 #define RATE            0.02                                // speed of the interrupt for Sensors and PID
 
 #define P_VALUE         0.05                                // PID values
-#define I_VALUE         5  
+#define I_VALUE         100  
 #define D_VALUE         0.015
 
 //#define COMPASSCALIBRATE // decomment if you want to calibrate the Compass on start
+#define PC_CONNECTED // decoment if you want to debug per USB and your PC
 
 Timer GlobalTimer;                      // global time to calculate processing speed
 Ticker Datagetter;                      // timecontrolled interrupt to get data form IMU and RC
 
 // initialisation of hardware (see includes for more info)
 LED         LEDs;
-PC          pc(USBTX, USBRX, 115200);
+#ifdef PC_CONNECTED
+    PC          pc(USBTX, USBRX, 115200);
+#endif
 L3G4200D    Gyro(p28, p27);
 ADXL345     Acc(p28, p27);
 HMC5883     Comp(p28, p27);
 BMP085_old      Alt(p28, p27);
-RC_Channel  RC[] = {(p11), (p12), (p13), (p14)};    // noooo p19/p20 !
-Servo_PWM   Motor[] = {(p21), (p22), (p23), (p24)}; // p21 - p26 only !
+RC_Channel  RC[] = {p11, p12, p13, p14};    // noooo p19/p20 !
+Servo_PWM   Motor[] = {p21, p22, p23, p24}; // p21 - p26 only !
 
-//PID         Controller[] = {(P_VALUE, I_VALUE, D_VALUE, RATE), (P_VALUE, I_VALUE, D_VALUE, RATE), (P_VALUE, I_VALUE, D_VALUE, RATE)}; // TODO: RATE != dt immer anpassen
-//PID       P:3,0 bis 3,5     I:0,010 und 0,050       D:5 und 25 
-PID     Controller(P_VALUE, I_VALUE, D_VALUE, RATE);
-
+// 0:X:Roll 1:Y:Pitch 2:Z:Yaw
+PID     Controller[] = {PID(P_VALUE, I_VALUE, D_VALUE, RATE), PID(P_VALUE, I_VALUE, D_VALUE, RATE), PID(P_VALUE, I_VALUE, D_VALUE, RATE)}; // TODO: RATE != dt immer anpassen
 
 // global varibles
 bool            armed = false;          // this variable is for security
@@ -46,7 +46,13 @@
 float           angle[3] = {0,0,0}; // calculated values of the position [0: x,roll | 1: y,pitch | 2: z,yaw]
 float           tempangle = 0; // temporärer winkel für yaw ohne kompass
 float           Gyro_angle[3] ={0,0,0};
-float co; // PID test
+float           controller_value[] = {0,0,0};
+float           motor_value[] = {0,0,0,0};
+
+int motor_calc(int rc_value, float contr_value)
+{
+    return rc_value + contr_value > 0 ? rc_value + contr_value : 0; // nicht unter 0 sinken TODO: nicht Motor halten -> langsame Reaktion
+}
 
 void get_Data() // method which is called by the Ticker Datagetter every RATE seconds
 {
@@ -55,7 +61,7 @@
     // read data from sensors // ATTENTION! the I2C option repeated true is important because otherwise interrupts while bus communications cause crashes
     Gyro.read();
     Acc.read(); // TODO: nicht jeder Sensor immer? höhe nicht so wichtig
-    Comp.read();
+    //Comp.read();
     //Alt.Update(); TODO braucht zu lange zum auslesen!
     
     dt_read_sensors = GlobalTimer.read_us() - time_read_sensors;
@@ -71,128 +77,151 @@
     // calculate angles for roll, pitch an yaw
     angle[0] += (Acc.angle[0] - angle[0])/50 + Gyro.data[0] *dt_get_data/15000000.0;
     angle[1] += (Acc.angle[1]+3 - angle[1])/50 + Gyro.data[1] *dt_get_data/15000000.0;// TODO Offset accelerometer einstellen
-    tempangle += (Comp.get_angle() - tempangle)/50 + Gyro.data[2] *dt_get_data/15000000.0;
+    //tempangle += (Comp.get_angle() - tempangle)/50 + Gyro.data[2] *dt_get_data/15000000.0;
     angle[2] = Gyro_angle[2]; // gyro only here
     
     // PID controlling
-    Controller.setProcessValue(angle[1]);
+    if (!(RC[0].read() == -100)) {
+        Controller[0].setSetPoint((int)((RC[0].read()-440)/440.0*90.0));
+        Controller[1].setSetPoint(-(int)((RC[1].read()-430)/430.0*90.0));
+    }
+    for(int i=0;i<3;i++) {
+        Controller[i].setProcessValue(angle[i]);
+        controller_value[i] = Controller[i].compute() - 1000;
+    }
     
-    // Aming/ disarming
-    if(RC[2].read() < 1020 && RC[3].read() < 1020)
+    // Arming / disarming
+    if(RC[2].read() < 20 && RC[3].read() > 850)
+        armed = true;
+    if(RC[2].read() < 30 && RC[3].read() < 30)
         armed = false;
-    if(RC[2].read() < 500 || RC[1].read() < 500 || RC[0].read() < 500)
+    if(RC[3].read() < -10 || RC[2].read() < -10 || RC[1].read() < -10 || RC[0].read() < -10)
         armed = false;
-    if(RC[2].read() < 1020 && RC[3].read() > 1850)
-        armed = true;
     
     // calculate new motorspeeds
-    co = Controller.compute() - 1000;
-    if (armed) // zur SICHERHEIT!
+    if (armed) // for SECURITY!
     {
-        #if 0
-            Motor[0] = RC[2].read();
-            Motor[1] = RC[2].read();
-            Motor[2] = RC[2].read();
-            Motor[3] = RC[2].read();
-        #else
-            Motor[0] = RC[2].read()+co;
-            Motor[2] = RC[2].read()-co;
-        #endif
-        
-        /*Motor[0] = RC[2].read()+((RC[0].read() - 1500)/10.0)+40;
-        Motor[2] = RC[2].read()-((RC[0].read() - 1500)/10.0)-40;*/
-        /**/
+            // Pitch
+            motor_value[0] = motor_calc(RC[2].read(), +controller_value[1]);
+            motor_value[2] = motor_calc(RC[2].read(), -controller_value[1]);
+            
+            // Roll
+            motor_value[1] = motor_calc(RC[2].read(), +controller_value[0]);
+            motor_value[3] = motor_calc(RC[2].read(), -controller_value[0]);
+            
+            // Yaw
+            //motor_value[0] -= controller_value[2];
+            //motor_value[2] -= controller_value[2];
+            
+            //motor_value[1] += controller_value[2];
+            //motor_value[3] += controller_value[2];
+            
     } else {
-        Motor[0] = 1000;
-        Motor[1] = 1000;
-        Motor[2] = 1000;
-        Motor[3] = 1000;
-    }    
-    
-    /*Motor[0] = 1000 + (100 - (angle[1] * 500/90)) * (RC[2].read() - 1000) / 1000; // test für erste reaktion der motoren entgegen der Auslenkung
-    Motor[1] = 1000 + (100 - (angle[0] * 500/90)) * (RC[2].read() - 1000) / 1000;
-    Motor[2] = 1000 + (100 + (angle[1] * 500/90)) * (RC[2].read() - 1000) / 1000;
-    Motor[3] = 1000 + (100 + (angle[0] * 500/90)) * (RC[2].read() - 1000) / 1000;*/
+        for(int i=0;i<4;i++)
+            motor_value[i] = 0;
+    }
+    // Set new motorspeeds
+    for(int i=0;i<4;i++)
+        Motor[i] = motor_value[i];
 }
 
 int main() { // main programm only used for initialisation and debug output
     NVIC_SetPriority(TIMER3_IRQn, 1); // set priorty of tickers below hardware interrupts (standard priority is 0)
     
-    //for(int i=0;i<3;i++)
-        Controller.setInputLimits(-90.0, 90.0);
-        Controller.setOutputLimits(0.0, 2000.0);
-        Controller.setBias(1000);
-        Controller.setMode(MANUAL_MODE);//AUTO_MODE);
-        Controller.setSetPoint(0);
+    for(int i=0;i<3;i++) {
+        Controller[i].setInputLimits(-90.0, 90.0);
+        Controller[i].setOutputLimits(0.0, 2000.0);
+        Controller[i].setBias(1000);
+        Controller[i].setMode(MANUAL_MODE);//AUTO_MODE);
+        Controller[i].setSetPoint(0);
+    }
     
-    #ifdef COMPASSCALIBRATE
+    #ifdef PC_CONNECTED
+        #ifdef COMPASSCALIBRATE
+            pc.locate(10,5);
+            pc.printf("CALIBRATING");
+            Comp.calibrate(60);
+        #endif
+        
+        // init screen
         pc.locate(10,5);
-        pc.printf("CALIBRATING");
-        Comp.calibrate(60);
+        pc.printf("Flybed v0.2");
     #endif
-    
-    // init screen
-    pc.locate(10,5);
-    pc.printf("Flybed v0.2");
     LEDs.roll(2);
     
-    // Start! TODO: Motor und RC start (armed....?)
+    // Start!
     GlobalTimer.start();
     Datagetter.attach(&get_Data, RATE);     // start to get data all RATEms
     
     while(1) { 
-        pc.locate(30,0); // PC output
-        pc.printf("dt:%dms   dt_sensors:%dus    Altitude:%6.1fm   ", dt_get_data/1000, dt_read_sensors, Alt.CalcAltitude(Alt.Pressure));
-        pc.locate(5,1);
-        if(armed)
-            pc.printf("ARMED!!!!!!!!!!!!!");
-        else
-            pc.printf("DIS_ARMED            ");
-        pc.locate(5,3);
-        pc.printf("Roll:%6.1f   Pitch:%6.1f   Yaw:%6.1f    ", angle[0], angle[1], angle[2]);
-        
-        pc.locate(5,5);
-        pc.printf("Gyro.data: X:%6.1f  Y:%6.1f  Z:%6.1f", Gyro.data[0], Gyro.data[1], Gyro.data[2]);
-        pc.locate(5,6);
-        pc.printf("Gyro_angle: X:%6.1f  Y:%6.1f  Z:%6.1f", Gyro_angle[0], Gyro_angle[1], Gyro_angle[2]);
-        
-        pc.locate(5,8);
-        pc.printf("Acc.data: X:%6d  Y:%6d  Z:%6d", Acc.data[0], Acc.data[1], Acc.data[2]); 
-        pc.locate(5,9);
-        pc.printf("Acc.angle: Roll:%6.1f Pitch:%6.1f Yaw:%6.1f    ", Acc.angle[0], Acc.angle[1], Acc.angle[2]);
-        
-        pc.locate(5,11);
-        pc.printf("PID Test: %6.1f", co);
+        #ifdef PC_CONNECTED
+            pc.locate(30,0); // PC output
+            pc.printf("dt:%dms   dt_sensors:%dus    Altitude:%6.1fm   ", dt_get_data/1000, dt_read_sensors, Alt.CalcAltitude(Alt.Pressure));
+            pc.locate(5,1);
+            if(armed)
+                pc.printf("ARMED!!!!!!!!!!!!!");
+            else
+                pc.printf("DIS_ARMED            ");
+            pc.locate(5,3);
+            pc.printf("Roll:%6.1f   Pitch:%6.1f   Yaw:%6.1f    ", angle[0], angle[1], angle[2]);
+            pc.printf("\n\r   control Roll: %d   control Pitch: %d           ", (int)((RC[0].read()-440)/440.0*90.0), (int)((RC[1].read()-430)/430.0*90.0));
+            
+            pc.locate(5,5);
+            pc.printf("Gyro.data: X:%6.1f  Y:%6.1f  Z:%6.1f", Gyro.data[0], Gyro.data[1], Gyro.data[2]);
+            pc.locate(5,6);
+            pc.printf("Gyro_angle: X:%6.1f  Y:%6.1f  Z:%6.1f", Gyro_angle[0], Gyro_angle[1], Gyro_angle[2]);
+            
+            pc.locate(5,8);
+            pc.printf("Acc.data: X:%6d  Y:%6d  Z:%6d", Acc.data[0], Acc.data[1], Acc.data[2]); 
+            pc.locate(5,9);
+            pc.printf("Acc.angle: Roll:%6.1f Pitch:%6.1f Yaw:%6.1f    ", Acc.angle[0], Acc.angle[1], Acc.angle[2]);
+            
+            pc.locate(5,11);
+            pc.printf("PID Result:");
+            for(int i=0;i<3;i++)
+                pc.printf("  %d: %6.1f", i, controller_value[i]);
+            
+            
+            
+            pc.locate(10,15);
+            pc.printf("Debug_Yaw:  Comp:%6.1f tempangle:%6.1f  ", Comp.get_angle(), tempangle);
+            pc.locate(10,16);
+            pc.printf("Comp_data: %6.1f %6.1f %6.1f |||| %6.1f ", Comp.data[0], Comp.data[1], Comp.data[2], Comp.get_angle());
+            pc.locate(10,17);
+            //pc.printf("Comp_scale: %6.4f %6.4f %6.4f   ", Comp.scale[0], Comp.scale[1], Comp.scale[2]); no more accessible its private
+            pc.locate(10,18);
+            pc.printf("Comp_data: %6.1f %6.1f %6.1f |||| %6.1f ", Comp.data[0], Comp.data[1], Comp.data[2], Comp.get_angle());
+            
+            pc.locate(10,19);
+            pc.printf("RC0: %4d :[", RC[0].read());
+            for (int i = 0; i < RC[0].read()/17; i++)
+                pc.printf("=");
+            pc.printf("                                                       ");
+            pc.locate(10,20);
+            pc.printf("RC1: %4d :[", RC[1].read());
+            for (int i = 0; i < RC[1].read()/17; i++)
+                pc.printf("=");
+            pc.printf("                                                       ");
+            pc.locate(10,21);
+            pc.printf("RC2: %4d :[", RC[2].read());
+            for (int i = 0; i < RC[2].read()/17; i++)
+                pc.printf("=");
+            pc.printf("                                                       ");
+            pc.locate(10,22);
+            pc.printf("RC3: %4d :[", RC[3].read());
+            for (int i = 0; i < RC[3].read()/17; i++)
+                pc.printf("=");
+            pc.printf("                                                       ");
+        #endif
+        wait(0.01);
+        if(armed){
+            LEDs.rollnext();
+        } else {
+            LEDs.set(1);
+            LEDs.set(2);
+            LEDs.set(3);
+            LEDs.set(4);
+        }
         
-        pc.locate(10,15);
-        pc.printf("Debug_Yaw:  Comp:%6.1f tempangle:%6.1f  ", Comp.get_angle(), tempangle);
-        pc.locate(10,16);
-        pc.printf("Comp_data: %6.1f %6.1f %6.1f |||| %6.1f ", Comp.data[0], Comp.data[1], Comp.data[2], Comp.get_angle());
-        pc.locate(10,17);
-        //pc.printf("Comp_scale: %6.4f %6.4f %6.4f   ", Comp.scale[0], Comp.scale[1], Comp.scale[2]); no more accessible its private
-        pc.locate(10,18);
-        pc.printf("Comp_data: %6.1f %6.1f %6.1f |||| %6.1f ", Comp.data[0], Comp.data[1], Comp.data[2], Comp.get_angle());
-        
-        pc.locate(10,19);
-        pc.printf("RC0: %4d :[", RC[0].read());
-        for (int i = 0; i < (RC[0].read() - 1000)/17; i++)
-            pc.printf("=");
-        pc.printf("                                                       ");
-        pc.locate(10,20);
-        pc.printf("RC1: %4d :[", RC[1].read());
-        for (int i = 0; i < (RC[1].read() - 1000)/17; i++)
-            pc.printf("=");
-        pc.printf("                                                       ");
-        pc.locate(10,21);
-        pc.printf("RC2: %4d :[", RC[2].read());
-        for (int i = 0; i < (RC[2].read() - 1000)/17; i++)
-            pc.printf("=");
-        pc.printf("                                                       ");
-        pc.locate(10,22);
-        pc.printf("RC3: %4d :[", RC[3].read());
-        for (int i = 0; i < (RC[3].read() - 1000)/17; i++)
-            pc.printf("=");
-        pc.printf("                                                       ");
-        LEDs.rollnext();
     }
 }