APM:Libraries
AP_Airspeed_MS4525.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 /*
18  backend driver for airspeed from I2C
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Param/AP_Param.h>
23 #include <AP_HAL/utility/OwnPtr.h>
24 #include <AP_HAL/I2CDevice.h>
25 #include <utility>
26 
27 #include "AP_Airspeed_Backend.h"
28 #include <AP_HAL/I2CDevice.h>
29 
31 {
32 public:
33  AP_Airspeed_MS4525(AP_Airspeed &frontend, uint8_t _instance);
35 
36  // probe and initialise the sensor
37  bool init() override;
38 
39  // return the current differential_pressure in Pascal
40  bool get_differential_pressure(float &pressure) override;
41 
42  // return the current temperature in degrees C, if available
43  bool get_temperature(float &temperature) override;
44 
45 private:
46  void _measure();
47  void _collect();
48  void _timer();
49  void _voltage_correction(float &diff_press_pa, float &temperature);
50  float _get_pressure(int16_t dp_raw) const;
51  float _get_temperature(int16_t dT_raw) const;
52 
53  float _temp_sum;
54  float _press_sum;
55  uint32_t _temp_count;
56  uint32_t _press_count;
57  float _temperature;
58  float _pressure;
62 };
bool get_differential_pressure(float &pressure) override
uint32_t _measurement_started_ms
A system for managing and storing variables that are of general interest to the system.
float temperature
Definition: Airspeed.cpp:32
void _voltage_correction(float &diff_press_pa, float &temperature)
bool get_temperature(float &temperature) override
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
AP_Airspeed_MS4525(AP_Airspeed &frontend, uint8_t _instance)
float _get_pressure(int16_t dp_raw) const
float _get_temperature(int16_t dT_raw) const