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.
Revision 18:c8c09a3913ba, committed 2012-11-03
- Comitter:
- maetugr
- Date:
- Sat Nov 03 07:44:07 2012 +0000
- Parent:
- 17:e096e85f6c36
- Child:
- 19:40c252b4a792
- Commit message:
- mit allem in der I2C_Sensors klasse, zwischenspeichern, da nichts funktioniert
Changed in this revision
--- a/Sensors/Acc/ADXL345.cpp Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/Acc/ADXL345.cpp Sat Nov 03 07:44:07 2012 +0000 @@ -31,8 +31,8 @@ // calculate the angles for roll and pitch (0,1) float R = sqrt(pow((float)data[0],2) + pow((float)data[1],2) + pow((float)data[2],2)); // calculate the absolute of the magnetic field vector - angle[0] = -(RAD2DEG * acos((float)data[1] / R)-90); // roll - angle of magnetic field vector in x direction - angle[1] = RAD2DEG * acos((float)data[0] / R)-90; // pitch - angle of magnetic field vector in y direction + angle[0] = -(RAD2DEG * acos((float)data[1] / R)-90); // roll - angle of magnetic field vector in x direction + angle[1] = RAD2DEG * acos((float)data[0] / R)-90; // pitch - angle of magnetic field vector in y direction angle[2] = RAD2DEG * acos((float)data[2] / R); // angle from magnetic field vector in direction which it has }
--- a/Sensors/Acc/ADXL345.h Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/Acc/ADXL345.h Sat Nov 03 07:44:07 2012 +0000 @@ -72,8 +72,7 @@ { public: ADXL345(PinName sda, PinName scl); // constructor, uses I2C_Sensor - void read(); // reads all axis to array - int data[3]; // where the measured data is saved + virtual void read(); // read all axis from register to array data float angle[3]; // where the calculated angles are stored private:
--- a/Sensors/Alt/BMP085.cpp Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/Alt/BMP085.cpp Sat Nov 03 07:44:07 2012 +0000 @@ -1,4 +1,3 @@ -#include "mbed.h" #include "BMP085.h" BMP085::BMP085(PinName sda, PinName scl) : I2C_Sensor(sda, scl, BMP085_I2C_ADDRESS) @@ -6,4 +5,53 @@ // initialize BMP085 with settings //writeRegister(0xf4, 0x2e); // TODO: was macht das + register in header! -} \ No newline at end of file +} + +/*void BMP085::read() + { + long P, UTemp, UPressure, X1, X2, X3, B3, B5, B6; + unsigned long B4, B7; + + // TODO: writeRegister(0xf4, 0x2e); ?!!! + twi_writechar(BMP085_ADRESS, 0xf4, 0x2e); + // Wait at least 4.5ms + wait(0.005); + UTemp = twi_readshort(BMP085_ADRESS, 0xf6); + + X1 = ((UTemp - AC6) * AC5) >> 15; + X2 = (MC << 11) / (X1 + MD); + B5 = X1 + X2; + Temperature = (float)((B5 + 8) >> 4)/10.0; + + twi_writechar(BMP085_ADRESS, 0xf4, 0x34 + (oss << 6)); + // Wait at least 4.5ms + wait(0.005); + UPressure = twi_readlong(BMP085_ADRESS, 0xf6) >> (8 - oss); + + B6 = B5 - 4000; + X1 = (B2 * (B6 * B6) >> 12) >> 11; + X2 = (AC2 * B6) >> 11; + X3 = X1 + X2; + B3 = ((AC1 * 4 + X3) << oss) >> 2; + + X1 = (AC3 * B6) >> 13; + X2 = (B1 * (B6 * B6) >> 12) >> 16; + X3 = ((X1 + X2) + 2) >> 2; + B4 = AC4 * (X3 + 32768) >> 15; + + B7 = (unsigned long)(UPressure - B3) * (50000 >> oss); + + if (B7 < 0x80000000) + { + P = (2 * B7) / B4; + } + else + { + P = 2* (B7 / B4); + } + X1 = (P >> 8) * (P >> 8); + X1 = (X1 * 3038) >> 16; + X2 = (-7357 * P) >> 16; + P = P + ((X1 + X2 + 3791) >> 4); + Pressure = (float)P / 100.0; + }*/ \ No newline at end of file
--- a/Sensors/Alt/BMP085.h Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/Alt/BMP085.h Sat Nov 03 07:44:07 2012 +0000 @@ -1,3 +1,5 @@ +// based on http://mbed.org/users/okini3939/code/BMP085/ + #ifndef BMP085_H #define BMP085_H @@ -11,13 +13,11 @@ public: BMP085(PinName sda, PinName scl); - float data[3]; - - void read(); + //virtual void read(); void calibrate(int s); - float get_angle(); + float get_height(); private: // raw data and function to measure it
--- a/Sensors/Comp/HMC5883.cpp Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/Comp/HMC5883.cpp Sat Nov 03 07:44:07 2012 +0000 @@ -1,39 +1,16 @@ #include "HMC5883.h" -HMC5883::HMC5883(PinName sda, PinName scl) : I2C_Sensor(sda, scl, HMC5883_I2C_ADDRESS), local("local") +HMC5883::HMC5883(PinName sda, PinName scl) : I2C_Sensor(sda, scl, HMC5883_I2C_ADDRESS) { // load calibration values - FILE *fp = fopen("/local/compass.txt", "r"); - for(int i = 0; i < 3; i++) - fscanf(fp, "%f", &scale[i]); - for(int i = 0; i < 3; i++) - fscanf(fp, "%f", &offset[i]); - fclose(fp); - - // initialize HMC5883 for scaling - writeRegister(HMC5883_CONF_REG_A, 0x19); // 8 samples, 75Hz output, test mode for scaling! - writeRegister(HMC5883_CONF_REG_B, 0x20); // Gain for +- 1.3 gauss (earth compass ~0.6 gauss) - writeRegister(HMC5883_MODE_REG, 0x00); // continuous measurement-mode + loadCalibrationValues(scale, 3, "COMPASS_SCALE.txt"); + loadCalibrationValues(offset, 3, "COMPASS_OFFSET.txt"); - /* (not important, just from data sheet) - // Scaling with testmode - for(int j = 0; j < 3; j++) // set all scales to 1 first so the measurement for scaling is not already scaled - scale[j] = 1; - - int data50[3] = {0,0,0}; // to save the 50 measurements - for(int i = 0; i < 50; i++) // measure 50 times the testmode value to get an average - { - read(); - for(int j = 0; j < 3; j++) - data50[j] += data[j]; - } - scale[0] = (1.16 * 1090)/(data50[0]/50.0); // value that it should be with selftest of 1.1 Gauss * 1090 LSB/Gauss / the value it is - scale[1] = (1.16 * 1090)/(data50[1]/50.0); - scale[2] = (1.08 * 1090)/(data50[2]/50.0); - */ - - // set normal mode - writeRegister(HMC5883_CONF_REG_A, 0x78); // 8 samples, 75Hz output, normal mode + // initialize HMC5883 + writeRegister(HMC5883_CONF_REG_A, 0x78); // 8 samples, 75Hz output, normal mode + //writeRegister(HMC5883_CONF_REG_A, 0x19); // 8 samples, 75Hz output, test mode! (should get constant values from measurement, see datasheet) + writeRegister(HMC5883_CONF_REG_B, 0x20); // Gain for +- 1.3 gauss (earth compass ~0.6 gauss) + writeRegister(HMC5883_MODE_REG, 0x00); // continuous measurement-mode } void HMC5883::read() @@ -45,30 +22,28 @@ void HMC5883::calibrate(int s) { - Timer calibrate_timer; + int Min[3]; // values for achieved maximum and minimum amplitude in calibrating environment + int Max[3]; + + Timer calibrate_timer; // timer to know when calibration is finished calibrate_timer.start(); - while(calibrate_timer.read() < s) + while(calibrate_timer.read() < s) // take measurements for s seconds { readraw(); for(int i = 0; i < 3; i++) { - Min[i]= Min[i] < raw[i] ? Min[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]; - - //Scale und Offset aus gesammelten Min Max Werten berechnen - //Die neue Untere und obere Grenze bilden -1 und +1 - scale[i]= 2000 / (float)(Max[i]-Min[i]); - offset[i]= 1000 - (float)(Max[i]) * scale[i]; } } - // save values - FILE *fp = fopen("/local/compass.txt", "w"); - for(int i = 0; i < 3; i++) - fprintf(fp, "%f\r\n", scale[i]); - for(int i = 0; i < 3; i++) - fprintf(fp, "%f\r\n", offset[i]); - fclose(fp); + for(int i = 0; i < 3; i++) { + scale[i]= 2000 / (float)(Max[i]-Min[i]); // calculate scale and offset out of the measured maxima and minima + offset[i]= 1000 - (float)(Max[i]) * scale[i]; // the lower bound is -1000, the higher one 1000 + } + + saveCalibrationValues(scale, 3, "COMPASS_SCALE.txt"); // save new scale and offset values to flash + saveCalibrationValues(offset, 3, "COMPASS_OFFSET.txt"); } void HMC5883::readraw() @@ -89,10 +64,11 @@ float Heading; Heading = RAD2DEG * atan2(data[0],data[1]); - Heading += 1.367; //bei Ost-Deklination += DecAngle, bei West-Deklination -= DecAngle - //Missweisung = Winkel zwischen geographischer und magnetischer Nordrichtung - //Bern ca. 1.367 Grad Ost - //http://www.swisstopo.admin.ch/internet/swisstopo/de/home/apps/calc/declination.html + Heading += 1.367; // correction of the angle between geographical and magnetical north direction, called declination + // if you need an east-declination += DecAngle, if you need west-declination -= DecAngle + // for me in Switzerland, Bern it's ca. 1.367 degree east + // see: http://magnetic-declination.com/ + // for me: http://www.swisstopo.admin.ch/internet/swisstopo/de/home/apps/calc/declination.html if(Heading < 0) Heading += 360; // minimum 0 degree
--- a/Sensors/Comp/HMC5883.h Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/Comp/HMC5883.h Sat Nov 03 07:44:07 2012 +0000 @@ -6,35 +6,27 @@ #include "mbed.h" #include "I2C_Sensor.h" +#define HMC5883_I2C_ADDRESS 0x1E + #define HMC5883_CONF_REG_A 0x00 #define HMC5883_CONF_REG_B 0x01 #define HMC5883_MODE_REG 0x02 #define HMC5883_DATA_OUT_X_MSB 0x03 -// I2C addresses -#define HMC5883_I2C_ADDRESS 0x1E - class HMC5883 : public I2C_Sensor { public: HMC5883(PinName sda, PinName scl); - float data[3]; - void read(); + virtual void read(); // read all axis from register to array data void calibrate(int s); float get_angle(); private: - // raw data and function to get it - int raw[3]; - void readraw(); + void readraw(); // function to get raw data - // calibration parameters and their saving - int Min[3]; - int Max[3]; - float scale[3]; + float scale[3]; // calibration parameters float offset[3]; - LocalFileSystem local; }; #endif
--- a/Sensors/Gyro/L3G4200D.h Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/Gyro/L3G4200D.h Sat Nov 03 07:44:07 2012 +0000 @@ -44,8 +44,7 @@ { public: L3G4200D(PinName sda, PinName scl); // constructor, uses I2C_Sensor class - void read(); // read all axis to array - float data[3]; // where the measured data is saved + virtual void read(); // read all axis from register to array data int readTemp(); // read temperature from sensor private:
--- a/Sensors/I2C_Sensor.h Wed Oct 31 16:53:01 2012 +0000 +++ b/Sensors/I2C_Sensor.h Sat Nov 03 07:44:07 2012 +0000 @@ -10,9 +10,9 @@ public: I2C_Sensor(PinName sda, PinName scl, int8_t address); - float data[3]; - void read(); - void calibrate(); + float data[3]; // where the measured data is saved + virtual void read() = 0; // read all axis from register to array data + //TODO: virtual void calibrate() = 0; // calibrate the sensor and if desired write calibration values to a file protected: // Calibration value saving @@ -26,7 +26,7 @@ // raw data and function to measure it int raw[3]; - void readraw(); + //virtual void readraw() = 0; private: I2C i2c; // I2C-Bus
--- a/main.cpp Wed Oct 31 16:53:01 2012 +0000 +++ b/main.cpp Sat Nov 03 07:44:07 2012 +0000 @@ -25,7 +25,7 @@ // initialisation of hardware (see includes for more info) LED LEDs; -PC pc(USBTX, USBRX, 57600); +PC pc(USBTX, USBRX, 57600); // TODO: Testen ?!!! 115.200 L3G4200D Gyro(p28, p27); ADXL345 Acc(p28, p27); HMC5883 Comp(p28, p27);