1 #include "oXs_ads1115.h"
4 //#define DEBUGADS1115SCAN
5 //#define DEBUGADS1115EACHREAD
6 //#define DEBUGADS1115REQUESTCONV
7 //#define DEBUGADS1115MVOLT
8 //#define DEBUGADSAIRSPEEDDATA
12 //#define DEBUG_FORCE_ADS_VOLT_1_4_WITHOUT_ADS1115
13 //#define DEBUG_AIRSPEED_WITH_DUMMY_ADS_DATA
15 extern unsigned long micros( void ) ;
16 extern unsigned long millis( void ) ;
17 extern void delay(unsigned long ms
) ;
19 #if defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined( ADS_MEASURE)
20 const uint8_t ads_Measure
[4] = {ADS_MEASURE
} ; // how to configure the multiplexer
21 const uint8_t ads_Gain
[4] = { ADS_FULL_SCALE_VOLT
}; // how to configure the programmable gain amplifier
22 const uint8_t ads_Rate
[4] = { ADS_RATE
}; // how to configure the time of conversion
23 const float ads_Offset
[4] = { ADS_OFFSET
};
24 const float ads_Scale
[4] = { ADS_SCALE
};
25 const uint8_t ads_MaxCount
[4] = { ADS_AVERAGING_ON
} ; //number of conversion before averaging
27 uint32_t ads_MilliAskConv
;
29 uint8_t ads_CurrentIdx
;
30 uint8_t I2CErrorCodeAds1115
;
31 int32_t ads_SumOfConv
[4] ; // summarise all conversion in order to calculate average
32 uint8_t ads_Counter
[4] ;
33 struct ONE_MEASUREMENT ads_Conv
[4] ; //averaged conversion including offset and scale
34 uint8_t ads_Last_Conv_Idx
;
38 OXS_ADS1115::OXS_ADS1115(uint8_t addr
, HardwareSerial
&print
)
40 OXS_ADS1115::OXS_ADS1115(uint8_t addr
)
50 // **************** Setup the ADS1115 sensor *********************
51 void OXS_ADS1115::setup() {
53 printer
->print(F("ADS1115 sensor I2C Addr="));
54 printer
->println(ads_Addr
,HEX
);
57 I2c
.timeOut( 80); //initialise the time out in order to avoid infinite loop
58 #ifdef DEBUGADS1115SCAN
59 I2c
.scan() ; // scan all I2C address
60 printer
->print(F("I2C scan adr: "));
61 printer
->println( I2c
.scanAdr
, HEX
);
63 ads_Counter
[0] = ads_MaxCount
[0] ;
64 ads_Counter
[1] = ads_MaxCount
[1] ;
65 ads_Counter
[2] = ads_MaxCount
[2] ;
66 ads_Counter
[3] = ads_MaxCount
[3] ;
68 #if defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON)
69 adsCurrentData
.milliAmps
.available
= false ;
70 adsCurrentData
.consumedMilliAmps
.available
= false ;
73 ads_requestNextConv() ; // Write next config and ask for conversion
75 printer
->print(F("Set up Ads1115 done. I2C Error code= "));
76 printer
->println(I2CErrorCodeAds1115
);
77 printer
->print(F(" milli="));
78 printer
->println(millis());
83 /****************************************************************************/
84 /* readSensor - Read ADS115 */
85 /********************* *******************************************************/
86 boolean
OXS_ADS1115::readSensor() { // return true when there is a new average data to calculate
87 if ( ( millis() - ads_MilliAskConv
) > (uint32_t) ( ( 0x88 >> ads_Rate
[ads_CurrentIdx
]) + 1) ) { // when delay of conversion expires (NB delay is 137 msec when ads_rate = 0, and goes down up to 3ms then is divided by 2 for each increase )
88 #ifdef DEBUG_FORCE_ADS_VOLT_1_4_WITHOUT_ADS1115
89 ads_SumOfConv
[ads_CurrentIdx
] += ads_CurrentIdx
+ 1 ; // so at the end e.g. the ADS_VOLT_3 should be equal to 3
90 ads_Counter
[ads_CurrentIdx
]-- ;
91 if ( ads_Counter
[ads_CurrentIdx
] == 0 ) {
92 ads_Conv
[ads_CurrentIdx
].value
= round( ((float) ads_SumOfConv
[ads_CurrentIdx
] / (float) ads_MaxCount
[ads_CurrentIdx
] / 32768 ) * ads_Scale
[ads_CurrentIdx
] ) + ads_Offset
[ads_CurrentIdx
];
93 ads_Conv
[ads_CurrentIdx
].available
= true ;
94 ads_SumOfConv
[ads_CurrentIdx
] = 0 ; // reset the sum
95 ads_Counter
[ads_CurrentIdx
] = ads_MaxCount
[ads_CurrentIdx
] ; // reset the counter to the number of count before averaging
96 ads_Last_Conv_Idx
= ads_CurrentIdx
;
97 #if defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON)
98 if ( ads_CurrentIdx
== ( ADS_CURRENT_BASED_ON
- ADS_VOLT_1
) ) ads_calculateCurrent() ;
102 printer
->print(F("At ")); printer
->print(millis());
103 printer
->print(F(" idx=")); printer
->print(ads_CurrentIdx
);
104 printer
->print(F(" wait=")); printer
->print( ( (uint8_t) 0x88 >> ads_Rate
[ads_CurrentIdx
] ) + 1 );
105 printer
->print(F(" val=")); printer
->print(ads_Conv
[ads_CurrentIdx
].value
);
106 printer
->println(" ");
108 ads_requestNextConv() ;
111 #else // normal code = when DEBUG_FORCE_ADS_VOLT_1_4_WITHOUT_ADS1115 is not activated
112 if( I2CErrorCodeAds1115
== 0 ) { // if there is no error on previous I2C request
113 I2CErrorCodeAds1115
= I2c
.write(ads_Addr
, 0X0 ) ; // send the Address, 0 = conversion register (in order to be able to read the conversion register)
114 if( I2CErrorCodeAds1115
== 0 ) { // if there is no error on previous I2C request
115 I2CErrorCodeAds1115
= I2c
.read( ads_Addr
, 2 ) ; // read 2 bytes , they are in a buffer and must be retrieved with a receive function.
116 if( I2CErrorCodeAds1115
== 0 ) { // if there is no error on previous I2C request
118 valueAdc
= I2c
.receive() << 8 | I2c
.receive() ;
119 #if defined(ADS_AIRSPEED_BASED_ON) and (ADS_AIRSPEED_BASED_ON >= ADS_VOLT1) and (ADS_AIRSPEED_BASED_ON <= ADS_VOLT_4)
120 if (ads_CurrentIdx
== ( ADS_AIRSPEED_BASED_ON
- ADS_VOLT_1
) ) {
121 ads_calculate_airspeed( ( int16_t)valueAdc
) ;
124 ads_SumOfConv
[ads_CurrentIdx
] += (int16_t) valueAdc
;
126 #ifdef DEBUGADS1115EACHREAD
127 printer
->print(F("At ")); printer
->print(millis()) ;
128 printer
->print(F(" idx=")); printer
->print(ads_CurrentIdx
) ;
129 printer
->print(F(" Val=")); printer
->print( (int16_t) valueAdc
) ;
130 printer
->print(F(" count=")); printer
->print(ads_Counter
[ads_CurrentIdx
]) ;
131 printer
->println(" ");
133 ads_Counter
[ads_CurrentIdx
]-- ;
134 if ( ads_Counter
[ads_CurrentIdx
] == 0 ) {
135 float adcToMvoltScaling
;
136 if (ads_Gain
[ads_CurrentIdx
]) {
137 adcToMvoltScaling
= (0X2000 >> ads_Gain
[ads_CurrentIdx
] ) / 32768.0 ; // When ads_Gain[] = 1, it means that 32768 = 4096 mvolt; 4096 = 0x1000) , when 2, it is 2048 mvolt, ...
139 adcToMvoltScaling
= 6144 / 32768.0 ; // When ads_Gain[] = 0, it means that 32768 = 6144 mvolt
141 ads_Conv
[ads_CurrentIdx
].value
= round( ((float) ads_SumOfConv
[ads_CurrentIdx
] / (float) ads_MaxCount
[ads_CurrentIdx
] * adcToMvoltScaling
) * ads_Scale
[ads_CurrentIdx
] ) + ads_Offset
[ads_CurrentIdx
];
142 ads_Conv
[ads_CurrentIdx
].available
= true ;
143 #ifdef DEBUGADS1115MVOLT
144 printer
->print(F("At ")); printer
->print(millis()) ;
145 printer
->print(F(" idx=")); printer
->print(ads_CurrentIdx
) ;
146 printer
->print(F(" Val=")); printer
->print( ads_Conv
[ads_CurrentIdx
].value
) ;
147 printer
->println(" ");
151 ads_SumOfConv
[ads_CurrentIdx
] = 0 ; // reset the sum
152 ads_Counter
[ads_CurrentIdx
] = ads_MaxCount
[ads_CurrentIdx
] ; // reset the counter to the number of count before averaging
153 ads_Last_Conv_Idx
= ads_CurrentIdx
;
154 #if defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON)
155 if ( ads_CurrentIdx
== ( ADS_CURRENT_BASED_ON
- ADS_VOLT_1
) ) ads_calculateCurrent() ;
158 ads_requestNextConv() ;
164 #endif // end of debug with forced values
165 ads_requestNextConv() ; // new request for conversion in case of error
169 } // end of readSensor
172 void OXS_ADS1115::ads_requestNextConv(void) {
175 if( ads_CurrentIdx
> 3 ) ads_CurrentIdx
= 0 ;
176 } while ( ads_Measure
[ads_CurrentIdx
] == ADS_OFF
) ;
177 // perhaps this line has to be splitted in 2 in order to let multiplexer, gain and rate to set up before asking for a conversion.
179 uint8_t dataToWrite
[2] ;
180 dataToWrite
[0] = (( 1 << 7 | ads_Measure
[ads_CurrentIdx
] << 4 | ads_Gain
[ads_CurrentIdx
] << 1 | 1 ) ) ;
181 dataToWrite
[1] = ( ads_Rate
[ads_CurrentIdx
] << 5 | 0B11
);
182 // bit 15 says that a conversion is requested, bit 8 says on shot mode, bits 0 and 1 = 11 says comparator is disabled.
183 I2CErrorCodeAds1115
= I2c
.write((uint8_t) ads_Addr
, (uint8_t) 0X01 , (uint8_t) 2 , &dataToWrite
[0] ) ; // send the Address, 1 = config register , 2 bytes , pointer to the data to write
184 // if ( I2CErrorCodeAds1115 ) I2CErrorCodeAds1115 = I2c.write( (uint8_t) ads_Addr , (uint8_t) 0X01 , (uint8_t) 2 , &dataToWrite[0] ) ; // retry once if there is an error (probably we should add a clear of I2C bus in between)
185 #ifdef DEBUGADS1115REQUESTCONV
186 printer
->print(F("At ")); printer
->print(millis()) ;
187 printer
->print(F(" cmd=")); printer
->print(dataToWrite
[0], HEX
) ;
188 printer
->print(F(" ")); printer
->print( dataToWrite
[1] , HEX
) ;
189 printer
->println(" ");
194 ads_MilliAskConv
= millis() ;
195 } // end of Ads_requestNextConv
198 #if defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON) // this part is compiled only when the config ask for current
199 void OXS_ADS1115::ads_calculateCurrent(void) {
201 static int32_t sumCurrent
= 0 ;
202 static uint16_t cnt
;
203 static uint32_t milliTmp
;
204 static uint32_t lastCurrentMillis
;
205 sumCurrent
+= ads_Conv
[ads_CurrentIdx
].value
;
207 milliTmp
= millis() ;
208 if (lastCurrentMillis
== 0) {
209 lastCurrentMillis
= milliTmp
;
211 else if ( (milliTmp
- lastCurrentMillis
) > 200 ) { // calculate average only once per 200 millisec
212 adsCurrentData
.milliAmps
.value
= ((sumCurrent
/ cnt
) - MVOLT_AT_ZERO_AMP
) * 1000 / MVOLT_PER_AMP
;
213 // if (currentData.milliAmps.value < 0) currentData.milliAmps.value = 0 ;
214 adsCurrentData
.milliAmps
.available
= true ;
215 floatConsumedMilliAmps
+= ((float) adsCurrentData
.milliAmps
.value
) * (milliTmp
- lastCurrentMillis
) / 3600.0 /1000.0 ;
216 adsCurrentData
.consumedMilliAmps
.value
= (int32_t) floatConsumedMilliAmps
;
217 adsCurrentData
.consumedMilliAmps
.available
= true ;
218 lastCurrentMillis
= milliTmp
;
220 printer
->print("At time = ");
221 printer
->print(milliTmp
);
222 printer
->print(" Cnt = ");
224 printer
->print(" average current = ");
225 printer
->print(adsCurrentData
.milliAmps
.value
);
226 printer
->print(" consumed milliAmph = ");
227 printer
->println(adsCurrentData
.consumedMilliAmps
.value
);
236 #if defined(ADS_AIRSPEED_BASED_ON) and (ADS_AIRSPEED_BASED_ON >= ADS_VOLT1) and (ADS_AIRSPEED_BASED_ON <= ADS_VOLT_4) // this part is compiled only when required
237 float ads_sumDifPressureAdc_0
;
238 uint8_t ads_cntDifPressureAdc_0
;
240 void OXS_ADS1115::ads_calculate_airspeed( int16_t ads_difPressureAdc
) {
241 // convert ads_volt to pressure.
242 static int32_t ads_pressure
;
243 static int32_t difPressureSum
;
244 static float offset7002
;
245 static int16_t calibrateCount7002
;
246 static boolean calibrated7002
= false ;
247 static float ads_difPressureAdc_0
;
248 static float ads_abs_deltaDifPressureAdc
;
249 static float ads_smoothDifPressureAdc
;
250 static float expoSmooth7002_adc_auto
;
251 static int32_t ads_smoothAirSpeed
;
252 uint32_t ads_airSpeedMillis
;
253 static uint32_t ads_nextAirSpeedMillis
;
254 //#define DEBUG_AIRSPEED_WITH_DUMMY_ADS_DATA
255 #ifdef DEBUG_AIRSPEED_WITH_DUMMY_ADS_DATA
256 static int16_t dummy_ads_value
;
257 ads_difPressureAdc
= ((millis() / 1000 ) % (100) ) * 300 ;
259 if ( calibrated7002
== false) {
260 calibrateCount7002
++ ;
261 if (calibrateCount7002
== 256 ) { // after 256 reading , we can calculate the offset
262 offset7002
= ( (float) difPressureSum
/ 128.0 ) ; //there has been 128 reading (256-128)
263 calibrated7002
= true ;
264 } else if (calibrateCount7002
>= 128 ){ // after 128 reading, we can start cummulate the ADC values in order to calculate the offset
265 difPressureSum
+= ads_difPressureAdc
;
267 } else { // sensor is calibrated
268 ads_difPressureAdc_0
= ( ads_difPressureAdc
- offset7002
) ;
269 ads_sumDifPressureAdc_0
+= ads_difPressureAdc_0
;
270 ads_cntDifPressureAdc_0
++ ;
271 #define FILTERING7002_ADC_MIN 0.001 //
272 #define FILTERING7002_ADC_MAX 0.01 //
273 #define FILTERING7002_ADC_MIN_AT 10 // when abs(delta between ADC and current value) is less than MIN_AT , apply MIN
274 #define FILTERING7002_ADC_MAX_AT 100 // when abs(delta between ADC and current value) is more than MAX_AT , apply MAX (interpolation in between)
275 ads_abs_deltaDifPressureAdc
= abs(ads_difPressureAdc_0
- ads_smoothDifPressureAdc
) ;
276 if (ads_abs_deltaDifPressureAdc
<= FILTERING7002_ADC_MIN_AT
) {
277 expoSmooth7002_adc_auto
= FILTERING7002_ADC_MIN
;
278 } else if (ads_abs_deltaDifPressureAdc
>= FILTERING7002_ADC_MAX_AT
) {
279 expoSmooth7002_adc_auto
= FILTERING7002_ADC_MAX
;
281 expoSmooth7002_adc_auto
= FILTERING7002_ADC_MIN
+ ( FILTERING7002_ADC_MAX
- FILTERING7002_ADC_MIN
) * (ads_abs_deltaDifPressureAdc
- FILTERING7002_ADC_MIN_AT
) / (FILTERING7002_ADC_MAX_AT
- FILTERING7002_ADC_MIN_AT
) ;
283 if ( ( ads_smoothDifPressureAdc
<=2 ) && ( ads_smoothDifPressureAdc
>= -2 ) ) expoSmooth7002_adc_auto
*= 0.2 ;
284 ads_smoothDifPressureAdc
+= expoSmooth7002_adc_auto
* ( ads_difPressureAdc_0
- ads_smoothDifPressureAdc
) ; //
286 // calculate airspeed based on pressure, altitude and temperature
287 // airspeed (m/sec) = sqr(2 * differential_pressure_in_Pa / air_mass_kg_per_m3)
288 // air_mass_kg_per_m3 = pressure_in_pa / (287.05 * (Temp celcius + 273.15))
289 // and differantial_pressure_Pa = ((smoothDifPressureAdc ) * 2048 / 32768) ; // with 7002, 1 mvolt = 1 pa and ads1115 ADC gives 32768 when volt = 2048 mvolt; so 1 step ADC = 2048 / 32768
290 //2048 is used because we supposed that ads gain is set on 2048 ; MPXV7002 provides 1 mvolt per pa wit 5 volt Vcc; it is ratiometric so there should be some Vcc correction
291 // so airspeed m/sec =sqr( 2 * 287.05 * 2048 / 32768 * smoothDifPressureAdc * (temperature Celsius + 273.15) / pressure_in_pa )
292 // rawAirSpeed cm/sec = 5,99 * 100 * sqrt( (float) abs(smoothDifPressureAdc) * temperature4525 / actualPressure) ); // in cm/sec ; actual pressure must be in Pa (so 101325 about at sea level
293 // = 32.32 * sqrt( (float) abs(smoothDifPressureAdc) ); // in cm/sec ; if pressure is standard = 101325 and temp = 15 C°)
294 // = 10256 * sqrt( (float) abs(smoothDifPressureAdc) / actualPressure) ); // in cm/sec ; temp is supposed to be 20 C°, pressure is in Pa
295 #ifdef AIRSPEED_AT_SEA_LEVEL_AND_15C
296 ads_smoothAirSpeed
= 32.32 * sqrt( (float) ( abs(ads_smoothDifPressureAdc
) ) ); // indicated airspeed is calculated at 15 Celsius and 101325 pascal
298 ads_smoothAirSpeed
= 10256.0 * sqrt( (float) ( abs(ads_smoothDifPressureAdc
) / (float) actualPressure
) ); // in cm/sec ; actual pressure must be in pa (so 101325 about at sea level)
300 if ( ads_smoothDifPressureAdc
< 0 ) ads_smoothAirSpeed
= - ads_smoothAirSpeed
; // apply the sign
302 } // end of test on calibration
303 ads_airSpeedMillis
= millis() ;
304 if ( ads_airSpeedMillis
> ads_nextAirSpeedMillis
){ // publish airspeed only once every xx ms
305 ads_nextAirSpeedMillis
= ads_airSpeedMillis
+ 200 ;
306 // if ( ads_smoothAirSpeed > 0) { // normally send only if positive and greater than 300 cm/sec , otherwise send 0 but for test we keep all values to check for drift
307 #ifdef AIRSPEED_IN_KMH // uncomment this line if AIR speed has to be in knot instead of km/h
308 adsAirSpeedData
.airSpeed
.value
= ads_smoothAirSpeed
* 0.36 ; // from cm/sec to 1/10 km/h
310 adsAirSpeedData
.airSpeed
.value
= ads_smoothAirSpeed
* 0.1943844492 ; // from cm/sec to 1/10 knot/h
313 // adsAirSpeedData.airSpeed.value = 0 ;
315 adsAirSpeedData
.airSpeed
.available
= true ;
317 // check if offset must be reset
318 if (adsAirSpeedData
.airspeedReset
) { // adjust the offset if a reset command is received from Tx
319 offset7002
= offset7002
+ ads_smoothDifPressureAdc
;
320 ads_smoothDifPressureAdc
= 0 ;
321 adsAirSpeedData
.airspeedReset
= false ; // avoid that offset is changed again and again if PPM do not send a command
323 #ifdef DEBUGADSAIRSPEEDDATA
324 static bool firstRawData
= true ;
325 if ( firstRawData
) {
326 printer
->println(F("at, difPressureAdc ,difPressADC_0 , ads_smoothDifPressureAdc , actualPressure , adsAirSpeedData.airSpeed, offset, reset ")) ;
327 firstRawData
= false ;
329 printer
->print( ads_airSpeedMillis
); printer
->print(F(" , "));
330 printer
->print( ads_difPressureAdc
); printer
->print(F(" , "));
331 printer
->print( ads_difPressureAdc_0
); printer
->print(F(" , "));
332 printer
->print( ads_smoothDifPressureAdc
* 1000); printer
->print(F(" , "));
333 printer
->print( actualPressure
); printer
->print(F(" , "));
334 printer
->print( ads_smoothAirSpeed
* 3.6 / 100 ); printer
->print(F(" , "));
335 printer
->print( offset7002
* 1000); printer
->print(F(" , "));
336 if ( ads_smoothDifPressureAdc
== 0) printer
->print(F(" reset")) ;
338 printer
->println(" ") ;
344 } // end test on millis()
347 #endif // end of conditional compiling for calculate airspeed.
349 #endif // end of #if defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined( ADS_MEASURE)