Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_MS4525.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#pragma once1516#include "AP_Airspeed_config.h"1718#if AP_AIRSPEED_MS4525_ENABLED1920/*21backend driver for airspeed from I2C22*/2324#include <AP_HAL/AP_HAL.h>25#include <AP_HAL/utility/OwnPtr.h>26#include <AP_HAL/I2CDevice.h>27#include <utility>2829#include "AP_Airspeed_Backend.h"3031class AP_Airspeed_MS4525 : public AP_Airspeed_Backend32{33public:34AP_Airspeed_MS4525(AP_Airspeed &frontend, uint8_t _instance);35~AP_Airspeed_MS4525(void) {}3637// probe and initialise the sensor38bool init() override;3940// return the current differential_pressure in Pascal41bool get_differential_pressure(float &pressure) override;4243// return the current temperature in degrees C, if available44bool get_temperature(float &temperature) override;4546private:47void _measure();48void _collect();49void _timer();50void _voltage_correction(float &diff_press_pa, float &temperature);51float _get_pressure(int16_t dp_raw) const;52float _get_temperature(int16_t dT_raw) const;5354float _temp_sum;55float _press_sum;56uint32_t _temp_count;57uint32_t _press_count;58float _temperature;59float _pressure;60uint32_t _last_sample_time_ms;61uint32_t _measurement_started_ms;62AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;6364bool probe(uint8_t bus, uint8_t address);65};6667#endif // AP_AIRSPEED_MS4525_ENABLED686970