green rosh
/
BAE_FRDM_INTEGRATION
bae integrated final (may be)
Fork of BAE_FRDMTESIN2 by
Revision 8:667fbc82d634, committed 2014-12-15
- Comitter:
- greenroshks
- Date:
- Mon Dec 15 05:58:23 2014 +0000
- Parent:
- 7:f06840d848e3
- Commit message:
- BAE FINAL INTEGRATED (may be)
Changed in this revision
diff -r f06840d848e3 -r 667fbc82d634 ACS.cpp --- a/ACS.cpp Wed Dec 10 06:34:17 2014 +0000 +++ b/ACS.cpp Mon Dec 15 05:58:23 2014 +0000 @@ -1,18 +1,34 @@ #include "ACS.h" +#include "MPU3300.h" - -PwmOut PWM1(PTD4); //Functions used to generate PWM signal +//PwmOut PWM1(PTD4); //Functions used to generate PWM signal //PWM output comes from pins p6 Serial pc1(USBTX, USBRX); - +SPI spi_acs (D11, D12, D13); // mosi, miso, sclk +DigitalOut SSN_MAG (D8); // ssn for magnetometer +DigitalIn DRDY (D9); // drdy for magnetometer +DigitalOut ssn_gyr (D10); //Slave Select pin of gyroscope +InterruptIn dr(D7); //Interrupt pin for gyro +PwmOut PWM1(A0); //Functions used to generate PWM signal +PwmOut PWM2(A1); +PwmOut PWM3(A2); //PWM output comes from pins p6 +Ticker tr; //Ticker function to give values for limited amount of time for gyro +Timeout tr_mag; +uint8_t trflag_mag; +uint8_t trFlag; //ticker Flag for gyro +uint8_t drFlag; //data-ready interrupt flag for gyro -void FUNC_ACS_GENPWM() +//--------------------------------TORQUE ROD--------------------------------------------------------------------------------------------------------------// + +void FUNC_ACS_GENPWM(float M[3]) { + + printf("\nEnterd PWMGEN function\n"); - double DCx = 0; //Duty cycle of Moment in x, y, z directions - double ix = 0; //Current sent in x, y, z TR's + float DCx = 0; //Duty cycle of Moment in x, y, z directions + float ix = 0; //Current sent in x, y, z TR's float timep = 0.02 ; - double Mx=1.5; //Time period is set to 0.2s + float Mx=M[0]; //Time period is set to 0.02s //Moment in x, y, z directions @@ -54,8 +70,516 @@ { // printf("!!!!!!!!!!Error!!!!!!!!!"); } + float DCy = 0; //Duty cycle of Moment in x, y, z directions + float iy = 0; //Current sent in x, y, z TR's + + float My=M[1]; //Time period is set to 0.2s + //Moment in x, y, z directions + + + iy = My * 0.3 ; //Moment and Current always have the linear relationship + + if( iy>0&& iy < 0.006 ) //Current and Duty cycle have the linear relationship between 1% and 100% + { + DCy = 6*1000000*pow(iy,4) - 377291*pow(iy,3) + 4689.6*pow(iy,2) + 149.19*iy - 0.0008; + PWM2.period(timep); + PWM2 = DCy/100 ; + } + else if( iy >= 0.006&& iy < 0.0116) + { + DCy = 1*100000000*pow(iy,4) - 5*1000000*pow(iy,3) + 62603*pow(iy,2) - 199.29*iy + 0.7648; + PWM2.period(timep); + PWM2 = DCy/100 ; + } + else if (iy >= 0.0116&& iy < 0.0624) + { + DCy = 212444*pow(iy,4) - 33244*pow(iy,3) + 1778.4*pow(iy,2) + 120.91*iy + 0.3878; + PWM2.period(timep); + PWM2 = DCy/100 ; + } + else if(iy >= 0.0624&& iy < 0.555) + { + printf("\nACS entered if\n"); + DCy = 331.15*pow(iy,4) - 368.09*pow(iy,3) + 140.43*pow(iy,2) + 158.59*iy + 0.0338; + PWM2.period(timep); + PWM2 = DCy/100 ; + } + else if(iy==0) + { + DCy = 0; + PWM2.period(timep); + PWM2 = DCy/100 ; + } + else + { + // printf("!!!!!!!!!!Error!!!!!!!!!"); + } + float DCz = 0; //Duty cycle of Moment in x, y, z directions + float iz = 0; //Current sent in x, y, z TR's + + float Mz=M[2]; //Time period is set to 0.2s + //Moment in x, y, z directions + + + iz = Mz * 0.3 ; //Moment and Current always have the linear relationship + + if( iz>0&& iz < 0.006 ) //Current and Duty cycle have the linear relationship between 1% and 100% + { + DCz = 6*1000000*pow(iz,4) - 377291*pow(iz,3) + 4689.6*pow(iz,2) + 149.19*iz - 0.0008; + PWM3.period(timep); + PWM3 = DCz/100 ; + } + else if( iz >= 0.006&& iz < 0.0116) + { + DCz = 1*100000000*pow(iz,4) - 5*1000000*pow(iz,3) + 62603*pow(iz,2) - 199.29*iz + 0.7648; + PWM3.period(timep); + PWM3 = DCz/100 ; + } + else if (iz >= 0.0116&& iz < 0.0624) + { + + DCz = 212444*pow(iz,4) - 33244*pow(iz,3) + 1778.4*pow(iz,2) + 120.91*iz + 0.3878; + PWM3.period(timep); + PWM3 = DCz/100 ; + } + else if(iz >= 0.0624&& iz < 0.555) + { + printf("\nACS entered if\n"); + DCz = 331.15*pow(iz,4) - 368.09*pow(iz,3) + 140.43*pow(iz,2) + 158.59*iz + 0.0338; + PWM3.period(timep); + PWM3 = DCz/100 ; + } + else if(iz==0) + { + DCz = 0; + PWM3.period(timep); + PWM3 = DCz/100 ; + } + else + { + // printf("!!!!!!!!!!Error!!!!!!!!!"); + } printf("\nExited PWMGEN function\n"); } - \ No newline at end of file +/*------------------------------------------------------------------------------------------------------------------------------------------------------- +-------------------------------------------MAGNETOMETER-------------------------------------------------------------------------------------------------*/ + +void trsub_mag() +{ + trflag_mag=0; +} + +void FUNC_ACS_MAG_INIT() + { + + SSN_MAG=1; //pin is disabled + spi_acs.format(8,0); // 8bits,Mode 0 + spi_acs.frequency(100000); //clock frequency + + SSN_MAG=0; // Selecting pin + wait_ms(10); //accounts for delay.can be minimised. + + spi_acs.write(0x83); // + + wait_ms(10); + + unsigned char i; + for(i=0;i<3;i++)//initialising values. + { + spi_acs.write(0x00); //MSB of X,y,Z + spi_acs.write(0xc8); //LSB of X,Y,z;pointer increases automatically. + } + SSN_MAG=1; + +} + +float* FUNC_ACS_MAG_EXEC() +{ + printf("\nEntered magnetometer function\n"); + SSN_MAG=0; //enabling slave to measure the values + wait_ms(10); + spi_acs.write(0x82); //initiates measurement + wait_ms(10); + spi_acs.write(0x01); //selecting x,y and z axes, measurement starts now + SSN_MAG=1; + wait_ms(10); + + trflag_mag=1; + tr_mag.attach(&trsub_mag,1); //runs in background,makes trflag_mag=0 after 1s + + while(trflag_mag) /*initially flag is 1,so loop is executed,if DRDY is high,then data is retrieved and programme ends,else + loop runs for at the max 1s and if still DRDY is zero,the flag becomes 0 and loop is not executed and + programme is terminated*/ + { + if(DRDY==1) + { + SSN_MAG=0; + spi_acs.write(0xc9); //command byte for retrieving data + + unsigned char axis; + float Bnewvalue[3]={0.0,0.0,0.0}; + int32_t Bvalue[3]={0,0,0}; + int32_t a= pow(2.0,24.0); + int32_t b= pow(2.0,23.0); + + for(axis=0;axis<3;axis++) + { + Bvalue[axis]=spi_acs.write(0x00)<<16; //MSB 1 is send first + wait_ms(10); + Bvalue[axis]|=spi_acs.write(0x00)<<8; //MSB 2 is send next + wait_ms(10); + Bvalue[axis]|=spi_acs.write(0x00); //LSB is send.....total length is 24 bits(3*8bits)...which are appended to get actual bit configuration + + + if((Bvalue[axis]&b)==b) + { + Bvalue[axis]=Bvalue[axis]-a; //converting 2s complement to signed decimal + + } + Bnewvalue[axis]=(float)Bvalue[axis]*22.0*pow(10.0,-3.0); //1 LSB=(22nT)...final value of field obtained in micro tesla + + wait_ms(10); + printf("\t%lf\n",Bnewvalue[axis]); + + } + SSN_MAG=1; + + return Bnewvalue; //return here? doubt.. + break; + } + + } + +} +/*------------------------------------------------------------------------------------------------------------------------------------------------------ +-------------------------------------------CONTROL ALGORITHM------------------------------------------------------------------------------------------*/ + +float * FUNC_ACS_CNTRLALGO(float b[3],float omega[3]) +{ + float db[3]; /// inputs +//initialization + float bb[3] = {0, 0, 0}; + float d[3] = {0, 0, 0}; + float Jm[3][3] = {{0.2730, 0, 0}, {0, 0.3018, 0}, {0, 0, 0.3031}}; + float den = 0; + float den2; + int i, j; //temporary variables + float Mu[2], z[2], dv[2], v[2], u[2], tauc[3] = {0, 0, 0}; //outputs + float invJm[3][3]; + float kmu2 = 0.07, gamma2 = 1.9e4, kz2 = 0.4e-2, kmu = 0.003, gamma = 5.6e4, kz = 0.1e-4; + printf("Entered cntrl algo\n"); + //structure parameters + + void inverse (float mat[3][3], float inv[3][3]); + void getInput (float x[9]); + //functions + +////////// Input from Matlab ////////////// + while(1) + { + + /*getInput(inputs); +//while(1) + b[0] = inputs[0]; + b[1] = inputs[1]; + b[2] = inputs[2]; + db[0] = inputs[3]; + db[1] = inputs[4]; + db[2] = inputs[5]; + omega[0] = inputs[6]; + omega[1] = inputs[7]; + omega[2] = inputs[8];*/ +/////////// Control Algorithm ////////////////////// +// calculate norm b, norm db + den = sqrt((b[0]*b[0]) + (b[1]*b[1]) + (b[2]*b[2])); + den2 = (b[0]*db[0]) + (b[1]*db[1]) + (b[2]*db[2]); + + for(i=0;i<3;i++) + { + db[i] = (db[i]*den*den-b[i]*den2) / (pow(den,3)); +//db[i]/=den*den*den; + } + + for(i=0;i<3;i++) + { + printf("\nreached here\n"); + if(den!=0) + b[i]=b[i]/den; //there is a problem here. The code gets stuck here + + } + +// select kz, kmu, gamma + if(b[0]>0.9 || b[0]<-0.9) + { + kz = kz2; + kmu = kmu2; + gamma = gamma2; + } +// calculate Mu, v, dv, z, u + for(i=0;i<2;i++) + { + Mu[i] = b[i+1]; + v[i] = -kmu*Mu[i]; + dv[i] = -kmu*db[i+1]; + z[i] = db[i+1] - v[i]; + u[i] = -kz*z[i] + dv[i]-(Mu[i] / gamma); + } + inverse(Jm, invJm); +// calculate cross(omega,J*omega)for(i=0;i<3;i++) + + for(j=0;j<3;j++) + bb[i] += omega[j]*(omega[(i+1)%3]*Jm[(i+2)%3][j] - omega[(i+2)%3]*Jm[(i+1)%3][j]); + +// calculate invJm*cross(omega,J*omega) store in d + for(i=0;i<3;i++) + { + for(j=0;j<3;j++) + d[i] += bb[j]*invJm[i][j]; + } +// calculate d = cross(invJm*cross(omega,J*omega),b) -cross(omega,db) +// bb =[0;u-d(2:3)] +// store in bb + bb[1] = u[0] + (d[0]*b[2])-(d[2]*b[0])-(omega[0]*db[2]) + (omega[2]*db[0]); + bb[2] = u[1]-(d[0]*b[1]) + (d[1]*b[0]) + (omega[0]*db[1])-(omega[1]*db[0]); + bb[0] = 0; +// calculate N +// reusing invJm as N + + for(i=0;i<3;i++) + { + d[i] = invJm[1][i]; + invJm[ 1][i] = b[2]*invJm[0][i] - b[0]*invJm[2][i]; + invJm[2][i] = -b[1]*invJm[0][i] + b[0]*d[i]; + invJm[0][i] = b[i]; + } +// calculate inv(N) store in Jm + inverse(invJm, Jm); +// calculate tauc + for(i=0;i<3;i++) + { + for(j=0;j<3;j++) + tauc[i] += Jm[i][j]*bb[j]; + } + + return(tauc); + } +} +/////////// Output to Matlab ////////////////// +/* for(i=0;i<3;i++) { + printf("%f\n",tauc[i]*10000000); + wait_ms(10); + } + } + +}*/ + void inverse(float mat[3][3], float inv[3][3]) +{ +int i, j; +float det = 0; +for(i=0;i<3;i++) +{ for(j=0;j<3;j++) +inv[j][i] = (mat[(i+1)%3][(j+1)%3]*mat[(i+2)%3][(j+2)%3]) - (mat[(i+2)%3] +[(j+1)%3]*mat[(i+1)%3][(j+2)%3]); +} +det += (mat[0][0]*inv[0][0]) + (mat[0][1]*inv[1][0]) + (mat[0][2]*inv[2][0]); +for(i=0;i<3;i++) +{ for(j=0;j<3;j++) +inv[i][j] /= det; +} +}/* +void getInput (float x[9]) { + //Functions used to generate PWM signal + //PWM output comes from pins p6 +Serial pc1(USBTX, USBRX); + char c[10]; + char tempchar[8]; + int i, j; + //float f[9]; + long n = 0; + float flval = 0; + for(j=0;j<9;j++) { + for(i=0;i<9;i++) { + c[i] = pc1.getc(); if(i<8) { + tempchar[i] = c[i]; + } + } + sscanf (tempchar, "%8x", &n); + memcpy(&flval, &n, sizeof(long)); + printf("%f\n", flval); + x[j] = flval; + } +}*/ + +void trSub(); +void drSub(); +void init_gyro(); +float * FUNC_ACS_EXEC_GYR(); + +void drSub() //In this function we setting data-ready flag to 1 +{ + drFlag=1; +} +void trSub() //In this function we are setting ticker flag to 0 +{ + trFlag=0; +} +void FUNC_ACS_INIT_GYR() +{ + uint8_t response; + ssn_gyr=1; //Deselecting the chip + spi_acs.format(8,3); // Spi format is 8 bits, and clock mode 3 + spi_acs.frequency(1000000); //frequency to be set as 1MHz + drFlag=0; //Intially defining data-ready flag to be 0 + dr.mode(PullDown); + dr.rise(&drSub); + __disable_irq(); + +/*Following the above mentioned algorithm for initializing the register and changing its configuration*/ + ssn_gyr=0; //Selecting chip(Mpu-3300) + spi_acs.write(USER_CTRL|READFLAG); //sending USER_CTRL address with read bit + response=spi_acs.write(DUMMYBIT); //sending dummy bit to get default values of the register + + ssn_gyr=1; //Deselecting the chip + wait(0.1); //waiting according the product specifications + + ssn_gyr=0; //again selecting the chip + spi_acs.write(USER_CTRL); //sending USER_CTRL address without read bit + spi_acs.write(response|BIT_I2C_IF_DIS); //disabling the I2C mode in the register + ssn_gyr=1; //deselecting the chip + wait(0.1); // waiting for 100ms before going for another register + + ssn_gyr=0; + spi_acs.write(PWR_MGMT_1|READFLAG); //Power Management register-1 + response=spi_acs.write(DUMMYBIT); + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(PWR_MGMT_1); + response=spi_acs.write(response|BIT_CLKSEL_X); //Selecting the X axis gyroscope as clock as mentioned above + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(GYRO_CONFIG|READFLAG); //sending GYRO_CONFIG address with read bit + response=spi_acs.write(DUMMYBIT); + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(GYRO_CONFIG); //sending GYRO_CONFIG address to write to register + spi_acs.write(response&(~(BITS_FS_SEL_3|BITS_FS_SEL_4))); //selecting a full scale mode of +/=225 deg/sec + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(CONFIG|READFLAG); //sending CONFIG address with read bit + response=spi_acs.write(DUMMYBIT); + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(CONFIG); //sending CONFIG address to write to register + spi_acs.write(response|BITS_DLPF_CFG); //selecting a bandwidth of 42 hz and delay of 4.8ms + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(SMPLRT_DIV|READFLAG); //sending SMPLRT_DIV address with read bit + response=spi_acs.write(DUMMYBIT); + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(SMPLRT_DIV); //sending SMPLRT_DIV address to write to register + spi_acs.write(response&BITS_SMPLRT_DIV); //setting the sampling rate division to be 0 to make sample rate = gyroscopic output rate + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(INT_ENABLE|READFLAG); //sending address of INT_ENABLE with readflag + response=spi_acs.write(DUMMYBIT); //sending dummy byte to get the default values of the + // regiser + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(INT_ENABLE); //sending INT_ENABLE address to write to register + spi_acs.write(response|BIT_DATA_RDY_ENABLE); //Enbling data ready interrupt + ssn_gyr=1; + wait(0.1); + + __enable_irq(); +} + +float * FUNC_ACS_EXEC_GYR() +{ + printf("\nEntered gyro\n"); + uint8_t response; + uint8_t MSB,LSB; + int16_t bit_data; + float data[3],error[3]={0,0,0}; //declaring error array to add to the values when required + float senstivity = 145.6; //senstivity is 145.6 for full scale mode of +/-225 deg/sec + ssn_gyr=0; + spi_acs.write(PWR_MGMT_1|READFLAG); //sending address of INT_ENABLE with readflag + response=spi_acs.write(DUMMYBIT); // + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(PWR_MGMT_1); //sending PWR_MGMT_1 address to write to register + response=spi_acs.write(response&(~(BIT_SLEEP))); //waking up the gyroscope from sleep + ssn_gyr=1; + wait(0.1); + + trFlag=1; + tr.attach(&trSub,1); //executes the function trSub afer 1sec + + while(trFlag) + { + wait_ms(5); //This is required for this while loop to exit. I don't know why. + if(drFlag==1) + { + ssn_gyr=0; + spi_acs.write(GYRO_XOUT_H|READFLAG); //sending address of PWR_MGMT_1 with readflag + for(int i=0;i<3;i++) + { + MSB = spi_acs.write(DUMMYBIT); //reading the MSB values of x,y and z respectively + LSB = spi_acs.write(DUMMYBIT); //reading the LSB values of x,y and z respectively + bit_data= ((int16_t)MSB<<8)|LSB; //concatenating to get 16 bit 2's complement of the required gyroscope values + data[i]=(float)bit_data; + data[i]=data[i]/senstivity; //dividing with senstivity to get the readings in deg/sec + data[i]+=error[i]; //adding with error to remove offset errors + } + ssn_gyr=1; + for (int i=0;i<3;i++) + { + printf("%f\t",data[i]); //printing the angular velocity values + } + printf("\n"); + break; + } + drFlag=0; + } + ssn_gyr=0; + spi_acs.write(PWR_MGMT_1|READFLAG); //sending address of PWR_MGMT_1 with readflag + response=spi_acs.write(DUMMYBIT); + ssn_gyr=1; + wait(0.1); + + ssn_gyr=0; + spi_acs.write(PWR_MGMT_1); //sending PWR_MGMT_1 address to write to register + response=spi_acs.write(response|BIT_SLEEP); //setting the gyroscope in sleep mode + ssn_gyr=1; + wait(0.1); + printf("\nExited gyro\n"); + return data; +} + + + + + +
diff -r f06840d848e3 -r 667fbc82d634 ACS.h --- a/ACS.h Wed Dec 10 06:34:17 2014 +0000 +++ b/ACS.h Mon Dec 15 05:58:23 2014 +0000 @@ -1,3 +1,10 @@ #include "mbed.h" +#include "math.h" -void FUNC_ACS_GENPWM(void); \ No newline at end of file +void FUNC_ACS_GENPWM(float *); +float * FUNC_ACS_MAG_EXEC(void); +void FUNC_ACS_MAG_INIT(); +//void Read_data_acs() +float * FUNC_ACS_CNTRLALGO(float*,float*); +float * FUNC_ACS_EXEC_GYR(); +void FUNC_ACS_INIT_GYRO();
diff -r f06840d848e3 -r 667fbc82d634 HK.cpp --- a/HK.cpp Wed Dec 10 06:34:17 2014 +0000 +++ b/HK.cpp Mon Dec 15 05:58:23 2014 +0000 @@ -1,79 +1,139 @@ #include "HK.h" - -DigitalOut SelectLine3 (D4); // MSB of Select Lines -DigitalOut SelectLine2 (D3); -DigitalOut SelectLine1 (D2); -DigitalOut SelectLine0 (D1); // LSB of Select Lines + MAX17048 master(A4,A5,100000);//CHECK SDA,SCL LINES,FREQUENCY +int quantiz(float start,float step,float x); +//GPIO pins used=> D2-D13, A0-A1 +DigitalOut SelectLinesA[]={D2,D3,D4,D5};//to mux1 +DigitalOut SelectLinesB[]={D6,D7,D8,D9};//to mux2 +DigitalOut SelectLinesC[]={D10,D11,D12,D13};//to mux3 + +//--------------------------------------------MSB is SelectLines[0],LSB is SelectLines[3]-------------------------------- + +AnalogIn CurrentInput(A0); // Input from Current +AnalogIn VoltageInput(A1); // Input from Voltage Multiplexer +AnalogIn TemperatureInput(A2); /*Input from Temperature Multiplexer,thermistor Multiplexer- same multiplexer for both(0-3 for thermistor,4-15 for temperature sensor)*/ + +SensorData Sensor;//struct variable -AnalogIn CurrentInput(A1); // Input from Current Multiplexer -AnalogIn VoltageInput(A2); // Input from Voltage Multiplexer -AnalogIn TemperatureInput(A3); // input from Temperature Multiplexer - -SensorData Sensor; -int quantiz(float start,float step,float x) +int quantiz(float start,float step,float x) // accepts min and measured values and step->quantises on a scale 0-15 { int y=(x-start)/step; if(y<=0)y=0; if(y>=15)y=15; return y; } -ShortBeacy Shortbeacon; -void init_beacon(ShortBeacy x){ - ; + +void init_beacon(ShortBeacy x) //dummy values----------to be changed------------------- +{ + x.Voltage[0]=1; + x.AngularSpeed[0]=2; + x.AngularSpeed[1]=3; + x.SubsystemStatus[0]=145; + x.Temp[0]=1; + x.Temp[1]=2; + x.Temp[2]=3; + x.ErrorFlag[0]=3; } - - -void FUNC_HK_MAIN() + ShortBeacy Shortbeacon;//struct variable +void FUNC_HK_MAIN() { - printf("\nEntered function HK MAIN\n"); - Shortbeacon.Voltage[0]=1; - Shortbeacon.AngularSpeed[0]=2; - Shortbeacon.AngularSpeed[1]=3; - Shortbeacon.SubsystemStatus[0]=145; - Shortbeacon.Temp[0]=1; - Shortbeacon.Temp[1]=2; - Shortbeacon.Temp[2]=3; - Shortbeacon.ErrorFlag[0]=3; + init_beacon(Shortbeacon); + //initialise all selectlines to zeroes->1st line of mux selected + SelectLinesA[0]=SelectLinesA[1]=SelectLinesA[2]=SelectLinesA[3]=0; + SelectLinesB[0]=SelectLinesB[1]=SelectLinesB[2]=SelectLinesB[3]=0; + SelectLinesC[0]=SelectLinesC[1]=SelectLinesC[2]=SelectLinesC[3]=0; int LoopIterator; + float resistance_thermistor,voltage_thermistor;//for thermistor + + for(LoopIterator=0; LoopIterator<16; LoopIterator++) +{ - SelectLine0=0; - SelectLine1=0; - SelectLine2=0; - SelectLine3=0; - - for(LoopIterator=0; LoopIterator<16; LoopIterator++) { - - if(LoopIterator%2==0) { - Sensor.Current[LoopIterator/2]=quantiz(cstart,cstep,((CurrentInput.read()*3.18)/(50*rsens))); + if(LoopIterator%2==0) + { + Sensor.Voltage[LoopIterator/2]=quantiz(vstart,vstep,(VoltageInput.read()*3.18*5.37)); - Sensor.Temperature[LoopIterator/2]=quantiz(tstart,tstep,(-90.7*3.18*TemperatureInput.read()+190.1543)); - } else { - Sensor.Current[(LoopIterator-1)/2]=(Sensor.Current[(LoopIterator-1)/2]<<4)+quantiz(cstart,cstep,((CurrentInput.read()*3.18)/(50*rsens))); - Sensor.Voltage[(LoopIterator-1)/2]=(Sensor.Voltage[(LoopIterator-1)/2]<<4)+quantiz(vstart,vstep,(VoltageInput.read()*3.18*5.37)); - Sensor.Temperature[(LoopIterator-1)/2]=(Sensor.Temperature[(LoopIterator-1)/2]<<4)+quantiz(tstart,tstep,(-90.7*3.18*TemperatureInput.read()+190.1543)); + Sensor.Current[LoopIterator/2]=quantiz(cstart,cstep,(CurrentInput.read()*3.18/(50*rsens))); + if(LoopIterator>3) + Sensor.Temperature[(LoopIterator-4)/2]=quantiz(tstart,tstep,(-90.7*3.18*TemperatureInput.read()+190.1543)); + else + { voltage_thermistor=TemperatureInput.read()*3.18; + resistance_thermistor=24000*voltage_thermistor/(3.3-voltage_thermistor); + if(voltage_thermistor<1.378) //Temperature>12 degC + Sensor.PanelTemperature[(LoopIterator)/2]=quantiz(tstart_thermistor,tstep_thermistor,(3694/log(24.032242*resistance_thermistor))); + + else { + Sensor.PanelTemperature[(LoopIterator)/2]=quantiz(tstart_thermistor,tstep_thermistor,(3365.4792/log(7.60404*resistance_thermistor))); + } } + } + + else + { + + Sensor.Voltage[(LoopIterator-1)/2]=Sensor.Voltage[(LoopIterator-1)/2]<<4+quantiz(vstart,vstep,(VoltageInput.read()*3.18*5.37)); + Sensor.Current[(LoopIterator-1)/2]=Sensor.Current[(LoopIterator-1)/2]<<4+quantiz(cstart,cstep,(CurrentInput.read()*3.18/(50*rsens))); + if(LoopIterator>3) + Sensor.Temperature[(LoopIterator-5)/2]=Sensor.Temperature[(LoopIterator-5)/2]<<4+quantiz(tstart,tstep,(-90.7*3.18*TemperatureInput.read()+190.1543)); + else + { voltage_thermistor=TemperatureInput.read()*3.18; + resistance_thermistor=24000*voltage_thermistor/(3.3-voltage_thermistor); + if(voltage_thermistor<1.378) //Temperature>12 degC + Sensor.PanelTemperature[(LoopIterator-1)/2]=Sensor.PanelTemperature[(LoopIterator-1)/2]<<4+quantiz(tstart_thermistor,tstep_thermistor,(3694/log(24.032242*resistance_thermistor))); + else + Sensor.PanelTemperature[(LoopIterator-1)/2]=Sensor.PanelTemperature[(LoopIterator-1)/2]<<4+quantiz(tstart_thermistor,tstep_thermistor,(3364.4792/log(7.60404*resistance_thermistor))); + + } + } + float batteryparameters[4];//to populate battery parameters of struct variable Sensor + FUNC_BATTERYGAUGE_MAIN(batteryparameters);//passing array to function + + Sensor.Vcell=batteryparameters[0]; + Sensor.soc=batteryparameters[1]; + Sensor.crate=batteryparameters[2]; + Sensor.alerts=batteryparameters[3]; + // The following lines are used to iterate the select lines from 0 to 15 - SelectLine0=!(SelectLine0); - - if(LoopIterator%2==1) - SelectLine1=!(SelectLine1); - - if(LoopIterator%4==3) - SelectLine2=!(SelectLine2); - - if(LoopIterator%8==7) - SelectLine3=!(SelectLine3); - + int SelectLineIterator; + //following is an algorithm similar to counting binary numbers of 4 bit + for(SelectLineIterator=3;SelectLineIterator>=0;SelectLineIterator--) + { + if(SelectLinesA[SelectLineIterator]==0) + { + SelectLinesA[SelectLineIterator]=1; + break; + } + else SelectLinesA[SelectLineIterator]=0; + + SelectLinesB[SelectLineIterator]=SelectLinesA[SelectLineIterator]; + SelectLinesC[SelectLineIterator]=SelectLinesA[SelectLineIterator]; + } + + wait_us(10.0); // A delay of 10 microseconds between each sensor output. Can be changed. } - - printf("\nVoltage is %u\n",Shortbeacon.Voltage[0]); - printf("\nCurrent is %u\n",Shortbeacon.Temp[0]); - + +} +void FUNC_BATTERYGAUGE_MAIN(float array[]) +{ + float vcell=master.vcell(); + float soc=master.soc(); + float crate=master.crate(); + + printf("\nVcell=%f",vcell); + printf("\nSOC=%f",soc); + printf("\nC_rate=%f",crate); - - printf("\nExited function HK MAIN\n"); -} + array[0]=vcell; + array[1]=soc; + array[2]=crate; + if (master.alerting()== true) //alert is on + { + array[3]=master.alertFlags(); + master.clearAlert();//clear alert + master.clearAlertFlags();//clear all alert flags + } + + +} \ No newline at end of file
diff -r f06840d848e3 -r 667fbc82d634 HK.h --- a/HK.h Wed Dec 10 06:34:17 2014 +0000 +++ b/HK.h Mon Dec 15 05:58:23 2014 +0000 @@ -1,36 +1,429 @@ + +//to be saved as HK.h + #include "mbed.h" #define tstart -40 #define tstep 8 +#define tstep_thermistor 8//verify!! +#define tstart_thermistor -40 #define vstart 3.3 #define vstep 0.84667 #define cstart 0.0691 #define cstep 0.09133 #define rsens 0.095 - - - struct SensorData { char Voltage[10]; char Current[10]; char Temperature[10]; - char faultpoll; - char faultir; - char power_mode; - //float Battery[2]; + char PanelTemperature[2];//read by the 4 thermistors on solar panels + char Vcell;//unquantised + char soc;//unquantised + char alerts;//UNQUANTISED + //(alerts[0]=1)-> reset indicator=>dont care + //(alerts[1]=1)-> Vcell>ValrtMax(5.1V)->will always be on->dont care + //(alerts[2]=1)-> Vcell<ValrtMin(5.1V)->indicates deep discharge + //(alerts[3]=1)-> Vcell<Vreset(2.5V) + //(alerts[5]=1)-> Soc CROSSES the threshold value + //(alerts[6]=1)-> alert on (alerts[3]) enabled when Vcell<Vreset(here we set it to be 2.5V) + char crate;//unquantised + char faultpoll; //polled faults + char faultir; //interupted faults + char power_mode; //power modes + + + //float magnetometer,gyro=>to be addes }; typedef struct ShortBeacon { - char Voltage[1]; - char AngularSpeed[2]; - char SubsystemStatus[1]; - char Temp[3]; - char ErrorFlag[1]; -}ShortBeacy; - + char Voltage[1]; //battery voltage from gauge + char AngularSpeed[2]; //all the 3 data + char SubsystemStatus[1]; //power modes + char Temp[3]; //temp of solar panel + char ErrorFlag[1]; //fault +}ShortBeacy; + + void FUNC_HK_MAIN(); int quantiz(float start,float step,float x); - + + +//--------------------------------following is header details for battery gauge------------------------------------------- + + + +#define MAX17048_H + +class MAX17048 +{ +public: + /** The default compensation value for the MAX17048 + */ + static const char RCOMP0= 0x97; + + /** Represents the different alert flags for the MAX17048 + */ + enum AlertFlags { + ALERT_RI = (1 << 0), /**< Reset indicator */ + ALERT_VH = (1 << 1), /**< Voltage high alert */ + ALERT_VL = (1 << 2), /**< Voltage low alert */ + ALERT_VR = (1 << 3), /**< Voltage reset alert */ + ALERT_HD = (1 << 4), /**< SOC low alert */ + ALERT_SC = (1 << 5) /**< SOC change alert */ + }; + + //parametrised constructor + MAX17048(PinName sda, PinName scl, int hz = 400000): m_I2C(sda, scl)//should it be same as the uC clock freq + { + //Set the I2C bus frequency + m_I2C.frequency(hz); + } + + // Probe for the MAX17048 and indicate if it's present on the bus + bool open() + { + //Probe for the MAX17048 using a Zero Length Transfer + if (!m_I2C.write(m_ADDR, NULL, 0)) { + //Return success + return true; + } else { + //Return failure + return false; + } + } + + + // Command the MAX17048 to perform a power-on reset + void reset() + { + //Write the POR command + write(REG_CMD, 0x5400); + } + + // Command the MAX17048 to perform a QuickStart + void quickStart() + { + //Read the current 16-bit register value + unsigned short value = read(REG_MODE); + + //Set the QuickStart bit + value |= (1 << 14); + + //Write the value back out + write(REG_MODE, value); + } + + //disable sleep + void disable_sleep() + { + unsigned short value = read(REG_MODE); + value &= ~(1 << 13); + write(REG_MODE, value); + } + + //disable the hibernate of the MAX17048 + void disable_hibernate() + { + write(REG_HIBRT, 0x0000); + } + + // Determine whether or not the SOC 1% change alert is enabled on the MAX17048 + bool socChangeAlertEnabled() + { + //Read the 16-bit register value + unsigned short value = read(REG_CONFIG); + + //Return the status of the ALSC bit + if (value & (1 << 6)) + return true; + else + return false; + } + + // Enable or disable the SOC 1% change alert on the MAX17048 + void socChangeAlertEnabled(bool enabled) + { + //Read the current 16-bit register value + unsigned short value = read(REG_CONFIG); + + //Set or clear the ALSC bit + if (enabled) + value |= (1 << 6); + else + value &= ~(1 << 6); + + //Write the value back out + write(REG_CONFIG, value); +} + // Determine whether or not the MAX17048 is asserting the ALRT pin + bool alerting() + { + //Read the 16-bit register value + unsigned short value = read(REG_CONFIG); + + //Return the status of the ALRT bit + if (value & (1 << 5)) + return true; + else + return false; + } + + // Command the MAX17048 to de-assert the ALRT pin + void clearAlert() + { + //Read the current 16-bit register value + unsigned short value = read(REG_CONFIG); + + //Clear the ALRT bit + value &= ~(1 << 5); + + //Write the value back out + write(REG_CONFIG, value); + } + // return The current SOC empty alert threshold in %. + char emptyAlertThreshold() + { + //Read the 16-bit register value + unsigned short value = read(REG_CONFIG); + + //Extract the threshold + return 32 - (value & 0x001F); + } + + //Set the SOC empty alert threshold of the MAX17048 + void emptyAlertThreshold(char threshold) + { + //Read the current 16-bit register value + unsigned short value = read(REG_CONFIG); + + //Update the register value + value &= 0xFFE0; + value |= 32 - threshold; + + //Write the 16-bit register + write(REG_CONFIG, value); + } + //return The current low voltage alert threshold in volts. + float vAlertMinThreshold() + { + //Read the 16-bit register value + unsigned short value = read(REG_VALRT); + + //Extract the alert threshold + return (value >> 8) * 0.02;//least count is 20mV + } + // Set the low and high voltage alert threshold of the MAX17048 + void vAlertMinMaxThreshold() + { + //Read the current 16-bit register value + unsigned short value = read(REG_VALRT); + + //Mask off the old value + + value = 0xFFFF; + + //Write the 16-bit register + write(REG_VALRT, value); + } + + //return The current high voltage alert threshold in volts. + float vAlertMaxThreshold() + { + //Read the 16-bit register value + unsigned short value = read(REG_VALRT); + + //Extract the active threshold + return (value & 0x00FF) * 0.02; + } + + //return The current reset voltage threshold in volts. + float vResetThreshold() + { + //Read the 16-bit register value + unsigned short value = read(REG_VRESET_ID); + + //Extract the threshold + return (value >> 9) * 0.04; + } + + // Set the reset voltage threshold of the MAX17048 + void vResetThresholdSet() + { + //Read the current 16-bit register value + unsigned short value = read(REG_VRESET_ID); + + //Mask off the old //value + value &= 0x00FF;//Dis=0 + + value |= 0x7C00;//corresponding to 2.5 V + + + //Write the 16-bit register + write(REG_VRESET_ID, value); + } + + // Get the factory programmed 8-bit ID of the MAX17048 + char id() + { + //Read the 16-bit register value + unsigned short value = read(REG_VRESET_ID); + + //Return only the ID bits + return value; + } + + // Determine whether or not the voltage reset alert is enabled on the MAX17048 + bool vResetAlertEnabled() + { + //Read the 16-bit register value + unsigned short value = read(REG_STATUS); + + //Return the status of the EnVR bit + if (value & (1 << 14)) + return true; + else + return false; + } + + // Enable or disable the voltage reset alert on the MAX17048 + void vResetAlertEnabled(bool enabled) + { + //Read the current 16-bit register value + unsigned short value = read(REG_STATUS); + + //Set or clear the EnVR bit + if (enabled) + value |= (1 << 14); + else + value &= ~(1 << 14); + + //Write the value back out + write(REG_STATUS, value); + } + + //Get the current alert flags on the MAX17048 + //refer datasheet-status registers section to decode it. + char alertFlags() + { + //Read the 16-bit register value + unsigned short value = read(REG_STATUS); + + //Return only the flag bits + return (value >> 8) & 0x3F; + } + + // Clear all the alert flags on the MAX17048 + void clearAlertFlags() + { + //Read the current 16-bit register value + unsigned short value = read(REG_STATUS); + + //Clear the specified flag bits + value &= ~( 0x3F<< 8); + + //Write the value back out + write(REG_STATUS, value); + } + + // Get the current cell voltage measurement of the MAX17048 + float vcell() + { + //Read the 16-bit raw Vcell value + unsigned short value = read(REG_VCELL); + + //Return Vcell in volts + return value * 0.000078125; + } + + // Get the current state of charge measurement of the MAX17048 as a float + float soc() + { + //Read the 16-bit raw SOC value + unsigned short value = read(REG_SOC); + + //Return SOC in percent + return value * 0.00390625; + } + + // Get the current state of charge measurement of the MAX17048 as an int + int soc_int() + { + //Read the 16-bit raw SOC value + unsigned short value = read(REG_SOC); + + //Return only the top byte + return value >> 8; + } + + // Get the current C rate measurement of the MAX17048 + float crate() + { + //Read the 16-bit raw C/Rate value + short value = read(REG_CRATE); + + //Return C/Rate in %/hr + return value * 0.208; + } + + + //I2C register addresses + enum Register { + REG_VCELL = 0x02, + REG_SOC = 0x04, + REG_MODE = 0x06, + REG_VERSION = 0x08, + REG_HIBRT = 0x0A, + REG_CONFIG = 0x0C, + REG_VALRT = 0x14, + REG_CRATE = 0x16, + REG_VRESET_ID = 0x18, + REG_STATUS = 0x1A, + REG_TABLE = 0x40, + REG_CMD = 0xFE + }; + + //Member constants + static const int m_ADDR=(0x36 << 1); + + //Member variables + I2C m_I2C; + + //Internal functions + unsigned short read(char reg) + { + //Create a temporary buffer + char buff[2]; + + //Select the register + m_I2C.write(m_ADDR, ®, 1, true); + + //Read the 16-bit register + m_I2C.read(m_ADDR, buff, 2); + + //Return the combined 16-bit value + return (buff[0] << 8) | buff[1]; + } + + + void write(char reg, unsigned short data) + { + //Create a temporary buffer + char buff[3]; + + //Load the register address and 16-bit data + buff[0] = reg; + buff[1] = data >> 8; + buff[2] = data; + + //Write the data + m_I2C.write(m_ADDR, buff, 3); + } +}; + + + void FUNC_BATTERYGAUGE_MAIN(float[]); + + \ No newline at end of file
diff -r f06840d848e3 -r 667fbc82d634 MPU3300.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MPU3300.h Mon Dec 15 05:58:23 2014 +0000 @@ -0,0 +1,26 @@ +//MPU 3300 registers +#define SMPLRT_DIV 0x19 +#define CONFIG 0x1A +#define GYRO_CONFIG 0x1B +#define GYRO_XOUT_H 0x43 +#define GYRO_XOUT_L 0x44 +#define GYRO_YOUT_H 0x45 +#define GYRO_YOUT_L 0x46 +#define GYRO_ZOUT_H 0x47 +#define GYRO_ZOUT_L 0x48 +#define USER_CTRL 0x6A +#define PWR_MGMT_1 0x6B +#define INT_ENABLE 0x38 + +//MPU configuration bits +#define READFLAG 0x80 +#define DUMMYBIT 0x00 +#define BITS_DLPF_CFG 0x07 +#define BITS_FS_SEL_3 0x08 +#define BITS_FS_SEL_4 0x10 +#define BIT_I2C_IF_DIS 0x10 +#define BITS_SMPLRT_DIV 0x00 +#define BIT_SLEEP 0x40 +#define BIT_DATA_RDY_ENABLE 0x01 +#define BIT_DATA_RDY_INT 0x01 +#define BIT_CLKSEL_X 0x01
diff -r f06840d848e3 -r 667fbc82d634 fault.cpp --- a/fault.cpp Wed Dec 10 06:34:17 2014 +0000 +++ b/fault.cpp Mon Dec 15 05:58:23 2014 +0000 @@ -1,8 +1,8 @@ #include "fault.h" #include "HK.h" - - - + + +DigitalIn fault0(FAULT0,PullUp); DigitalIn fault1(FAULT1,PullUp); DigitalIn fault2(FAULT2,PullUp); DigitalIn fault3(FAULT3,PullUp); @@ -11,85 +11,124 @@ //DigitalIn fault6(FAULT6,PullUp); //DigitalIn fault7(FAULT7,PullUp); //DigitalIn fault8(FAULT8,PullUp); - - + + InterruptIn fault_IR1(FAULT5); InterruptIn fault_IR2(FAULT6); InterruptIn fault_IR3(FAULT7); InterruptIn fault_IR4(FAULT8); InterruptIn fault_IR5(FAULT9); - - - + + + DigitalOut clear1(FAULT_CLEAR1,0); DigitalOut clear2(FAULT_CLEAR2,0); DigitalOut clear3(FAULT_CLEAR3,0); DigitalOut clear4(FAULT_CLEAR4,0); -DigitalOut clear5(FAULT_CLEAR5,0); -DigitalOut clear6(FAULT_CLEAR6,0); -DigitalOut clear7(FAULT_CLEAR7,0); -DigitalOut clear8(FAULT_CLEAR8,0); -DigitalOut clear9(FAULT_CLEAR9,0); - - +DigitalOut clear5(FAULT_CLEAR5); +DigitalOut clear6(FAULT_CLEAR6); +DigitalOut clear7(FAULT_CLEAR7); +DigitalOut clear8(FAULT_CLEAR8); +DigitalOut clear9(FAULT_CLEAR9); + + DigitalOut acs_active(ACS); - - + + +BusIn fault_poll(FAULT0,FAULT1,FAULT2,FAULT3,FAULT4); +BusIn fault_ir(FAULT5,FAULT6,FAULT7,FAULT8,FAULT9); + BusOut clear_poll(FAULT_CLEAR1,FAULT_CLEAR2,FAULT_CLEAR3,FAULT_CLEAR4);//to send fault data along with hk -BusOut clear_interrupt(FAULT_CLEAR5,FAULT_CLEAR6,FAULT_CLEAR7,FAULT_CLEAR8,FAULT_CLEAR9); - +BusOut clear_ir(FAULT_CLEAR5,FAULT_CLEAR6,FAULT_CLEAR7,FAULT_CLEAR8,FAULT_CLEAR9); + + extern SensorData Sensor; extern int beacon_sc; //to switch beacon between low and high power mode extern int acs_pflag; //to activate/deactivate control algo - - +char out_poll; +char out_ir; + void FAULTS() { printf("Entered Fault management \n"); - clear1 = !fault1; - clear2 = !fault2; - clear3 = !fault3; - clear4 = !fault4; + if(fault0==0)printf("CHARGER IS CHARGING THE BATTERY "); + if(fault0==1)printf("CHRGER GONE OFFLINE, BATTERY DRAINING"); + + if(fault1==0) + { clear1=1;printf("");} + else + { clear1=0;} + + if(fault2==0) + { clear2=1;printf("");} + else + { clear2=0;} + + if(fault3==0) + { clear3=1;printf("");} + else + { clear3=0;} + + if(fault4==0) + { clear4=1;printf("");} + else + { clear4=0;} + + + + + + + + + //clear1 = !fault1; + //clear2 = !fault2; + //clear3 = !fault3; + //clear4 = !fault4; //clear5 = !fault5; //clear6 = !fault6; //clear7 = !fault7; //clear8 = !fault8; - Sensor.faultpoll = clear_poll; - Sensor.faultir=clear_interrupt; - printf(" %d , %d \n",Sensor.faultpoll, Sensor.faultir ) ; + + + out_poll = clear_poll; + out_ir = clear_ir; + Sensor.faultpoll = fault_poll ; + Sensor.faultir=fault_ir ; + printf(" %d , %d \n %d , %d\n",Sensor.faultpoll, Sensor.faultir , out_poll , out_ir) ; } - - - + + + void Clear_IR1() {clear5=!clear5; } - + void Clear_IR2() {clear6=!clear6; } - + void Clear_IR3() {clear7=!clear7; } - + void Clear_IR4() {clear8=!clear8; } - + void Clear_IR5() {clear9=!clear9; } - + void interrupt_fault() { - /*fault_IR1.rise(&Clear_IR1); + fault_IR1.rise(&Clear_IR1); fault_IR2.rise(&Clear_IR2); fault_IR3.rise(&Clear_IR3); fault_IR4.rise(&Clear_IR4); - fault_IR5.rise(&Clear_IR5);*/ + fault_IR5.rise(&Clear_IR5); fault_IR1.fall(&Clear_IR1); fault_IR2.fall(&Clear_IR2); fault_IR3.fall(&Clear_IR3); @@ -97,7 +136,7 @@ fault_IR5.fall(&Clear_IR5); } - + void POWER(char flag) //flag corresponds to the power mode { printf("Entered Power Management \n"); @@ -129,4 +168,5 @@ acs_pflag = 1; else acs_pflag = 0; */ -} \ No newline at end of file +} + \ No newline at end of file
diff -r f06840d848e3 -r 667fbc82d634 fault.h --- a/fault.h Wed Dec 10 06:34:17 2014 +0000 +++ b/fault.h Mon Dec 15 05:58:23 2014 +0000 @@ -1,7 +1,7 @@ #include "mbed.h" #include "pin_config.h" - - + +#define FAULT0 PIN31 #define FAULT1 PIN42 // FAULTBAR #define FAULT2 PIN40 // 3V3APGOOD #define FAULT3 PIN39 // 3V3BPGOOD @@ -11,7 +11,7 @@ #define FAULT7 PIN97 // SW8FAULT #define FAULT8 PIN83 // SW6FAULT #define FAULT9 PIN89 // SW7FAULT - + //CONTROL SIGNALS #define FAULT_CLEAR1 D8 #define FAULT_CLEAR2 D9 @@ -22,13 +22,14 @@ #define FAULT_CLEAR7 PTC7 #define FAULT_CLEAR8 PTC10 #define FAULT_CLEAR9 PTC11 - - - + + + #define ACS PTC4 #define TX PTC6 #define PAYLOAD PTC7 - - + + void FAULTS(); -void POWER(char flag); \ No newline at end of file +void POWER(char flag); +void interrupt_fault(); \ No newline at end of file
diff -r f06840d848e3 -r 667fbc82d634 main.cpp --- a/main.cpp Wed Dec 10 06:34:17 2014 +0000 +++ b/main.cpp Mon Dec 15 05:58:23 2014 +0000 @@ -6,6 +6,7 @@ #include "ACS.h" #include "fault.h" +#define DEFAULT_POW_MODE 0 //power mode initialization Serial pc(USBTX, USBRX); @@ -14,12 +15,14 @@ Timer t1; //To know the time of entering of each thread -Thread *ptr_t_hk_acq; -Thread *ptr_t_acs; -Thread *ptr_t_acs_write2flash; -Thread *ptr_t_bea; -Thread *ptr_t_bea_telecommand; -Thread *ptr_t_fault; +Thread *ptr_t_hk; //every 20 seconds +Thread *ptr_t_acs; //every 10 seconds +//Thread *ptr_t_acs_write2flash; +Thread *ptr_t_bea; //every 30 seconds +//Thread *ptr_t_bea_telecommand; +//Thread *ptr_t_fault; //will be taken care by HK thread and interrupts +Thread *ptr_t_i2c; //for interprocessor communication +Thread *ptr_t_exec_tc; //Taking data from i2c mail box and execute the stuff //-------------------------------------------------------------------------------------------------------------------------------------------------- @@ -27,38 +30,39 @@ //-------------------------------------------------------------------------------------------------------------------------------------------------- - -void t_hk_acq(void const *args) +extern SensorData Sensor; +void t_hk(void const *args) { - + Sensor.power_mode = DEFAULT_POW_MODE; while(1) { Thread::signal_wait(0x2); printf("\nTHIS IS HK %f\n",t1.read()); - t.start(); - + //t.start(); + FAULTS(); + POWER(Sensor.power_mode); FUNC_HK_MAIN(); //Collecting HK data //thread_2.signal_set(0x4); - FUNC_I2C_SLAVE_MAIN(24); //Sending to CDMS via I2C + // FUNC_I2C_SLAVE_MAIN(24); //Put HK data to I2C thread instead - t.stop(); - printf("The time to execute hk_acq is %f seconds\n",t.read()); - t.reset(); + // t.stop(); + //printf("The time to execute hk_acq is %f seconds\n",t.read()); + //t.reset(); } } //--------------------------------------------------------------------------------------------------------------------------------------- //TASK 1 : ACS //--------------------------------------------------------------------------------------------------------------------------------------- -typedef struct { +/*typedef struct { float mag_field; float omega; } sensor_data; + */ +//Mail <sensor_data, 16> q_acs; //Will be taken care of by HK structure every 20 seconds -Mail <sensor_data, 16> q_acs; - -void func_acs_readdata(sensor_data *ptr) +/*void func_acs_readdata(sensor_data *ptr) { printf("Reading the data\n"); ptr -> mag_field = 10; @@ -76,32 +80,38 @@ { printf("The magnetic field is %.2f T\n\r",ptr2->mag_field); printf("The angular velocity is %.2f rad/s\n\r",ptr2->omega); -} +}*/ -int acs_pflag = 1; +int acs_pflag = 1; //for executing acs power modes void t_acs(void const *args) { + float *mag_field; + float *omega; + float *moment; while(1) { Thread::signal_wait(0x1); printf("\nTHIS IS ACS %f\n",t1.read()); - t.start(); - sensor_data *ptr = q_acs.alloc(); + // t.start(); + // sensor_data *ptr = q_acs.alloc(); //done by HK instead + + //func_acs_readda=ta(ptr); + mag_field= FUNC_ACS_MAG_EXEC(); //actual execution + omega = FUNC_ACS_EXEC_GYR(); - func_acs_readdata(ptr); - //printf("\ngdhd\n"); - q_acs.put(ptr); - if(acs_pflag == 1) + + //q_acs.put(ptr); //done by HK + if(acs_pflag == 1) //for the respective power mode { - func_acs_ctrlalgo(); - FUNC_ACS_GENPWM(); //Generating PWM signal. + moment = FUNC_ACS_CNTRLALGO(mag_field,omega); + FUNC_ACS_GENPWM(moment); //Generating PWM signal. } - t.reset(); + //t.reset(); } } -void t_acs_write2flash(void const *args) +/*void t_acs_write2flash(void const *args) //unwanted thread { while(1) { @@ -115,7 +125,7 @@ } printf("Writing acs data in the flash\n"); } -} +}*/ //---------------------------------------------------BEACON-------------------------------------------------------------------------------------------- @@ -123,7 +133,7 @@ int beac_flag=0; //To receive telecommand from ground. -void t_bea_telecommand(void const *args) +/*void t_bea_telecommand(void const *args) //taken care of by t_exec_tc { char c = pc.getc(); if(c=='a') @@ -132,7 +142,7 @@ beac_flag=1; } } - +*/ void t_bea(void const *args) { @@ -140,21 +150,21 @@ { Thread::signal_wait(0x3); printf("\nTHIS IS BEACON %f\n",t1.read()); - t.start(); + //t.start(); FUNC_BEA(); - if(beac_flag==1) + /*if(beac_flag==1) //beacon standby can be doe to { Thread::wait(600000); beac_flag = 0; - } + }*/ - printf("The time to execute beacon thread is %f seconds\n",t.read()); - t.reset(); + //printf("The time to execute beacon thread is %f seconds\n",t.read()); + //t.reset(); } } @@ -195,9 +205,9 @@ } }*/ -extern SensorData Sensor; +/* void T_FAULT(void const *args) { Sensor.power_mode='0'; @@ -209,7 +219,7 @@ //Sensor.power_mode++; //testing ... should be removed } } - +*/ //------------------------------------------------------------------------------------------------------------------------------------------------ //SCHEDULER //------------------------------------------------------------------------------------------------------------------------------------------------ @@ -230,8 +240,8 @@ } if(schedcount%2==0) { - ptr_t_fault -> signal_set(0x2); - ptr_t_hk_acq -> signal_set(0x2); + // ptr_t_fault -> signal_set(0x2); + ptr_t_hk -> signal_set(0x2); } if(schedcount%beacon_sc==0) @@ -251,28 +261,28 @@ { t1.start(); - ptr_t_hk_acq = new Thread(t_hk_acq); + ptr_t_hk = new Thread(t_hk); ptr_t_acs = new Thread(t_acs); - ptr_t_acs_write2flash = new Thread(t_acs_write2flash); + //ptr_t_acs_write2flash = new Thread(t_acs_write2flash); ptr_t_bea = new Thread(t_bea); - ptr_t_bea_telecommand = new Thread(t_bea_telecommand); - ptr_t_fault = new Thread(T_FAULT); + //ptr_t_bea_telecommand = new Thread(t_bea_telecommand); + //ptr_t_fault = new Thread(T_FAULT); //ptr_t_sc = new Thread(t_sc); - ptr_t_fault -> set_priority(osPriorityRealtime); + // ptr_t_fault -> set_priority(osPriorityRealtime); ptr_t_acs->set_priority(osPriorityHigh); - ptr_t_hk_acq->set_priority(osPriorityNormal); - ptr_t_acs_write2flash->set_priority(osPriorityBelowNormal); + ptr_t_hk->set_priority(osPriorityNormal); + //ptr_t_acs_write2flash->set_priority(osPriorityBelowNormal); ptr_t_bea->set_priority(osPriorityAboveNormal); - ptr_t_bea_telecommand->set_priority(osPriorityIdle); + //ptr_t_bea_telecommand->set_priority(osPriorityIdle); //ptr_t_sc->set_priority(osPriorityAboveNormal); // ---------------------------------------------------------------------------------------------- - printf("\n T_FAULT priority is %d",ptr_t_fault->get_priority()); + //printf("\n T_FAULT priority is %d",ptr_t_fault->get_priority()); printf("\n T_ACS priority is %d",ptr_t_acs->get_priority()); - printf("\n T_HK_ACQ priority is %d",ptr_t_hk_acq->get_priority()); - printf("\n T_ACS_WRITE2FLASH priority is %d",ptr_t_acs_write2flash->get_priority()); + printf("\n T_HK_ACQ priority is %d",ptr_t_hk->get_priority()); + //printf("\n T_ACS_WRITE2FLASH priority is %d",ptr_t_acs_write2flash->get_priority()); printf("\n T_BEA priority is %d",ptr_t_bea->get_priority()); RtosTimer t_sc_timer(t_sc,osTimerPeriodic); t_sc_timer.start(10000);
diff -r f06840d848e3 -r 667fbc82d634 slave.cpp --- a/slave.cpp Wed Dec 10 06:34:17 2014 +0000 +++ b/slave.cpp Mon Dec 15 05:58:23 2014 +0000 @@ -1,5 +1,6 @@ +/*******************Below is an old version**********************************************************************************************/ /* Added fault to hk structure and being sent through I2C. Need to verify the format */ -#include "slave.h" +/*#include "slave.h" #include "HK.h" extern struct SensorData Sensor; @@ -98,4 +99,155 @@ } screen.printf("\nexited slave function\n"); } - \ No newline at end of file +*/ + +//******************The following is a new version********************************************************************************/ +#include "HK.h" +#include "slave.h" + + + +I2CSlave slave(D14,D15); //configuring pins p27, p28 as I2Cslave +Serial pc_slave (USBTX,USBRX); +//InterruptIn interrupt(D9); //This should be in the main +//DigitalOut data_ready(D10); //Again in the main function +//int i2c_status=0; //read/write mode for i2c 0 : write2slave, 1 : write2master (Again in tha main) + +typedef struct +{ + char data; // To avoid dynamic memory allocation + int length; +}i2c_data; + +//Mail<i2c_data,16> i2c_data_receive; To be done in the main +//Mail<i2c_data,16> i2c_data_send; To be done in the main + +void FUNC_I2C_WRITE2CDMS(char *data, int length=1) +{ + + int slave_status = 1; + while(slave_status) + { + slave.address(0x20); + if(slave.receive()==1) + { + slave_status=slave.write(data,length); + // printf("\n In the while loop\n"); + + /*if(!slave_status) + { + printf("slave wrote %c to master\n\r",*data); + + }*/ + + } + else + if(slave.receive()==3 || slave.receive()==2) + { + //i2c_data *i2c_data_r = i2c_data_receive.alloc(); + slave_status=slave.read(data,length); + /*if(!slave_status) + { + printf("1 read %c from master\n\r",*data); + }*/ + } + //slave.stop(); + } + printf("2 done"); + +} + +/*void T_I2C_BAE(void const * args) +{ + char data_send,data_receive; + //data_send = 'a'; + while(1) + { + Thread::signal_wait(0x1); + printf("\ndetected interrupt\n"); + if(i2c_status == 0) + { + + FUNC_I2C_WRITE2CDMS(&data_receive); + //printf("\n Data received from CDMS is %c\n",data_receive); + i2c_data * i2c_data_r = i2c_data_receive.alloc(); + i2c_data_r->data = data_receive; + i2c_data_r->length = 1; + i2c_data_receive.put(i2c_data_r); + } + else if(i2c_status ==1 ) + { + osEvent evt = i2c_data_send.get(); + if (evt.status == osEventMail) + { + i2c_data *i2c_data_s = (i2c_data*)evt.value.p; + //printf("\nData read from CDMS is %c\n",i2c_data_r->data); + data_send = i2c_data_s -> data; + FUNC_I2C_WRITE2CDMS(&data_send); + printf("\nData sent to CDMS is %c\n",data_send); + i2c_data_send.free(i2c_data_s); + i2c_status = 0; + //delete i2c_data_r; + } + } + } +} + +void FUNC_INT() +{ + // char * data = new char; + //*data = 'a'; + //printf("\nInterrupt from master detected\n"); + ptr_t_i2c->signal_set(0x1); + // + //delete data; +} + + + +void main() +{ + printf("\nStarted slave... waiting for master\n"); + ptr_t_i2c = new Thread(T_I2C_BAE); + char data='a'; + interrupt.rise(&FUNC_INT); + + /* i2c_data * i2c_data_s = i2c_data_send.alloc(); + i2c_data_s->data = data; + i2c_data_s->length = 1; + i2c_data_send.put(i2c_data_s); + //data_ready=1; + i2c_status=1;*/ + // while(1) + //{ + //*(data_send)=pc.getc(); + + //FUNC_I2C_WRITE2CDMS(&data,1); + //printf("\n The data send or received by slave is %c\n",data); + //(data)++; + //wait(1); + //Remove the comments for receiving data + /* osEvent evt = i2c_data_receive.get(); + if (evt.status == osEventMail) + { + i2c_data *i2c_data_r = (i2c_data*)evt.value.p; + printf("\nData read from CDMS is %c\n",i2c_data_r->data); + + i2c_data_receive.free(i2c_data_r); + //delete i2c_data_r; + }*/ +/* //put in comments for receiving data + data_ready=0; + data = pc.getc(); + i2c_data * i2c_data_s = i2c_data_send.alloc(); + i2c_data_s->data = data; + i2c_data_s->length = 1; + i2c_data_send.put(i2c_data_s); + data_ready=1; + i2c_status=1; + + } +} +*/ + +//To be done in the main \ No newline at end of file