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_ICP101XX.h
Views: 1798
1
#pragma once
2
3
#include "AP_Baro_Backend.h"
4
5
#if AP_BARO_ICP101XX_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_ICP101XX : 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_ICP101XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
20
21
bool init();
22
bool send_cmd16(uint16_t cmd);
23
bool read_measure_results(uint8_t *buf, uint8_t len);
24
bool read_response(uint16_t cmd, uint8_t *buf, uint8_t len);
25
bool send_command(uint16_t cmd);
26
bool send_command(uint16_t cmd, uint8_t *data, uint8_t len);
27
int8_t cal_crc(uint8_t seed, uint8_t data);
28
bool start_measure(uint16_t mode);
29
bool read_calibration_data(void);
30
void convert_data(uint32_t Praw, uint32_t Traw);
31
void calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],
32
float &A, float &B, float &C);
33
float get_pressure(uint32_t p_LSB, uint32_t T_LSB);
34
void timer(void);
35
36
// calibration data
37
int16_t sensor_constants[4];
38
39
uint8_t instance;
40
41
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
42
43
// time last read command was sent
44
uint32_t last_measure_us;
45
46
// accumulation structure, protected by _sem
47
struct {
48
float tsum;
49
float psum;
50
uint32_t count;
51
} accum;
52
53
// conversion constants. Thanks to invensense for including python
54
// sample code in the datasheet!
55
const float p_Pa_calib[3] = {45000.0, 80000.0, 105000.0};
56
const float LUT_lower = 3.5 * (1U<<20);
57
const float LUT_upper = 11.5 * (1U<<20);
58
const float quadr_factor = 1 / 16777216.0;
59
const float offst_factor = 2048.0;
60
uint32_t measure_interval = 0;
61
};
62
63
#endif // AP_BARO_ICP101XX_ENABLED
64
65