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_MS5525.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/*17backend driver for airspeed from I2C18*/1920#include "AP_Airspeed_config.h"2122#if AP_AIRSPEED_MS5525_ENABLED2324#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_MS5525 : public AP_Airspeed_Backend32{33public:34enum MS5525_ADDR {35MS5525_ADDR_1 = 0,36MS5525_ADDR_2 = 1,37MS5525_ADDR_AUTO = 255, // does not need to be 255, just needs to be out of the address array38};3940AP_Airspeed_MS5525(AP_Airspeed &frontend, uint8_t _instance, MS5525_ADDR address);41~AP_Airspeed_MS5525(void) {}4243// probe and initialise the sensor44bool init() override;4546// return the current differential_pressure in Pascal47bool get_differential_pressure(float &pressure) override;4849// return the current temperature in degrees C, if available50bool get_temperature(float &temperature) override;5152private:53void measure();54void collect();55void timer();56bool read_prom(void);57uint16_t crc4_prom(void);58int32_t read_adc();59void calculate();6061float pressure;62float temperature;63float temperature_sum;64float pressure_sum;65uint32_t temp_count;66uint32_t press_count;6768uint32_t last_sample_time_ms;6970uint16_t prom[8];71uint8_t state;72int32_t D1;73int32_t D2;74uint32_t command_send_us;75bool ignore_next;76uint8_t cmd_sent;77MS5525_ADDR _address;7879AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;80};8182#endif // AP_AIRSPEED_MS5525_ENABLED838485