I am able to get angle from ADXL345 and L3GD20. Please use this program. Angle is made by deg/sec and acceramater. I used Kalmanfilter.
Fork of ANGLE by
Diff: angle.cpp
- Revision:
- 0:15e41c824e3b
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/angle.cpp Sun Nov 30 11:06:13 2014 +0000 @@ -0,0 +1,492 @@ +#include "angle.h" +#include "mbed.h" +ANGLE::ANGLE(PinName sda, PinName scl) : i2c_(sda, scl) { + Rate=0.00390635;sampleTime=0.001;sampleNum=500; + + kalma[0].setAngle(0); + kalma[1].setAngle(0); + kalma[2].setAngle(0); + //400kHz, allowing us to use the fastest data rates. + i2c_.frequency(400000); + // initialize the BW data rate + char tx[2]; + tx[0] = ADXL345_BW_RATE_REG; + tx[1] = ADXL345_200HZ; //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( acc_i2c_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]; + rx[0] = ADXL345_DATA_FORMAT_REG; + rx[1] = 0x0B; + // full res and +_16g + i2c_.write( acc_i2c_write , rx, 2); + + // 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] = 253; + i2c_.write( acc_i2c_write , x, 2); + char y[2]; + y[0] = ADXL345_OFSY_REG ; + y[1] = 5; + i2c_.write( acc_i2c_write, y, 2); + char z[2]; + z[0] = ADXL345_OFSZ_REG ; + z[1] = 0xFE; + i2c_.write( acc_i2c_write , z, 2); + char reg_v; + sampleTime=0.001; + sampleNum=500; + angle[0]=angle[1]=angle[2]=0; + prev_rate[0]=prev_rate[1]=prev_rate[2]=0; + + // 0x0F = 0b00001111 + // Normal power mode, all axes enabled + reg_v = 0; + reg_v |= 0x0F; + write_reg(GYR_ADDRESS,L3GD20_CTRL_REG1,reg_v); + set_offset(); + set_noise(); + + offset_angle[0]=0; + offset_angle[1]=0; + offset_angle[2]=0; + ADXL_setup(); + set_angleoffset(); + } +void ANGLE::ADXL_setup(){ + z_offset=2;x_offset=0;y_offset=0; + char buffer[6]; + + for(int i=0;i<sampleNum;i++) + { + data_multi_get(ADXL345_DATAX0_REG, buffer, 6); + int Xacc = (int)buffer[1] << 8 | (int)buffer[0]; + int Yacc = (int)buffer[3] << 8 | (int)buffer[2]; + int Zacc = (int)buffer[5] << 8 | (int)buffer[4]-255; + if((int)Xacc-x_offset>xnoise) + xnoise=(int)Xacc-x_offset; + else if((int)Xacc-x_offset<-xnoise) + xnoise=-(int)Xacc-x_offset; + + if((int)Yacc-y_offset>ynoise) + ynoise=(int)Yacc-y_offset; + else if((int)Yacc-y_offset<-ynoise) + ynoise=-(int)Yacc-y_offset; + + if((int)Zacc-z_offset>znoise) + znoise=(int)Zacc-z_offset; + else if((int)Zacc-z_offset<-znoise) + znoise=-(int)Zacc-z_offset; + } + + +} +void ANGLE::ADXL_setnum(int Num,float time,double rate){ + sampleNum=Num;sampleTime=time;Rate=rate; +} +char ANGLE::data_single_get(char reg){ + char tx = reg; + char output; + i2c_.write( acc_i2c_write , &tx, 1); //tell it what you want to read + i2c_.read( acc_i2c_read , &output, 1); //tell it where to store the data + return output; +} +int ANGLE::data_single_put(char reg, char data){ + int ack = 0; + char tx[2]; + tx[0] = reg; + tx[1] = data; + return ack | i2c_.write( acc_i2c_write , tx, 2); +} + + + +void ANGLE::data_multi_get(char reg, char* data, int size) { + i2c_.write( acc_i2c_write, ®, 1); //tell it where to read from + i2c_.read( acc_i2c_read , data, size); //tell it where to store the data read +} + + +int ANGLE::data_multi_put(char reg, char* data, int size) { + int ack; + + ack = i2c_.write( acc_i2c_write, ®, 1); //tell it where to write to + return ack | i2c_.write( acc_i2c_read, data, size); //tell it what data to write +} +void ANGLE::getangle_acc(double* DATA_ANGLE){ + char buffer[6]; + short data[3]; + //data_multi_get(ADXL345_DATAX0_REG, buffer, 6); + getaxis_acc(data); + // calculate the absolute of the magnetic field vector // 8-Bit pieces of axis data + // read axis registers using I2C + + /*data[0] = (short) (buffer[1] << 8 | buffer[0]);//-x_offset; // join 8-Bit pieces to 16-bit short integers + data[1] = (short) (buffer[3] << 8 | buffer[2]);//-y_offset; + data[2] = (short) (buffer[5] << 8 | buffer[4]);//-z_offset;*/ + float R = sqrt(pow((float)data[0],2) + pow((float)data[1],2) + pow((float)data[2],2)); + DATA_ANGLE[1] = -((180 / 3.1415) * acos((float)data[1] / R)-90); // roll - angle of magnetic field vector in x direction + DATA_ANGLE[0] = (180 / 3.1415) * acos((float)data[0] / R)-90; // pitch - angle of magnetic field vector in y direction + DATA_ANGLE[2] = (180 / 3.1415) * acos((float)data[2] / R); //*/ + DATA_ANGLE[0] = atan2(data[0],sqrt(pow((float)data[1],2)+pow((float)data[2],2)))*180/3.1415; + DATA_ANGLE[1] = atan2(data[1],sqrt(pow((float)data[0],2)+pow((float)data[2],2)))*180/3.1415; + DATA_ANGLE[2] = atan2(sqrt(pow((float)data[1],2)+pow((float)data[2],2)),data[2])*180/3.1415; + /*DATA_ANGLE[0]=atan2((double)data[0],(double)data[2])* (180 / 3.1415); + DATA_ANGLE[1]=atan2((double)data[1],(double)data[2])* (180 / 3.1415); + /* if(data[0]>255) + DATA_ANGLE[0]=-90; + else if(data[0]<-263) + DATA_ANGLE[0]=90; + if(data[1]>260) + DATA_ANGLE[1]=90; + else if(data[1]<-246) + DATA_ANGLE[1]=-90; + /*if(DATA[1]>250) + DATA_ANGLE[1]=90; + else if(DATA[1]<-260) + DATA_ANGLE[1]=-90; + if(DATA[0]>250) + DATA_ANGLE[0]=90; + else if(DATA[0]<-260) + DATA_ANGLE[0]=-90;*/ + } +void ANGLE::getaxis_acc(short* DATA_ACC){ + char buffer[6]; + data_multi_get(ADXL345_DATAX0_REG, buffer, 6); + + DATA_ACC[0] = ((short)buffer[1] << 8 | (short)buffer[0]);//+0.1*tempDATA_ACC[0];//-x_offset; + DATA_ACC[1] = ((short)buffer[3] << 8 | (short)buffer[2]);//+0.1*tempDATA_ACC[1];//-y_offset; + DATA_ACC[2] = ((short)buffer[5] << 8 | (short)buffer[4]);//+0.1*tempDATA_ACC[2];//-z_offset; + DATA_ACC[0] = (short)(DATA_ACC[0]*0.9+tempDATA_ACC[0]*0.1); + DATA_ACC[1] = (short)(DATA_ACC[1]*0.9+tempDATA_ACC[0]*0.1); + DATA_ACC[2] = (short)(DATA_ACC[2]*0.9+tempDATA_ACC[0]*0.1); + tempDATA_ACC[0]=DATA_ACC[0]; + tempDATA_ACC[1]=DATA_ACC[1]; + tempDATA_ACC[2]=DATA_ACC[2];//*/ +} +void ANGLE::get_rate(short* RATE) +{ + short axis[3]; + short offset_t[3]={-1,+1,0}; + read(axis); + for(int i=0; i<3; i++){ + RATE[i]=(short)(axis[i])*0.01-offset_t[i]; + //RATE[i]=(floor(RATE[i])); + } +} +void ANGLE::get_angle(double *x,double *y,double *z) +{ + *x=(floor(angle[0]*100.0)/100.0); + *y=(floor(angle[1]*100.0)/100.0); + *z=(floor(angle[2]*100.0)/100.0); +} +void ANGLE::get_angle_rate(double *x,double *y,double *z) +{ + + *x=t[0]; + *y=t[1]; + *z=t[2]; +} + +void ANGLE::get_Synthesis_angle(double* X,double* Y) +{ + *X=Synthesis_angle[0]; + *Y=Synthesis_angle[1]; +} +void ANGLE::get_Comp_angle(double* X,double* Y) +{ + *X=comp_angle[0]; + *Y=comp_angle[1]; +} +void ANGLE::get_Kalman_angle(double* X,double* Y) +{ + *X=kalman_angle[0]; + *Y=kalman_angle[1]; +} +void ANGLE::set_angle(double ANG_x,double ANG_y,double ANG_z) +{ + Synthesis_angle[0]=angle[0]=ANG_x; + Synthesis_angle[1]=angle[1]=ANG_y; + angle[2]=ANG_z; +} +void ANGLE::set_angle() +{ + get_rate(rate); + double g[3], d[3]; + get_angle(g,g+1,g+2); + getangle_acc(d); + double S[3]; + for(int i=0; i<3; i++) { + //rate[i]=rate[i]*0.00875; + + S[i] =((double)(rate[i]+prev_rate[i])*sampleTime/2); + // S[i]=(floor(S[i]*100.0)/100.0);//-offset_angle[i]; + //angle[i]+=(floor(t[i]*100.0)/100.0);//-offset_angle[i]; + angle[i]+=(double)S[i]; + Synthesis_angle[i]+=(double)S[i]; + Synthesis_angle[i]=0.99*(double)(Synthesis_angle[i]+(double)rate[i]/1020.5)+0.01*d[i]; + kalman_angle[i]=kalma[i].getAngle((double)d[i], (double)rate[i], (double)sampleTime*1000); + comp_angle[i]=kalman_angle[i]*0.01+Synthesis_angle[i]*0.01+comp_angle[i]*0.98; + prev_rate[i]=rate[i]; + } +} +void ANGLE::set_angleoffset() +{ + double axis[3],offseta[3]; + offseta[0]=offseta[1]=offseta[2]=0; + offset_angle[0]=0; + offset_angle[1]=0; + offset_angle[2]=0; + for(int i=0; i<sampleNum; i++) { + set_angle(); + get_angle_rate(axis,axis+1,axis+2); + offseta[0]+=axis[0]; + offseta[1]+=axis[1]; + offseta[2]+=axis[2]; + } + offset_angle[0]=offseta[0]/sampleNum; + offset_angle[1]=offseta[1]/sampleNum; + offset_angle[2]=offseta[2]/sampleNum; + offset_angle[0]=(floor(offset_angle[0]*100.0)/100.0); + offset_angle[1]=(floor(offset_angle[1]*100.0)/100.0); + offset_angle[2]=(floor(offset_angle[2]*100.0)/100.0); + angle[0]=0; + angle[1]=0; + angle[2]=0; +} +void ANGLE::set_noise() +{ + short gyal[3]; + noise[0]=noise[1]=noise[2]=0; + + for(int i=0; i<sampleNum; i++) { + + for(int t=0; t<3; t++) { + read(gyal); + if((int)gyal[t]>noise[t]) + noise[t]=(int)gyal[t]; + else if((int)gyal[t]<-noise[t]) + noise[t]=-(int)gyal[t]; + } + } + noise[0]*=sampleTime; + noise[1]*=sampleTime; + noise[2]*=sampleTime; +} +void ANGLE::set_offset() +{ + short axis[3],offseta[3]; + offseta[0]=0; + offseta[1]=0; + offseta[2]=0; + for(int i=0; i<sampleNum; i++) { + read(axis); + offseta[0]+=axis[0]; + offseta[1]+=axis[1]; + offseta[2]+=axis[2]; + } + offset[0]=offseta[0]/sampleNum; + offset[1]=offseta[1]/sampleNum; + offset[2]=offseta[2]/sampleNum; +} +bool ANGLE::read(short *axis) +{ + char gyr[6]; + + if (recv(GYR_ADDRESS, L3GD20_OUT_X_L, gyr, 6)) { + //scale is 8.75 mdps/digit + axis[0] = (short(gyr[1] << 8 | gyr[0]))-offset[0]; + axis[1] = (short(gyr[3] << 8 | gyr[2]))-offset[1]; + axis[2] = (short(gyr[5] << 8 | gyr[4]))-offset[2]; + + + return true; + } + + return false; +} +bool ANGLE::read(float *gx, float *gy, float *gz) +{ + char gyr[6]; + + if (recv(GYR_ADDRESS, L3GD20_OUT_X_L, gyr, 6)) { + //scale is 8.75 mdps/digit + *gx = float(short(gyr[1] << 8 | gyr[0])-offset[0])*0.00875*sampleTime; + *gy = float(short(gyr[3] << 8 | gyr[2])-offset[1])*0.00875*sampleTime; + *gz = float(short(gyr[5] << 8 | gyr[4])-offset[2])*0.00875*sampleTime; + + + return true; + } + + return false; +} + + + + +bool ANGLE::write_reg(int addr_i2c,int addr_reg, char v) +{ + char data[2] = {addr_reg, v}; + return ANGLE::i2c_.write(addr_i2c, data, 2) == 0; +} + +bool ANGLE::read_reg(int addr_i2c,int addr_reg, char *v) +{ + char data = addr_reg; + bool result = false; + + __disable_irq(); + if ((i2c_.write(addr_i2c, &data, 1) == 0) && (i2c_.read(addr_i2c, &data, 1) == 0)) { + *v = data; + result = true; + } + __enable_irq(); + return result; +} + + +bool ANGLE::recv(char sad, char sub, char *buf, int length) +{ + if (length > 1) sub |= 0x80; + + return i2c_.write(sad, &sub, 1, true) == 0 && i2c_.read(sad, buf, length) == 0; +} +int ANGLE::setPowerMode(char mode) { + + //Get the current register contents, so we don't clobber the rate value. + char registerContents = (mode << 4) | data_single_get(ADXL345_BW_RATE_REG); + + return data_single_put(ADXL345_BW_RATE_REG, registerContents); + +} +int ANGLE::setDataRate(char rate) { + + //Get the current register contents, so we don't clobber the power bit. + char registerContents = data_single_get(ADXL345_BW_RATE_REG); + + registerContents &= 0x10; + registerContents |= rate; + + return data_single_put(ADXL345_BW_RATE_REG, registerContents); + +} +char ANGLE::getOffset(char axis) { + + char address = 0; + + if (axis == ADXL345_X) { + address = ADXL345_OFSX_REG; + } else if (axis == ADXL345_Y) { + address = ADXL345_OFSY_REG; + } else if (axis == ADXL345_Z) { + address = ADXL345_OFSZ_REG; + } + + return data_single_get(address); +} + +int ANGLE::setOffset(char axis, char offset) { + + char address = 0; + + if (axis == ADXL345_X) { + address = ADXL345_OFSX_REG; + } else if (axis == ADXL345_Y) { + address = ADXL345_OFSY_REG; + } else if (axis == ADXL345_Z) { + address = ADXL345_OFSZ_REG; + } + + return data_single_put(address, offset); + +} +int ANGLE::setTapDuration(short int duration_us) { + + short int tapDuration = duration_us / 625; + char tapChar[2]; + tapChar[0] = (tapDuration & 0x00FF); + tapChar[1] = (tapDuration >> 8) & 0x00FF; + return data_multi_put(ADXL345_DUR_REG, tapChar, 2); + +} +int ANGLE::setTapLatency(short int latency_ms) { + + latency_ms = latency_ms / 1.25; + char latChar[2]; + latChar[0] = (latency_ms & 0x00FF); + latChar[1] = (latency_ms << 8) & 0xFF00; + return data_multi_put(ADXL345_LATENT_REG, latChar, 2); + +} +int ANGLE::setWindowTime(short int window_ms) { + + window_ms = window_ms / 1.25; + char windowChar[2]; + windowChar[0] = (window_ms & 0x00FF); + windowChar[1] = ((window_ms << 8) & 0xFF00); + return data_multi_put(ADXL345_WINDOW_REG, windowChar, 2); + +} +int ANGLE::setFreefallTime(short int freefallTime_ms) { + freefallTime_ms = freefallTime_ms / 5; + char fallChar[2]; + fallChar[0] = (freefallTime_ms & 0x00FF); + fallChar[1] = (freefallTime_ms << 8) & 0xFF00; + + return data_multi_put(ADXL345_TIME_FF_REG, fallChar, 2); + +} +ANGLE::kalman::kalman(void){ + P[0][0] = 0; + P[0][1] = 0; + P[1][0] = 0; + P[1][1] = 0; + + angle = 0; + bias = 0; + + Q_angle = 0.001; + Q_gyroBias = 0.003; + R_angle = 0.03; +} + +double ANGLE::kalman::getAngle(double newAngle, double newRate, double dt){ + //predict the angle according to the gyroscope + rate = newRate - bias; + angle = dt * rate; + //update the error covariance + P[0][0] += dt * (dt * P[1][1] * P[0][1] - P[1][0] + Q_angle); + P[0][1] -= dt * P[1][1]; + P[1][0] -= dt * P[1][1]; + P[1][1] += dt * Q_gyroBias; + //difference between the predicted angle and the accelerometer angle + y = newAngle - angle; + //estimation error + S = P[0][0] + R_angle; + //determine the kalman gain according to the error covariance and the distrust + K[0] = P[0][0]/S; + K[1] = P[1][0]/S; + //adjust the angle according to the kalman gain and the difference with the measurement + angle += K[0] * y; + bias += K[1] * y; + //update the error covariance + P[0][0] -= K[0] * P[0][0]; + P[0][1] -= K[0] * P[0][1]; + P[1][0] -= K[1] * P[0][0]; + P[1][1] -= K[1] * P[0][1]; + + return angle; +} +void ANGLE::kalman::setAngle(double newAngle) { angle = newAngle; }; +void ANGLE::kalman::setQangle(double newQ_angle) { Q_angle = newQ_angle; }; +void ANGLE::kalman::setQgyroBias(double newQ_gyroBias) { Q_gyroBias = newQ_gyroBias; }; +void ANGLE::kalman::setRangle(double newR_angle) { R_angle = newR_angle; }; + +double ANGLE::kalman::getRate(void) { return rate; }; +double ANGLE::kalman::getQangle(void) { return Q_angle; }; +double ANGLE::kalman::getQbias(void) { return Q_gyroBias; }; +double ANGLE::kalman::getRangle(void) { return R_angle; }; +