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 17:e096e85f6c36, committed 2012-10-31
- Comitter:
- maetugr
- Date:
- Wed Oct 31 16:53:01 2012 +0000
- Parent:
- 16:74a6531350b5
- Child:
- 18:c8c09a3913ba
- Commit message:
- alle Sensoren mit i2c auf I2C_Sensor umgestellt (nicht getestet), noch keine calibration save per I2C_Sensor
Changed in this revision
--- a/Sensors/Acc/ADXL345.cpp Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/Acc/ADXL345.cpp Wed Oct 31 16:53:01 2012 +0000 @@ -1,91 +1,47 @@ #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); +ADXL345::ADXL345(PinName sda, PinName scl) : I2C_Sensor(sda, scl, ADXL345_I2C_ADDRESS) +{ // initialize the BW data rate - char tx[2]; - 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); + writeRegister(ADXL345_BW_RATE_REG, 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 //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]; - rx[0] = ADXL345_DATA_FORMAT_REG; - rx[1] = 0x0B; - // full res and +_16g - i2c.write( ADXL345_WRITE , rx, 2); + writeRegister(ADXL345_DATA_FORMAT_REG, 0x0B); // full res and +_16g // Set Offset - programmed into the OFSX, OFSY, and OFXZ registers, respectively, as 0xFD, 0x03 and 0xFE. - char x[2]; - x[0] = ADXL345_OFSX_REG ; - //x[1] = 0xFD; - x[1] = 0x00; - i2c.write( ADXL345_WRITE , x, 2); - char y[2]; - y[0] = ADXL345_OFSY_REG ; - //y[1] = 0x03; - y[1] = 0x00; - i2c.write( ADXL345_WRITE , y, 2); - char z[2]; - z[0] = ADXL345_OFSZ_REG ; - //z[1] = 0xFE; - z[1] = 0x00; - i2c.write( ADXL345_WRITE , z, 2); + writeRegister(ADXL345_OFSX_REG, 0x00); // TODO: 0xFD (sein offset! brauch ich auch?) + writeRegister(ADXL345_OFSY_REG, 0x00); // y[1] = 0x03; + writeRegister(ADXL345_OFSZ_REG, 0x00); // z[1] = 0xFE; - // MY INITIALISATION ------------------------------------------------------- - - writeReg(ADXL345_POWER_CTL_REG, 0x00); // set power control - writeReg(ADXL345_DATA_FORMAT_REG, 0x0B); // set data format - setDataRate(ADXL345_3200HZ); // set data rate - writeReg(ADXL345_POWER_CTL_REG, 0x08); // set mode + writeRegister(ADXL345_POWER_CTL_REG, 0x00); // set power control + writeRegister(ADXL345_DATA_FORMAT_REG, 0x0B); // set data format + setDataRate(ADXL345_3200HZ); // set data rate + writeRegister(ADXL345_POWER_CTL_REG, 0x08); // set mode } -void ADXL345::read(){ - char buffer[6]; - readMultiReg(ADXL345_DATAX0_REG, buffer, 6); +void ADXL345::read() +{ + char buffer[6]; // 8-Bit pieces of axis data - data[0] = (short) ((int)buffer[1] << 8 | (int)buffer[0]); - data[1] = (short) ((int)buffer[3] << 8 | (int)buffer[2]); - data[2] = (short) ((int)buffer[5] << 8 | (int)buffer[4]); + readMultiRegister(ADXL345_DATAX0_REG, buffer, 6); // read axis registers using I2C + + data[0] = (short) (buffer[1] << 8 | buffer[0]); // join 8-Bit pieces to 16-bit short integers + data[1] = (short) (buffer[3] << 8 | buffer[2]); + data[2] = (short) (buffer[5] << 8 | buffer[4]); // 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)); - angle[0] = -(Rad2Deg * acos((float)data[1] / R)-90); - angle[1] = Rad2Deg * acos((float)data[0] / R)-90; - angle[2] = Rad2Deg * acos((float)data[2] / R); + 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[2] = RAD2DEG * acos((float)data[2] / R); // angle from magnetic field vector in direction which it has } -void ADXL345::writeReg(char address, char data){ - char tx[2]; - tx[0] = address; - tx[1] = data; - i2c.write(ADXL345_WRITE, tx, 2); -} - -char ADXL345::readReg(char address){ - char tx = address; - char output; - i2c.write( ADXL345_WRITE , &tx, 1); //tell it what you want to read - i2c.read( ADXL345_READ , &output, 1); //tell it where to store the data - return output; -} - -void ADXL345::readMultiReg(char address, char* output, int size) { - i2c.write(ADXL345_WRITE, &address, 1, true); //tell it where to read from - i2c.read(ADXL345_READ , output, size, true); //tell it where to store the data read -} - -void ADXL345::setDataRate(char rate) { - //Get the current register contents, so we don't clobber the power bit. - char registerContents = readReg(ADXL345_BW_RATE_REG); +void ADXL345::setDataRate(char rate) +{ + char registerContents = readRegister(ADXL345_BW_RATE_REG); // get the current register contents, so we don't clobber the power bit registerContents &= 0x10; registerContents |= rate; - writeReg(ADXL345_BW_RATE_REG, registerContents); + writeRegister(ADXL345_BW_RATE_REG, registerContents); } \ No newline at end of file
--- a/Sensors/Acc/ADXL345.h Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/Acc/ADXL345.h Wed Oct 31 16:53:01 2012 +0000 @@ -4,38 +4,45 @@ #define ADXL345_H #include "mbed.h" +#include "I2C_Sensor.h" + +#define ADXL345_I2C_ADDRESS 0 +// read or write bytes +//#define ADXL345_READ 0xA7 +//#define ADXL345_WRITE 0xA6 +//#define ADXL345_ADDRESS 0x53 // register addresses -#define ADXL345_DEVID_REG 0x00 -#define ADXL345_THRESH_TAP_REG 0x1D -#define ADXL345_OFSX_REG 0x1E -#define ADXL345_OFSY_REG 0x1F -#define ADXL345_OFSZ_REG 0x20 -#define ADXL345_DUR_REG 0x21 -#define ADXL345_LATENT_REG 0x22 -#define ADXL345_WINDOW_REG 0x23 -#define ADXL345_THRESH_ACT_REG 0x24 -#define ADXL345_THRESH_INACT_REG 0x25 -#define ADXL345_TIME_INACT_REG 0x26 -#define ADXL345_ACT_INACT_CTL_REG 0x27 -#define ADXL345_THRESH_FF_REG 0x28 -#define ADXL345_TIME_FF_REG 0x29 -#define ADXL345_TAP_AXES_REG 0x2A -#define ADXL345_ACT_TAP_STATUS_REG 0x2B -#define ADXL345_BW_RATE_REG 0x2C -#define ADXL345_POWER_CTL_REG 0x2D -#define ADXL345_INT_ENABLE_REG 0x2E -#define ADXL345_INT_MAP_REG 0x2F -#define ADXL345_INT_SOURCE_REG 0x30 -#define ADXL345_DATA_FORMAT_REG 0x31 -#define ADXL345_DATAX0_REG 0x32 -#define ADXL345_DATAX1_REG 0x33 -#define ADXL345_DATAY0_REG 0x34 -#define ADXL345_DATAY1_REG 0x35 -#define ADXL345_DATAZ0_REG 0x36 -#define ADXL345_DATAZ1_REG 0x37 -#define ADXL345_FIFO_CTL 0x38 -#define ADXL345_FIFO_STATUS 0x39 +#define ADXL345_DEVID_REG 0x00 +#define ADXL345_THRESH_TAP_REG 0x1D +#define ADXL345_OFSX_REG 0x1E +#define ADXL345_OFSY_REG 0x1F +#define ADXL345_OFSZ_REG 0x20 +#define ADXL345_DUR_REG 0x21 +#define ADXL345_LATENT_REG 0x22 +#define ADXL345_WINDOW_REG 0x23 +#define ADXL345_THRESH_ACT_REG 0x24 +#define ADXL345_THRESH_INACT_REG 0x25 +#define ADXL345_TIME_INACT_REG 0x26 +#define ADXL345_ACT_INACT_CTL_REG 0x27 +#define ADXL345_THRESH_FF_REG 0x28 +#define ADXL345_TIME_FF_REG 0x29 +#define ADXL345_TAP_AXES_REG 0x2A +#define ADXL345_ACT_TAP_STATUS_REG 0x2B +#define ADXL345_BW_RATE_REG 0x2C +#define ADXL345_POWER_CTL_REG 0x2D +#define ADXL345_INT_ENABLE_REG 0x2E +#define ADXL345_INT_MAP_REG 0x2F +#define ADXL345_INT_SOURCE_REG 0x30 +#define ADXL345_DATA_FORMAT_REG 0x31 +#define ADXL345_DATAX0_REG 0x32 +#define ADXL345_DATAX1_REG 0x33 +#define ADXL345_DATAY0_REG 0x34 +#define ADXL345_DATAY1_REG 0x35 +#define ADXL345_DATAZ0_REG 0x36 +#define ADXL345_DATAZ1_REG 0x37 +#define ADXL345_FIFO_CTL 0x38 +#define ADXL345_FIFO_STATUS 0x39 // data rate codes #define ADXL345_3200HZ 0x0F @@ -49,11 +56,6 @@ #define ADXL345_12HZ5 0x07 #define ADXL345_6HZ25 0x06 -// read or write bytes -#define ADXL345_READ 0xA7 -#define ADXL345_WRITE 0xA6 -#define ADXL345_ADDRESS 0x53 - //the ADXL345 7-bit address is 0x53 when ALT ADDRESS is low as it is on the sparkfun chip: when ALT ADDRESS is high the address is 0x1D //when ALT ADDRESS pin is high: //#define ADXL345_READ 0x3B @@ -64,24 +66,18 @@ #define ADXL345_Y 0x01 #define ADXL345_Z 0x02 -#define Rad2Deg 57.295779513082320876798154814105 +#define RAD2DEG 57.295779513082320876798154814105 -typedef char byte; - -class ADXL345 +class ADXL345 : public I2C_Sensor { public: - ADXL345(PinName sda, PinName scl); // constructor, uses i2c - void read(); // read all axis to array - int data[3]; // where the measured data is saved - float angle[3]; // where the calculated angles are stored + 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 + float angle[3]; // where the calculated angles are stored private: - I2C i2c; // i2c object to communicate - void writeReg(byte reg, byte value); // write one single register to sensor - byte readReg(byte reg); // read one single register from sensor - void readMultiReg(char startAddress, char* ptr_output, int size); // read multiple regs - void setDataRate(char rate); // data rate configuration (not only a reg to write) + void setDataRate(char rate); // data rate configuration (not only a reg to write) }; #endif
--- a/Sensors/Alt/BMP085.h Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/Alt/BMP085.h Wed Oct 31 16:53:01 2012 +0000 @@ -4,7 +4,6 @@ #include "mbed.h" #include "I2C_Sensor.h" -// I2C address #define BMP085_I2C_ADDRESS 0xEE class BMP085 : public I2C_Sensor
--- a/Sensors/Comp/HMC5883.cpp Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/Comp/HMC5883.cpp Wed Oct 31 16:53:01 2012 +0000 @@ -1,10 +1,7 @@ -#include "mbed.h" #include "HMC5883.h" -HMC5883::HMC5883(PinName sda, PinName scl) : i2c(sda, scl), local("local") -{ - i2c.frequency(400000); // TODO: zu testen!! - +HMC5883::HMC5883(PinName sda, PinName scl) : I2C_Sensor(sda, scl, HMC5883_I2C_ADDRESS), local("local") +{ // load calibration values FILE *fp = fopen("/local/compass.txt", "r"); for(int i = 0; i < 3; i++) @@ -14,9 +11,9 @@ fclose(fp); // initialize HMC5883 for scaling - writeReg(HMC5883_CONF_REG_A, 0x19); // 8 samples, 75Hz output, test mode for scaling! - writeReg(HMC5883_CONF_REG_B, 0x20); // Gain for +- 1.3 gauss (earth compass ~0.6 gauss) - writeReg(HMC5883_MODE_REG, 0x00); // continuous measurement-mode + 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 /* (not important, just from data sheet) // Scaling with testmode @@ -36,7 +33,7 @@ */ // set normal mode - writeReg(HMC5883_CONF_REG_A, 0x78); // 8 samples, 75Hz output, normal mode + writeRegister(HMC5883_CONF_REG_A, 0x78); // 8 samples, 75Hz output, normal mode } void HMC5883::read() @@ -76,35 +73,22 @@ void HMC5883::readraw() { - char buffer[6]; - - readMultiReg(HMC5883_DATA_OUT_X_MSB, buffer, 6); // read the raw data from I2C + char buffer[6]; // 8-Bit pieces of axis data - // join MSB and LSB of X, Z and Y (yes, order is so stupid, see datasheet) - raw[0] = (short) (buffer[0] << 8 | buffer[1]); - raw[1] = (short) (buffer[4] << 8 | buffer[5]); + readMultiRegister(HMC5883_DATA_OUT_X_MSB, buffer, 6); // read axis registers using I2C + + raw[0] = (short) (buffer[0] << 8 | buffer[1]); // join 8-Bit pieces to 16-bit short integers + raw[1] = (short) (buffer[4] << 8 | buffer[5]); // X, Z and Y (yes, order is stupid like this, see datasheet) raw[2] = (short) (buffer[2] << 8 | buffer[3]); } -void HMC5883::writeReg(char address, char data){ - char tx[2]; - tx[0] = address; - tx[1] = data; - i2c.write(I2CADR_W(HMC5883_ADDRESS), tx, 2); -} - -void HMC5883::readMultiReg(char address, char* output, int size) { - i2c.write(I2CADR_W(HMC5883_ADDRESS), &address, 1, true); //tell it where to read from - i2c.read(I2CADR_R(HMC5883_ADDRESS) , output, size, true); //tell it where to store the data read -} - float HMC5883::get_angle() { - #define Rad2Deg 57.295779513082320876798154814105 + #define RAD2DEG 57.295779513082320876798154814105 float Heading; - Heading = Rad2Deg * atan2(data[0],data[1]); + 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
--- a/Sensors/Comp/HMC5883.h Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/Comp/HMC5883.h Wed Oct 31 16:53:01 2012 +0000 @@ -1,17 +1,20 @@ +// based on http://mbed.org/users/BlazeX/code/HMC5883/ + #ifndef HMC5883_H #define HMC5883_H +#include "mbed.h" +#include "I2C_Sensor.h" + #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_ADDRESS 0x1E -#define I2CADR_W(ADR) (ADR << 1&0xFE) // ADR & 1111 1110 -#define I2CADR_R(ADR) (ADR << 1|0x01) // ADR | 0000 0001 +#define HMC5883_I2C_ADDRESS 0x1E -class HMC5883 +class HMC5883 : public I2C_Sensor { public: HMC5883(PinName sda, PinName scl); @@ -22,16 +25,10 @@ float get_angle(); private: - I2C i2c; - - // raw data and function to measure it + // raw data and function to get it int raw[3]; void readraw(); - // I2C functions - void writeReg(char address, char data); - void readMultiReg(char address, char* output, int size); - // calibration parameters and their saving int Min[3]; int Max[3];
--- a/Sensors/Gyro/L3G4200D.cpp Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/Gyro/L3G4200D.cpp Wed Oct 31 16:53:01 2012 +0000 @@ -1,8 +1,4 @@ -#include "mbed.h" #include "L3G4200D.h" -#include <math.h> - -#define L3G4200D_I2C_ADDRESS 0xD0 // TODO: Adressen??? L3G4200D::L3G4200D(PinName sda, PinName scl) : I2C_Sensor(sda, scl, L3G4200D_I2C_ADDRESS) { @@ -37,7 +33,8 @@ float Gyro_calib[3] = {0,0,0}; // temporary var for the sum of calibration measurement - for (int i = 0; i < 50; i++) { // read 50 times the data in a very short time + const int count = 50; + for (int i = 0; i < count; i++) { // read 50 times the data in a very short time read(); for (int j = 0; j < 3; j++) Gyro_calib[j] += data[j]; @@ -52,11 +49,11 @@ { char buffer[6]; // 8-Bit pieces of axis data - buffer[0] = L3G4200D_OUT_X_L | (1 << 7); + //buffer[0] = L3G4200D_OUT_X_L | (1 << 7); // TODO: wiiiiiiso?! - readMultiRegister(L3G4200D_OUT_X_L, buffer, 6); // parameter: + readMultiRegister(L3G4200D_OUT_X_L | (1 << 7), buffer, 6); // read axis registers using I2C - data[0] = (short) (buffer[1] << 8 | buffer[0]); // compose 8-Bit pieces to 16-bit short integers + data[0] = (short) (buffer[1] << 8 | buffer[0]); // join 8-Bit pieces to 16-bit short integers data[1] = (short) (buffer[3] << 8 | buffer[2]); data[2] = (short) (buffer[5] << 8 | buffer[4]);
--- a/Sensors/Gyro/L3G4200D.h Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/Gyro/L3G4200D.h Wed Oct 31 16:53:01 2012 +0000 @@ -6,37 +6,39 @@ #include "mbed.h" #include "I2C_Sensor.h" +#define L3G4200D_I2C_ADDRESS 0xD0 // TODO: Adressen??? + // register addresses -#define L3G4200D_WHO_AM_I 0x0F +#define L3G4200D_WHO_AM_I 0x0F -#define L3G4200D_CTRL_REG1 0x20 -#define L3G4200D_CTRL_REG2 0x21 -#define L3G4200D_CTRL_REG3 0x22 -#define L3G4200D_CTRL_REG4 0x23 -#define L3G4200D_CTRL_REG5 0x24 -#define L3G4200D_REFERENCE 0x25 -#define L3G4200D_OUT_TEMP 0x26 -#define L3G4200D_STATUS_REG 0x27 +#define L3G4200D_CTRL_REG1 0x20 +#define L3G4200D_CTRL_REG2 0x21 +#define L3G4200D_CTRL_REG3 0x22 +#define L3G4200D_CTRL_REG4 0x23 +#define L3G4200D_CTRL_REG5 0x24 +#define L3G4200D_REFERENCE 0x25 +#define L3G4200D_OUT_TEMP 0x26 +#define L3G4200D_STATUS_REG 0x27 -#define L3G4200D_OUT_X_L 0x28 -#define L3G4200D_OUT_X_H 0x29 -#define L3G4200D_OUT_Y_L 0x2A -#define L3G4200D_OUT_Y_H 0x2B -#define L3G4200D_OUT_Z_L 0x2C -#define L3G4200D_OUT_Z_H 0x2D +#define L3G4200D_OUT_X_L 0x28 +#define L3G4200D_OUT_X_H 0x29 +#define L3G4200D_OUT_Y_L 0x2A +#define L3G4200D_OUT_Y_H 0x2B +#define L3G4200D_OUT_Z_L 0x2C +#define L3G4200D_OUT_Z_H 0x2D -#define L3G4200D_FIFO_CTRL_REG 0x2E -#define L3G4200D_FIFO_SRC_REG 0x2F +#define L3G4200D_FIFO_CTRL_REG 0x2E +#define L3G4200D_FIFO_SRC_REG 0x2F -#define L3G4200D_INT1_CFG 0x30 -#define L3G4200D_INT1_SRC 0x31 -#define L3G4200D_INT1_THS_XH 0x32 -#define L3G4200D_INT1_THS_XL 0x33 -#define L3G4200D_INT1_THS_YH 0x34 -#define L3G4200D_INT1_THS_YL 0x35 -#define L3G4200D_INT1_THS_ZH 0x36 -#define L3G4200D_INT1_THS_ZL 0x37 -#define L3G4200D_INT1_DURATION 0x38 +#define L3G4200D_INT1_CFG 0x30 +#define L3G4200D_INT1_SRC 0x31 +#define L3G4200D_INT1_THS_XH 0x32 +#define L3G4200D_INT1_THS_XL 0x33 +#define L3G4200D_INT1_THS_YH 0x34 +#define L3G4200D_INT1_THS_YL 0x35 +#define L3G4200D_INT1_THS_ZH 0x36 +#define L3G4200D_INT1_THS_ZL 0x37 +#define L3G4200D_INT1_DURATION 0x38 class L3G4200D : public I2C_Sensor { @@ -47,7 +49,7 @@ int readTemp(); // read temperature from sensor private: - float offset[3]; // offset that's subtracted from every measurement + float offset[3]; // offset that's subtracted from every measurement }; #endif \ No newline at end of file
--- a/Sensors/I2C_Sensor.cpp Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/I2C_Sensor.cpp Wed Oct 31 16:53:01 2012 +0000 @@ -1,4 +1,3 @@ -#include "mbed.h" #include "I2C_Sensor.h" // calculate the 8-Bit write/read I2C-Address from the 7-Bit adress of the device
--- a/Sensors/I2C_Sensor.h Wed Oct 31 14:44:07 2012 +0000 +++ b/Sensors/I2C_Sensor.h Wed Oct 31 16:53:01 2012 +0000 @@ -1,6 +1,10 @@ +// by MaEtUgR + #ifndef I2C_Sensor_H #define I2C_Sensor_H +#include "mbed.h" + class I2C_Sensor { public:
--- a/main.cpp Wed Oct 31 14:44:07 2012 +0000 +++ b/main.cpp Wed Oct 31 16:53:01 2012 +0000 @@ -11,7 +11,7 @@ #include "IntCtrl.h" // Interrupt Control by Roland Elmiger #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) #define RATE 0.02 // speed of the interrupt for Sensors and PID #define P_VALUE 0.1 // viel zu tief!!!!!