2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
23 #include "build/build_config.h"
25 #include "common/maths.h"
26 #include "common/utils.h"
28 #include "drivers/pitotmeter/pitotmeter.h"
29 #include "drivers/pitotmeter/pitotmeter_adc.h"
30 #include "drivers/adc.h"
32 #if defined(USE_ADC) && defined(USE_PITOT_ADC)
35 * NXP MPXV7002DP differential pressure sensor
39 #define PITOT_ADC_VOLTAGE_SCALER (2.0f / 1.0f) // MPXV7002DP is 5V device, assumed resistive divider 1K:1K
40 #define PITOT_ADC_VOLTAGE_ZERO (2.5f) // Pressure offset is 2.5V
41 #define PITOT_ADC_VOLTAGE_TO_PRESSURE (1000.0f) // 1V/kPa = 1000 Pa/V
43 static bool adcPitotStart(pitotDev_t
*pitot
)
49 static bool adcPitotRead(pitotDev_t
*pitot
)
55 static void adcPitotCalculate(pitotDev_t
*pitot
, float *pressure
, float *temperature
)
58 uint16_t adcRaw
= adcGetChannel(ADC_AIRSPEED
);
59 float voltage
= (float)adcRaw
* (3.3f
/ 4095.0f
); // 12 bit ADC with 3.3V VREF
62 *pressure
= (voltage
* PITOT_ADC_VOLTAGE_SCALER
- PITOT_ADC_VOLTAGE_ZERO
) * PITOT_ADC_VOLTAGE_TO_PRESSURE
;
64 *temperature
= SSL_AIR_TEMPERATURE
; // Temperature at standard sea level
67 bool adcPitotDetect(pitotDev_t
*pitot
)
70 pitot
->calibThreshold
= 0.00001f
; // TODO :: should be tested !!!
71 pitot
->start
= adcPitotStart
;
72 pitot
->get
= adcPitotRead
;
73 pitot
->calculate
= adcPitotCalculate
;
74 return adcIsFunctionAssigned(ADC_AIRSPEED
);