Skip to content

Commit 5fe8802

Browse files
author
BasicAirData
committed
0.0.1
Serial output format
1 parent 78e3d2e commit 5fe8802

5 files changed

Lines changed: 40 additions & 47 deletions

File tree

Software/Arduino/Libraries/AirDC/AirDC.cpp

Lines changed: 26 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,13 @@ AirDC::AirDC(int pid)
3131
_uqc=5.0;
3232
_uIAS=0.0;//To be calculated, 0 default value
3333
_uTAT=0.0;//To be calculated, 0 default value
34-
34+
//Inertial Unit
35+
_Ip=0;
36+
_Iq=2.6;
37+
_Ir=0;
38+
_Ipdot=0.00;
39+
_Iqdot=0.00;
40+
_Irdot=0.00;
3541
}
3642
//RhoAir(Pressure,Temperature,Relative Humidity,mode)
3743
//Mode 1 is the default BasicAirData routine
@@ -252,10 +258,10 @@ String AirDC::OutputSerial(int mode)
252258
String s4(_qc, 6);
253259
String s5(_AOA, 6);
254260
String s6(_AOS, 6);
255-
StreamOut='$'+s1+','+s2+','+s3+','+s4+','+s5+','+s6;
261+
StreamOut='$TMO,'+s1+','+s2+','+s3+','+s4+','+s5+','+s6;
256262
//To read string on the other side
257263
/*
258-
if (Serial.find("$")) {
264+
if (Serial.find("$TMO,")) {
259265
_p = Serial.parseFloat(); //
260266
_T = Serial.parseFloat();//
261267
_RH = Serial.parseFloat();//
@@ -276,7 +282,7 @@ String AirDC::OutputSerial(int mode)
276282
String s8(_h, 6);
277283
String s9(_mu, 6);
278284
String s10(_Re, 6);
279-
StreamOut='$'+s1+','+s2+','+s3+','+s4+','+s5+','+s6+','+s7+','+s8+','+s9+','+s10;
285+
StreamOut='$TAD,'+s1+','+s2+','+s3+','+s4+','+s5+','+s6+','+s7+','+s8+','+s9+','+s10;
280286
break;
281287
}
282288
case 3: //Measurements uncertainty output
@@ -286,7 +292,7 @@ String AirDC::OutputSerial(int mode)
286292
String s2(_uT, 6);
287293
String s3(_uRH, 6);
288294
String s4(_uqc, 6);
289-
StreamOut='$'+s1+','+s2+','+s3+','+s4;
295+
StreamOut='$TMU,'+s1+','+s2+','+s3+','+s4;
290296
break;
291297
}
292298
case 4: //Air data uncertainty output
@@ -298,7 +304,7 @@ String AirDC::OutputSerial(int mode)
298304
String s4(_uTAS, 6);
299305
String s5(_uTAT, 6);
300306
String s6(_uh, 6);
301-
StreamOut='$'+s1+','+s2+','+s3+','+s4+','+s5+','+s6;
307+
StreamOut='$TAU,'+s1+','+s2+','+s3+','+s4+','+s5+','+s6;
302308
break;
303309
}
304310
return StreamOut;
@@ -327,24 +333,29 @@ void AirDC::PitotCorrection(int mode)
327333
PB[1][1]=0.5; //Installation position respect c.o.g.
328334
PB[2][1]=0;
329335
PB[3][1]=0;
330-
WB[1][1]=0.5; //Angular rates . P, q, r from sensors
331-
WB[2][1]=0.5;
332-
WB[3][1]=0.5;
336+
WB[1][1]=_Ip; //Angular rates . P, q, r from sensors
337+
WB[2][1]=_Iq;
338+
WB[3][1]=_Ir;
333339

334340
R[1][1]=cos(_AOA)*cos(_AOS);
335341
R[1][2]=sin(_AOS);
336342
R[1][3]=sin(_AOA)*sin(_AOS);
337-
R[2][1]=-cos(_AOA)*sin(_AOS);
343+
R[2][1]=-1*cos(_AOA)*sin(_AOS);
338344
R[2][2]=cos(_AOS);
339-
R[2][3]=-sin(_AOA)*sin(_AOS);
340-
R[3][1]=-sin(_AOA);
345+
R[2][3]=-1*sin(_AOA)*sin(_AOS);
346+
R[3][1]=-1*sin(_AOA);
341347
R[3][2]=0;
342348
R[3][3]=cos(_AOA);
349+
Serial.Println("Debug")
350+
Matrix.Print((float*)R,3,3,"R");
343351

344352
//Calculation of Position vector in wind axes
345353
Matrix.Multiply((float*)R,(float*)PB,3,3,1,(float*)PW);
346-
//Calculation angular rates at tip in wind frame, attention low angular acceleration assumed. High rates in method 2.
354+
//Calculation of angular rates at tip in wind frame. Attention, assumed low angular acceleration. High rates in another method.
347355
Matrix.Multiply((float*)R,(float*)WB,3,3,1,(float*)WW);
356+
Serial.Println("Debug")
357+
Matrix.Print((float*)PW,3,1,"PW");
358+
Matrix.Print((float*)WW,3,1,"WW");
348359
//Calculation of velocity vector at tip in wind coordinates
349360
//Cross product WWxPW
350361
PWDOT[1][1]=WW[2][1]*PW[3][1]-WW[3][1]*PW[2][1];
@@ -354,6 +365,8 @@ void AirDC::PitotCorrection(int mode)
354365
VCorrected[1][1]=_TAS-PWDOT[1][1];
355366
VCorrected[2][1]= -PWDOT[2][1];
356367
VCorrected[3][1]= -PWDOT[3][1];
368+
Serial.Println("Debug")
369+
Matrix.Print((float*)VCorrected,3,1,"VCorrected");
357370
// _TASPCorrected=sqrt(pow(VCorrected[1][1],2)+pow(VCorrected[2][1],2)+pow(VCorrected[3][1],2));
358371
_TASPCorrected=0;
359372
break;

Software/Arduino/Libraries/AirDC/AirDC.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,13 @@ class AirDC
5757
double _uTAS;
5858
double _uTAT;
5959
double _uh;
60+
//Inertial Unit
61+
double _Ip;
62+
double _Iq;
63+
double _Ir;
64+
double _Ipdot;
65+
double _Iqdot;
66+
double _Irdot;
6067
};
6168
#endif
6269

Software/Arduino/Libraries/AirDC/Examples/DifferentialPressureSensor/DifferentialPressureSensor.ino

Lines changed: 5 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -64,37 +64,14 @@ void loop() {
6464
//Auxiliary data
6565
AirDataComputer.Viscosity(1);// Calculates the dynamic viscosity, Algorithm 1
6666
AirDataComputer.Red(1);// Calculates the ISA altitude from static pressure, Algorithm 1
67-
delay(2000); //loop delay
67+
delay(2000);
6868
//Data Output
69+
Serial.println("$TMO,_p,_T,_RH,_qc,AOA,AOS");
6970
Serial.println(AirDataComputer.OutputSerial(1)); // Measurements
71+
Serial.println("$TAD,_Rho,_IAS,_CAS,_TAS,_TASPCorrected,_M,_TAT,_h,_mu,_Re");
7072
Serial.println(AirDataComputer.OutputSerial(2)); // Air Data
73+
Serial.println("$TMU,_up,_uT,_uRH,_uqc");
7174
Serial.println(AirDataComputer.OutputSerial(3)); // Measurements uncertainty
75+
Serial.println("$TAU,_uRho,_uIAS,_uCAS,_uTAS,_uTAT,_uh");
7276
Serial.println(AirDataComputer.OutputSerial(4)); // Measurements uncertainty
7377
}
74-
75-
/* Serial.println(dpsensor); //Prints the Selected sensor
76-
Serial.println(psensor); //Prints the Selected sensor
77-
Serial.println(AirDataComputer._qc); //Differential pressure reading
78-
Serial.println(AirDataComputer._uqc, 10); //Uncertainty of differential pressure measurement
79-
Serial.println(AirDataComputer._p); //Static Pressure
80-
Serial.println(AirDataComputer._up, 10); //Uncertainty of static pressure
81-
Serial.println(AirDataComputer._IAS);//Sends the indicated Airspeed
82-
Serial.println(AirDataComputer._uIAS, 10); //Sends the uncertainty of IAS measurement
83-
Serial.println(AirDataComputer._Rho,4);//Sends the density of Air
84-
Serial.println(AirDataComputer._uRho, 10); //Sends the uncertainty of the density of air
85-
Serial.println(AirDataComputer._CAS); //Calibrated AirSpeed
86-
Serial.println(AirDataComputer._uCAS); //Calibrated AirSpeed uncertainty
87-
Serial.println(AirDataComputer._TAS); //True Airspeed
88-
Serial.println(AirDataComputer._uTAS); //True Airspeed uncertainty
89-
Serial.println(AirDataComputer._M,10); //Mach number
90-
Serial.println(AirDataComputer._TAT,4); //Total Air Temperature
91-
Serial.println(AirDataComputer._uTAT); //Total Air Temperature uncertainty
92-
Serial.println(AirDataComputer._T,4); //Outside Temperature, Static Temperature
93-
Serial.println(AirDataComputer._uT); //Outside Temperature, Static Temperature uncertainty
94-
Serial.println(AirDataComputer._RH); //Relative Humidity
95-
Serial.println(AirDataComputer._uRH); //Relative Humidity Uncertainty
96-
Serial.println(AirDataComputer._h,4); //Altitude
97-
Serial.println(AirDataComputer._uh); //Altitude Uncertainty
98-
Serial.println(AirDataComputer._TASPCorrected); //True Airspeed Corrected for probe position
99-
Serial.println(AirDataComputer._mu,10); //Viscosity Pas
100-
Serial.println(AirDataComputer._Re); //Reynolds*/

Software/Arduino/Libraries/AirDC/TODO.txt

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,4 @@ Compensate Relative Humidity sensor dynamic
55
Add SD Card enable Air Data Computer Example
66

77
CHECK/VALIDATE
8-
Pitot Position, angular rates, correction routine
9-
Viscosity
10-
Specific gravity
11-
Altitude uncertainty
8+
Pitot Position, angular rates, correction routine

Software/Arduino/Libraries/AirSensor/AirSensor.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
Created by J. Larragueta, December 3, 2015.
44
Refer to http:\\www.basicairdata.eu
55
*/
6-
#define DEBUG 1
76
#include "AirSensor.h"
87
#include <math.h>
98
#include <Wire.h>
@@ -108,7 +107,7 @@ void AirSensor::ReadDifferentialPressure(AirDC *out,int sensor)
108107
Pread=(Vread-2.5-offsetv)*1000;
109108
#if DEBUG==1
110109
Pread=1000;
111-
#endif // DEBUG
110+
#endif
112111
out->_qc=Pread; //pa
113112
out->_uqc=50.0;//pa
114113
}

0 commit comments

Comments
 (0)