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_Baro/AP_Baro_ICP201XX.h
Views: 1798
#pragma once12#include "AP_Baro_Backend.h"34#if AP_BARO_ICP201XX_ENABLED56#include <AP_HAL/AP_HAL.h>7#include <AP_HAL/Semaphores.h>8#include <AP_HAL/Device.h>910class AP_Baro_ICP201XX : public AP_Baro_Backend11{12public:13void update() override;1415static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);1617private:18AP_Baro_ICP201XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);1920bool init();21void dummy_reg();22bool read_reg(uint8_t reg, uint8_t *buf, uint8_t len);23bool read_reg(uint8_t reg, uint8_t *val);24bool write_reg(uint8_t reg, uint8_t val);25bool mode_select(uint8_t mode);26bool read_otp_data(uint8_t addr, uint8_t cmd, uint8_t *val);27bool get_sensor_data(float *pressure, float *temperature);28void soft_reset();29bool boot_sequence();30bool configure();31void wait_read();32bool flush_fifo();33void timer();3435uint8_t instance;3637AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;3839// accumulation structure, protected by _sem40struct {41float tsum;42float psum;43uint32_t count;44} accum;4546// time last read command was sent47uint32_t last_measure_us;4849enum class OP_MODE : uint8_t {50OP_MODE0 = 0, /* Mode 0: Bw:6.25 Hz ODR: 25Hz */51OP_MODE1, /* Mode 1: Bw:30 Hz ODR: 120Hz */52OP_MODE2, /* Mode 2: Bw:10 Hz ODR: 40Hz */53OP_MODE3, /* Mode 3: Bw:0.5 Hz ODR: 2Hz */54OP_MODE4, /* Mode 4: User configurable Mode */55} _op_mode{OP_MODE::OP_MODE2};5657enum class FIFO_READOUT_MODE : uint8_t {58FIFO_READOUT_MODE_PRES_TEMP = 0, /* Pressure and temperature as pair and address wraps to the start address of the Pressure value ( pressure first ) */59FIFO_READOUT_MODE_TEMP_ONLY = 1, /* Temperature only reporting */60FIFO_READOUT_MODE_TEMP_PRES = 2, /* Pressure and temperature as pair and address wraps to the start address of the Temperature value ( Temperature first ) */61FIFO_READOUT_MODE_PRES_ONLY = 3 /* Pressure only reporting */62} _fifo_readout_mode{FIFO_READOUT_MODE::FIFO_READOUT_MODE_PRES_TEMP};6364enum class POWER_MODE : uint8_t {65POWER_MODE_NORMAL = 0, /* Normal Mode: Device is in standby and goes to active mode during the execution of a measurement */66POWER_MODE_ACTIVE = 1 /* Active Mode: Power on DVDD and enable the high frequency clock */67} _power_mode{POWER_MODE::POWER_MODE_NORMAL};6869enum MEAS_MODE : uint8_t {70MEAS_MODE_FORCED_TRIGGER = 0, /* Force trigger mode based on icp201xx_forced_meas_trigger_t **/71MEAS_MODE_CONTINUOUS = 1 /* Continuous measurements based on selected mode ODR settings*/72} _meas_mode{MEAS_MODE::MEAS_MODE_CONTINUOUS};7374enum FORCED_MEAS_TRIGGER : uint8_t {75FORCE_MEAS_STANDBY = 0, /* Stay in Stand by */76FORCE_MEAS_TRIGGER_FORCE_MEAS = 1 /* Trigger for forced measurements */77} _forced_meas_trigger{FORCED_MEAS_TRIGGER::FORCE_MEAS_STANDBY};78};7980#endif // AP_BARO_ICP201XX_ENABLED818283