mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
ca21fc01ee
git-svn-id: https://arducopter.googlecode.com/svn/trunk@49 f9c3cf11-9bcb-44bc-f272-b75c42450872
171 lines
6.1 KiB
Plaintext
171 lines
6.1 KiB
Plaintext
/* ******* ADC functions ********************* */
|
|
// Read all the ADC channles
|
|
void Read_adc_raw(void)
|
|
{
|
|
int temp;
|
|
|
|
for (int i=0;i<6;i++)
|
|
AN[i] = APM_ADC.Ch(sensors[i]);
|
|
|
|
// Correction for non ratiometric sensor (test code)
|
|
//temp = APM_ADC.Ch(3);
|
|
//AN[0] += 1500-temp;
|
|
//AN[1] += 1500-temp;
|
|
//AN[2] += 1500-temp;
|
|
}
|
|
|
|
// Returns an analog value with the offset
|
|
int read_adc(int select)
|
|
{
|
|
if (SENSOR_SIGN[select]<0)
|
|
return (AN_OFFSET[select]-AN[select]);
|
|
else
|
|
return (AN[select]-AN_OFFSET[select]);
|
|
}
|
|
/* ******************************************* */
|
|
|
|
/* ******* DCM IMU functions ********************* */
|
|
/**************************************************/
|
|
void Normalize(void)
|
|
{
|
|
float error=0;
|
|
float temporary[3][3];
|
|
float renorm=0;
|
|
|
|
error= -Vector_Dot_Product(&DCM_Matrix[0][0],&DCM_Matrix[1][0])*.5; //eq.19
|
|
|
|
Vector_Scale(&temporary[0][0], &DCM_Matrix[1][0], error); //eq.19
|
|
Vector_Scale(&temporary[1][0], &DCM_Matrix[0][0], error); //eq.19
|
|
|
|
Vector_Add(&temporary[0][0], &temporary[0][0], &DCM_Matrix[0][0]);//eq.19
|
|
Vector_Add(&temporary[1][0], &temporary[1][0], &DCM_Matrix[1][0]);//eq.19
|
|
|
|
Vector_Cross_Product(&temporary[2][0],&temporary[0][0],&temporary[1][0]); // c= a x b //eq.20
|
|
|
|
renorm= .5 *(3 - Vector_Dot_Product(&temporary[0][0],&temporary[0][0])); //eq.21
|
|
Vector_Scale(&DCM_Matrix[0][0], &temporary[0][0], renorm);
|
|
|
|
renorm= .5 *(3 - Vector_Dot_Product(&temporary[1][0],&temporary[1][0])); //eq.21
|
|
Vector_Scale(&DCM_Matrix[1][0], &temporary[1][0], renorm);
|
|
|
|
renorm= .5 *(3 - Vector_Dot_Product(&temporary[2][0],&temporary[2][0])); //eq.21
|
|
Vector_Scale(&DCM_Matrix[2][0], &temporary[2][0], renorm);
|
|
}
|
|
|
|
/**************************************************/
|
|
void Drift_correction(void)
|
|
{
|
|
//Compensation the Roll, Pitch and Yaw drift.
|
|
float errorCourse;
|
|
static float Scaled_Omega_P[3];
|
|
static float Scaled_Omega_I[3];
|
|
float Accel_magnitude;
|
|
float Accel_weight;
|
|
|
|
//*****Roll and Pitch***************
|
|
|
|
// Calculate the magnitude of the accelerometer vector
|
|
//Accel_magnitude = sqrt(Accel_Vector[0]*Accel_Vector[0] + Accel_Vector[1]*Accel_Vector[1] + Accel_Vector[2]*Accel_Vector[2]);
|
|
//Accel_magnitude = Accel_magnitude / GRAVITY; // Scale to gravity.
|
|
// Weight for accelerometer info (<0.75G = 0.0, 1G = 1.0 , >1.25G = 0.0)
|
|
// Accel_weight = constrain(1 - 4*abs(1 - Accel_magnitude),0,1);
|
|
// Weight for accelerometer info (<0.5G = 0.0, 1G = 1.0 , >1.5G = 0.0)
|
|
//Accel_weight = constrain(1 - 2*abs(1 - Accel_magnitude),0,1);
|
|
Accel_weight = 1.0;
|
|
|
|
Vector_Cross_Product(&errorRollPitch[0],&Accel_Vector[0],&DCM_Matrix[2][0]); //adjust the ground of reference
|
|
Vector_Scale(&Omega_P[0],&errorRollPitch[0],Kp_ROLLPITCH*Accel_weight);
|
|
|
|
Vector_Scale(&Scaled_Omega_I[0],&errorRollPitch[0],Ki_ROLLPITCH*Accel_weight);
|
|
Vector_Add(Omega_I,Omega_I,Scaled_Omega_I);
|
|
|
|
//*****YAW***************
|
|
// We make the gyro YAW drift correction based on compass magnetic heading
|
|
if (MAGNETOMETER == 1) {
|
|
errorCourse= (DCM_Matrix[0][0]*APM_Compass.Heading_Y) - (DCM_Matrix[1][0]*APM_Compass.Heading_X); //Calculating YAW error
|
|
Vector_Scale(errorYaw,&DCM_Matrix[2][0],errorCourse); //Applys the yaw correction to the XYZ rotation of the aircraft, depeding the position.
|
|
|
|
Vector_Scale(&Scaled_Omega_P[0],&errorYaw[0],Kp_YAW);
|
|
Vector_Add(Omega_P,Omega_P,Scaled_Omega_P);//Adding Proportional.
|
|
|
|
Vector_Scale(&Scaled_Omega_I[0],&errorYaw[0],Ki_YAW);
|
|
Vector_Add(Omega_I,Omega_I,Scaled_Omega_I);//adding integrator to the Omega_I
|
|
}
|
|
|
|
}
|
|
/**************************************************/
|
|
void Accel_adjust(void)
|
|
{
|
|
//Accel_Vector[1] += Accel_Scale(speed_3d*Omega[2]); // Centrifugal force on Acc_y = GPS_speed*GyroZ
|
|
//Accel_Vector[2] -= Accel_Scale(speed_3d*Omega[1]); // Centrifugal force on Acc_z = GPS_speed*GyroY
|
|
}
|
|
/**************************************************/
|
|
|
|
void Matrix_update(void)
|
|
{
|
|
Gyro_Vector[0]=Gyro_Scaled_X(read_adc(0)); //gyro x roll
|
|
Gyro_Vector[1]=Gyro_Scaled_Y(read_adc(1)); //gyro y pitch
|
|
Gyro_Vector[2]=Gyro_Scaled_Z(read_adc(2)); //gyro Z yaw
|
|
|
|
Accel_Vector[0]=read_adc(3); // acc x
|
|
Accel_Vector[1]=read_adc(4); // acc y
|
|
Accel_Vector[2]=read_adc(5); // acc z
|
|
|
|
// Low pass filter on accelerometer data (to filter vibrations)
|
|
//Accel_Vector[0]=Accel_Vector[0]*0.5 + (float)read_adc(3)*0.5; // acc x
|
|
//Accel_Vector[1]=Accel_Vector[1]*0.5 + (float)read_adc(4)*0.5; // acc y
|
|
//Accel_Vector[2]=Accel_Vector[2]*0.5 + (float)read_adc(5)*0.5; // acc z
|
|
|
|
Vector_Add(&Omega[0], &Gyro_Vector[0], &Omega_I[0]);//adding integrator
|
|
Vector_Add(&Omega_Vector[0], &Omega[0], &Omega_P[0]);//adding proportional
|
|
|
|
//Accel_adjust();//adjusting centrifugal acceleration. // Not used for quadcopter
|
|
|
|
#if OUTPUTMODE==1 // corrected mode
|
|
Update_Matrix[0][0]=0;
|
|
Update_Matrix[0][1]=-G_Dt*Omega_Vector[2];//-z
|
|
Update_Matrix[0][2]=G_Dt*Omega_Vector[1];//y
|
|
Update_Matrix[1][0]=G_Dt*Omega_Vector[2];//z
|
|
Update_Matrix[1][1]=0;
|
|
Update_Matrix[1][2]=-G_Dt*Omega_Vector[0];//-x
|
|
Update_Matrix[2][0]=-G_Dt*Omega_Vector[1];//-y
|
|
Update_Matrix[2][1]=G_Dt*Omega_Vector[0];//x
|
|
Update_Matrix[2][2]=0;
|
|
#endif
|
|
#if OUTPUTMODE==0 // uncorrected data of the gyros (with drift)
|
|
Update_Matrix[0][0]=0;
|
|
Update_Matrix[0][1]=-G_Dt*Gyro_Vector[2];//-z
|
|
Update_Matrix[0][2]=G_Dt*Gyro_Vector[1];//y
|
|
Update_Matrix[1][0]=G_Dt*Gyro_Vector[2];//z
|
|
Update_Matrix[1][1]=0;
|
|
Update_Matrix[1][2]=-G_Dt*Gyro_Vector[0];
|
|
Update_Matrix[2][0]=-G_Dt*Gyro_Vector[1];
|
|
Update_Matrix[2][1]=G_Dt*Gyro_Vector[0];
|
|
Update_Matrix[2][2]=0;
|
|
#endif
|
|
|
|
Matrix_Multiply(DCM_Matrix,Update_Matrix,Temporary_Matrix); //a*b=c
|
|
|
|
for(int x=0; x<3; x++) //Matrix Addition (update)
|
|
{
|
|
for(int y=0; y<3; y++)
|
|
{
|
|
DCM_Matrix[x][y]+=Temporary_Matrix[x][y];
|
|
}
|
|
}
|
|
}
|
|
|
|
void Euler_angles(void)
|
|
{
|
|
#if (OUTPUTMODE==2) // Only accelerometer info (debugging purposes)
|
|
roll = atan2(Accel_Vector[1],Accel_Vector[2]); // atan2(acc_y,acc_z)
|
|
pitch = -asin((Accel_Vector[0])/(float)GRAVITY); // asin(acc_x)
|
|
yaw = 0;
|
|
#else // Euler angles from DCM matrix
|
|
pitch = asin(-DCM_Matrix[2][0]);
|
|
roll = atan2(DCM_Matrix[2][1],DCM_Matrix[2][2]);
|
|
yaw = atan2(DCM_Matrix[1][0],DCM_Matrix[0][0]);
|
|
#endif
|
|
}
|
|
|