CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_ICP201XX.h
Views: 1798
1
#pragma once
2
3
#include "AP_Baro_Backend.h"
4
5
#if AP_BARO_ICP201XX_ENABLED
6
7
#include <AP_HAL/AP_HAL.h>
8
#include <AP_HAL/Semaphores.h>
9
#include <AP_HAL/Device.h>
10
11
class AP_Baro_ICP201XX : public AP_Baro_Backend
12
{
13
public:
14
void update() override;
15
16
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
17
18
private:
19
AP_Baro_ICP201XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
20
21
bool init();
22
void dummy_reg();
23
bool read_reg(uint8_t reg, uint8_t *buf, uint8_t len);
24
bool read_reg(uint8_t reg, uint8_t *val);
25
bool write_reg(uint8_t reg, uint8_t val);
26
bool mode_select(uint8_t mode);
27
bool read_otp_data(uint8_t addr, uint8_t cmd, uint8_t *val);
28
bool get_sensor_data(float *pressure, float *temperature);
29
void soft_reset();
30
bool boot_sequence();
31
bool configure();
32
void wait_read();
33
bool flush_fifo();
34
void timer();
35
36
uint8_t instance;
37
38
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
39
40
// accumulation structure, protected by _sem
41
struct {
42
float tsum;
43
float psum;
44
uint32_t count;
45
} accum;
46
47
// time last read command was sent
48
uint32_t last_measure_us;
49
50
enum class OP_MODE : uint8_t {
51
OP_MODE0 = 0, /* Mode 0: Bw:6.25 Hz ODR: 25Hz */
52
OP_MODE1, /* Mode 1: Bw:30 Hz ODR: 120Hz */
53
OP_MODE2, /* Mode 2: Bw:10 Hz ODR: 40Hz */
54
OP_MODE3, /* Mode 3: Bw:0.5 Hz ODR: 2Hz */
55
OP_MODE4, /* Mode 4: User configurable Mode */
56
} _op_mode{OP_MODE::OP_MODE2};
57
58
enum class FIFO_READOUT_MODE : uint8_t {
59
FIFO_READOUT_MODE_PRES_TEMP = 0, /* Pressure and temperature as pair and address wraps to the start address of the Pressure value ( pressure first ) */
60
FIFO_READOUT_MODE_TEMP_ONLY = 1, /* Temperature only reporting */
61
FIFO_READOUT_MODE_TEMP_PRES = 2, /* Pressure and temperature as pair and address wraps to the start address of the Temperature value ( Temperature first ) */
62
FIFO_READOUT_MODE_PRES_ONLY = 3 /* Pressure only reporting */
63
} _fifo_readout_mode{FIFO_READOUT_MODE::FIFO_READOUT_MODE_PRES_TEMP};
64
65
enum class POWER_MODE : uint8_t {
66
POWER_MODE_NORMAL = 0, /* Normal Mode: Device is in standby and goes to active mode during the execution of a measurement */
67
POWER_MODE_ACTIVE = 1 /* Active Mode: Power on DVDD and enable the high frequency clock */
68
} _power_mode{POWER_MODE::POWER_MODE_NORMAL};
69
70
enum MEAS_MODE : uint8_t {
71
MEAS_MODE_FORCED_TRIGGER = 0, /* Force trigger mode based on icp201xx_forced_meas_trigger_t **/
72
MEAS_MODE_CONTINUOUS = 1 /* Continuous measurements based on selected mode ODR settings*/
73
} _meas_mode{MEAS_MODE::MEAS_MODE_CONTINUOUS};
74
75
enum FORCED_MEAS_TRIGGER : uint8_t {
76
FORCE_MEAS_STANDBY = 0, /* Stay in Stand by */
77
FORCE_MEAS_TRIGGER_FORCE_MEAS = 1 /* Trigger for forced measurements */
78
} _forced_meas_trigger{FORCED_MEAS_TRIGGER::FORCE_MEAS_STANDBY};
79
};
80
81
#endif // AP_BARO_ICP201XX_ENABLED
82
83